From d630ec9092f039cb5e51c5dd6d92fc47b91407e4 Mon Sep 17 00:00:00 2001 From: Erich Moraga <33645296+ErichMoraga@users.noreply.github.com> Date: Mon, 22 Nov 2021 16:22:28 -0600 Subject: [PATCH 001/102] Add Lexus RC support (#22941) * Add f/w firmware for Lexus RC under LEXUS_IS `@ph33rl355#0529` 2020 Lexus RC F Track Edition DongleID/route 32696cea52831b02|2021-11-16--23-12-02 Doesn't seem to need a full port, per user feedback... https://discord.com/channels/469524606043160576/524327905937850394/910400788319326229 * Update CARS.md * Separated Lexus RC from IS... still using IS DBC * match lexus IS for now * Update wheelbase to match published specs I'm hesitant to touch `mass`, even though I know it's different from the IS. * Add TOYOTA.LEXUS_RC test route Co-authored-by: Willem Melching Co-authored-by: Adeeb Shihadeh --- docs/CARS.md | 1 + selfdrive/car/toyota/carcontroller.py | 2 +- selfdrive/car/toyota/carstate.py | 6 +++--- selfdrive/car/toyota/interface.py | 9 +++++++++ selfdrive/car/toyota/values.py | 24 +++++++++++++++++++++++- selfdrive/test/test_routes.py | 1 + 6 files changed, 38 insertions(+), 5 deletions(-) diff --git a/docs/CARS.md b/docs/CARS.md index 30f3131c72..1f1d08cc04 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -37,6 +37,7 @@ | Lexus | NX 2018 | All | Stock3| 0mph | 0mph | | Lexus | NX 2020 | All | openpilot | 0mph | 0mph | | Lexus | NX Hybrid 2018-19 | All | Stock3| 0mph | 0mph | +| Lexus | RC 2020 | All | Stock | 22mph | 0mph | | Lexus | RX 2016-18 | All | Stock3| 0mph | 0mph | | Lexus | RX 2020-21 | All | openpilot | 0mph | 0mph | | Lexus | RX Hybrid 2016-19 | All | Stock3| 0mph | 0mph | diff --git a/selfdrive/car/toyota/carcontroller.py b/selfdrive/car/toyota/carcontroller.py index 72cde0e537..fdbf5cc8d5 100644 --- a/selfdrive/car/toyota/carcontroller.py +++ b/selfdrive/car/toyota/carcontroller.py @@ -113,7 +113,7 @@ class CarController(): lead = lead or CS.out.vEgo < 12. # at low speed we always assume the lead is present do ACC can be engaged # Lexus IS uses a different cancellation message - if pcm_cancel_cmd and CS.CP.carFingerprint == CAR.LEXUS_IS: + if pcm_cancel_cmd and CS.CP.carFingerprint in [CAR.LEXUS_IS, CAR.LEXUS_RC]: can_sends.append(create_acc_cancel_command(self.packer)) elif CS.CP.openpilotLongitudinalControl: can_sends.append(create_accel_command(self.packer, pcm_accel_cmd, pcm_cancel_cmd, self.standstill_req, lead, CS.acc_type)) diff --git a/selfdrive/car/toyota/carstate.py b/selfdrive/car/toyota/carstate.py index cacd5b7bed..1327cb36dc 100644 --- a/selfdrive/car/toyota/carstate.py +++ b/selfdrive/car/toyota/carstate.py @@ -79,7 +79,7 @@ class CarState(CarStateBase): ret.steeringPressed = abs(ret.steeringTorque) > STEER_THRESHOLD ret.steerWarning = cp.vl["EPS_STATUS"]["LKA_STATE"] not in [1, 5] - if self.CP.carFingerprint == CAR.LEXUS_IS: + if self.CP.carFingerprint in [CAR.LEXUS_IS, CAR.LEXUS_RC]: ret.cruiseState.available = cp.vl["DSU_CRUISE"]["MAIN_ON"] != 0 ret.cruiseState.speed = cp.vl["DSU_CRUISE"]["SET_SPEED"] * CV.KPH_TO_MS else: @@ -93,7 +93,7 @@ class CarState(CarStateBase): # these cars are identified by an ACC_TYPE value of 2. # TODO: it is possible to avoid the lockout and gain stop and go if you # send your own ACC_CONTROL msg on startup with ACC_TYPE set to 1 - if (self.CP.carFingerprint not in TSS2_CAR and self.CP.carFingerprint != CAR.LEXUS_IS) or \ + if (self.CP.carFingerprint not in TSS2_CAR and self.CP.carFingerprint not in [CAR.LEXUS_IS, CAR.LEXUS_RC]) or \ (self.CP.carFingerprint in TSS2_CAR and self.acc_type == 1): self.low_speed_lockout = cp.vl["PCM_CRUISE_2"]["LOW_SPEED_LOCKOUT"] == 2 @@ -168,7 +168,7 @@ class CarState(CarStateBase): ("STEER_TORQUE_SENSOR", 50), ] - if CP.carFingerprint == CAR.LEXUS_IS: + if CP.carFingerprint in [CAR.LEXUS_IS, CAR.LEXUS_RC]: signals.append(("MAIN_ON", "DSU_CRUISE", 0)) signals.append(("SET_SPEED", "DSU_CRUISE", 0)) checks.append(("DSU_CRUISE", 5)) diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py index a1221ae8a4..0759c7bf95 100755 --- a/selfdrive/car/toyota/interface.py +++ b/selfdrive/car/toyota/interface.py @@ -186,6 +186,15 @@ class CarInterface(CarInterfaceBase): ret.mass = 3736.8 * CV.LB_TO_KG + STD_CARGO_KG set_lat_tune(ret.lateralTuning, LatTunes.PID_L) + elif candidate == CAR.LEXUS_RC: + ret.safetyConfigs[0].safetyParam = 77 + stop_and_go = False + ret.wheelbase = 2.73050 + ret.steerRatio = 13.3 + tire_stiffness_factor = 0.444 + ret.mass = 3736.8 * CV.LB_TO_KG + STD_CARGO_KG + set_lat_tune(ret.lateralTuning, LatTunes.PID_L) + elif candidate == CAR.LEXUS_CTH: ret.safetyConfigs[0].safetyParam = 100 stop_and_go = True diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 73198d925f..80db86a9f5 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -58,6 +58,7 @@ class CAR: LEXUS_NX = "LEXUS NX 2018" LEXUS_NXH = "LEXUS NX HYBRID 2018" LEXUS_NX_TSS2 = "LEXUS NX 2020" + LEXUS_RC = "LEXUS RC 2020" LEXUS_RX = "LEXUS RX 2016" LEXUS_RXH = "LEXUS RX HYBRID 2017" LEXUS_RX_TSS2 = "LEXUS RX 2020" @@ -804,10 +805,10 @@ FW_VERSIONS = { b'\x018966353M7100\x00\x00\x00\x00', b'\x018966353Q2000\x00\x00\x00\x00', b'\x018966353Q2300\x00\x00\x00\x00', + b'\x018966353Q4000\x00\x00\x00\x00', b'\x018966353R1100\x00\x00\x00\x00', b'\x018966353R7100\x00\x00\x00\x00', b'\x018966353R8100\x00\x00\x00\x00', - b'\x018966353Q4000\x00\x00\x00\x00', ], (Ecu.engine, 0x7e0, None): [ b'\x0232480000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', @@ -1358,6 +1359,26 @@ FW_VERSIONS = { b'8646F7801100\x00\x00\x00\x00', ], }, + CAR.LEXUS_RC: { + (Ecu.engine, 0x7e0, None): [ + b'\x0232484000\x00\x00\x00\x00\x00\x00\x00\x0052422000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.esp, 0x7b0, None): [ + b'F152624221\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881512409100\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B24081\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F2402200\x00\x00\x00\x00', + ], + }, CAR.LEXUS_RX: { (Ecu.engine, 0x700, None): [ b'\x01896630E36200\x00\x00\x00\x00', @@ -1558,6 +1579,7 @@ DBC = { CAR.RAV4: dbc_dict('toyota_rav4_2017_pt_generated', 'toyota_adas'), CAR.PRIUS: dbc_dict('toyota_prius_2017_pt_generated', 'toyota_adas'), CAR.COROLLA: dbc_dict('toyota_corolla_2017_pt_generated', 'toyota_adas'), + CAR.LEXUS_RC: dbc_dict('lexus_is_2018_pt_generated', 'toyota_adas'), 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'), diff --git a/selfdrive/test/test_routes.py b/selfdrive/test/test_routes.py index 5344f8fd75..61f0adff74 100755 --- a/selfdrive/test/test_routes.py +++ b/selfdrive/test/test_routes.py @@ -122,6 +122,7 @@ routes = [ TestRoute("25057fa6a5a63dfb|2020-03-04--08-44-23", TOYOTA.LEXUS_CTH), TestRoute("f49e8041283f2939|2019-05-30--11-51-51", TOYOTA.LEXUS_ESH_TSS2), TestRoute("37041c500fd30100|2020-12-30--12-17-24", TOYOTA.LEXUS_ESH), + TestRoute("32696cea52831b02|2021-11-19--18-13-30", TOYOTA.LEXUS_RC), TestRoute("886fcd8408d570e9|2020-01-29--05-11-22", TOYOTA.LEXUS_RX), TestRoute("886fcd8408d570e9|2020-01-29--02-18-55", TOYOTA.LEXUS_RX), TestRoute("d27ad752e9b08d4f|2021-05-26--19-39-51", TOYOTA.LEXUS_RXH), From a941a1040da3bcacca24f2eeee1745d7376d2394 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 22 Nov 2021 14:26:00 -0800 Subject: [PATCH 002/102] back to 0.8.12 --- RELEASES.md | 4 ++++ selfdrive/common/version.h | 2 +- 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/RELEASES.md b/RELEASES.md index 12a90fba6c..d4d579cfc4 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,3 +1,7 @@ +Version 0.8.12 (2021-12-XX) +======================== + * Lexus RC 2020 support thanks to ErichMoraga! + Version 0.8.11 (2021-11-29) ======================== * Support for CAN FD on the red panda diff --git a/selfdrive/common/version.h b/selfdrive/common/version.h index 9f00fac4f9..aa786903c4 100644 --- a/selfdrive/common/version.h +++ b/selfdrive/common/version.h @@ -1 +1 @@ -#define COMMA_VERSION "0.8.11" +#define COMMA_VERSION "0.8.12" From d482b2d0a265473bbb3a44e88810a436d53566bb Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 22 Nov 2021 15:15:03 -0800 Subject: [PATCH 003/102] boardd: small cleanup (#23005) --- selfdrive/boardd/boardd.cc | 30 +++++++++--------------------- 1 file changed, 9 insertions(+), 21 deletions(-) diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index f9c4891d03..431b5a86e0 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -70,7 +70,10 @@ std::string get_time_str(const struct tm &time) { bool check_all_connected(const std::vector &pandas) { for (const auto& panda : pandas) { - if (!panda->connected) return false; + if (!panda->connected) { + do_exit = true; + return false; + } } return true; } @@ -194,14 +197,8 @@ void can_send_thread(std::vector pandas, bool fake_send) { subscriber->setTimeout(100); // run as fast as messages come in - while (!do_exit) { - if (!check_all_connected(pandas)) { - do_exit = true; - break; - } - + while (!do_exit && check_all_connected(pandas)) { Message * msg = subscriber->receive(); - if (!msg) { if (errno == EINTR) { do_exit = true; @@ -239,12 +236,7 @@ void can_recv_thread(std::vector pandas) { uint64_t next_frame_time = nanos_since_boot() + dt; std::vector raw_can_data; - while (!do_exit) { - if (!check_all_connected(pandas)){ - do_exit = true; - break; - } - + while (!do_exit && check_all_connected(pandas)) { bool comms_healthy = true; raw_can_data.clear(); for (const auto& panda : pandas) { @@ -416,12 +408,8 @@ void panda_state_thread(PubMaster *pm, std::vector pandas, bool spoofin LOGD("start panda state thread"); // run at 2hz - while (!do_exit) { - if(!check_all_connected(pandas)) { - do_exit = true; - break; - } - + while (!do_exit && check_all_connected(pandas)) { + // send out peripheralState send_peripheral_state(pm, peripheral_panda); ignition = send_panda_states(pm, pandas, spoofing_started); @@ -433,7 +421,7 @@ void panda_state_thread(PubMaster *pm, std::vector pandas, bool spoofin break; } - // clear VIN, CarParams, and set new safety on car start + // clear ignition-based params and set new safety on car start if (ignition && !ignition_last) { params.clearAll(CLEAR_ON_IGNITION_ON); if (!safety_future.valid() || safety_future.wait_for(0ms) == std::future_status::ready) { From 20d5c0c1cb73f848770bcf8b887eff9ccd43a442 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 22 Nov 2021 16:53:59 -0800 Subject: [PATCH 004/102] camerad: lower YUV vipc buffer count to 40 on tici --- selfdrive/camerad/cameras/camera_common.cc | 4 +--- selfdrive/camerad/cameras/camera_common.h | 5 ++++- 2 files changed, 5 insertions(+), 4 deletions(-) diff --git a/selfdrive/camerad/cameras/camera_common.cc b/selfdrive/camerad/cameras/camera_common.cc index 4db6eaa121..b901dc39d3 100644 --- a/selfdrive/camerad/cameras/camera_common.cc +++ b/selfdrive/camerad/cameras/camera_common.cc @@ -28,8 +28,6 @@ #include "selfdrive/camerad/cameras/camera_replay.h" #endif -const int YUV_COUNT = 100; - class Debayer { public: Debayer(cl_device_id device_id, cl_context context, const CameraBuf *b, const CameraState *s) { @@ -109,7 +107,7 @@ void CameraBuf::init(cl_device_id device_id, cl_context context, CameraState *s, vipc_server->create_buffers(rgb_type, UI_BUF_COUNT, true, rgb_width, rgb_height); rgb_stride = vipc_server->get_buffer(rgb_type)->stride; - vipc_server->create_buffers(yuv_type, YUV_COUNT, false, rgb_width, rgb_height); + vipc_server->create_buffers(yuv_type, YUV_BUFFER_COUNT, false, rgb_width, rgb_height); if (ci->bayer) { debayer = new Debayer(device_id, context, this, s); diff --git a/selfdrive/camerad/cameras/camera_common.h b/selfdrive/camerad/cameras/camera_common.h index e994fc2208..f55bbd8401 100644 --- a/selfdrive/camerad/cameras/camera_common.h +++ b/selfdrive/camerad/cameras/camera_common.h @@ -14,6 +14,7 @@ #include "selfdrive/common/queue.h" #include "selfdrive/common/swaglog.h" #include "selfdrive/common/visionimg.h" +#include "selfdrive/hardware/hw.h" #define CAMERA_ID_IMX298 0 #define CAMERA_ID_IMX179 1 @@ -26,7 +27,9 @@ #define CAMERA_ID_AR0231 8 #define CAMERA_ID_MAX 9 -#define UI_BUF_COUNT 4 +const int UI_BUF_COUNT = 4; +const int YUV_BUFFER_COUNT = Hardware::EON() ? 100 : 40; + enum CameraType { RoadCam = 0, From c1f617db46e3ed0aa9993dadd278f4f0c0efef6b Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Tue, 23 Nov 2021 13:46:46 +0800 Subject: [PATCH 005/102] UI: fix cameraview crash after going offroad in settings window (#23009) --- selfdrive/ui/qt/widgets/cameraview.cc | 19 ++++++++++++------- 1 file changed, 12 insertions(+), 7 deletions(-) diff --git a/selfdrive/ui/qt/widgets/cameraview.cc b/selfdrive/ui/qt/widgets/cameraview.cc index 1daabd7d1e..6cc26a0ca4 100644 --- a/selfdrive/ui/qt/widgets/cameraview.cc +++ b/selfdrive/ui/qt/widgets/cameraview.cc @@ -153,16 +153,21 @@ void CameraViewWidget::initializeGL() { void CameraViewWidget::showEvent(QShowEvent *event) { latest_frame = nullptr; - vipc_thread = new QThread(); - connect(vipc_thread, &QThread::started, [=]() { vipcThread(); }); - connect(vipc_thread, &QThread::finished, vipc_thread, &QObject::deleteLater); - vipc_thread->start(); + if (!vipc_thread) { + vipc_thread = new QThread(); + connect(vipc_thread, &QThread::started, [=]() { vipcThread(); }); + connect(vipc_thread, &QThread::finished, vipc_thread, &QObject::deleteLater); + vipc_thread->start(); + } } void CameraViewWidget::hideEvent(QHideEvent *event) { - vipc_thread->requestInterruption(); - vipc_thread->quit(); - vipc_thread->wait(); + if (vipc_thread) { + vipc_thread->requestInterruption(); + vipc_thread->quit(); + vipc_thread->wait(); + vipc_thread = nullptr; + } } void CameraViewWidget::updateFrameMat(int w, int h) { From 9b9cbe1f375bddb4665fd53e63697663e84a8130 Mon Sep 17 00:00:00 2001 From: Erich Moraga <33645296+ErichMoraga@users.noreply.github.com> Date: Tue, 23 Nov 2021 08:35:08 -0600 Subject: [PATCH 006/102] Add several missing CHRH f/w (#23002) `Hookler#6341` 2017 C-HR DongleID/route 9de14f6c78d29e91|2021-11-22--03-48-14 His car was previously FP'ing over FPv1 on OP 0.8.1, and he didn't realize it, until I verified it. Relevant FPv1 was pruned from newer code. --- selfdrive/car/toyota/values.py | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 80db86a9f5..32923b43ab 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -443,6 +443,7 @@ FW_VERSIONS = { b'\x0189663F438000\x00\x00\x00\x00', ], (Ecu.esp, 0x7b0, None): [ + b'F152610012\x00\x00\x00\x00\x00\x00', b'F152610013\x00\x00\x00\x00\x00\x00', b'F152610014\x00\x00\x00\x00\x00\x00', b'F152610040\x00\x00\x00\x00\x00\x00', @@ -456,6 +457,7 @@ FW_VERSIONS = { b'8821FF402400 ', b'8821FF404000 ', b'8821FF404100 ', + b'8821FF405000 ', b'8821FF406000 ', b'8821FF407100 ', ], @@ -471,10 +473,12 @@ FW_VERSIONS = { b'8821FF402400 ', b'8821FF404000 ', b'8821FF404100 ', + b'8821FF405000 ', b'8821FF406000 ', b'8821FF407100 ', ], (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646FF401700 ', b'8646FF402100 ', b'8646FF404000 ', b'8646FF406000 ', From 9417051062b80a6df8b21043186cacf348d90d31 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Tue, 23 Nov 2021 16:25:51 +0100 Subject: [PATCH 007/102] don't build internal kalman objects on device (#23011) --- SConstruct | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/SConstruct b/SConstruct index 67acd3eac4..30bb425461 100644 --- a/SConstruct +++ b/SConstruct @@ -387,7 +387,7 @@ rednose_config = { }, } -if arch != "aarch64": +if arch not in ["aarch64", "larch64"]: rednose_config['to_build'].update({ 'gnss': ('#selfdrive/locationd/models/gnss_kf.py', True, []), 'loc_4': ('#selfdrive/locationd/models/loc_kf.py', True, []), From 6964adec39b8264d4332fe1daee99a336a4a275b Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Wed, 24 Nov 2021 07:24:28 +0800 Subject: [PATCH 008/102] networking: remove unused #inculde (#23016) --- selfdrive/ui/qt/offroad/networking.h | 1 - 1 file changed, 1 deletion(-) diff --git a/selfdrive/ui/qt/offroad/networking.h b/selfdrive/ui/qt/offroad/networking.h index b5a0c2ba2e..037ef82f67 100644 --- a/selfdrive/ui/qt/offroad/networking.h +++ b/selfdrive/ui/qt/offroad/networking.h @@ -1,7 +1,6 @@ #pragma once #include -#include #include #include From 6462ced209fe545c2354c0d04bee98767a03eea7 Mon Sep 17 00:00:00 2001 From: George Hotz <72895+geohot@users.noreply.github.com> Date: Tue, 23 Nov 2021 16:08:20 -0800 Subject: [PATCH 009/102] thermald: track power usage / pmic temps (#23013) Co-authored-by: Comma Device Co-authored-by: Adeeb Shihadeh --- cereal | 2 +- selfdrive/hardware/base.py | 2 +- selfdrive/hardware/eon/hardware.py | 2 +- selfdrive/hardware/pc/hardware.py | 2 +- selfdrive/hardware/tici/hardware.py | 2 +- selfdrive/thermald/thermald.py | 3 +++ 6 files changed, 8 insertions(+), 5 deletions(-) diff --git a/cereal b/cereal index 032aca6ca3..238e0c5793 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 032aca6ca38a342e26fb9cc986b7f72b91cd9b55 +Subproject commit 238e0c5793daed7dce6e1e072c4ae510f06ea515 diff --git a/selfdrive/hardware/base.py b/selfdrive/hardware/base.py index a1b67cb38b..06c86f0c26 100644 --- a/selfdrive/hardware/base.py +++ b/selfdrive/hardware/base.py @@ -1,7 +1,7 @@ from abc import abstractmethod from collections import namedtuple -ThermalConfig = namedtuple('ThermalConfig', ['cpu', 'gpu', 'mem', 'bat', 'ambient']) +ThermalConfig = namedtuple('ThermalConfig', ['cpu', 'gpu', 'mem', 'bat', 'ambient', 'pmic']) class HardwareBase: @staticmethod diff --git a/selfdrive/hardware/eon/hardware.py b/selfdrive/hardware/eon/hardware.py index 2296c26e6d..4ba85d2f8c 100644 --- a/selfdrive/hardware/eon/hardware.py +++ b/selfdrive/hardware/eon/hardware.py @@ -369,7 +369,7 @@ class Android(HardwareBase): os.system('LD_LIBRARY_PATH="" svc power shutdown') def get_thermal_config(self): - return ThermalConfig(cpu=((5, 7, 10, 12), 10), gpu=((16,), 10), mem=(2, 10), bat=(29, 1000), ambient=(25, 1)) + return ThermalConfig(cpu=((5, 7, 10, 12), 10), gpu=((16,), 10), mem=(2, 10), bat=(29, 1000), ambient=(25, 1), pmic=((22,), 1)) def set_screen_brightness(self, percentage): with open("/sys/class/leds/lcd-backlight/brightness", "w") as f: diff --git a/selfdrive/hardware/pc/hardware.py b/selfdrive/hardware/pc/hardware.py index b2be6ca91c..8231bbc2f9 100644 --- a/selfdrive/hardware/pc/hardware.py +++ b/selfdrive/hardware/pc/hardware.py @@ -78,7 +78,7 @@ class Pc(HardwareBase): print("SHUTDOWN!") def get_thermal_config(self): - return ThermalConfig(cpu=((None,), 1), gpu=((None,), 1), mem=(None, 1), bat=(None, 1), ambient=(None, 1)) + return ThermalConfig(cpu=((None,), 1), gpu=((None,), 1), mem=(None, 1), bat=(None, 1), ambient=(None, 1), pmic=((None,), 1)) def set_screen_brightness(self, percentage): pass diff --git a/selfdrive/hardware/tici/hardware.py b/selfdrive/hardware/tici/hardware.py index ca2705c801..5b7596df26 100644 --- a/selfdrive/hardware/tici/hardware.py +++ b/selfdrive/hardware/tici/hardware.py @@ -275,7 +275,7 @@ class Tici(HardwareBase): os.system("sudo poweroff") def get_thermal_config(self): - return ThermalConfig(cpu=((1, 2, 3, 4, 5, 6, 7, 8), 1000), gpu=((48,49), 1000), mem=(15, 1000), bat=(None, 1), ambient=(65, 1000)) + return ThermalConfig(cpu=((1, 2, 3, 4, 5, 6, 7, 8), 1000), gpu=((48,49), 1000), mem=(15, 1000), bat=(None, 1), ambient=(65, 1000), pmic=((35, 36), 1000)) def set_screen_brightness(self, percentage): try: diff --git a/selfdrive/thermald/thermald.py b/selfdrive/thermald/thermald.py index f68a0accb8..114110891e 100755 --- a/selfdrive/thermald/thermald.py +++ b/selfdrive/thermald/thermald.py @@ -66,6 +66,7 @@ def read_thermal(thermal_config): dat.deviceState.gpuTempC = [read_tz(z) / thermal_config.gpu[1] for z in thermal_config.gpu[0]] dat.deviceState.memoryTempC = read_tz(thermal_config.mem[0]) / thermal_config.mem[1] dat.deviceState.ambientTempC = read_tz(thermal_config.ambient[0]) / thermal_config.ambient[1] + dat.deviceState.pmicTempC = [read_tz(z) / thermal_config.pmic[1] for z in thermal_config.pmic[0]] return dat @@ -406,6 +407,8 @@ def thermald_thread(): power_monitor.calculate(peripheralState, startup_conditions["ignition"]) msg.deviceState.offroadPowerUsageUwh = power_monitor.get_power_used() msg.deviceState.carBatteryCapacityUwh = max(0, power_monitor.get_car_battery_capacity()) + current_power_draw = HARDWARE.get_current_power_draw() # pylint: disable=assignment-from-none + msg.deviceState.powerDrawW = current_power_draw if current_power_draw is not None else 0 # Check if we need to disable charging (handled by boardd) msg.deviceState.chargingDisabled = power_monitor.should_disable_charging(startup_conditions["ignition"], in_car, off_ts) From 75dd0d6296753dea9f6817955ef975f8d543fd19 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Wed, 24 Nov 2021 09:53:49 +0800 Subject: [PATCH 010/102] loggerd: split loggerd.cc into three files --- release/files_common | 2 + selfdrive/loggerd/SConscript | 4 +- selfdrive/loggerd/loggerd.cc | 140 +---------------------------------- selfdrive/loggerd/loggerd.h | 118 +++++++++++++++++++++++++++++ selfdrive/loggerd/main.cc | 20 +++++ 5 files changed, 144 insertions(+), 140 deletions(-) create mode 100644 selfdrive/loggerd/loggerd.h create mode 100644 selfdrive/loggerd/main.cc diff --git a/release/files_common b/release/files_common index aeae351dfb..2ef34106c3 100644 --- a/release/files_common +++ b/release/files_common @@ -306,6 +306,8 @@ selfdrive/loggerd/omx_encoder.h selfdrive/loggerd/logger.cc selfdrive/loggerd/logger.h selfdrive/loggerd/loggerd.cc +selfdrive/loggerd/loggerd.h +selfdrive/loggerd/main.cc selfdrive/loggerd/bootlog.cc selfdrive/loggerd/raw_logger.cc selfdrive/loggerd/raw_logger.h diff --git a/selfdrive/loggerd/SConscript b/selfdrive/loggerd/SConscript index 7e41c9d3ee..0d3fe55048 100644 --- a/selfdrive/loggerd/SConscript +++ b/selfdrive/loggerd/SConscript @@ -7,7 +7,7 @@ libs = [logger_lib, common, cereal, messaging, visionipc, 'avformat', 'avcodec', 'swscale', 'avutil', 'yuv', 'bz2', 'OpenCL'] -src = ['loggerd.cc'] +src = ['main.cc', 'loggerd.cc'] if arch in ["aarch64", "larch64"]: src += ['omx_encoder.cc'] libs += ['OmxCore', 'gsl', 'CB'] + gpucommon @@ -24,7 +24,7 @@ if arch == "Darwin": del libs[libs.index('OpenCL')] env['FRAMEWORKS'] = ['OpenCL'] -env.Program(src, LIBS=libs) +env.Program('loggerd', src, LIBS=libs) env.Program('bootlog.cc', LIBS=libs) if GetOption('test'): diff --git a/selfdrive/loggerd/loggerd.cc b/selfdrive/loggerd/loggerd.cc index f6d89b8091..0721e836be 100644 --- a/selfdrive/loggerd/loggerd.cc +++ b/selfdrive/loggerd/loggerd.cc @@ -1,128 +1,7 @@ -#include -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include "cereal/messaging/messaging.h" -#include "cereal/services.h" -#include "cereal/visionipc/visionipc.h" -#include "cereal/visionipc/visionipc_client.h" -#include "selfdrive/camerad/cameras/camera_common.h" -#include "selfdrive/common/params.h" -#include "selfdrive/common/swaglog.h" -#include "selfdrive/common/timing.h" -#include "selfdrive/common/util.h" -#include "selfdrive/hardware/hw.h" - -#include "selfdrive/loggerd/encoder.h" -#include "selfdrive/loggerd/logger.h" -#if defined(QCOM) || defined(QCOM2) -#include "selfdrive/loggerd/omx_encoder.h" -#define Encoder OmxEncoder -#else -#include "selfdrive/loggerd/raw_logger.h" -#define Encoder RawLogger -#endif - -namespace { - -constexpr int MAIN_FPS = 20; -const int MAIN_BITRATE = Hardware::TICI() ? 10000000 : 5000000; -const int DCAM_BITRATE = Hardware::TICI() ? MAIN_BITRATE : 2500000; - -#define NO_CAMERA_PATIENCE 500 // fall back to time-based rotation if all cameras are dead - -const bool LOGGERD_TEST = getenv("LOGGERD_TEST"); -const int SEGMENT_LENGTH = LOGGERD_TEST ? atoi(getenv("LOGGERD_SEGMENT_LENGTH")) : 60; +#include "selfdrive/loggerd/loggerd.h" ExitHandler do_exit; -const LogCameraInfo cameras_logged[] = { - { - .type = RoadCam, - .stream_type = VISION_STREAM_YUV_BACK, - .filename = "fcamera.hevc", - .frame_packet_name = "roadCameraState", - .fps = MAIN_FPS, - .bitrate = MAIN_BITRATE, - .is_h265 = true, - .downscale = false, - .has_qcamera = true, - .trigger_rotate = true, - .enable = true, - .record = true, - }, - { - .type = DriverCam, - .stream_type = VISION_STREAM_YUV_FRONT, - .filename = "dcamera.hevc", - .frame_packet_name = "driverCameraState", - .fps = MAIN_FPS, // on EONs, more compressed this way - .bitrate = DCAM_BITRATE, - .is_h265 = true, - .downscale = false, - .has_qcamera = false, - .trigger_rotate = Hardware::TICI(), - .enable = !Hardware::PC(), - .record = Params().getBool("RecordFront"), - }, - { - .type = WideRoadCam, - .stream_type = VISION_STREAM_YUV_WIDE, - .filename = "ecamera.hevc", - .frame_packet_name = "wideRoadCameraState", - .fps = MAIN_FPS, - .bitrate = MAIN_BITRATE, - .is_h265 = true, - .downscale = false, - .has_qcamera = false, - .trigger_rotate = true, - .enable = Hardware::TICI(), - .record = Hardware::TICI(), - }, -}; -const LogCameraInfo qcam_info = { - .filename = "qcamera.ts", - .fps = MAIN_FPS, - .bitrate = 256000, - .is_h265 = false, - .downscale = true, - .frame_width = Hardware::TICI() ? 526 : 480, - .frame_height = Hardware::TICI() ? 330 : 360 // keep pixel count the same? -}; - -struct LoggerdState { - Context *ctx; - LoggerState logger = {}; - char segment_path[4096]; - std::mutex rotate_lock; - std::condition_variable rotate_cv; - std::atomic rotate_segment; - std::atomic last_camera_seen_tms; - std::atomic ready_to_rotate; // count of encoders ready to rotate - int max_waiting = 0; - double last_rotate_tms = 0.; // last rotate time in ms - - // Sync logic for startup - std::atomic encoders_ready = 0; - std::atomic start_frame_id = 0; - bool camera_ready[WideRoadCam + 1] = {}; - bool camera_synced[WideRoadCam + 1] = {}; -}; LoggerdState s; // Handle initial encoder syncing by waiting for all encoders to reach the same frame id @@ -306,20 +185,7 @@ void rotate_if_needed() { } } -} // namespace - -int main(int argc, char** argv) { - if (Hardware::EON()) { - setpriority(PRIO_PROCESS, 0, -20); - } else if (Hardware::TICI()) { - int ret; - ret = set_core_affinity({0, 1, 2, 3}); - assert(ret == 0); - // TODO: why does this impact camerad timings? - //ret = set_realtime_priority(1); - //assert(ret == 0); - } - +void loggerd_thread() { clear_locks(); // setup messaging @@ -397,6 +263,4 @@ int main(int argc, char** argv) { for (auto &[sock, qs] : qlog_states) delete sock; delete poller; delete s.ctx; - - return 0; } diff --git a/selfdrive/loggerd/loggerd.h b/selfdrive/loggerd/loggerd.h new file mode 100644 index 0000000000..59f4cb6709 --- /dev/null +++ b/selfdrive/loggerd/loggerd.h @@ -0,0 +1,118 @@ +#pragma once + +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include "cereal/messaging/messaging.h" +#include "cereal/services.h" +#include "cereal/visionipc/visionipc.h" +#include "cereal/visionipc/visionipc_client.h" +#include "selfdrive/camerad/cameras/camera_common.h" +#include "selfdrive/common/params.h" +#include "selfdrive/common/swaglog.h" +#include "selfdrive/common/timing.h" +#include "selfdrive/common/util.h" +#include "selfdrive/hardware/hw.h" + +#include "selfdrive/loggerd/encoder.h" +#include "selfdrive/loggerd/logger.h" +#if defined(QCOM) || defined(QCOM2) +#include "selfdrive/loggerd/omx_encoder.h" +#define Encoder OmxEncoder +#else +#include "selfdrive/loggerd/raw_logger.h" +#define Encoder RawLogger +#endif + +constexpr int MAIN_FPS = 20; +const int MAIN_BITRATE = Hardware::TICI() ? 10000000 : 5000000; +const int DCAM_BITRATE = Hardware::TICI() ? MAIN_BITRATE : 2500000; + +#define NO_CAMERA_PATIENCE 500 // fall back to time-based rotation if all cameras are dead + +const bool LOGGERD_TEST = getenv("LOGGERD_TEST"); +const int SEGMENT_LENGTH = LOGGERD_TEST ? atoi(getenv("LOGGERD_SEGMENT_LENGTH")) : 60; + +const LogCameraInfo cameras_logged[] = { + { + .type = RoadCam, + .stream_type = VISION_STREAM_YUV_BACK, + .filename = "fcamera.hevc", + .frame_packet_name = "roadCameraState", + .fps = MAIN_FPS, + .bitrate = MAIN_BITRATE, + .is_h265 = true, + .downscale = false, + .has_qcamera = true, + .trigger_rotate = true, + .enable = true, + .record = true, + }, + { + .type = DriverCam, + .stream_type = VISION_STREAM_YUV_FRONT, + .filename = "dcamera.hevc", + .frame_packet_name = "driverCameraState", + .fps = MAIN_FPS, // on EONs, more compressed this way + .bitrate = DCAM_BITRATE, + .is_h265 = true, + .downscale = false, + .has_qcamera = false, + .trigger_rotate = Hardware::TICI(), + .enable = !Hardware::PC(), + .record = Params().getBool("RecordFront"), + }, + { + .type = WideRoadCam, + .stream_type = VISION_STREAM_YUV_WIDE, + .filename = "ecamera.hevc", + .frame_packet_name = "wideRoadCameraState", + .fps = MAIN_FPS, + .bitrate = MAIN_BITRATE, + .is_h265 = true, + .downscale = false, + .has_qcamera = false, + .trigger_rotate = true, + .enable = Hardware::TICI(), + .record = Hardware::TICI(), + }, +}; +const LogCameraInfo qcam_info = { + .filename = "qcamera.ts", + .fps = MAIN_FPS, + .bitrate = 256000, + .is_h265 = false, + .downscale = true, + .frame_width = Hardware::TICI() ? 526 : 480, + .frame_height = Hardware::TICI() ? 330 : 360 // keep pixel count the same? +}; + +struct LoggerdState { + Context *ctx; + LoggerState logger = {}; + char segment_path[4096]; + std::mutex rotate_lock; + std::condition_variable rotate_cv; + std::atomic rotate_segment; + std::atomic last_camera_seen_tms; + std::atomic ready_to_rotate; // count of encoders ready to rotate + int max_waiting = 0; + double last_rotate_tms = 0.; // last rotate time in ms + + // Sync logic for startup + std::atomic encoders_ready = 0; + std::atomic start_frame_id = 0; + bool camera_ready[WideRoadCam + 1] = {}; + bool camera_synced[WideRoadCam + 1] = {}; +}; + +void loggerd_thread(); diff --git a/selfdrive/loggerd/main.cc b/selfdrive/loggerd/main.cc new file mode 100644 index 0000000000..04da0f67e8 --- /dev/null +++ b/selfdrive/loggerd/main.cc @@ -0,0 +1,20 @@ +#include "selfdrive/loggerd/loggerd.h" + +#include + +int main(int argc, char** argv) { + if (Hardware::EON()) { + setpriority(PRIO_PROCESS, 0, -20); + } else if (Hardware::TICI()) { + int ret; + ret = set_core_affinity({0, 1, 2, 3}); + assert(ret == 0); + // TODO: why does this impact camerad timings? + //ret = set_realtime_priority(1); + //assert(ret == 0); + } + + loggerd_thread(); + + return 0; +} From c77354009c61da8a322dc9aaaa4c1ecaec432449 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Wed, 24 Nov 2021 12:15:22 +0800 Subject: [PATCH 011/102] panda: add unit tests for usb protocol (pack/unpack) (#22955) * prepare for unit tests * add to selfdrive_tests.yaml * test header * test chunk count * rename test function * continue * don't check chunks count * test recv_can * continue * small cleanup * merge master * cleanup * rename functions * test different packet size * fix operator precedence problem * refactor unpack_can_buffer * cleanup test * cleanup unpack_can_buffer * add test for multiple pandas * rename to test_panda * restore test_boardd * rename to test_boardd_usbprotocol * fix typo * bus_offset = [0,4] * change src * use USBPACKET_MAX_SIZE --- .github/workflows/selfdrive_tests.yaml | 1 + selfdrive/boardd/.gitignore | 1 + selfdrive/boardd/SConscript | 5 +- selfdrive/boardd/panda.cc | 19 ++- selfdrive/boardd/panda.h | 8 ++ .../boardd/tests/test_boardd_usbprotocol.cc | 115 ++++++++++++++++++ 6 files changed, 144 insertions(+), 5 deletions(-) create mode 100644 selfdrive/boardd/tests/test_boardd_usbprotocol.cc diff --git a/.github/workflows/selfdrive_tests.yaml b/.github/workflows/selfdrive_tests.yaml index aa217735bf..3b0cc29963 100644 --- a/.github/workflows/selfdrive_tests.yaml +++ b/.github/workflows/selfdrive_tests.yaml @@ -247,6 +247,7 @@ jobs: $UNIT_TEST selfdrive/athena && \ $UNIT_TEST selfdrive/thermald && \ $UNIT_TEST tools/lib/tests && \ + ./selfdrive/boardd/tests/test_boardd_usbprotocol && \ ./selfdrive/common/tests/test_util && \ ./selfdrive/loggerd/tests/test_logger &&\ ./selfdrive/proclogd/tests/test_proclog && \ diff --git a/selfdrive/boardd/.gitignore b/selfdrive/boardd/.gitignore index 1f653bde8f..e8daa2ef27 100644 --- a/selfdrive/boardd/.gitignore +++ b/selfdrive/boardd/.gitignore @@ -1,2 +1,3 @@ boardd boardd_api_impl.cpp +tests/test_boardd_usbprotocol diff --git a/selfdrive/boardd/SConscript b/selfdrive/boardd/SConscript index f2a1f3f7bd..07ded56e1b 100644 --- a/selfdrive/boardd/SConscript +++ b/selfdrive/boardd/SConscript @@ -1,6 +1,9 @@ Import('env', 'envCython', 'common', 'cereal', 'messaging') -env.Program('boardd', ['boardd.cc', 'panda.cc', 'pigeon.cc'], LIBS=['usb-1.0', common, cereal, messaging, 'pthread', 'zmq', 'capnp', 'kj']) +libs = ['usb-1.0', common, cereal, messaging, 'pthread', 'zmq', 'capnp', 'kj'] +env.Program('boardd', ['boardd.cc', 'panda.cc', 'pigeon.cc'], LIBS=libs) env.Library('libcan_list_to_can_capnp', ['can_list_to_can_capnp.cc']) envCython.Program('boardd_api_impl.so', 'boardd_api_impl.pyx', LIBS=["can_list_to_can_capnp", 'capnp', 'kj'] + envCython["LIBS"]) +if GetOption('test'): + env.Program('tests/test_boardd_usbprotocol', ['tests/test_boardd_usbprotocol.cc', 'panda.cc'], LIBS=libs) diff --git a/selfdrive/boardd/panda.cc b/selfdrive/boardd/panda.cc index 78b123f698..6dc458a8c3 100644 --- a/selfdrive/boardd/panda.cc +++ b/selfdrive/boardd/panda.cc @@ -363,7 +363,8 @@ uint8_t Panda::len_to_dlc(uint8_t len) { } } -void Panda::can_send(capnp::List::Reader can_data_list) { +void Panda::pack_can_buffer(const capnp::List::Reader &can_data_list, + std::function write_func) { if (send.size() < (can_data_list.size() * CANPACKET_MAX_SIZE)) { send.resize(can_data_list.size() * CANPACKET_MAX_SIZE); } @@ -410,11 +411,17 @@ void Panda::can_send(capnp::List::Reader can_data_list) { ptr += copy_size + 1; counter++; } - usb_bulk_write(3, to_write, ptr, 5); + write_func(to_write, ptr); } } } +void Panda::can_send(capnp::List::Reader can_data_list) { + pack_can_buffer(can_data_list, [=](uint8_t* data, size_t size) { + usb_bulk_write(3, data, size, 5); + }); +} + bool Panda::can_receive(std::vector& out_vec) { uint8_t data[RECV_SIZE]; int recv = usb_bulk_read(0x81, (uint8_t*)data, RECV_SIZE); @@ -429,18 +436,22 @@ bool Panda::can_receive(std::vector& out_vec) { if (!comms_healthy) { return false; } + return unpack_can_buffer(data, recv, out_vec); +} + +bool Panda::unpack_can_buffer(uint8_t *data, int size, std::vector &out_vec) { static uint8_t tail[CANPACKET_MAX_SIZE]; uint8_t tail_size = 0; uint8_t counter = 0; - for (int i = 0; i < recv; i += USBPACKET_MAX_SIZE) { + for (int i = 0; i < size; i += USBPACKET_MAX_SIZE) { // Check for counter every 64 bytes (length of USB packet) if (counter != data[i]) { LOGE("CAN: MALFORMED USB RECV PACKET"); break; } counter++; - uint8_t chunk_len = ((recv - i) > USBPACKET_MAX_SIZE) ? 63 : (recv - i - 1); // as 1 is always reserved for counter + uint8_t chunk_len = ((size - i) > USBPACKET_MAX_SIZE) ? 63 : (size - i - 1); // as 1 is always reserved for counter uint8_t chunk[USBPACKET_MAX_SIZE + CANPACKET_MAX_SIZE]; memcpy(chunk, tail, tail_size); memcpy(&chunk[tail_size], &data[i+1], chunk_len); diff --git a/selfdrive/boardd/panda.h b/selfdrive/boardd/panda.h index 4be9454cf5..9be454a930 100644 --- a/selfdrive/boardd/panda.h +++ b/selfdrive/boardd/panda.h @@ -3,6 +3,7 @@ #include #include #include +#include #include #include #include @@ -113,4 +114,11 @@ class Panda { uint8_t len_to_dlc(uint8_t len); void can_send(capnp::List::Reader can_data_list); bool can_receive(std::vector& out_vec); + +protected: + // for unit tests + Panda(uint32_t bus_offset) : bus_offset(bus_offset) {} + void pack_can_buffer(const capnp::List::Reader &can_data_list, + std::function write_func); + bool unpack_can_buffer(uint8_t *data, int size, std::vector &out_vec); }; diff --git a/selfdrive/boardd/tests/test_boardd_usbprotocol.cc b/selfdrive/boardd/tests/test_boardd_usbprotocol.cc new file mode 100644 index 0000000000..58cea3c681 --- /dev/null +++ b/selfdrive/boardd/tests/test_boardd_usbprotocol.cc @@ -0,0 +1,115 @@ +#define CATCH_CONFIG_MAIN +#define CATCH_CONFIG_ENABLE_BENCHMARKING +#include + +#include "catch2/catch.hpp" +#include "cereal/messaging/messaging.h" +#include "selfdrive/boardd/panda.h" + +const unsigned char dlc_to_len[] = {0U, 1U, 2U, 3U, 4U, 5U, 6U, 7U, 8U, 12U, 16U, 20U, 24U, 32U, 48U, 64U}; + +int random_int(int min, int max) { + std::random_device dev; + std::mt19937 rng(dev()); + std::uniform_int_distribution dist(min, max); + return dist(rng); +} + +struct PandaTest : public Panda { + PandaTest(uint32_t bus_offset, int can_list_size); + void test_can_send(); + void test_can_recv(); + + std::map test_data; + int can_list_size = 0; + int total_pakets_size = 0; + MessageBuilder msg; + capnp::List::Reader can_data_list; +}; + +PandaTest::PandaTest(uint32_t bus_offset_, int can_list_size) : can_list_size(can_list_size), Panda(bus_offset_) { + // prepare test data + for (int i = 0; i < std::size(dlc_to_len); ++i) { + std::random_device rd; + std::independent_bits_engine rbe(rd()); + + int data_len = dlc_to_len[i]; + std::string bytes(data_len, '\0'); + std::generate(bytes.begin(), bytes.end(), std::ref(rbe)); + test_data[data_len] = bytes; + } + + // generate can messages for this panda + auto can_list = msg.initEvent().initSendcan(can_list_size); + for (uint8_t i = 0; i < can_list_size; ++i) { + auto can = can_list[i]; + uint32_t id = random_int(0, std::size(dlc_to_len) - 1); + const std::string &dat = test_data[dlc_to_len[id]]; + can.setAddress(i); + can.setSrc(random_int(0, 3) + bus_offset); + can.setDat(kj::ArrayPtr((uint8_t *)dat.data(), dat.size())); + total_pakets_size += CANPACKET_HEAD_SIZE + dat.size(); + } + + can_data_list = can_list.asReader(); + INFO("test " << can_list_size << " packets, total size " << total_pakets_size); +} + +void PandaTest::test_can_send() { + std::vector unpacked_data; + this->pack_can_buffer(can_data_list, [&](uint8_t *chunk, size_t size) { + int size_left = size; + for (int i = 0, counter = 0; i < size; i += USBPACKET_MAX_SIZE, counter++) { + REQUIRE(chunk[i] == counter); + + const int len = std::min(USBPACKET_MAX_SIZE, (uint32_t)size_left); + unpacked_data.insert(unpacked_data.end(), &chunk[i + 1], &chunk[i + len]); + size_left -= len; + } + }); + REQUIRE(unpacked_data.size() == total_pakets_size); + + int cnt = 0; + INFO("test can message integrity"); + for (int pos = 0, pckt_len = 0; pos < unpacked_data.size(); pos += pckt_len) { + can_header header; + memcpy(&header, &unpacked_data[pos], CANPACKET_HEAD_SIZE); + const uint8_t data_len = dlc_to_len[header.data_len_code]; + pckt_len = CANPACKET_HEAD_SIZE + data_len; + + REQUIRE(header.addr == cnt); + REQUIRE(test_data.find(data_len) != test_data.end()); + const std::string &dat = test_data[data_len]; + REQUIRE(memcmp(dat.data(), &unpacked_data[pos + 5], dat.size()) == 0); + ++cnt; + } + REQUIRE(cnt == can_list_size); +} + +void PandaTest::test_can_recv() { + std::vector frames; + this->pack_can_buffer(can_data_list, [&](uint8_t *data, size_t size) { + this->unpack_can_buffer(data, size, frames); + }); + + REQUIRE(frames.size() == can_list_size); + for (int i = 0; i < frames.size(); ++i) { + REQUIRE(frames[i].address == i); + REQUIRE(test_data.find(frames[i].dat.size()) != test_data.end()); + const std::string &dat = test_data[frames[i].dat.size()]; + REQUIRE(memcmp(dat.data(), frames[i].dat.data(), dat.size()) == 0); + } +} + +TEST_CASE("send/recv can packets") { + auto bus_offset = GENERATE(0, 4); + auto can_list_size = GENERATE(1, 3, 5, 10, 30, 60, 100, 200); + PandaTest test(bus_offset, can_list_size); + + SECTION("can_send") { + test.test_can_send(); + } + SECTION("can_receive") { + test.test_can_recv(); + } +} From 239c7c1d4e7c5b854490bc44f6f4dc252b331cf3 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 23 Nov 2021 23:19:11 -0800 Subject: [PATCH 012/102] Bring back Accord 2021 + 2021 Hybrid (#23021) Co-authored-by: Chris Souers --- RELEASES.md | 2 + docs/CARS.md | 4 +- selfdrive/car/honda/carstate.py | 6 +-- selfdrive/car/honda/interface.py | 2 +- selfdrive/car/honda/values.py | 83 ++++++++++++++++++++++++++++++-- selfdrive/test/test_models.py | 6 +++ selfdrive/test/test_routes.py | 2 + 7 files changed, 95 insertions(+), 10 deletions(-) diff --git a/RELEASES.md b/RELEASES.md index d4d579cfc4..481ecceb5e 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,5 +1,7 @@ Version 0.8.12 (2021-12-XX) ======================== + * Honda Accord 2021 support thanks to csouers! + * Honda Accord Hybrid 2021 support thanks to csouers! * Lexus RC 2020 support thanks to ErichMoraga! Version 0.8.11 (2021-11-29) diff --git a/docs/CARS.md b/docs/CARS.md index 1f1d08cc04..d88ee6c65f 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -7,8 +7,8 @@ | Acura | ILX 2016-19 | AcuraWatch Plus | openpilot | 25mph1 | 25mph | | Acura | RDX 2016-18 | AcuraWatch Plus | openpilot | 25mph1 | 12mph | | Acura | RDX 2019-21 | All | Stock | 0mph | 3mph | -| Honda | Accord 2018-20 | All | Stock | 0mph | 3mph | -| Honda | Accord Hybrid 2018-20 | All | Stock | 0mph | 3mph | +| Honda | Accord 2018-21 | All | Stock | 0mph | 3mph | +| Honda | Accord Hybrid 2018-21 | All | Stock | 0mph | 3mph | | Honda | Civic Hatchback 2017-21 | Honda Sensing | Stock | 0mph | 12mph | | Honda | Civic Coupe 2016-18 | Honda Sensing | openpilot | 0mph | 12mph | | Honda | Civic Coupe 2019-20 | All | Stock | 0mph | 2mph2 | diff --git a/selfdrive/car/honda/carstate.py b/selfdrive/car/honda/carstate.py index 8bf3ac58f6..b9deaedf12 100644 --- a/selfdrive/car/honda/carstate.py +++ b/selfdrive/car/honda/carstate.py @@ -107,7 +107,7 @@ def get_can_signals(CP, gearbox_msg, main_on_sig_msg): else: checks += [("CRUISE_PARAMS", 50)] - if CP.carFingerprint in (CAR.ACCORD, CAR.ACCORDH, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_HYBRID, CAR.INSIGHT, CAR.ACURA_RDX_3G, CAR.HONDA_E): + if CP.carFingerprint in (CAR.ACCORD, CAR.ACCORD_2021, CAR.ACCORDH, CAR.ACCORDH_2021, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_HYBRID, CAR.INSIGHT, CAR.ACURA_RDX_3G, CAR.HONDA_E): signals += [("DRIVERS_DOOR_OPEN", "SCM_FEEDBACK", 1)] elif CP.carFingerprint == CAR.ODYSSEY_CHN: signals += [("DRIVERS_DOOR_OPEN", "SCM_BUTTONS", 1)] @@ -185,7 +185,7 @@ class CarState(CarStateBase): # ******************* parse out can ******************* # TODO: find wheels moving bit in dbc - if self.CP.carFingerprint in (CAR.ACCORD, CAR.ACCORDH, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_HYBRID, CAR.INSIGHT, CAR.ACURA_RDX_3G, CAR.HONDA_E): + if self.CP.carFingerprint in (CAR.ACCORD, CAR.ACCORD_2021, CAR.ACCORDH, CAR.ACCORDH_2021, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_HYBRID, CAR.INSIGHT, CAR.ACURA_RDX_3G, CAR.HONDA_E): 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: @@ -235,7 +235,7 @@ class CarState(CarStateBase): 250, cp.vl["SCM_FEEDBACK"]["LEFT_BLINKER"], cp.vl["SCM_FEEDBACK"]["RIGHT_BLINKER"]) ret.brakeHoldActive = cp.vl["VSA_STATUS"]["BRAKE_HOLD_ACTIVE"] == 1 - if self.CP.carFingerprint in (CAR.CIVIC, CAR.ODYSSEY, CAR.ODYSSEY_CHN, CAR.CRV_5G, CAR.ACCORD, CAR.ACCORDH, CAR.CIVIC_BOSCH, + if self.CP.carFingerprint in (CAR.CIVIC, CAR.ODYSSEY, CAR.ODYSSEY_CHN, CAR.CRV_5G, CAR.ACCORD, CAR.ACCORD_2021, CAR.ACCORDH, CAR.ACCORDH_2021, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_HYBRID, CAR.INSIGHT, CAR.ACURA_RDX_3G, CAR.HONDA_E): self.park_brake = cp.vl["EPB_STATUS"]["EPB_STATE"] != 0 else: diff --git a/selfdrive/car/honda/interface.py b/selfdrive/car/honda/interface.py index 802ce980ab..5ae167a160 100755 --- a/selfdrive/car/honda/interface.py +++ b/selfdrive/car/honda/interface.py @@ -110,7 +110,7 @@ class CarInterface(CarInterfaceBase): tire_stiffness_factor = 1. ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] - elif candidate in (CAR.ACCORD, CAR.ACCORDH): + elif candidate in (CAR.ACCORD, CAR.ACCORD_2021, CAR.ACCORDH, CAR.ACCORDH_2021): stop_and_go = True ret.mass = 3279. * CV.LB_TO_KG + STD_CARGO_KG ret.wheelbase = 2.83 diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py index 97e0ded663..e1698562df 100644 --- a/selfdrive/car/honda/values.py +++ b/selfdrive/car/honda/values.py @@ -59,6 +59,8 @@ VISUAL_HUD = { class CAR: ACCORD = "HONDA ACCORD 2018" ACCORDH = "HONDA ACCORD HYBRID 2018" + ACCORD_2021 = "HONDA ACCORD 2021" + ACCORDH_2021 = "HONDA ACCORD HYBRID 2021" CIVIC = "HONDA CIVIC 2016" CIVIC_BOSCH = "HONDA CIVIC (BOSCH) 2019" CIVIC_BOSCH_DIESEL = "HONDA CIVIC SEDAN 1.6 DIESEL 2019" @@ -268,12 +270,10 @@ FW_VERSIONS = { ], (Ecu.fwdCamera, 0x18dab5f1, None): [ b'36161-TWA-A070\x00\x00', - b'36161-TWA-A330\x00\x00', ], (Ecu.fwdRadar, 0x18dab0f1, None): [ b'36802-TWA-A080\x00\x00', b'36802-TWA-A070\x00\x00', - b'36802-TWA-A330\x00\x00', ], (Ecu.eps, 0x18da30f1, None): [ b'39990-TVA-A160\x00\x00', @@ -281,6 +281,78 @@ FW_VERSIONS = { b'39990-TVA-A340\x00\x00', ], }, + CAR.ACCORD_2021: { + (Ecu.programmedFuelInjection, 0x18da10f1, None): [ + b'37805-6B2-C520\x00\x00', + ], + (Ecu.transmission, 0x18da1ef1, None): [ + b'28102-6B8-A700\x00\x00', + ], + (Ecu.electricBrakeBooster, 0x18da2bf1, None): [ + b'46114-TVA-A320\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-TVA-A020\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TVA-E520\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-TVA-L420\x00\x00', + ], + (Ecu.combinationMeter, 0x18da60f1, None): [ + b'78109-TVC-A230\x00\x00', + ], + (Ecu.hud, 0x18da61f1, None): [ + b'78209-TVA-A110\x00\x00', + ], + (Ecu.shiftByWire, 0x18da0bf1, None): [ + b'54008-TVC-A910\x00\x00', + ], + (Ecu.fwdCamera, 0x18dab5f1, None): [ + b'36161-TVC-A330\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36802-TVC-A330\x00\x00', + ], + (Ecu.eps, 0x18da30f1, None): [ + b'39990-TVA-A340\x00\x00', + ], + (Ecu.unknown, 0x18da3af1, None): [ + b'39390-TVA-A120\x00\x00', + ], + }, + CAR.ACCORDH_2021: { + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-TWD-J020\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TWA-A530\x00\x00', + b'57114-TWA-B520\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-TWA-L420\x00\x00', + ], + (Ecu.combinationMeter, 0x18da60f1, None): [ + b'78109-TWA-A030\x00\x00', + b'78109-TWA-A230\x00\x00', + ], + (Ecu.shiftByWire, 0x18da0bf1, None): [ + b'54008-TWA-A910\x00\x00', + ], + (Ecu.fwdCamera, 0x18dab5f1, None): [ + b'36161-TWA-A330\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36802-TWA-A330\x00\x00', + ], + (Ecu.eps, 0x18da30f1, None): [ + b'39990-TVA-A340\x00\x00', + ], + (Ecu.unknown, 0x18da3af1, None): [ + b'39390-TVA-A120\x00\x00', + ], + }, CAR.CIVIC: { (Ecu.programmedFuelInjection, 0x18da10f1, None): [ b'37805-5AA-A640\x00\x00', @@ -1324,7 +1396,9 @@ FW_VERSIONS = { DBC = { CAR.ACCORD: dbc_dict('honda_accord_2018_can_generated', None), + CAR.ACCORD_2021: dbc_dict('honda_accord_2018_can_generated', None), CAR.ACCORDH: dbc_dict('honda_accord_2018_can_generated', None), + CAR.ACCORDH_2021: dbc_dict('honda_accord_2018_can_generated', None), CAR.ACURA_ILX: dbc_dict('acura_ilx_2016_can_generated', 'acura_ilx_2016_nidec'), CAR.ACURA_RDX: dbc_dict('acura_rdx_2018_can_generated', 'acura_ilx_2016_nidec'), CAR.ACURA_RDX_3G: dbc_dict('acura_rdx_2020_can_generated', None), @@ -1367,5 +1441,6 @@ SPEED_FACTOR = { HONDA_NIDEC_ALT_PCM_ACCEL = set([CAR.ODYSSEY]) HONDA_NIDEC_ALT_SCM_MESSAGES = set([CAR.ACURA_ILX, CAR.ACURA_RDX, CAR.CRV, CAR.CRV_EU, CAR.FIT, CAR.FREED, CAR.HRV, CAR.ODYSSEY_CHN, CAR.PILOT, CAR.PILOT_2019, CAR.PASSPORT, CAR.RIDGELINE]) -HONDA_BOSCH = set([CAR.ACCORD, CAR.ACCORDH, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_5G, CAR.CRV_HYBRID, CAR.INSIGHT, CAR.ACURA_RDX_3G, CAR.HONDA_E]) -HONDA_BOSCH_ALT_BRAKE_SIGNAL = set([CAR.ACCORD, CAR.CRV_5G, CAR.ACURA_RDX_3G]) +HONDA_BOSCH = set([CAR.ACCORD, CAR.ACCORD_2021, CAR.ACCORDH, CAR.ACCORDH_2021, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_5G, + CAR.CRV_HYBRID, CAR.INSIGHT, CAR.ACURA_RDX_3G, CAR.HONDA_E]) +HONDA_BOSCH_ALT_BRAKE_SIGNAL = set([CAR.ACCORD, CAR.ACCORD_2021, CAR.CRV_5G, CAR.ACURA_RDX_3G]) diff --git a/selfdrive/test/test_models.py b/selfdrive/test/test_models.py index a55ad35a12..8c7245234a 100755 --- a/selfdrive/test/test_models.py +++ b/selfdrive/test/test_models.py @@ -197,6 +197,12 @@ class TestCarModel(unittest.TestCase): if failed_checks['brakePressed'] < 150: del failed_checks['brakePressed'] + # TODO: use the same signal in panda and carState + # tolerate a small delay between the button press and PCM entering a cruise state + if self.car_model == HONDA.ACCORD_2021: + if failed_checks['controlsAllowed'] < 500: + del failed_checks['controlsAllowed'] + self.assertFalse(len(failed_checks), f"panda safety doesn't agree with CarState: {failed_checks}") if __name__ == "__main__": diff --git a/selfdrive/test/test_routes.py b/selfdrive/test/test_routes.py index 61f0adff74..696fe0de04 100755 --- a/selfdrive/test/test_routes.py +++ b/selfdrive/test/test_routes.py @@ -53,7 +53,9 @@ routes = [ TestRoute("81722949a62ea724|2019-04-06--15-19-25", HONDA.ODYSSEY_CHN), TestRoute("08a3deb07573f157|2020-03-06--16-11-19", HONDA.ACCORD), # 1.5T TestRoute("1da5847ac2488106|2021-05-24--19-31-50", HONDA.ACCORD), # 2.0T + TestRoute("085ac1d942c35910|2021-03-25--20-11-15", HONDA.ACCORD_2021), # 2.0T TestRoute("07585b0da3c88459|2021-05-26--18-52-04", HONDA.ACCORDH), + TestRoute("f29e2b57a55e7ad5|2021-03-24--20-52-38", HONDA.ACCORDH_2021), TestRoute("1ad763dd22ef1a0e|2020-02-29--18-37-03", HONDA.CRV_5G), TestRoute("0a96f86fcfe35964|2020-02-05--07-25-51", HONDA.ODYSSEY), TestRoute("d83f36766f8012a5|2020-02-05--18-42-21", HONDA.CIVIC_BOSCH_DIESEL), From b8393f7271c3b1845e7ad49e35db8688c01770cc Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 23 Nov 2021 23:33:26 -0800 Subject: [PATCH 013/102] can_replay: warning & clone cmd if jungle lib is missing --- tools/replay/can_replay.py | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/tools/replay/can_replay.py b/tools/replay/can_replay.py index dd16493abf..6d68e75fe7 100755 --- a/tools/replay/can_replay.py +++ b/tools/replay/can_replay.py @@ -6,6 +6,7 @@ from tqdm import tqdm os.environ['FILEREADER_CACHE'] = '1' +from common.basedir import BASEDIR from common.realtime import config_realtime_process, Ratekeeper, DT_CTRL from selfdrive.boardd.boardd import can_capnp_to_can_list from tools.lib.logreader import LogReader @@ -81,6 +82,10 @@ def connect(): if __name__ == "__main__": + if PandaJungle is None: + print("\33[31m", "WARNING: cannot connect to jungles. Clone the jungle library to enable support:", "\033[0m") + print("\033[34m", f"cd {BASEDIR} && git clone https://github.com/commaai/panda_jungle", "\033[0m") + print("Loading log...") ROUTE = "77611a1fac303767/2020-03-24--09-50-38" REPLAY_SEGS = list(range(10, 16)) # route has 82 segments available From 1fd8fc45938ea245314b35d9dc8e53f2445d1b9d Mon Sep 17 00:00:00 2001 From: Robbe Derks Date: Wed, 24 Nov 2021 11:19:04 +0100 Subject: [PATCH 014/102] Typo in Quectel FCC ID --- selfdrive/assets/offroad/fcc.html | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/assets/offroad/fcc.html b/selfdrive/assets/offroad/fcc.html index 7f03a72046..793bea533c 100644 --- a/selfdrive/assets/offroad/fcc.html +++ b/selfdrive/assets/offroad/fcc.html @@ -11,7 +11,7 @@

FCC ID: 2AOHHTURBOXSOMD845

Quectel/EG25-G
-

FCC ID: XMR201903EG25GM

+

FCC ID: XMR201903EG25G

This device complies with Part 15 of the FCC Rules. Operation is subject to the following two conditions: From f0f7359f6a7b38613d2ffc11c900add7631f46a4 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 24 Nov 2021 11:53:10 -0800 Subject: [PATCH 015/102] mazda: capitalize CX9 like all others cars --- selfdrive/car/mazda/values.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/car/mazda/values.py b/selfdrive/car/mazda/values.py index ada3ea1ddb..58e1dd7033 100644 --- a/selfdrive/car/mazda/values.py +++ b/selfdrive/car/mazda/values.py @@ -21,7 +21,7 @@ class CAR: CX9 = "MAZDA CX-9" MAZDA3 = "MAZDA 3" MAZDA6 = "MAZDA 6" - CX9_2021 = "Mazda CX-9 2021" # No Steer Lockout + CX9_2021 = "MAZDA CX-9 2021" # No Steer Lockout class LKAS_LIMITS: STEER_THRESHOLD = 15 From eb55226c2bc53b787834eb51997d2df1900cc892 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 24 Nov 2021 13:30:57 -0800 Subject: [PATCH 016/102] update refs for new mazda name --- 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 9021aaec7a..d1485807ee 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -567866c06976f8f95fa7d1670b51d8723e663ea1 \ No newline at end of file +f0f7359f6a7b38613d2ffc11c900add7631f46a4 \ No newline at end of file From b5eb02181c84285ecc89c4cfe0292ca866354985 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Thu, 25 Nov 2021 05:34:16 +0800 Subject: [PATCH 017/102] loggerd: add test case for sync_encoders (#23020) --- selfdrive/loggerd/SConscript | 6 +-- selfdrive/loggerd/loggerd.h | 1 + selfdrive/loggerd/tests/test_loggerd.cc | 50 +++++++++++++++++++++++++ 3 files changed, 54 insertions(+), 3 deletions(-) create mode 100644 selfdrive/loggerd/tests/test_loggerd.cc diff --git a/selfdrive/loggerd/SConscript b/selfdrive/loggerd/SConscript index 0d3fe55048..2adcfb846c 100644 --- a/selfdrive/loggerd/SConscript +++ b/selfdrive/loggerd/SConscript @@ -7,7 +7,7 @@ libs = [logger_lib, common, cereal, messaging, visionipc, 'avformat', 'avcodec', 'swscale', 'avutil', 'yuv', 'bz2', 'OpenCL'] -src = ['main.cc', 'loggerd.cc'] +src = ['loggerd.cc'] if arch in ["aarch64", "larch64"]: src += ['omx_encoder.cc'] libs += ['OmxCore', 'gsl', 'CB'] + gpucommon @@ -24,8 +24,8 @@ if arch == "Darwin": del libs[libs.index('OpenCL')] env['FRAMEWORKS'] = ['OpenCL'] -env.Program('loggerd', src, LIBS=libs) +env.Program('loggerd', ['main.cc'] + src, LIBS=libs) env.Program('bootlog.cc', LIBS=libs) if GetOption('test'): - env.Program('tests/test_logger', ['tests/test_runner.cc', 'tests/test_logger.cc', env.Object('logger_util', '#/selfdrive/ui/replay/util.cc')], LIBS=[libs] + ['curl', 'crypto']) + env.Program('tests/test_logger', ['tests/test_runner.cc', 'tests/test_loggerd.cc', 'tests/test_logger.cc', env.Object('logger_util', '#/selfdrive/ui/replay/util.cc')] + src, LIBS=[libs] + ['curl', 'crypto', 'bz2']) diff --git a/selfdrive/loggerd/loggerd.h b/selfdrive/loggerd/loggerd.h index 59f4cb6709..ca5a638f85 100644 --- a/selfdrive/loggerd/loggerd.h +++ b/selfdrive/loggerd/loggerd.h @@ -115,4 +115,5 @@ struct LoggerdState { bool camera_synced[WideRoadCam + 1] = {}; }; +bool sync_encoders(LoggerdState *state, CameraType cam_type, uint32_t frame_id); void loggerd_thread(); diff --git a/selfdrive/loggerd/tests/test_loggerd.cc b/selfdrive/loggerd/tests/test_loggerd.cc new file mode 100644 index 0000000000..500aa6f338 --- /dev/null +++ b/selfdrive/loggerd/tests/test_loggerd.cc @@ -0,0 +1,50 @@ +#include + +#include "catch2/catch.hpp" +#include "selfdrive/loggerd/loggerd.h" + +int random_int(int min, int max) { + std::random_device dev; + std::mt19937 rng(dev()); + std::uniform_int_distribution dist(min, max); + return dist(rng); +} + +int get_synced_frame_id(LoggerdState *s, CameraType cam_type, int start_frame_id) { + int frame_id = start_frame_id; + while (!sync_encoders(s, cam_type, frame_id)) { + ++frame_id; + usleep(0); + } + return frame_id; +}; + +TEST_CASE("sync_encoders") { + const int max_waiting = GENERATE(1, 2, 3); + + for (int test_cnt = 0; test_cnt < 10; ++test_cnt) { + LoggerdState s{.max_waiting = max_waiting}; + std::vector start_frames; + std::vector> futures; + + for (int i = 0; i < max_waiting; ++i) { + int start_frame_id = random_int(0, 20); + start_frames.push_back(start_frame_id); + futures.emplace_back(std::async(std::launch::async, get_synced_frame_id, &s, (CameraType)i, start_frame_id)); + } + + // get results + int synced_frame_id = 0; + for (int i = 0; i < max_waiting; ++i) { + if (i == 0) { + synced_frame_id = futures[i].get(); + // require synced_frame_id equal start_frame_id if max_waiting == 1 + if (max_waiting == 1) { + REQUIRE(synced_frame_id == start_frames[0]); + } + } else { + REQUIRE(futures[i].get() == synced_frame_id); + } + } + } +} From 5bcb4c03581fac92dd1418ed94b5125d180461e9 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 24 Nov 2021 14:08:46 -0800 Subject: [PATCH 018/102] process replay: add cx9 route to migration list --- selfdrive/test/process_replay/process_replay.py | 1 + selfdrive/test/process_replay/ref_commit | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index 451a7cfc50..b5be15f253 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -371,6 +371,7 @@ def python_replay_process(cfg, lr, fingerprint=None): "HONDA CIVIC 2016 TOURING": "HONDA CIVIC 2016", "HONDA ACCORD 2018 SPORT 2T": "HONDA ACCORD 2018", "HONDA ACCORD 2T 2018": "HONDA ACCORD 2018", + "Mazda CX-9 2021": "MAZDA CX-9 2021", } if fingerprint is not None: diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index d1485807ee..1014685633 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -f0f7359f6a7b38613d2ffc11c900add7631f46a4 \ No newline at end of file +b5eb02181c84285ecc89c4cfe0292ca866354985 \ No newline at end of file From 8b6a14758329eb977beb5cba73403dd113495aeb Mon Sep 17 00:00:00 2001 From: Vivek Aithal Date: Wed, 24 Nov 2021 15:24:25 -0800 Subject: [PATCH 019/102] locationd: Fix Nav localization reliability (#22959) * modify reset logic * remove debug statements * use ecef pos and vel covariances during reset * reset orientations initialized to 0,0,GPSbearing * refactor nav fix * add fake gps observations to control ecef pos and ecef vel std * replace fake_P with individual fake cov * set gps mode flag * add gps invalid flag names * update refs * more accurate gps accuracy check + update refs --- selfdrive/locationd/locationd.cc | 97 +++++++++++++++++------- selfdrive/locationd/locationd.h | 7 +- selfdrive/locationd/models/live_kf.cc | 19 +++++ selfdrive/locationd/models/live_kf.h | 7 ++ selfdrive/locationd/models/live_kf.py | 14 +++- selfdrive/test/process_replay/ref_commit | 2 +- 6 files changed, 115 insertions(+), 31 deletions(-) diff --git a/selfdrive/locationd/locationd.cc b/selfdrive/locationd/locationd.cc index 8bdc30a8d2..0056687e51 100755 --- a/selfdrive/locationd/locationd.cc +++ b/selfdrive/locationd/locationd.cc @@ -18,6 +18,7 @@ const double MIN_STD_SANITY_CHECK = 1e-5; // m or rad const double VALID_TIME_SINCE_RESET = 1.0; // s const double VALID_POS_STD = 50.0; // m const double MAX_RESET_TRACKER = 5.0; +const double SANE_GPS_UNCERTAINTY = 1500.0; // m static VectorXd floatlist2vector(const capnp::List::Reader& floatlist) { VectorXd res(floatlist.size()); @@ -130,16 +131,16 @@ void Localizer::build_live_location(cereal::LiveLocationKalman::Builder& fix) { Vector3d nans = Vector3d(NAN, NAN, NAN); // write measurements to msg - init_measurement(fix.initPositionGeodetic(), fix_pos_geo_vec, nans, this->last_gps_fix > 0); - init_measurement(fix.initPositionECEF(), fix_ecef, fix_ecef_std, this->last_gps_fix > 0); - init_measurement(fix.initVelocityECEF(), vel_ecef, vel_ecef_std, this->last_gps_fix > 0); - init_measurement(fix.initVelocityNED(), ned_vel, nans, this->last_gps_fix > 0); + init_measurement(fix.initPositionGeodetic(), fix_pos_geo_vec, nans, this->gps_mode); + init_measurement(fix.initPositionECEF(), fix_ecef, fix_ecef_std, this->gps_mode); + init_measurement(fix.initVelocityECEF(), vel_ecef, vel_ecef_std, this->gps_mode); + init_measurement(fix.initVelocityNED(), ned_vel, nans, this->gps_mode); init_measurement(fix.initVelocityDevice(), vel_device, vel_device_std, true); init_measurement(fix.initAccelerationDevice(), accDevice, accDeviceErr, true); - init_measurement(fix.initOrientationECEF(), orientation_ecef, orientation_ecef_std, this->last_gps_fix > 0); - init_measurement(fix.initCalibratedOrientationECEF(), calibrated_orientation_ecef, nans, this->calibrated && this->last_gps_fix > 0); - init_measurement(fix.initOrientationNED(), orientation_ned, nans, this->last_gps_fix > 0); - init_measurement(fix.initCalibratedOrientationNED(), calibrated_orientation_ned, nans, this->calibrated && this->last_gps_fix > 0); + init_measurement(fix.initOrientationECEF(), orientation_ecef, orientation_ecef_std, this->gps_mode); + init_measurement(fix.initCalibratedOrientationECEF(), calibrated_orientation_ecef, nans, this->calibrated && this->gps_mode); + init_measurement(fix.initOrientationNED(), orientation_ned, nans, this->gps_mode); + init_measurement(fix.initCalibratedOrientationNED(), calibrated_orientation_ned, nans, this->calibrated && this->gps_mode); init_measurement(fix.initAngularVelocityDevice(), angVelocityDevice, angVelocityDeviceErr, true); init_measurement(fix.initVelocityCalibrated(), vel_calib, vel_calib_std, this->calibrated); init_measurement(fix.initAngularVelocityCalibrated(), ang_vel_calib, ang_vel_calib_std, this->calibrated); @@ -243,27 +244,39 @@ void Localizer::handle_sensors(double current_time, const capnp::List observe current obs with reasonable STD + this->kf->predict(current_time); + + VectorXd current_x = this->kf->get_x(); + VectorXd ecef_pos = current_x.segment<3>(0); + VectorXd ecef_vel = current_x.segment<3>(7); + MatrixXdr ecef_pos_R = this->kf->get_fake_gps_pos_cov(); + MatrixXdr ecef_vel_R = this->kf->get_fake_gps_vel_cov(); + + this->kf->predict_and_observe(current_time, OBSERVATION_ECEF_POS, { ecef_pos }, { ecef_pos_R }); + this->kf->predict_and_observe(current_time, OBSERVATION_ECEF_VEL, { ecef_vel }, { ecef_vel_R }); +} + void Localizer::handle_gps(double current_time, const cereal::GpsLocationData::Reader& log) { // ignore the message if the fix is invalid - if (log.getFlags() % 2 == 0) { - return; - } - - // Sanity checks - if ((log.getVerticalAccuracy() <= 0) || (log.getSpeedAccuracy() <= 0) || (log.getBearingAccuracyDeg() <= 0)) { - return; - } - if ((std::abs(log.getLatitude()) > 90) || (std::abs(log.getLongitude()) > 180) || (std::abs(log.getAltitude()) > ALTITUDE_SANITY_CHECK)) { - return; - } + bool gps_invalid_flag = (log.getFlags() % 2 == 0); + bool gps_unreasonable = (Vector2d(log.getAccuracy(), log.getVerticalAccuracy()).norm() >= SANE_GPS_UNCERTAINTY); + bool gps_accuracy_insane = ((log.getVerticalAccuracy() <= 0) || (log.getSpeedAccuracy() <= 0) || (log.getBearingAccuracyDeg() <= 0)); + bool gps_lat_lng_alt_insane = ((std::abs(log.getLatitude()) > 90) || (std::abs(log.getLongitude()) > 180) || (std::abs(log.getAltitude()) > ALTITUDE_SANITY_CHECK)); + bool gps_vel_insane = (floatlist2vector(log.getVNED()).norm() > TRANS_SANITY_CHECK); - if (floatlist2vector(log.getVNED()).norm() > TRANS_SANITY_CHECK) { + if (gps_invalid_flag || gps_unreasonable || gps_accuracy_insane || gps_lat_lng_alt_insane || gps_vel_insane){ + this->determine_gps_mode(current_time); return; } // Process message this->last_gps_fix = current_time; + this->gps_mode = true; Geodetic geodetic = { log.getLatitude(), log.getLongitude(), log.getAltitude() }; this->converter = std::make_unique(geodetic); @@ -290,11 +303,11 @@ void Localizer::handle_gps(double current_time, const cereal::GpsLocationData::R if (ecef_vel.norm() > 5.0 && orientation_error.norm() > 1.0) { LOGE("Locationd vs ubloxLocation orientation difference too large, kalman reset"); - this->reset_kalman(NAN, initial_pose_ecef_quat, ecef_pos); + this->reset_kalman(NAN, initial_pose_ecef_quat, ecef_pos, ecef_vel, ecef_pos_R, ecef_vel_R); this->kf->predict_and_observe(current_time, OBSERVATION_ECEF_ORIENTATION_FROM_GPS, { initial_pose_ecef_quat }); } else if (gps_est_error > 100.0) { LOGE("Locationd vs ubloxLocation position difference too large, kalman reset"); - this->reset_kalman(NAN, initial_pose_ecef_quat, ecef_pos); + this->reset_kalman(NAN, initial_pose_ecef_quat, ecef_pos, ecef_vel, ecef_pos_R, ecef_vel_R); } this->kf->predict_and_observe(current_time, OBSERVATION_ECEF_POS, { ecef_pos }, { ecef_pos_R }); @@ -358,7 +371,8 @@ void Localizer::handle_live_calib(double current_time, const cereal::LiveCalibra void Localizer::reset_kalman(double current_time) { VectorXd init_x = this->kf->get_initial_x(); - this->reset_kalman(current_time, init_x.segment<4>(3), init_x.head(3)); + MatrixXdr init_P = this->kf->get_initial_P(); + this->reset_kalman(current_time, init_x, init_P); } void Localizer::finite_check(double current_time) { @@ -390,13 +404,26 @@ void Localizer::update_reset_tracker() { } } -void Localizer::reset_kalman(double current_time, VectorXd init_orient, VectorXd init_pos) { +void Localizer::reset_kalman(double current_time, VectorXd init_orient, VectorXd init_pos, VectorXd init_vel, MatrixXdr init_pos_R, MatrixXdr init_vel_R) { // too nonlinear to init on completely wrong - VectorXd init_x = this->kf->get_initial_x(); + VectorXd current_x = this->kf->get_x(); + MatrixXdr current_P = this->kf->get_P(); MatrixXdr init_P = this->kf->get_initial_P(); - init_x.segment<4>(3) = init_orient; - init_x.head(3) = init_pos; + MatrixXdr reset_orientation_P = this->kf->get_reset_orientation_P(); + + current_x.segment<4>(3) = init_orient; + current_x.segment<3>(7) = init_vel; + current_x.head(3) = init_pos; + + init_P.block<3,3>(0,0).diagonal() = init_pos_R.diagonal(); + init_P.block<3,3>(3,3).diagonal() = reset_orientation_P.diagonal(); + init_P.block<3,3>(6,6).diagonal() = init_vel_R.diagonal(); + init_P.block<16,16>(9,9).diagonal() = current_P.block<16,16>(9,9).diagonal(); + + this->reset_kalman(current_time, current_x, init_P); +} +void Localizer::reset_kalman(double current_time, VectorXd init_x, MatrixXdr init_P) { this->kf->init_state(init_x, init_P, current_time); this->last_reset_time = current_time; this->reset_tracker += 1.0; @@ -447,6 +474,22 @@ bool Localizer::isGpsOK() { return this->kf->get_filter_time() - this->last_gps_fix < 1.0; } +void Localizer::determine_gps_mode(double current_time) { + // 1. If the pos_std is greater than what's not acceptible and localizer is in gps-mode, reset to no-gps-mode + // 2. If the pos_std is greater than what's not acceptible and localizer is in no-gps-mode, fake obs + // 3. If the pos_std is smaller than what's not acceptible, let gps-mode be whatever it is + VectorXd current_pos_std = this->kf->get_P().block<3,3>(0,0).diagonal().array().sqrt(); + if (current_pos_std.norm() > SANE_GPS_UNCERTAINTY){ + if (this->gps_mode){ + this->gps_mode = false; + this->reset_kalman(current_time); + } + else{ + this->input_fake_gps_observations(current_time); + } + } +} + int Localizer::locationd_thread() { const std::initializer_list service_list = { "gpsLocationExternal", "sensorEvents", "cameraOdometry", "liveCalibration", "carState" }; diff --git a/selfdrive/locationd/locationd.h b/selfdrive/locationd/locationd.h index 60fed112cf..9bc864bf6d 100755 --- a/selfdrive/locationd/locationd.h +++ b/selfdrive/locationd/locationd.h @@ -27,11 +27,13 @@ public: int locationd_thread(); void reset_kalman(double current_time = NAN); - void reset_kalman(double current_time, Eigen::VectorXd init_orient, Eigen::VectorXd init_pos); + void reset_kalman(double current_time, Eigen::VectorXd init_orient, Eigen::VectorXd init_pos, Eigen::VectorXd init_vel, MatrixXdr init_pos_R, MatrixXdr init_vel_R); + void reset_kalman(double current_time, Eigen::VectorXd init_x, MatrixXdr init_P); void finite_check(double current_time = NAN); void time_check(double current_time = NAN); void update_reset_tracker(); bool isGpsOK(); + void determine_gps_mode(double current_time); kj::ArrayPtr get_message_bytes(MessageBuilder& msg_builder, uint64_t logMonoTime, bool inputsOK, bool sensorsOK, bool gpsOK); @@ -49,6 +51,8 @@ public: void handle_cam_odo(double current_time, const cereal::CameraOdometry::Reader& log); void handle_live_calib(double current_time, const cereal::LiveCalibrationData::Reader& log); + void input_fake_gps_observations(double current_time); + private: std::unique_ptr kf; @@ -67,4 +71,5 @@ private: double last_gps_fix = 0; double reset_tracker = 0.0; bool device_fell = false; + bool gps_mode = false; }; diff --git a/selfdrive/locationd/models/live_kf.cc b/selfdrive/locationd/models/live_kf.cc index 541c0f7730..914f272fd3 100755 --- a/selfdrive/locationd/models/live_kf.cc +++ b/selfdrive/locationd/models/live_kf.cc @@ -33,6 +33,9 @@ LiveKalman::LiveKalman() { this->initial_x = live_initial_x; this->initial_P = live_initial_P_diag.asDiagonal(); + this->fake_gps_pos_cov = live_fake_gps_pos_cov_diag.asDiagonal(); + this->fake_gps_vel_cov = live_fake_gps_vel_cov_diag.asDiagonal(); + this->reset_orientation_P = live_reset_orientation_diag.asDiagonal(); this->Q = live_Q_diag.asDiagonal(); for (auto& pair : live_obs_noise_diag) { this->obs_noise[pair.first] = pair.second.asDiagonal(); @@ -87,6 +90,10 @@ std::optional LiveKalman::predict_and_observe(double t, int kind, std: return r; } +void LiveKalman::predict(double t) { + this->filter->predict(t); +} + Eigen::VectorXd LiveKalman::get_initial_x() { return this->initial_x; } @@ -95,6 +102,18 @@ MatrixXdr LiveKalman::get_initial_P() { return this->initial_P; } +MatrixXdr LiveKalman::get_fake_gps_pos_cov() { + return this->fake_gps_pos_cov; +} + +MatrixXdr LiveKalman::get_fake_gps_vel_cov() { + return this->fake_gps_vel_cov; +} + +MatrixXdr LiveKalman::get_reset_orientation_P() { + return this->reset_orientation_P; +} + MatrixXdr LiveKalman::H(VectorXd in) { assert(in.size() == 6); Matrix res; diff --git a/selfdrive/locationd/models/live_kf.h b/selfdrive/locationd/models/live_kf.h index 4cd4756c9f..06ec3854cb 100755 --- a/selfdrive/locationd/models/live_kf.h +++ b/selfdrive/locationd/models/live_kf.h @@ -36,9 +36,13 @@ public: std::optional predict_and_update_odo_speed(std::vector speed, double t, int kind); std::optional predict_and_update_odo_trans(std::vector trans, double t, int kind); std::optional predict_and_update_odo_rot(std::vector rot, double t, int kind); + void predict(double t); Eigen::VectorXd get_initial_x(); MatrixXdr get_initial_P(); + MatrixXdr get_fake_gps_pos_cov(); + MatrixXdr get_fake_gps_vel_cov(); + MatrixXdr get_reset_orientation_P(); MatrixXdr H(Eigen::VectorXd in); @@ -52,6 +56,9 @@ private: Eigen::VectorXd initial_x; MatrixXdr initial_P; + MatrixXdr fake_gps_pos_cov; + MatrixXdr fake_gps_vel_cov; + MatrixXdr reset_orientation_P; MatrixXdr Q; // process noise std::unordered_map obs_noise; }; diff --git a/selfdrive/locationd/models/live_kf.py b/selfdrive/locationd/models/live_kf.py index 75415a2845..93aab2774f 100755 --- a/selfdrive/locationd/models/live_kf.py +++ b/selfdrive/locationd/models/live_kf.py @@ -57,8 +57,8 @@ class LiveKalman(): 0, 0, 0]) # state covariance - initial_P_diag = np.array([1e3**2, 1e3**2, 1e3**2, - 0.5**2, 0.5**2, 0.5**2, + initial_P_diag = np.array([10**2, 10**2, 10**2, + 0.01**2, 0.01**2, 0.01**2, 10**2, 10**2, 10**2, 1**2, 1**2, 1**2, 1**2, 1**2, 1**2, @@ -67,6 +67,13 @@ class LiveKalman(): 0.01**2, 0.01**2, 0.01**2, 0.01**2, 0.01**2, 0.01**2]) + # state covariance when resetting midway in a segment + reset_orientation_diag = np.array([1**2, 1**2, 1**2]) + + # fake observation covariance, to ensure the uncertainty estimate of the filter is under control + fake_gps_pos_cov_diag = np.array([1000**2, 1000**2, 1000**2]) + fake_gps_vel_cov_diag = np.array([10**2, 10**2, 10**2]) + # process noise Q_diag = np.array([0.03**2, 0.03**2, 0.03**2, 0.001**2, 0.001**2, 0.001**2, @@ -241,6 +248,9 @@ class LiveKalman(): live_kf_header += f"static const Eigen::VectorXd live_initial_x = {numpy2eigenstring(LiveKalman.initial_x)};\n" live_kf_header += f"static const Eigen::VectorXd live_initial_P_diag = {numpy2eigenstring(LiveKalman.initial_P_diag)};\n" + live_kf_header += f"static const Eigen::VectorXd live_fake_gps_pos_cov_diag = {numpy2eigenstring(LiveKalman.fake_gps_pos_cov_diag)};\n" + live_kf_header += f"static const Eigen::VectorXd live_fake_gps_vel_cov_diag = {numpy2eigenstring(LiveKalman.fake_gps_vel_cov_diag)};\n" + live_kf_header += f"static const Eigen::VectorXd live_reset_orientation_diag = {numpy2eigenstring(LiveKalman.reset_orientation_diag)};\n" live_kf_header += f"static const Eigen::VectorXd live_Q_diag = {numpy2eigenstring(LiveKalman.Q_diag)};\n" live_kf_header += "static const std::unordered_map> live_obs_noise_diag = {\n" for kind, noise in LiveKalman.obs_noise_diag.items(): diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 1014685633..b179c09e16 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -b5eb02181c84285ecc89c4cfe0292ca866354985 \ No newline at end of file +eb82d8fc821da3488dffe85f191211ee1fad5904 \ No newline at end of file From ab9c7a11a9c6ef6e891429b26e77d59a70b0f418 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Thu, 25 Nov 2021 07:45:48 +0800 Subject: [PATCH 020/102] boardd: const reference pandaStates to avoid copy (#23030) --- 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 431b5a86e0..bbaf28ca67 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -307,7 +307,7 @@ bool send_panda_states(PubMaster *pm, const std::vector &pandas, bool s for (uint32_t i=0; i Date: Wed, 24 Nov 2021 15:59:19 -0800 Subject: [PATCH 021/102] test: Replay both models on C2/C3 (#23019) * add dcam stream * delete model_test * both in jenkins * update spinner * get filename fn * they are not random names * update route * new ref commit * temporarily resize tmp * clean up unlog send * need calib 0 * revert device * cleanup * arg Co-authored-by: Comma Device --- Jenkinsfile | 9 ++ selfdrive/test/model_test.py | 30 ---- selfdrive/test/process_replay/model_replay.py | 138 +++++++++++------- .../process_replay/model_replay_ref_commit | 2 +- 4 files changed, 96 insertions(+), 83 deletions(-) delete mode 100755 selfdrive/test/model_test.py diff --git a/Jenkinsfile b/Jenkinsfile index bcdb7c99f4..6004849726 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -247,6 +247,15 @@ pipeline { } } + stage('C3: replay') { + steps { + phone_steps("tici-party", [ + ["build", "cd selfdrive/manager && ./build.py"], + ["model replay", "cd selfdrive/test/process_replay && ./model_replay.py"], + ]) + } + } + } } diff --git a/selfdrive/test/model_test.py b/selfdrive/test/model_test.py deleted file mode 100755 index b8a4ac0a86..0000000000 --- a/selfdrive/test/model_test.py +++ /dev/null @@ -1,30 +0,0 @@ -#!/usr/bin/env python3 -import os -import numpy as np - -from tools.lib.logreader import LogReader -from tools.lib.framereader import FrameReader -from tools.lib.cache import cache_path_for_file_path -from selfdrive.test.process_replay.model_replay import model_replay - - -if __name__ == "__main__": - lr = LogReader(os.path.expanduser('~/rlog.bz2')) - fr = FrameReader(os.path.expanduser('~/fcamera.hevc')) - desire = np.load(os.path.expanduser('~/desire.npy')) - calib = np.load(os.path.expanduser('~/calib.npy')) - - try: - msgs = model_replay(list(lr), fr, desire=desire, calib=calib) - finally: - cache_path = cache_path_for_file_path(os.path.expanduser('~/fcamera.hevc')) - if os.path.isfile(cache_path): - os.remove(cache_path) - - output_size = len(np.frombuffer(msgs[0].model.rawPredictions, dtype=np.float32)) - output_data = np.zeros((len(msgs), output_size), dtype=np.float32) - for i, msg in enumerate(msgs): - output_data[i] = np.frombuffer(msg.model.rawPredictions, dtype=np.float32) - np.save(os.path.expanduser('~/modeldata.npy'), output_data) - - print("Finished replay") diff --git a/selfdrive/test/process_replay/model_replay.py b/selfdrive/test/process_replay/model_replay.py index b3c52879ce..3b03bc8408 100755 --- a/selfdrive/test/process_replay/model_replay.py +++ b/selfdrive/test/process_replay/model_replay.py @@ -7,12 +7,12 @@ from typing import Any from tqdm import tqdm import cereal.messaging as messaging -from cereal import log from cereal.visionipc.visionipc_pyx import VisionIpcServer, VisionStreamType # pylint: disable=no-name-in-module, import-error from common.spinner import Spinner from common.timeout import Timeout -from common.transformations.camera import get_view_frame_from_road_frame, eon_f_frame_size, tici_f_frame_size -from selfdrive.hardware import PC +from common.transformations.camera import get_view_frame_from_road_frame, eon_f_frame_size, tici_f_frame_size, \ + eon_d_frame_size, tici_d_frame_size +from selfdrive.hardware import PC, TICI from selfdrive.manager.process_config import managed_processes from selfdrive.test.openpilotci import BASE_URL, get_url from selfdrive.test.process_replay.compare_logs import compare_logs, save_log @@ -21,8 +21,17 @@ from selfdrive.version import get_git_commit from tools.lib.framereader import FrameReader from tools.lib.logreader import LogReader -TEST_ROUTE = "99c94dc769b5d96e|2019-08-03--14-19-59" +if TICI: + TEST_ROUTE = "4cf7a6ad03080c90|2021-09-29--13-46-36" +else: + TEST_ROUTE = "303055c0002aefd1|2021-11-22--18-36-32" +CACHE_DIR = os.getenv("CACHE_DIR", None) + +packet_from_camera = {"roadCameraState":"modelV2", "driverCameraState":"driverState"} + +def get_log_fn(ref_commit): + return "%s_%s_%s.bz2" % (TEST_ROUTE, "model_tici" if TICI else "model", ref_commit) def replace_calib(msg, calib): msg = msg.as_builder() @@ -30,67 +39,78 @@ def replace_calib(msg, calib): msg.liveCalibration.extrinsicMatrix = get_view_frame_from_road_frame(*calib, 1.22).flatten().tolist() return msg - -def model_replay(lr, fr, desire=None, calib=None): - +def process_frame(msg, pm, sm, log_msgs, vipc_server, spinner, frs, frame_idxs, last_desire): + if msg.which() == "roadCameraState" and last_desire is not None: + dat = messaging.new_message('lateralPlan') + dat.lateralPlan.desire = last_desire + pm.send('lateralPlan', dat) + + f = msg.as_builder() + pm.send(msg.which(), f) + + img = frs[msg.which()].get(frame_idxs[msg.which()], pix_fmt="yuv420p")[0] + if msg.which == "roadCameraState": + vipc_server.send(VisionStreamType.VISION_STREAM_YUV_BACK, img.flatten().tobytes(), f.roadCameraState.frameId, + f.roadCameraState.timestampSof, f.roadCameraState.timestampEof) + else: + vipc_server.send(VisionStreamType.VISION_STREAM_YUV_FRONT, img.flatten().tobytes(), f.driverCameraState.frameId, + f.driverCameraState.timestampSof, f.driverCameraState.timestampEof) + with Timeout(seconds=15): + log_msgs.append(messaging.recv_one(sm.sock[packet_from_camera[msg.which()]])) + + frame_idxs[msg.which()] += 1 + if frame_idxs[msg.which()] >= frs[msg.which()].frame_count: + return None + update_spinner(spinner, frame_idxs['roadCameraState'], frs['roadCameraState'].frame_count, + frame_idxs['driverCameraState'], frs['driverCameraState'].frame_count) + return 0 + +def update_spinner(s, fidx, fcnt, didx, dcnt): + s.update("replaying models: road %d/%d, driver %d/%d" % (fidx, fcnt, didx, dcnt)) + +def model_replay(lr_list, frs): spinner = Spinner() spinner.update("starting model replay") - vipc_server = None - pm = messaging.PubMaster(['roadCameraState', 'liveCalibration', 'lateralPlan']) - sm = messaging.SubMaster(['modelV2']) + vipc_server = VisionIpcServer("camerad") + vipc_server.create_buffers(VisionStreamType.VISION_STREAM_YUV_BACK, 40, False, *(tici_f_frame_size if TICI else eon_f_frame_size)) + vipc_server.create_buffers(VisionStreamType.VISION_STREAM_YUV_FRONT, 40, False, *(tici_d_frame_size if TICI else eon_d_frame_size)) + vipc_server.start_listener() + + pm = messaging.PubMaster(['roadCameraState', 'driverCameraState', 'liveCalibration', 'lateralPlan']) + sm = messaging.SubMaster(['modelV2', 'driverState']) - # TODO: add dmonitoringmodeld try: managed_processes['modeld'].start() + managed_processes['dmonitoringmodeld'].start() time.sleep(5) sm.update(1000) - desires_by_index = {v:k for k,v in log.LateralPlan.Desire.schema.enumerants.items()} + last_desire = None + log_msgs = [] + frame_idxs = dict.fromkeys(['roadCameraState','driverCameraState'], 0) cal = [msg for msg in lr if msg.which() == "liveCalibration"] for msg in cal[:5]: - pm.send(msg.which(), replace_calib(msg, calib)) + pm.send(msg.which(), replace_calib(msg, None)) - log_msgs = [] - frame_idx = 0 - for msg in tqdm(lr): + for msg in tqdm(lr_list): if msg.which() == "liveCalibration": - pm.send(msg.which(), replace_calib(msg, calib)) - elif msg.which() == "roadCameraState": - if desire is not None: - for i in desire[frame_idx].nonzero()[0]: - dat = messaging.new_message('lateralPlan') - dat.lateralPlan.desire = desires_by_index[i] - pm.send('lateralPlan', dat) - - f = msg.as_builder() - pm.send(msg.which(), f) - - img = fr.get(frame_idx, pix_fmt="yuv420p")[0] - if vipc_server is None: - w, h = {int(3*w*h/2): (w, h) for (w, h) in [tici_f_frame_size, eon_f_frame_size]}[len(img)] - vipc_server = VisionIpcServer("camerad") - vipc_server.create_buffers(VisionStreamType.VISION_STREAM_YUV_BACK, 40, False, w, h) - vipc_server.start_listener() - time.sleep(1) # wait for modeld to connect - - vipc_server.send(VisionStreamType.VISION_STREAM_YUV_BACK, img.flatten().tobytes(), f.roadCameraState.frameId, - f.roadCameraState.timestampSof, f.roadCameraState.timestampEof) - - with Timeout(seconds=15): - log_msgs.append(messaging.recv_one(sm.sock['modelV2'])) - - spinner.update("modeld replay %d/%d" % (frame_idx, fr.frame_count)) - - frame_idx += 1 - if frame_idx >= fr.frame_count: + last_calib = list(msg.liveCalibration.rpyCalib) + pm.send(msg.which(), replace_calib(msg, last_calib)) + elif msg.which() == "lateralPlan": + last_desire = msg.lateralPlan.desire + elif msg.which() in ["roadCameraState", "driverCameraState"]: + ret = process_frame(msg, pm, sm, log_msgs, vipc_server, spinner, frs, frame_idxs, last_desire) + if ret is None: break + except KeyboardInterrupt: pass finally: spinner.close() managed_processes['modeld'].stop() + managed_processes['dmonitoringmodeld'].stop() return log_msgs @@ -98,26 +118,40 @@ if __name__ == "__main__": update = "--update" in sys.argv + if TICI: + os.system('sudo mount -o remount,size=200M /tmp') # c3 hevcs are 75M each + replay_dir = os.path.dirname(os.path.abspath(__file__)) ref_commit_fn = os.path.join(replay_dir, "model_replay_ref_commit") - lr = LogReader(get_url(TEST_ROUTE, 0)) - fr = FrameReader(get_url(TEST_ROUTE, 0, log_type="fcamera")) + segnum = 0 + frs = {} + if CACHE_DIR: + lr = LogReader(os.path.join(CACHE_DIR, '%s--%d--rlog.bz2' % (TEST_ROUTE.replace('|', '_'), segnum))) + frs['roadCameraState'] = FrameReader(os.path.join(CACHE_DIR, '%s--%d--fcamera.hevc' % (TEST_ROUTE.replace('|', '_'), segnum))) + frs['driverCameraState'] = FrameReader(os.path.join(CACHE_DIR, '%s--%d--dcamera.hevc' % (TEST_ROUTE.replace('|', '_'), segnum))) + else: + lr = LogReader(get_url(TEST_ROUTE, segnum)) + frs['roadCameraState'] = FrameReader(get_url(TEST_ROUTE, segnum, log_type="fcamera")) + frs['driverCameraState'] = FrameReader(get_url(TEST_ROUTE, segnum, log_type="dcamera")) - log_msgs = model_replay(list(lr), fr) + lr_list = list(lr) + log_msgs = model_replay(lr_list, frs) failed = False if not update: ref_commit = open(ref_commit_fn).read().strip() - log_fn = "%s_%s_%s.bz2" % (TEST_ROUTE, "model", ref_commit) + log_fn = get_log_fn(ref_commit) cmp_log = LogReader(BASE_URL + log_fn) ignore = ['logMonoTime', 'valid', 'modelV2.frameDropPerc', - 'modelV2.modelExecutionTime'] + 'modelV2.modelExecutionTime', + 'driverState.modelExecutionTime', + 'driverState.dspExecutionTime'] tolerance = None if not PC else 1e-3 results: Any = {TEST_ROUTE: {}} - results[TEST_ROUTE]["modeld"] = compare_logs(cmp_log, log_msgs, tolerance=tolerance, ignore_fields=ignore) + results[TEST_ROUTE]["models"] = compare_logs(cmp_log, log_msgs, tolerance=tolerance, ignore_fields=ignore) diff1, diff2, failed = format_diff(results, ref_commit) print(diff2) @@ -136,7 +170,7 @@ if __name__ == "__main__": print("Uploading new refs") new_commit = get_git_commit() - log_fn = "%s_%s_%s.bz2" % (TEST_ROUTE, "model", new_commit) + log_fn = get_log_fn(new_commit) save_log(log_fn, log_msgs) try: upload_file(log_fn, os.path.basename(log_fn)) diff --git a/selfdrive/test/process_replay/model_replay_ref_commit b/selfdrive/test/process_replay/model_replay_ref_commit index c006ea47a4..78f22ad969 100644 --- a/selfdrive/test/process_replay/model_replay_ref_commit +++ b/selfdrive/test/process_replay/model_replay_ref_commit @@ -1 +1 @@ -46abfc14629d16f84ee45255ac876dceea2e7a11 +c1f0accb010eea2d524427a5264055778063f464 \ No newline at end of file From adaffb33551ecfcf06097a6ac7196984e00a6f1e Mon Sep 17 00:00:00 2001 From: Jason Young <46612682+jyoung8607@users.noreply.github.com> Date: Thu, 25 Nov 2021 16:37:33 -0600 Subject: [PATCH 022/102] VW MQB: Add FW for 2013 Volkswagen Golf (#23036) --- selfdrive/car/volkswagen/values.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/selfdrive/car/volkswagen/values.py b/selfdrive/car/volkswagen/values.py index 7b3160e620..27bf9fb1b8 100755 --- a/selfdrive/car/volkswagen/values.py +++ b/selfdrive/car/volkswagen/values.py @@ -147,6 +147,7 @@ FW_VERSIONS = { (Ecu.engine, 0x7e0, None): [ b'\xf1\x8704E906016A \xf1\x897697', b'\xf1\x8704E906016AD\xf1\x895758', + b'\xf1\x8704E906016CE\xf1\x899096', b'\xf1\x8704E906023AG\xf1\x891726', b'\xf1\x8704E906023BN\xf1\x894518', b'\xf1\x8704E906024K \xf1\x896811', @@ -187,6 +188,7 @@ FW_VERSIONS = { b'\xf1\x870CW300042F \xf1\x891604', b'\xf1\x870CW300043B \xf1\x891601', b'\xf1\x870CW300044S \xf1\x894530', + b'\xf1\x870CW300044T \xf1\x895245', b'\xf1\x870CW300045 \xf1\x894531', b'\xf1\x870CW300047D \xf1\x895261', b'\xf1\x870CW300048J \xf1\x890611', @@ -269,6 +271,7 @@ FW_VERSIONS = { ], (Ecu.fwdRadar, 0x757, None): [ b'\xf1\x875Q0907567G \xf1\x890390\xf1\x82\00101', + b'\xf1\x875Q0907567J \xf1\x890396\xf1\x82\x0101', b'\xf1\x875Q0907572A \xf1\x890141\xf1\x82\00101', b'\xf1\x875Q0907572B \xf1\x890200\xf1\x82\00101', b'\xf1\x875Q0907572C \xf1\x890210\xf1\x82\00101', From 68c1a666a03a381768673a1b29a73f9131f0ed62 Mon Sep 17 00:00:00 2001 From: grekiki Date: Fri, 26 Nov 2021 00:53:11 +0100 Subject: [PATCH 023/102] replace list comprehensions with generators (#23037) --- selfdrive/debug/cpu_usage_stat.py | 2 +- selfdrive/manager/build.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/debug/cpu_usage_stat.py b/selfdrive/debug/cpu_usage_stat.py index 5931fda640..8975b3e832 100755 --- a/selfdrive/debug/cpu_usage_stat.py +++ b/selfdrive/debug/cpu_usage_stat.py @@ -66,7 +66,7 @@ if __name__ == "__main__": for p in psutil.process_iter(): if p == psutil.Process(): continue - matched = any([l for l in p.cmdline() if any([pn for pn in monitored_proc_names if re.match(r'.*{}.*'.format(pn), l, re.M | re.I)])]) + matched = any(l for l in p.cmdline() if any([pn for pn in monitored_proc_names if re.match(r'.*{}.*'.format(pn), l, re.M | re.I)])) if matched: k = ' '.join(p.cmdline()) print('Add monitored proc:', k) diff --git a/selfdrive/manager/build.py b/selfdrive/manager/build.py index 66f836ce6b..c4fd4746ef 100755 --- a/selfdrive/manager/build.py +++ b/selfdrive/manager/build.py @@ -69,7 +69,7 @@ def build(spinner, dirty=False): else: # Build failed log errors errors = [line.decode('utf8', 'replace') for line in compile_output - if any([err in line for err in [b'error: ', b'not found, needed by target']])] + if any(err in line for err in [b'error: ', b'not found, needed by target'])] error_s = "\n".join(errors) add_file_handler(cloudlog) cloudlog.error("scons build failed\n" + error_s) From 21ff97b8c93f63644345c77914ad12c8b178e8b8 Mon Sep 17 00:00:00 2001 From: eFini Date: Fri, 26 Nov 2021 14:30:07 +0800 Subject: [PATCH 024/102] UI: minor changes to make it translation friendly (#23032) --- selfdrive/ui/qt/home.cc | 2 +- selfdrive/ui/qt/offroad/onboarding.cc | 2 +- selfdrive/ui/qt/widgets/ssh_keys.cc | 4 ++-- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/selfdrive/ui/qt/home.cc b/selfdrive/ui/qt/home.cc index 5484c5d743..1e89264952 100644 --- a/selfdrive/ui/qt/home.cc +++ b/selfdrive/ui/qt/home.cc @@ -178,6 +178,6 @@ void OffroadHome::refresh() { update_notif->setVisible(updateAvailable); alert_notif->setVisible(alerts); if (alerts) { - alert_notif->setText(QString::number(alerts) + " ALERT" + (alerts > 1 ? "S" : "")); + alert_notif->setText(QString::number(alerts) + (alerts > 1 ? " ALERTS" : " ALERT")); } } diff --git a/selfdrive/ui/qt/offroad/onboarding.cc b/selfdrive/ui/qt/offroad/onboarding.cc index aa03ac63db..e6593f7679 100644 --- a/selfdrive/ui/qt/offroad/onboarding.cc +++ b/selfdrive/ui/qt/offroad/onboarding.cc @@ -145,7 +145,7 @@ void DeclinePage::showEvent(QShowEvent *event) { QObject::connect(back_btn, &QPushButton::clicked, this, &DeclinePage::getBack); - QPushButton *uninstall_btn = new QPushButton("Decline, uninstall " + getBrand()); + QPushButton *uninstall_btn = new QPushButton(QString("Decline, uninstall %1").arg(getBrand())); uninstall_btn->setStyleSheet("background-color: #B73D3D"); buttons->addWidget(uninstall_btn); QObject::connect(uninstall_btn, &QPushButton::clicked, [=]() { diff --git a/selfdrive/ui/qt/widgets/ssh_keys.cc b/selfdrive/ui/qt/widgets/ssh_keys.cc index c6af2f5cd1..ca360a3054 100644 --- a/selfdrive/ui/qt/widgets/ssh_keys.cc +++ b/selfdrive/ui/qt/widgets/ssh_keys.cc @@ -46,13 +46,13 @@ void SshControl::getUserKeys(const QString &username) { params.put("GithubUsername", username.toStdString()); params.put("GithubSshKeys", resp.toStdString()); } else { - ConfirmationDialog::alert("Username '" + username + "' has no keys on GitHub", this); + ConfirmationDialog::alert(QString("Username '%1' has no keys on GitHub").arg(username), this); } refresh(); request->deleteLater(); }); QObject::connect(request, &HttpRequest::failedResponse, [=] { - ConfirmationDialog::alert("Username '" + username + "' doesn't exist on GitHub", this); + ConfirmationDialog::alert(QString("Username '%1' doesn't exist on GitHub").arg(username), this); refresh(); request->deleteLater(); }); From 5069852573128f40dd0174eb1d0f3f983367863d Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 26 Nov 2021 14:38:02 +0100 Subject: [PATCH 025/102] navd: render map into VisionIPC (#22800) * navd: render simple map * render route * offscreen rendering * cleanup * more cleanup * render into visionIPC * rename class * split position update from route update * stop broadcast if not active * gate vipc server behind flag * add python library * faster * no vipc from python * put behind extras * only send when loaded * add glFlush just to be sure * cleanup settings into helper function * function ordering * broadcast thumbnails * put behind param * adjust zoom level * add route to python bindings * revert that freq change * add logging if map rendering is enabled * use rlogs if available * bump cereal --- cereal | 2 +- .../test/get_thumbnails_for_segment.py | 6 +- selfdrive/common/params.cc | 1 + selfdrive/ui/SConscript | 5 +- selfdrive/ui/navd/main.cc | 15 +- selfdrive/ui/navd/map_renderer.cc | 200 ++++++++++++++++++ selfdrive/ui/navd/map_renderer.h | 49 +++++ selfdrive/ui/navd/map_renderer.py | 78 +++++++ selfdrive/ui/navd/route_engine.cc | 36 +++- selfdrive/ui/navd/route_engine.h | 11 +- selfdrive/ui/qt/maps/map.h | 3 - selfdrive/ui/qt/maps/map_helpers.cc | 60 ++++++ selfdrive/ui/qt/maps/map_helpers.h | 8 +- selfdrive/ui/qt/offroad/driverview.cc | 2 +- selfdrive/ui/qt/onroad.cc | 16 +- selfdrive/ui/qt/onroad.h | 2 +- selfdrive/ui/qt/widgets/cameraview.cc | 6 +- selfdrive/ui/qt/widgets/cameraview.h | 3 +- selfdrive/ui/watch3.cc | 18 +- 19 files changed, 476 insertions(+), 45 deletions(-) create mode 100644 selfdrive/ui/navd/map_renderer.cc create mode 100644 selfdrive/ui/navd/map_renderer.h create mode 100755 selfdrive/ui/navd/map_renderer.py diff --git a/cereal b/cereal index 238e0c5793..9b245b6023 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 238e0c5793daed7dce6e1e072c4ae510f06ea515 +Subproject commit 9b245b60238b54867057c591b9ac2948b81a1794 diff --git a/selfdrive/camerad/test/get_thumbnails_for_segment.py b/selfdrive/camerad/test/get_thumbnails_for_segment.py index 2ffb4bf650..ab9a7b308d 100755 --- a/selfdrive/camerad/test/get_thumbnails_for_segment.py +++ b/selfdrive/camerad/test/get_thumbnails_for_segment.py @@ -20,9 +20,13 @@ if __name__ == "__main__": mkdirs_exists_ok(out_path) r = Route(args.route) - lr = list(LogReader(r.qlog_paths()[args.segment])) + path = r.log_paths()[args.segment] or r.qlog_paths()[args.segment] + lr = list(LogReader(path)) for msg in tqdm(lr): if msg.which() == 'thumbnail': with open(os.path.join(out_path, f"{msg.thumbnail.frameId}.jpg"), 'wb') as f: f.write(msg.thumbnail.thumbnail) + elif msg.which() == 'navThumbnail': + with open(os.path.join(out_path, f"nav_{msg.navThumbnail.frameId}.jpg"), 'wb') as f: + f.write(msg.navThumbnail.thumbnail) diff --git a/selfdrive/common/params.cc b/selfdrive/common/params.cc index 01bf9a8f4f..ebb37344ef 100644 --- a/selfdrive/common/params.cc +++ b/selfdrive/common/params.cc @@ -135,6 +135,7 @@ std::unordered_map keys = { {"LiveParameters", PERSISTENT}, {"NavDestination", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_OFF}, {"NavSettingTime24h", PERSISTENT}, + {"NavdRender", PERSISTENT}, {"OpenpilotEnabledToggle", PERSISTENT}, {"PandaHeartbeatLost", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_OFF}, {"Passive", PERSISTENT}, diff --git a/selfdrive/ui/SConscript b/selfdrive/ui/SConscript index bc21022dd9..cb1b929946 100644 --- a/selfdrive/ui/SConscript +++ b/selfdrive/ui/SConscript @@ -126,5 +126,8 @@ if arch in ['x86_64', 'Darwin'] or GetOption('extras'): # navd if maps: - navd_src = ["navd/main.cc", "navd/route_engine.cc"] + navd_src = ["navd/main.cc", "navd/route_engine.cc", "navd/map_renderer.cc"] qt_env.Program("navd/_navd", navd_src, LIBS=qt_libs + ['common', 'json11']) + + if GetOption('extras'): + qt_env.SharedLibrary("navd/map_renderer", ["navd/map_renderer.cc"], LIBS=qt_libs + ['common', 'messaging']) diff --git a/selfdrive/ui/navd/main.cc b/selfdrive/ui/navd/main.cc index cc8d9c339b..7ae0393a47 100644 --- a/selfdrive/ui/navd/main.cc +++ b/selfdrive/ui/navd/main.cc @@ -5,9 +5,11 @@ #include #include "selfdrive/ui/qt/util.h" +#include "selfdrive/ui/qt/maps/map_helpers.h" #include "selfdrive/ui/navd/route_engine.h" - -RouteEngine* route_engine = nullptr; +#include "selfdrive/ui/navd/map_renderer.h" +#include "selfdrive/hardware/hw.h" +#include "selfdrive/common/params.h" void sigHandler(int s) { qInfo() << "Shutting down"; @@ -30,7 +32,14 @@ int main(int argc, char *argv[]) { parser.process(app); const QStringList args = parser.positionalArguments(); - route_engine = new RouteEngine(); + + RouteEngine* route_engine = new RouteEngine(); + + if (Params().getBool("NavdRender")) { + MapRenderer * m = new MapRenderer(get_mapbox_settings()); + QObject::connect(route_engine, &RouteEngine::positionUpdated, m, &MapRenderer::updatePosition); + QObject::connect(route_engine, &RouteEngine::routeUpdated, m, &MapRenderer::updateRoute); + } return app.exec(); } diff --git a/selfdrive/ui/navd/map_renderer.cc b/selfdrive/ui/navd/map_renderer.cc new file mode 100644 index 0000000000..1d78d68dfe --- /dev/null +++ b/selfdrive/ui/navd/map_renderer.cc @@ -0,0 +1,200 @@ +#include "selfdrive/ui/navd/map_renderer.h" + +#include +#include +#include + +#include "selfdrive/ui/qt/maps/map_helpers.h" +#include "selfdrive/common/timing.h" + +const float ZOOM = 13.5; // Don't go below 13 or features will start to disappear +const int WIDTH = 256; +const int HEIGHT = WIDTH; + +const int NUM_VIPC_BUFFERS = 4; + +MapRenderer::MapRenderer(const QMapboxGLSettings &settings, bool enable_vipc) : m_settings(settings) { + QSurfaceFormat fmt; + fmt.setRenderableType(QSurfaceFormat::OpenGLES); + + ctx = std::make_unique(); + ctx->setFormat(fmt); + ctx->create(); + assert(ctx->isValid()); + + surface = std::make_unique(); + surface->setFormat(ctx->format()); + surface->create(); + + ctx->makeCurrent(surface.get()); + assert(QOpenGLContext::currentContext() == ctx.get()); + + gl_functions.reset(ctx->functions()); + gl_functions->initializeOpenGLFunctions(); + + QOpenGLFramebufferObjectFormat fbo_format; + fbo.reset(new QOpenGLFramebufferObject(WIDTH, HEIGHT, fbo_format)); + + m_map.reset(new QMapboxGL(nullptr, m_settings, fbo->size(), 1)); + m_map->setCoordinateZoom(QMapbox::Coordinate(0, 0), ZOOM); + m_map->setStyleUrl("mapbox://styles/commaai/ckvmksrpd4n0a14pfdo5heqzr"); + m_map->createRenderer(); + + m_map->resize(fbo->size()); + m_map->setFramebufferObject(fbo->handle(), fbo->size()); + gl_functions->glViewport(0, 0, WIDTH, HEIGHT); + + if (enable_vipc) { + qWarning() << "Enabling navd map rendering"; + vipc_server.reset(new VisionIpcServer("navd")); + vipc_server->create_buffers(VisionStreamType::VISION_STREAM_RGB_MAP, NUM_VIPC_BUFFERS, true, WIDTH, HEIGHT); + vipc_server->start_listener(); + + pm.reset(new PubMaster({"navThumbnail"})); + } +} + +void MapRenderer::updatePosition(QMapbox::Coordinate position, float bearing) { + if (m_map.isNull()) { + return; + } + + m_map->setCoordinate(position); + m_map->setBearing(bearing); + update(); +} + +bool MapRenderer::loaded() { + return m_map->isFullyLoaded(); +} + +void MapRenderer::update() { + gl_functions->glClear(GL_COLOR_BUFFER_BIT); + m_map->render(); + gl_functions->glFlush(); + + sendVipc(); +} + +void MapRenderer::sendVipc() { + if (!vipc_server || !loaded()) { + return; + } + + QImage cap = fbo->toImage().convertToFormat(QImage::Format_RGB888, Qt::AutoColor); + uint64_t ts = nanos_since_boot(); + VisionBuf* buf = vipc_server->get_buffer(VisionStreamType::VISION_STREAM_RGB_MAP); + VisionIpcBufExtra extra = { + .frame_id = frame_id, + .timestamp_sof = ts, + .timestamp_eof = ts, + }; + + assert(cap.sizeInBytes() == buf->len); + memcpy(buf->addr, cap.bits(), buf->len); + vipc_server->send(buf, &extra); + + if (frame_id % 100 == 0) { + // Write jpeg into buffer + QByteArray buffer_bytes; + QBuffer buffer(&buffer_bytes); + buffer.open(QIODevice::WriteOnly); + cap.save(&buffer, "JPG", 50); + + kj::Array buffer_kj = kj::heapArray((const capnp::byte*)buffer_bytes.constData(), buffer_bytes.size()); + + // Send thumbnail + MessageBuilder msg; + auto thumbnaild = msg.initEvent().initNavThumbnail(); + thumbnaild.setFrameId(frame_id); + thumbnaild.setTimestampEof(ts); + thumbnaild.setThumbnail(buffer_kj); + pm->send("navThumbnail", msg); + } + + frame_id++; +} + +uint8_t* MapRenderer::getImage() { + QImage cap = fbo->toImage().convertToFormat(QImage::Format_RGB888, Qt::AutoColor); + uint8_t* buf = new uint8_t[cap.sizeInBytes()]; + memcpy(buf, cap.bits(), cap.sizeInBytes()); + + return buf; +} + +void MapRenderer::updateRoute(QList coordinates) { + if (m_map.isNull()) return; + initLayers(); + + auto route_points = coordinate_list_to_collection(coordinates); + QMapbox::Feature feature(QMapbox::Feature::LineStringType, route_points, {}, {}); + QVariantMap navSource; + navSource["type"] = "geojson"; + navSource["data"] = QVariant::fromValue(feature); + m_map->updateSource("navSource", navSource); + m_map->setLayoutProperty("navLayer", "visibility", "visible"); +} + +void MapRenderer::initLayers() { + if (!m_map->layerExists("navLayer")) { + QVariantMap nav; + nav["id"] = "navLayer"; + nav["type"] = "line"; + nav["source"] = "navSource"; + m_map->addLayer(nav, "road-intersection"); + m_map->setPaintProperty("navLayer", "line-color", QColor("blue")); + m_map->setPaintProperty("navLayer", "line-width", 3); + m_map->setLayoutProperty("navLayer", "line-cap", "round"); + } +} + +MapRenderer::~MapRenderer() { +} + +extern "C" { + MapRenderer* map_renderer_init() { + char *argv[] = { + (char*)"navd", + nullptr + }; + int argc = 0; + QApplication *app = new QApplication(argc, argv); + assert(app); + + QMapboxGLSettings settings; + settings.setApiBaseUrl(MAPS_HOST); + settings.setAccessToken(get_mapbox_token()); + + return new MapRenderer(settings, false); + } + + void map_renderer_update_position(MapRenderer *inst, float lat, float lon, float bearing) { + inst->updatePosition({lat, lon}, bearing); + QApplication::processEvents(); + } + + void map_renderer_update_route(MapRenderer *inst, char* polyline) { + inst->updateRoute(polyline_to_coordinate_list(QString::fromUtf8(polyline))); + } + + void map_renderer_update(MapRenderer *inst) { + inst->update(); + } + + void map_renderer_process(MapRenderer *inst) { + QApplication::processEvents(); + } + + bool map_renderer_loaded(MapRenderer *inst) { + return inst->loaded(); + } + + uint8_t * map_renderer_get_image(MapRenderer *inst) { + return inst->getImage(); + } + + void map_renderer_free_image(MapRenderer *inst, uint8_t * buf) { + delete[] buf; + } +} diff --git a/selfdrive/ui/navd/map_renderer.h b/selfdrive/ui/navd/map_renderer.h new file mode 100644 index 0000000000..1746e76695 --- /dev/null +++ b/selfdrive/ui/navd/map_renderer.h @@ -0,0 +1,49 @@ +#pragma once + +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include "cereal/visionipc/visionipc_server.h" +#include "cereal/messaging/messaging.h" + + +class MapRenderer : public QObject { + Q_OBJECT + +public: + MapRenderer(const QMapboxGLSettings &, bool enable_vipc=true); + uint8_t* getImage(); + void update(); + bool loaded(); + ~MapRenderer(); + + +private: + std::unique_ptr ctx; + std::unique_ptr surface; + std::unique_ptr gl_functions; + std::unique_ptr fbo; + + std::unique_ptr vipc_server; + std::unique_ptr pm; + void sendVipc(); + + QMapboxGLSettings m_settings; + QScopedPointer m_map; + + void initLayers(); + + uint32_t frame_id = 0; + +public slots: + void updatePosition(QMapbox::Coordinate position, float bearing); + void updateRoute(QList coordinates); +}; diff --git a/selfdrive/ui/navd/map_renderer.py b/selfdrive/ui/navd/map_renderer.py new file mode 100755 index 0000000000..28d006841b --- /dev/null +++ b/selfdrive/ui/navd/map_renderer.py @@ -0,0 +1,78 @@ +#!/usr/bin/env python3 +# You might need to uninstall the PyQt5 pip package to avoid conflicts + +import os +import time +from cffi import FFI + +from common.ffi_wrapper import suffix +from common.basedir import BASEDIR + +HEIGHT = WIDTH = 256 + + +def get_ffi(): + lib = os.path.join(BASEDIR, "selfdrive", "ui", "navd", "libmap_renderer" + suffix()) + + ffi = FFI() + ffi.cdef(""" +void* map_renderer_init(); +void map_renderer_update_position(void *inst, float lat, float lon, float bearing); +void map_renderer_update_route(void *inst, char *polyline); +void map_renderer_update(void *inst); +void map_renderer_process(void *inst); +bool map_renderer_loaded(void *inst); +uint8_t* map_renderer_get_image(void *inst); +void map_renderer_free_image(void *inst, uint8_t *buf); +""") + return ffi, ffi.dlopen(lib) + + +def wait_ready(lib, renderer): + while not lib.map_renderer_loaded(renderer): + lib.map_renderer_update(renderer) + + # The main qt app is not execed, so we need to periodically process events for e.g. network requests + lib.map_renderer_process(renderer) + + time.sleep(0.01) + + +def get_image(lib, renderer): + buf = lib.map_renderer_get_image(renderer) + r = list(buf[0:3 * WIDTH * HEIGHT]) + lib.map_renderer_free_image(renderer, buf) + + # Convert to numpy + r = np.asarray(r) + return r.reshape((WIDTH, HEIGHT, 3)) + + +if __name__ == "__main__": + import matplotlib.pyplot as plt + import numpy as np + + ffi, lib = get_ffi() + renderer = lib.map_renderer_init() + wait_ready(lib, renderer) + + geometry = r"{yxk}@|obn~Eg@@eCFqc@J{RFw@?kA@gA?q|@Riu@NuJBgi@ZqVNcRBaPBkG@iSD{I@_H@cH?gG@mG@gG?aD@{LDgDDkVVyQLiGDgX@q_@@qI@qKhS{R~[}NtYaDbGoIvLwNfP_b@|f@oFnF_JxHel@bf@{JlIuxAlpAkNnLmZrWqFhFoh@jd@kX|TkJxH_RnPy^|[uKtHoZ~Um`DlkCorC``CuShQogCtwB_ThQcr@fk@sVrWgRhVmSb\\oj@jxA{Qvg@u]tbAyHzSos@xjBeKbWszAbgEc~@~jCuTrl@cYfo@mRn\\_m@v}@ij@jp@om@lk@y|A`pAiXbVmWzUod@xj@wNlTw}@|uAwSn\\kRfYqOdS_IdJuK`KmKvJoOhLuLbHaMzGwO~GoOzFiSrEsOhD}PhCqw@vJmnAxSczA`Vyb@bHk[fFgl@pJeoDdl@}}@zIyr@hG}X`BmUdBcM^aRR}Oe@iZc@mR_@{FScHxAn_@vz@zCzH~GjPxAhDlB~DhEdJlIbMhFfG|F~GlHrGjNjItLnGvQ~EhLnBfOn@p`@AzAAvn@CfC?fc@`@lUrArStCfSxEtSzGxM|ElFlBrOzJlEbDnC~BfDtCnHjHlLvMdTnZzHpObOf^pKla@~G|a@dErg@rCbj@zArYlj@ttJ~AfZh@r]LzYg@`TkDbj@gIdv@oE|i@kKzhA{CdNsEfOiGlPsEvMiDpLgBpHyB`MkB|MmArPg@|N?|P^rUvFz~AWpOCdAkB|PuB`KeFfHkCfGy@tAqC~AsBPkDs@uAiAcJwMe@s@eKkPMoXQux@EuuCoH?eI?Kas@}Dy@wAUkMOgDL" + lib.map_renderer_update_route(renderer, geometry.encode()) + + POSITIONS = [ + (32.71569271952601, -117.16384270868463, 0), (32.71569271952601, -117.16384270868463, 45), # San Diego + (52.378641991483136, 4.902623379456488, 0), (52.378641991483136, 4.902623379456488, 45), # Amsterdam + ] + plt.figure() + + for i, pos in enumerate(POSITIONS): + t = time.time() + lib.map_renderer_update_position(renderer, *pos) + wait_ready(lib, renderer) + + print(f"{pos} took {time.time() - t:.2f} s") + + plt.subplot(2, 2, i + 1) + plt.imshow(get_image(lib, renderer)) + + plt.show() diff --git a/selfdrive/ui/navd/route_engine.cc b/selfdrive/ui/navd/route_engine.cc index 30d070dc73..f3cb7df3d9 100644 --- a/selfdrive/ui/navd/route_engine.cc +++ b/selfdrive/ui/navd/route_engine.cc @@ -91,7 +91,6 @@ static void parse_banner(cereal::NavInstruction::Builder &instruction, const QMa } } } - } RouteEngine::RouteEngine() { @@ -99,14 +98,17 @@ RouteEngine::RouteEngine() { pm = new PubMaster({"navInstruction", "navRoute"}); // Timers - timer = new QTimer(this); - QObject::connect(timer, SIGNAL(timeout()), this, SLOT(timerUpdate())); - timer->start(1000); + route_timer = new QTimer(this); + QObject::connect(route_timer, SIGNAL(timeout()), this, SLOT(routeUpdate())); + route_timer->start(1000); + + msg_timer = new QTimer(this); + QObject::connect(msg_timer, SIGNAL(timeout()), this, SLOT(msgUpdate())); + msg_timer->start(50); // Build routing engine QVariantMap parameters; - QString token = MAPBOX_TOKEN.isEmpty() ? CommaApi::create_jwt({}, 4 * 7 * 24 * 3600) : MAPBOX_TOKEN; - parameters["mapbox.access_token"] = token; + parameters["mapbox.access_token"] = get_mapbox_token(); parameters["mapbox.directions_api_url"] = MAPS_HOST + "/directions/v5/mapbox/"; geoservice_provider = new QGeoServiceProvider("mapbox", parameters); @@ -124,12 +126,14 @@ RouteEngine::RouteEngine() { } } -void RouteEngine::timerUpdate() { - sm->update(0); +void RouteEngine::msgUpdate() { + sm->update(1000); if (!sm->updated("liveLocationKalman")) { + active = false; return; } + if (sm->updated("managerState")) { for (auto const &p : (*sm)["managerState"].getManagerState().getProcesses()) { if (p.getName() == "ui" && p.getRunning()) { @@ -153,6 +157,15 @@ void RouteEngine::timerUpdate() { if (localizer_valid) { last_bearing = RAD2DEG(orientation.getValue()[2]); last_position = QMapbox::Coordinate(pos.getValue()[0], pos.getValue()[1]); + emit positionUpdated(*last_position, *last_bearing); + } + + active = true; +} + +void RouteEngine::routeUpdate() { + if (!active) { + return; } recomputeRoute(); @@ -261,6 +274,10 @@ bool RouteEngine::shouldRecompute() { } void RouteEngine::recomputeRoute() { + if (!last_position) { + return; + } + auto new_destination = coordinate_from_param("NavDestination"); if (!new_destination) { clearRoute(); @@ -308,6 +325,9 @@ void RouteEngine::routeCalculated(QGeoRouteReply *reply) { route = reply->routes().at(0); segment = route.firstRouteSegment(); + + auto path = route.path(); + emit routeUpdated(path); } else { qWarning() << "Got empty route response"; } diff --git a/selfdrive/ui/navd/route_engine.h b/selfdrive/ui/navd/route_engine.h index 9a6c990417..33cbc79107 100644 --- a/selfdrive/ui/navd/route_engine.h +++ b/selfdrive/ui/navd/route_engine.h @@ -23,7 +23,8 @@ public: SubMaster *sm; PubMaster *pm; - QTimer* timer; + QTimer* msg_timer; + QTimer* route_timer; std::optional ui_pid; @@ -41,6 +42,7 @@ public: bool localizer_valid = false; // Route recompute + bool active = false; int recompute_backoff = 0; int recompute_countdown = 0; void calculateRoute(QMapbox::Coordinate destination); @@ -48,8 +50,13 @@ public: bool shouldRecompute(); private slots: - void timerUpdate(); + void routeUpdate(); + void msgUpdate(); void routeCalculated(QGeoRouteReply *reply); void recomputeRoute(); void sendRoute(); + +signals: + void positionUpdated(QMapbox::Coordinate position, float bearing); + void routeUpdated(QList coordinates); }; diff --git a/selfdrive/ui/qt/maps/map.h b/selfdrive/ui/qt/maps/map.h index b74f5bf29d..c62089cb25 100644 --- a/selfdrive/ui/qt/maps/map.h +++ b/selfdrive/ui/qt/maps/map.h @@ -22,9 +22,6 @@ #include "selfdrive/common/util.h" #include "cereal/messaging/messaging.h" -const QString MAPBOX_TOKEN = util::getenv("MAPBOX_TOKEN").c_str(); -const QString MAPS_HOST = util::getenv("MAPS_HOST", MAPBOX_TOKEN.isEmpty() ? "https://maps.comma.ai" : "https://api.mapbox.com").c_str(); - class MapInstructions : public QWidget { Q_OBJECT diff --git a/selfdrive/ui/qt/maps/map_helpers.cc b/selfdrive/ui/qt/maps/map_helpers.cc index 422ae99b6b..f87e80403f 100644 --- a/selfdrive/ui/qt/maps/map_helpers.cc +++ b/selfdrive/ui/qt/maps/map_helpers.cc @@ -4,7 +4,25 @@ #include #include "selfdrive/common/params.h" +#include "selfdrive/hardware/hw.h" +#include "selfdrive/ui/qt/api.h" +QString get_mapbox_token() { + // Valid for 4 weeks since we can't swap tokens on the fly + return MAPBOX_TOKEN.isEmpty() ? CommaApi::create_jwt({}, 4 * 7 * 24 * 3600) : MAPBOX_TOKEN; +} + +QMapboxGLSettings get_mapbox_settings() { + QMapboxGLSettings settings; + + if (!Hardware::PC()) { + settings.setCacheDatabasePath(MAPS_CACHE_PATH); + } + settings.setApiBaseUrl(MAPS_HOST); + settings.setAccessToken(get_mapbox_token()); + + return settings; +} QGeoCoordinate to_QGeoCoordinate(const QMapbox::Coordinate &in) { return QGeoCoordinate(in.first, in.second); @@ -83,6 +101,48 @@ QMapbox::CoordinatesCollections coordinate_list_to_collection(QList polyline_to_coordinate_list(const QString &polylineString) { + QList path; + if (polylineString.isEmpty()) + return path; + + QByteArray data = polylineString.toLatin1(); + + bool parsingLatitude = true; + + int shift = 0; + int value = 0; + + QGeoCoordinate coord(0, 0); + + for (int i = 0; i < data.length(); ++i) { + unsigned char c = data.at(i) - 63; + + value |= (c & 0x1f) << shift; + shift += 5; + + // another chunk + if (c & 0x20) + continue; + + int diff = (value & 1) ? ~(value >> 1) : (value >> 1); + + if (parsingLatitude) { + coord.setLatitude(coord.latitude() + (double)diff/1e6); + } else { + coord.setLongitude(coord.longitude() + (double)diff/1e6); + path.append(coord); + } + + parsingLatitude = !parsingLatitude; + + value = 0; + shift = 0; + } + + return path; +} + static QGeoCoordinate sub(QGeoCoordinate v, QGeoCoordinate w) { return QGeoCoordinate(v.latitude() - w.latitude(), v.longitude() - w.longitude()); } diff --git a/selfdrive/ui/qt/maps/map_helpers.h b/selfdrive/ui/qt/maps/map_helpers.h index 53a44f42d8..1c8cacbebc 100644 --- a/selfdrive/ui/qt/maps/map_helpers.h +++ b/selfdrive/ui/qt/maps/map_helpers.h @@ -5,12 +5,17 @@ #include #include +#include "selfdrive/common/util.h" #include "common/transformations/coordinates.hpp" #include "common/transformations/orientation.hpp" #include "cereal/messaging/messaging.h" -#define RAD2DEG(x) ((x) * 180.0 / M_PI) +const QString MAPBOX_TOKEN = util::getenv("MAPBOX_TOKEN").c_str(); +const QString MAPS_HOST = util::getenv("MAPS_HOST", MAPBOX_TOKEN.isEmpty() ? "https://maps.comma.ai" : "https://api.mapbox.com").c_str(); +const QString MAPS_CACHE_PATH = "/data/mbgl-cache-navd.db"; +QString get_mapbox_token(); +QMapboxGLSettings get_mapbox_settings(); QGeoCoordinate to_QGeoCoordinate(const QMapbox::Coordinate &in); QMapbox::CoordinatesCollections model_to_collection( const cereal::LiveLocationKalman::Measurement::Reader &calibratedOrientationECEF, @@ -19,6 +24,7 @@ QMapbox::CoordinatesCollections model_to_collection( QMapbox::CoordinatesCollections coordinate_to_collection(QMapbox::Coordinate c); QMapbox::CoordinatesCollections capnp_coordinate_list_to_collection(const capnp::List::Reader &coordinate_list); QMapbox::CoordinatesCollections coordinate_list_to_collection(QList coordinate_list); +QList polyline_to_coordinate_list(const QString &polylineString); float minimum_distance(QGeoCoordinate a, QGeoCoordinate b, QGeoCoordinate p); std::optional coordinate_from_param(std::string param); diff --git a/selfdrive/ui/qt/offroad/driverview.cc b/selfdrive/ui/qt/offroad/driverview.cc index f988d193e3..6f03e2ed4a 100644 --- a/selfdrive/ui/qt/offroad/driverview.cc +++ b/selfdrive/ui/qt/offroad/driverview.cc @@ -12,7 +12,7 @@ DriverViewWindow::DriverViewWindow(QWidget* parent) : QWidget(parent) { layout = new QStackedLayout(this); layout->setStackingMode(QStackedLayout::StackAll); - cameraView = new CameraViewWidget(VISION_STREAM_RGB_FRONT, true, this); + cameraView = new CameraViewWidget("camerad", VISION_STREAM_RGB_FRONT, true, this); layout->addWidget(cameraView); scene = new DriverViewScene(this); diff --git a/selfdrive/ui/qt/onroad.cc b/selfdrive/ui/qt/onroad.cc index e7a233000c..5abcf61047 100644 --- a/selfdrive/ui/qt/onroad.cc +++ b/selfdrive/ui/qt/onroad.cc @@ -5,9 +5,9 @@ #include "selfdrive/common/timing.h" #include "selfdrive/ui/paint.h" #include "selfdrive/ui/qt/util.h" -#include "selfdrive/ui/qt/api.h" #ifdef ENABLE_MAPS #include "selfdrive/ui/qt/maps/map.h" +#include "selfdrive/ui/qt/maps/map_helpers.h" #endif OnroadWindow::OnroadWindow(QWidget *parent) : QWidget(parent) { @@ -68,19 +68,7 @@ void OnroadWindow::offroadTransition(bool offroad) { #ifdef ENABLE_MAPS if (!offroad) { if (map == nullptr && (QUIState::ui_state.has_prime || !MAPBOX_TOKEN.isEmpty())) { - QMapboxGLSettings settings; - - // Valid for 4 weeks since we can't swap tokens on the fly - QString token = MAPBOX_TOKEN.isEmpty() ? CommaApi::create_jwt({}, 4 * 7 * 24 * 3600) : MAPBOX_TOKEN; - - if (!Hardware::PC()) { - settings.setCacheDatabasePath("/data/mbgl-cache.db"); - } - settings.setApiBaseUrl(MAPS_HOST); - settings.setCacheDatabaseMaximumSize(20 * 1024 * 1024); - settings.setAccessToken(token.trimmed()); - - MapWindow * m = new MapWindow(settings); + MapWindow * m = new MapWindow(get_mapbox_settings()); m->setFixedWidth(topWidget(this)->width() / 2); QObject::connect(this, &OnroadWindow::offroadTransitionSignal, m, &MapWindow::offroadTransition); split->addWidget(m, 0, Qt::AlignRight); diff --git a/selfdrive/ui/qt/onroad.h b/selfdrive/ui/qt/onroad.h index ee44973cf2..1076ed01e6 100644 --- a/selfdrive/ui/qt/onroad.h +++ b/selfdrive/ui/qt/onroad.h @@ -29,7 +29,7 @@ class NvgWindow : public CameraViewWidget { Q_OBJECT public: - explicit NvgWindow(VisionStreamType type, QWidget* parent = 0) : CameraViewWidget(type, true, parent) {} + explicit NvgWindow(VisionStreamType type, QWidget* parent = 0) : CameraViewWidget("camerad", type, true, parent) {} protected: void paintGL() override; diff --git a/selfdrive/ui/qt/widgets/cameraview.cc b/selfdrive/ui/qt/widgets/cameraview.cc index 6cc26a0ca4..240e4c837d 100644 --- a/selfdrive/ui/qt/widgets/cameraview.cc +++ b/selfdrive/ui/qt/widgets/cameraview.cc @@ -94,8 +94,8 @@ mat4 get_fit_view_transform(float widget_aspect_ratio, float frame_aspect_ratio) } // namespace -CameraViewWidget::CameraViewWidget(VisionStreamType type, bool zoom, QWidget* parent) : - stream_type(type), zoomed_view(zoom), QOpenGLWidget(parent) { +CameraViewWidget::CameraViewWidget(std::string stream_name, VisionStreamType type, bool zoom, QWidget* parent) : + stream_name(stream_name), stream_type(type), zoomed_view(zoom), QOpenGLWidget(parent) { setAttribute(Qt::WA_OpaquePaintEvent); connect(this, &CameraViewWidget::vipcThreadConnected, this, &CameraViewWidget::vipcConnected, Qt::BlockingQueuedConnection); connect(this, &CameraViewWidget::vipcThreadFrameReceived, this, &CameraViewWidget::vipcFrameReceived); @@ -276,7 +276,7 @@ void CameraViewWidget::vipcThread() { while (!QThread::currentThread()->isInterruptionRequested()) { if (!vipc_client || cur_stream_type != stream_type) { cur_stream_type = stream_type; - vipc_client.reset(new VisionIpcClient("camerad", cur_stream_type, true)); + vipc_client.reset(new VisionIpcClient(stream_name, cur_stream_type, true)); } if (!vipc_client->connected) { diff --git a/selfdrive/ui/qt/widgets/cameraview.h b/selfdrive/ui/qt/widgets/cameraview.h index 90622c6b77..5e0fc1300b 100644 --- a/selfdrive/ui/qt/widgets/cameraview.h +++ b/selfdrive/ui/qt/widgets/cameraview.h @@ -15,7 +15,7 @@ class CameraViewWidget : public QOpenGLWidget, protected QOpenGLFunctions { public: using QOpenGLWidget::QOpenGLWidget; - explicit CameraViewWidget(VisionStreamType stream_type, bool zoom, QWidget* parent = nullptr); + explicit CameraViewWidget(std::string stream_name, VisionStreamType stream_type, bool zoom, QWidget* parent = nullptr); ~CameraViewWidget(); void setStreamType(VisionStreamType type) { stream_type = type; } void setBackgroundColor(const QColor &color) { bg = color; } @@ -43,6 +43,7 @@ protected: QOpenGLShaderProgram *program; QColor bg = QColor("#000000"); + std::string stream_name; int stream_width = 0; int stream_height = 0; std::atomic stream_type; diff --git a/selfdrive/ui/watch3.cc b/selfdrive/ui/watch3.cc index e5e2864ccb..73c8e11318 100644 --- a/selfdrive/ui/watch3.cc +++ b/selfdrive/ui/watch3.cc @@ -17,12 +17,20 @@ int main(int argc, char *argv[]) { QVBoxLayout *layout = new QVBoxLayout(&w); layout->setMargin(0); layout->setSpacing(0); - layout->addWidget(new CameraViewWidget(VISION_STREAM_RGB_BACK, false)); - QHBoxLayout *hlayout = new QHBoxLayout(); - layout->addLayout(hlayout); - hlayout->addWidget(new CameraViewWidget(VISION_STREAM_RGB_FRONT, false)); - hlayout->addWidget(new CameraViewWidget(VISION_STREAM_RGB_WIDE, false)); + { + QHBoxLayout *hlayout = new QHBoxLayout(); + layout->addLayout(hlayout); + hlayout->addWidget(new CameraViewWidget("navd", VISION_STREAM_RGB_MAP, false)); + hlayout->addWidget(new CameraViewWidget("camerad", VISION_STREAM_RGB_BACK, false)); + } + + { + QHBoxLayout *hlayout = new QHBoxLayout(); + layout->addLayout(hlayout); + hlayout->addWidget(new CameraViewWidget("camerad", VISION_STREAM_RGB_FRONT, false)); + hlayout->addWidget(new CameraViewWidget("camerad", VISION_STREAM_RGB_WIDE, false)); + } return a.exec(); } From 723c8d6a7c8286fb85cb8e784f1d562410b91415 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Fri, 26 Nov 2021 21:39:04 +0800 Subject: [PATCH 026/102] qt/settings: use default parameter for params.get (#23042) --- selfdrive/ui/qt/offroad/settings.cc | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/selfdrive/ui/qt/offroad/settings.cc b/selfdrive/ui/qt/offroad/settings.cc index 7caa29c428..7eb31763fc 100644 --- a/selfdrive/ui/qt/offroad/settings.cc +++ b/selfdrive/ui/qt/offroad/settings.cc @@ -113,9 +113,7 @@ DevicePanel::DevicePanel(QWidget* parent) : ListWidget(parent) { setSpacing(50); Params params = Params(); addItem(new LabelControl("Dongle ID", getDongleId().value_or("N/A"))); - - QString serial = QString::fromStdString(params.get("HardwareSerial", false)); - addItem(new LabelControl("Serial", serial)); + addItem(new LabelControl("Serial", params.get("HardwareSerial").c_str())); // offroad-only buttons From ac179e2c36c3c9e2988016120bd7c1cf308872c5 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Fri, 26 Nov 2021 21:39:25 +0800 Subject: [PATCH 027/102] qt/settings: reuse params (#23041) --- selfdrive/ui/qt/offroad/settings.cc | 20 ++++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/selfdrive/ui/qt/offroad/settings.cc b/selfdrive/ui/qt/offroad/settings.cc index 7eb31763fc..ab2b0287f5 100644 --- a/selfdrive/ui/qt/offroad/settings.cc +++ b/selfdrive/ui/qt/offroad/settings.cc @@ -123,14 +123,14 @@ DevicePanel::DevicePanel(QWidget* parent) : ListWidget(parent) { QString resetCalibDesc = "openpilot requires the device to be mounted within 4° left or right and within 5° up or down. openpilot is continuously calibrating, resetting is rarely required."; auto resetCalibBtn = new ButtonControl("Reset Calibration", "RESET", resetCalibDesc); - connect(resetCalibBtn, &ButtonControl::clicked, [=]() { + connect(resetCalibBtn, &ButtonControl::clicked, [&]() { if (ConfirmationDialog::confirm("Are you sure you want to reset calibration?", this)) { - Params().remove("CalibrationParams"); + params.remove("CalibrationParams"); } }); - connect(resetCalibBtn, &ButtonControl::showDescription, [=]() { + connect(resetCalibBtn, &ButtonControl::showDescription, [&]() { QString desc = resetCalibDesc; - std::string calib_bytes = Params().get("CalibrationParams"); + std::string calib_bytes = params.get("CalibrationParams"); if (!calib_bytes.empty()) { try { AlignedBuffer aligned_buf; @@ -183,12 +183,12 @@ DevicePanel::DevicePanel(QWidget* parent) : ListWidget(parent) { QPushButton *reboot_btn = new QPushButton("Reboot"); reboot_btn->setObjectName("reboot_btn"); power_layout->addWidget(reboot_btn); - QObject::connect(reboot_btn, &QPushButton::clicked, [=]() { + QObject::connect(reboot_btn, &QPushButton::clicked, [&]() { if (QUIState::ui_state.status == UIStatus::STATUS_DISENGAGED) { if (ConfirmationDialog::confirm("Are you sure you want to reboot?", this)) { // Check engaged again in case it changed while the dialog was open if (QUIState::ui_state.status == UIStatus::STATUS_DISENGAGED) { - Params().putBool("DoReboot", true); + params.putBool("DoReboot", true); } } } else { @@ -199,12 +199,12 @@ DevicePanel::DevicePanel(QWidget* parent) : ListWidget(parent) { QPushButton *poweroff_btn = new QPushButton("Power Off"); poweroff_btn->setObjectName("poweroff_btn"); power_layout->addWidget(poweroff_btn); - QObject::connect(poweroff_btn, &QPushButton::clicked, [=]() { + QObject::connect(poweroff_btn, &QPushButton::clicked, [&]() { if (QUIState::ui_state.status == UIStatus::STATUS_DISENGAGED) { if (ConfirmationDialog::confirm("Are you sure you want to power off?", this)) { // Check engaged again in case it changed while the dialog was open if (QUIState::ui_state.status == UIStatus::STATUS_DISENGAGED) { - Params().putBool("DoShutdown", true); + params.putBool("DoShutdown", true); } } } else { @@ -244,9 +244,9 @@ SoftwarePanel::SoftwarePanel(QWidget* parent) : ListWidget(parent) { auto uninstallBtn = new ButtonControl("Uninstall " + getBrand(), "UNINSTALL"); - connect(uninstallBtn, &ButtonControl::clicked, [=]() { + connect(uninstallBtn, &ButtonControl::clicked, [&]() { if (ConfirmationDialog::confirm("Are you sure you want to uninstall?", this)) { - Params().putBool("DoUninstall", true); + params.putBool("DoUninstall", true); } }); connect(parent, SIGNAL(offroadTransition(bool)), uninstallBtn, SLOT(setEnabled(bool))); From 5ae51745097e3245c541456029fbc0fcce63a3c3 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Fri, 26 Nov 2021 21:41:14 +0800 Subject: [PATCH 028/102] framereader: replace swscale with libyuv, reduce cpu usage by half (#22992) * use libyuv * cleanup --- selfdrive/camerad/SConscript | 2 +- selfdrive/ui/SConscript | 2 +- selfdrive/ui/replay/framereader.cc | 67 ++++++++++-------------------- selfdrive/ui/replay/framereader.h | 7 +--- 4 files changed, 27 insertions(+), 51 deletions(-) diff --git a/selfdrive/camerad/SConscript b/selfdrive/camerad/SConscript index d018704d60..5a2b73c61f 100644 --- a/selfdrive/camerad/SConscript +++ b/selfdrive/camerad/SConscript @@ -21,7 +21,7 @@ else: if USE_FRAME_STREAM: cameras = ['cameras/camera_frame_stream.cc'] else: - libs += ['avutil', 'avcodec', 'avformat', 'swscale', 'bz2', 'ssl', 'curl', 'crypto'] + libs += ['avutil', 'avcodec', 'avformat', 'bz2', 'ssl', 'curl', 'crypto'] # TODO: import replay_lib from root SConstruct cameras = ['cameras/camera_replay.cc', env.Object('camera-util', '#/selfdrive/ui/replay/util.cc'), diff --git a/selfdrive/ui/SConscript b/selfdrive/ui/SConscript index cb1b929946..da16c12d14 100644 --- a/selfdrive/ui/SConscript +++ b/selfdrive/ui/SConscript @@ -116,7 +116,7 @@ if arch in ['x86_64', 'Darwin'] or GetOption('extras'): replay_lib_src = ["replay/replay.cc", "replay/camera.cc", "replay/filereader.cc", "replay/logreader.cc", "replay/framereader.cc", "replay/route.cc", "replay/util.cc"] replay_lib = qt_env.Library("qt_replay", replay_lib_src, LIBS=base_libs) - replay_libs = [replay_lib, 'avutil', 'avcodec', 'avformat', 'bz2', 'curl', 'swscale', 'yuv'] + qt_libs + replay_libs = [replay_lib, 'avutil', 'avcodec', 'avformat', 'bz2', 'curl', 'yuv'] + qt_libs qt_env.Program("replay/replay", ["replay/main.cc"], LIBS=replay_libs) qt_env.Program("watch3", ["watch3.cc"], LIBS=qt_libs + ['common', 'json11']) diff --git a/selfdrive/ui/replay/framereader.cc b/selfdrive/ui/replay/framereader.cc index fdbfc0672c..29172a58b2 100644 --- a/selfdrive/ui/replay/framereader.cc +++ b/selfdrive/ui/replay/framereader.cc @@ -34,8 +34,6 @@ enum AVPixelFormat get_hw_format(AVCodecContext *ctx, const enum AVPixelFormat * } // namespace FrameReader::FrameReader(bool local_cache, int chunk_size, int retries) : FileReader(local_cache, chunk_size, retries) { - input_ctx = avformat_alloc_context(); - sws_frame.reset(av_frame_alloc()); } FrameReader::~FrameReader() { @@ -47,9 +45,6 @@ FrameReader::~FrameReader() { if (input_ctx) avformat_close_input(&input_ctx); if (hw_device_ctx) av_buffer_unref(&hw_device_ctx); - if (rgb_sws_ctx_) sws_freeContext(rgb_sws_ctx_); - if (yuv_sws_ctx_) sws_freeContext(yuv_sws_ctx_); - if (avio_ctx_) { av_freep(&avio_ctx_->buffer); avio_context_free(&avio_ctx_); @@ -60,6 +55,9 @@ bool FrameReader::load(const std::string &url, bool no_cuda, std::atomic * std::string content = read(url, abort); if (content.empty()) return false; + input_ctx = avformat_alloc_context(); + if (!input_ctx) return false; + struct buffer_data bd = { .data = (uint8_t *)content.data(), .offset = 0, @@ -99,18 +97,11 @@ bool FrameReader::load(const std::string &url, bool no_cuda, std::atomic * if (!no_cuda) { if (!initHardwareDecoder(AV_HWDEVICE_TYPE_CUDA)) { printf("No CUDA capable device was found. fallback to CPU decoding.\n"); + } else { + nv12toyuv_buffer.resize(getYUVSize()); } } - rgb_sws_ctx_ = sws_getContext(decoder_ctx->width, decoder_ctx->height, sws_src_format, - width, height, AV_PIX_FMT_BGR24, - SWS_BILINEAR, NULL, NULL, NULL); - if (!rgb_sws_ctx_) return false; - yuv_sws_ctx_ = sws_getContext(decoder_ctx->width, decoder_ctx->height, sws_src_format, - width, height, AV_PIX_FMT_YUV420P, - SWS_BILINEAR, NULL, NULL, NULL); - if (!yuv_sws_ctx_) return false; - ret = avcodec_open2(decoder_ctx, decoder, NULL); if (ret < 0) return false; @@ -149,17 +140,6 @@ bool FrameReader::initHardwareDecoder(AVHWDeviceType hw_device_type) { return false; } - // get sws source format - AVHWFramesConstraints *hw_frames_const = av_hwdevice_get_hwframe_constraints(hw_device_ctx, nullptr); - assert(hw_frames_const != 0); - for (AVPixelFormat *p = hw_frames_const->valid_sw_formats; *p != AV_PIX_FMT_NONE; p++) { - if (sws_isSupportedInput(*p)) { - sws_src_format = *p; - break; - } - } - av_hwframe_constraints_free(&hw_frames_const); - decoder_ctx->hw_device_ctx = av_buffer_ref(hw_device_ctx); decoder_ctx->opaque = &hw_pix_fmt; decoder_ctx->get_format = get_hw_format; @@ -228,27 +208,26 @@ AVFrame *FrameReader::decodeFrame(AVPacket *pkt) { } bool FrameReader::copyBuffers(AVFrame *f, uint8_t *rgb, uint8_t *yuv) { - if (yuv) { - if (sws_src_format == AV_PIX_FMT_NV12) { - // libswscale crash if height is not 16 bytes aligned for NV12->YUV420 conversion - assert(sws_src_format == AV_PIX_FMT_NV12); + if (hw_pix_fmt == AV_PIX_FMT_CUDA) { + uint8_t *y = yuv ? yuv : nv12toyuv_buffer.data(); + uint8_t *u = y + width * height; + uint8_t *v = u + (width / 2) * (height / 2); + libyuv::NV12ToI420(f->data[0], f->linesize[0], f->data[1], f->linesize[1], + y, width, u, width / 2, v, width / 2, width, height); + libyuv::I420ToRGB24(y, width, u, width / 2, v, width / 2, + rgb, width * 3, width, height); + } else { + if (yuv) { uint8_t *u = yuv + width * height; uint8_t *v = u + (width / 2) * (height / 2); - libyuv::NV12ToI420(f->data[0], f->linesize[0], - f->data[1], f->linesize[1], - yuv, width, - u, width / 2, - v, width / 2, - width, height); - } else { - av_image_fill_arrays(sws_frame->data, sws_frame->linesize, yuv, AV_PIX_FMT_YUV420P, width, height, 1); - int ret = sws_scale(yuv_sws_ctx_, (const uint8_t **)f->data, f->linesize, 0, f->height, sws_frame->data, sws_frame->linesize); - if (ret < 0) return false; + memcpy(yuv, f->data[0], width * height); + memcpy(u, f->data[1], width / 2 * height / 2); + memcpy(v, f->data[2], width / 2 * height / 2); } + libyuv::I420ToRGB24(f->data[0], f->linesize[0], + f->data[1], f->linesize[1], + f->data[2], f->linesize[2], + rgb, width * 3, width, height); } - - // images is going to be written to output buffers, no alignment (align = 1) - av_image_fill_arrays(sws_frame->data, sws_frame->linesize, rgb, AV_PIX_FMT_BGR24, width, height, 1); - int ret = sws_scale(rgb_sws_ctx_, (const uint8_t **)f->data, f->linesize, 0, f->height, sws_frame->data, sws_frame->linesize); - return ret >= 0; + return true; } diff --git a/selfdrive/ui/replay/framereader.h b/selfdrive/ui/replay/framereader.h index c7b04138cf..7bb63d72f7 100644 --- a/selfdrive/ui/replay/framereader.h +++ b/selfdrive/ui/replay/framereader.h @@ -9,8 +9,6 @@ extern "C" { #include #include -#include -#include } struct AVFrameDeleter { @@ -42,9 +40,7 @@ private: bool failed = false; }; std::vector frames_; - AVPixelFormat sws_src_format = AV_PIX_FMT_YUV420P; - SwsContext *rgb_sws_ctx_ = nullptr, *yuv_sws_ctx_ = nullptr; - std::unique_ptrav_frame_, sws_frame, hw_frame; + std::unique_ptrav_frame_, hw_frame; AVFormatContext *input_ctx = nullptr; AVCodecContext *decoder_ctx = nullptr; int key_frames_count_ = 0; @@ -53,4 +49,5 @@ private: AVPixelFormat hw_pix_fmt = AV_PIX_FMT_NONE; AVBufferRef *hw_device_ctx = nullptr; + std::vector nv12toyuv_buffer; }; From 1d323e0fd6e6050180bdf1b0a9793a4f52c47e9a Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Fri, 26 Nov 2021 21:53:09 +0800 Subject: [PATCH 029/102] loggerd: add test case for trigger_rotate (#23038) * test rotate * remove global LoggerdState --- selfdrive/loggerd/loggerd.cc | 99 +++++++++++++------------ selfdrive/loggerd/loggerd.h | 4 +- selfdrive/loggerd/tests/test_loggerd.cc | 43 +++++++++++ 3 files changed, 98 insertions(+), 48 deletions(-) diff --git a/selfdrive/loggerd/loggerd.cc b/selfdrive/loggerd/loggerd.cc index 0721e836be..40065b5859 100644 --- a/selfdrive/loggerd/loggerd.cc +++ b/selfdrive/loggerd/loggerd.cc @@ -2,30 +2,42 @@ ExitHandler do_exit; -LoggerdState s; - // Handle initial encoder syncing by waiting for all encoders to reach the same frame id -bool sync_encoders(LoggerdState *state, CameraType cam_type, uint32_t frame_id) { - if (state->camera_synced[cam_type]) return true; +bool sync_encoders(LoggerdState *s, CameraType cam_type, uint32_t frame_id) { + if (s->camera_synced[cam_type]) return true; - if (state->max_waiting > 1 && state->encoders_ready != state->max_waiting) { + if (s->max_waiting > 1 && s->encoders_ready != s->max_waiting) { // add a small margin to the start frame id in case one of the encoders already dropped the next frame - update_max_atomic(state->start_frame_id, frame_id + 2); - if (std::exchange(state->camera_ready[cam_type], true) == false) { - ++state->encoders_ready; + update_max_atomic(s->start_frame_id, frame_id + 2); + if (std::exchange(s->camera_ready[cam_type], true) == false) { + ++s->encoders_ready; LOGE("camera %d encoder ready", cam_type); } return false; } else { - if (state->max_waiting == 1) update_max_atomic(state->start_frame_id, frame_id); - bool synced = frame_id >= state->start_frame_id; - state->camera_synced[cam_type] = synced; - if (!synced) LOGE("camera %d waiting for frame %d, cur %d", cam_type, (int)state->start_frame_id, frame_id); + if (s->max_waiting == 1) update_max_atomic(s->start_frame_id, frame_id); + bool synced = frame_id >= s->start_frame_id; + s->camera_synced[cam_type] = synced; + if (!synced) LOGE("camera %d waiting for frame %d, cur %d", cam_type, (int)s->start_frame_id, frame_id); return synced; } } -void encoder_thread(const LogCameraInfo &cam_info) { +bool trigger_rotate_if_needed(LoggerdState *s, int cur_seg, uint32_t frame_id) { + const int frames_per_seg = SEGMENT_LENGTH * MAIN_FPS; + if (cur_seg >= 0 && frame_id >= ((cur_seg + 1) * frames_per_seg) + s->start_frame_id) { + // trigger rotate and wait until the main logger has rotated to the new segment + ++s->ready_to_rotate; + std::unique_lock lk(s->rotate_lock); + s->rotate_cv.wait(lk, [&] { + return s->rotate_segment > cur_seg || do_exit; + }); + return !do_exit; + } + return false; +} + +void encoder_thread(LoggerdState *s, const LogCameraInfo &cam_info) { set_thread_name(cam_info.filename); int cur_seg = -1; @@ -62,37 +74,29 @@ void encoder_thread(const LogCameraInfo &cam_info) { if (buf == nullptr) continue; if (cam_info.trigger_rotate) { - s.last_camera_seen_tms = millis_since_boot(); - if (!sync_encoders(&s, cam_info.type, extra.frame_id)) { + s->last_camera_seen_tms = millis_since_boot(); + if (!sync_encoders(s, cam_info.type, extra.frame_id)) { continue; } // check if we're ready to rotate - const int frames_per_seg = SEGMENT_LENGTH * MAIN_FPS; - if (cur_seg >= 0 && extra.frame_id >= ((cur_seg+1) * frames_per_seg) + s.start_frame_id) { - // trigger rotate and wait until the main logger has rotated to the new segment - ++s.ready_to_rotate; - std::unique_lock lk(s.rotate_lock); - s.rotate_cv.wait(lk, [&] { - return s.rotate_segment > cur_seg || do_exit; - }); - if (do_exit) break; - } + trigger_rotate_if_needed(s, cur_seg, extra.frame_id); + if (do_exit) break; } // rotate the encoder if the logger is on a newer segment - if (s.rotate_segment > cur_seg) { - cur_seg = s.rotate_segment; + if (s->rotate_segment > cur_seg) { + cur_seg = s->rotate_segment; - LOGW("camera %d rotate encoder to %s", cam_info.type, s.segment_path); + LOGW("camera %d rotate encoder to %s", cam_info.type, s->segment_path); for (auto &e : encoders) { e->encoder_close(); - e->encoder_open(s.segment_path); + e->encoder_open(s->segment_path); } if (lh) { lh_close(lh); } - lh = logger_get_handle(&s.logger); + lh = logger_get_handle(&s->logger); } // encode a frame @@ -157,31 +161,31 @@ void clear_locks() { ftw(LOG_ROOT.c_str(), clear_locks_fn, 16); } -void logger_rotate() { +void logger_rotate(LoggerdState *s) { { - std::unique_lock lk(s.rotate_lock); + std::unique_lock lk(s->rotate_lock); int segment = -1; - int err = logger_next(&s.logger, LOG_ROOT.c_str(), s.segment_path, sizeof(s.segment_path), &segment); + int err = logger_next(&s->logger, LOG_ROOT.c_str(), s->segment_path, sizeof(s->segment_path), &segment); assert(err == 0); - s.rotate_segment = segment; - s.ready_to_rotate = 0; - s.last_rotate_tms = millis_since_boot(); + s->rotate_segment = segment; + s->ready_to_rotate = 0; + s->last_rotate_tms = millis_since_boot(); } - s.rotate_cv.notify_all(); - LOGW((s.logger.part == 0) ? "logging to %s" : "rotated to %s", s.segment_path); + s->rotate_cv.notify_all(); + LOGW((s->logger.part == 0) ? "logging to %s" : "rotated to %s", s->segment_path); } -void rotate_if_needed() { - if (s.ready_to_rotate == s.max_waiting) { - logger_rotate(); +void rotate_if_needed(LoggerdState *s) { + if (s->ready_to_rotate == s->max_waiting) { + logger_rotate(s); } double tms = millis_since_boot(); - if ((tms - s.last_rotate_tms) > SEGMENT_LENGTH * 1000 && - (tms - s.last_camera_seen_tms) > NO_CAMERA_PATIENCE && + if ((tms - s->last_rotate_tms) > SEGMENT_LENGTH * 1000 && + (tms - s->last_camera_seen_tms) > NO_CAMERA_PATIENCE && !LOGGERD_TEST) { LOGW("no camera packet seen. auto rotating"); - logger_rotate(); + logger_rotate(s); } } @@ -194,6 +198,7 @@ void loggerd_thread() { } QlogState; std::unordered_map qlog_states; + LoggerdState s; s.ctx = Context::create(); Poller * poller = Poller::create(); @@ -209,7 +214,7 @@ void loggerd_thread() { // init logger logger_init(&s.logger, "rlog", true); - logger_rotate(); + logger_rotate(&s); Params().put("CurrentRoute", s.logger.route_name); // init encoders @@ -217,7 +222,7 @@ void loggerd_thread() { std::vector encoder_threads; for (const auto &cam : cameras_logged) { if (cam.enable) { - encoder_threads.push_back(std::thread(encoder_thread, cam)); + encoder_threads.push_back(std::thread(encoder_thread, &s, cam)); if (cam.trigger_rotate) s.max_waiting++; } } @@ -236,7 +241,7 @@ void loggerd_thread() { bytes_count += msg->getSize(); delete msg; - rotate_if_needed(); + rotate_if_needed(&s); if ((++msg_count % 1000) == 0) { double seconds = (millis_since_boot() - start_ts) / 1000.0; diff --git a/selfdrive/loggerd/loggerd.h b/selfdrive/loggerd/loggerd.h index ca5a638f85..b3e45adfae 100644 --- a/selfdrive/loggerd/loggerd.h +++ b/selfdrive/loggerd/loggerd.h @@ -115,5 +115,7 @@ struct LoggerdState { bool camera_synced[WideRoadCam + 1] = {}; }; -bool sync_encoders(LoggerdState *state, CameraType cam_type, uint32_t frame_id); +bool sync_encoders(LoggerdState *s, CameraType cam_type, uint32_t frame_id); +bool trigger_rotate_if_needed(LoggerdState *s, int cur_seg, uint32_t frame_id); +void rotate_if_needed(LoggerdState *s); void loggerd_thread(); diff --git a/selfdrive/loggerd/tests/test_loggerd.cc b/selfdrive/loggerd/tests/test_loggerd.cc index 500aa6f338..d84185cbba 100644 --- a/selfdrive/loggerd/tests/test_loggerd.cc +++ b/selfdrive/loggerd/tests/test_loggerd.cc @@ -48,3 +48,46 @@ TEST_CASE("sync_encoders") { } } } + +const int MAX_SEGMENT_CNT = 100; + +std::pair encoder_thread(LoggerdState *s) { + int cur_seg = 0; + uint32_t frame_id = s->start_frame_id; + + while (cur_seg < MAX_SEGMENT_CNT) { + ++frame_id; + if (trigger_rotate_if_needed(s, cur_seg, frame_id)) { + cur_seg = s->rotate_segment; + } + util::sleep_for(0); + } + + return {cur_seg, frame_id}; +} + +TEST_CASE("trigger_rotate") { + const int encoders = GENERATE(1, 2, 3); + const int start_frame_id = random_int(0, 20); + + LoggerdState s{ + .max_waiting = encoders, + .start_frame_id = start_frame_id, + }; + + std::vector>> futures; + for (int i = 0; i < encoders; ++i) { + futures.emplace_back(std::async(std::launch::async, encoder_thread, &s)); + } + + while (s.rotate_segment < MAX_SEGMENT_CNT) { + rotate_if_needed(&s); + util::sleep_for(10); + } + + for (auto &f : futures) { + auto [encoder_seg, frame_id] = f.get(); + REQUIRE(encoder_seg == MAX_SEGMENT_CNT); + REQUIRE(frame_id == start_frame_id + encoder_seg * (SEGMENT_LENGTH * MAIN_FPS)); + } +} From 93fd662adf91eda4a17a0ebedbf9dfba61c09901 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Fri, 26 Nov 2021 07:57:39 -0600 Subject: [PATCH 030/102] Clean up planner files (#23031) * clean up planner files clean up planner files * fix plant instance --- selfdrive/controls/lib/lateral_planner.py | 35 ++++++++----------- .../controls/lib/longitudinal_planner.py | 17 +++++---- selfdrive/controls/plannerd.py | 4 +-- .../test/longitudinal_maneuvers/plant.py | 5 ++- 4 files changed, 27 insertions(+), 34 deletions(-) diff --git a/selfdrive/controls/lib/lateral_planner.py b/selfdrive/controls/lib/lateral_planner.py index 74b27f595d..0aa2359ae7 100644 --- a/selfdrive/controls/lib/lateral_planner.py +++ b/selfdrive/controls/lib/lateral_planner.py @@ -38,7 +38,7 @@ DESIRES = { } -class LateralPlanner(): +class LateralPlanner: def __init__(self, CP, use_lanelines=True, wide_camera=False): self.use_lanelines = use_lanelines self.LP = LanePlanner(wide_camera) @@ -55,8 +55,8 @@ class LateralPlanner(): self.prev_one_blinker = False self.desire = log.LateralPlan.Desire.none - self.path_xyz = np.zeros((TRAJECTORY_SIZE,3)) - self.path_xyz_stds = np.ones((TRAJECTORY_SIZE,3)) + self.path_xyz = np.zeros((TRAJECTORY_SIZE, 3)) + self.path_xyz_stds = np.ones((TRAJECTORY_SIZE, 3)) self.plan_yaw = np.zeros((TRAJECTORY_SIZE,)) self.t_idxs = np.arange(TRAJECTORY_SIZE) self.y_pts = np.zeros(TRAJECTORY_SIZE) @@ -67,12 +67,8 @@ class LateralPlanner(): def reset_mpc(self, x0=np.zeros(6)): self.x0 = x0 self.lat_mpc.reset(x0=self.x0) - self.desired_curvature = 0.0 - self.safe_desired_curvature = 0.0 - self.desired_curvature_rate = 0.0 - self.safe_desired_curvature_rate = 0.0 - def update(self, sm, CP): + def update(self, sm): v_ego = sm['carState'].vEgo active = sm['controlsState'].active measured_curvature = sm['controlsState'].curvature @@ -110,7 +106,7 @@ class LateralPlanner(): self.lane_change_direction = LaneChangeDirection.none 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)) blindspot_detected = ((sm['carState'].leftBlindspot and self.lane_change_direction == LaneChangeDirection.left) or @@ -124,7 +120,7 @@ class LateralPlanner(): # LaneChangeState.laneChangeStarting elif self.lane_change_state == LaneChangeState.laneChangeStarting: # fade out over .5s - self.lane_change_ll_prob = max(self.lane_change_ll_prob - 2*DT_MDL, 0.0) + self.lane_change_ll_prob = max(self.lane_change_ll_prob - 2 * DT_MDL, 0.0) # 98% certainty lane_change_prob = self.LP.l_lane_change_prob + self.LP.r_lane_change_prob @@ -167,14 +163,14 @@ class LateralPlanner(): self.LP.rll_prob *= self.lane_change_ll_prob if self.use_lanelines: d_path_xyz = self.LP.get_d_path(v_ego, self.t_idxs, self.path_xyz) - self.lat_mpc.set_weights(MPC_COST_LAT.PATH, MPC_COST_LAT.HEADING, CP.steerRateCost) + self.lat_mpc.set_weights(MPC_COST_LAT.PATH, MPC_COST_LAT.HEADING, self.steer_rate_cost) else: d_path_xyz = self.path_xyz - path_cost = np.clip(abs(self.path_xyz[0,1]/self.path_xyz_stds[0,1]), 0.5, 1.5) * MPC_COST_LAT.PATH + path_cost = np.clip(abs(self.path_xyz[0, 1] / self.path_xyz_stds[0, 1]), 0.5, 1.5) * MPC_COST_LAT.PATH # Heading cost is useful at low speed, otherwise end of plan can be off-heading heading_cost = interp(v_ego, [5.0, 10.0], [MPC_COST_LAT.HEADING, 0.0]) - self.lat_mpc.set_weights(path_cost, heading_cost, CP.steerRateCost) - y_pts = np.interp(v_ego * self.t_idxs[:LAT_MPC_N + 1], np.linalg.norm(d_path_xyz, axis=1), d_path_xyz[:,1]) + self.lat_mpc.set_weights(path_cost, heading_cost, self.steer_rate_cost) + y_pts = np.interp(v_ego * self.t_idxs[:LAT_MPC_N + 1], np.linalg.norm(d_path_xyz, axis=1), d_path_xyz[:, 1]) heading_pts = np.interp(v_ego * self.t_idxs[:LAT_MPC_N + 1], np.linalg.norm(self.path_xyz, axis=1), self.plan_yaw) self.y_pts = y_pts @@ -187,11 +183,10 @@ class LateralPlanner(): y_pts, heading_pts) # init state for next - self.x0[3] = interp(DT_MDL, self.t_idxs[:LAT_MPC_N + 1], self.lat_mpc.x_sol[:,3]) + self.x0[3] = interp(DT_MDL, self.t_idxs[:LAT_MPC_N + 1], self.lat_mpc.x_sol[:, 3]) - - # Check for infeasable MPC solution - mpc_nans = any(math.isnan(x) for x in self.lat_mpc.x_sol[:,3]) + # Check for infeasible MPC solution + mpc_nans = any(math.isnan(x) for x in self.lat_mpc.x_sol[:, 3]) t = sec_since_boot() if mpc_nans or self.lat_mpc.solution_status != 0: self.reset_mpc() @@ -212,8 +207,8 @@ class LateralPlanner(): plan_send.lateralPlan.laneWidth = float(self.LP.lane_width) plan_send.lateralPlan.dPathPoints = [float(x) for x in self.y_pts] plan_send.lateralPlan.psis = [float(x) for x in self.lat_mpc.x_sol[0:CONTROL_N, 2]] - plan_send.lateralPlan.curvatures = [float(x) for x in self.lat_mpc.x_sol[0:CONTROL_N,3]] - plan_send.lateralPlan.curvatureRates = [float(x) for x in self.lat_mpc.u_sol[0:CONTROL_N-1]] +[0.0] + plan_send.lateralPlan.curvatures = [float(x) for x in self.lat_mpc.x_sol[0:CONTROL_N, 3]] + plan_send.lateralPlan.curvatureRates = [float(x) for x in self.lat_mpc.u_sol[0:CONTROL_N - 1]] + [0.0] plan_send.lateralPlan.lProb = float(self.LP.lll_prob) plan_send.lateralPlan.rProb = float(self.LP.rll_prob) plan_send.lateralPlan.dProb = float(self.LP.d_prob) diff --git a/selfdrive/controls/lib/longitudinal_planner.py b/selfdrive/controls/lib/longitudinal_planner.py index 051a68a741..80c8f3e6d7 100755 --- a/selfdrive/controls/lib/longitudinal_planner.py +++ b/selfdrive/controls/lib/longitudinal_planner.py @@ -14,7 +14,7 @@ from selfdrive.controls.lib.drive_helpers import V_CRUISE_MAX, CONTROL_N from selfdrive.swaglog import cloudlog LON_MPC_STEP = 0.2 # first step is 0.2s -AWARENESS_DECEL = -0.2 # car smoothly decel at .2m/s^2 when user is distracted +AWARENESS_DECEL = -0.2 # car smoothly decel at .2m/s^2 when user is distracted A_CRUISE_MIN = -1.2 A_CRUISE_MAX_VALS = [1.2, 1.2, 0.8, 0.6] A_CRUISE_MAX_BP = [0., 15., 25., 40.] @@ -35,13 +35,13 @@ def limit_accel_in_turns(v_ego, angle_steers, a_target, CP): """ a_total_max = interp(v_ego, _A_TOTAL_MAX_BP, _A_TOTAL_MAX_V) - a_y = v_ego**2 * angle_steers * CV.DEG_TO_RAD / (CP.steerRatio * CP.wheelbase) - a_x_allowed = math.sqrt(max(a_total_max**2 - a_y**2, 0.)) + a_y = v_ego ** 2 * angle_steers * CV.DEG_TO_RAD / (CP.steerRatio * CP.wheelbase) + a_x_allowed = math.sqrt(max(a_total_max ** 2 - a_y ** 2, 0.)) return [a_target[0], min(a_target[1], a_x_allowed)] -class Planner(): +class Planner: def __init__(self, CP, init_v=0.0, init_a=0.0): self.CP = CP self.mpc = LongitudinalMpc() @@ -50,14 +50,13 @@ class Planner(): self.v_desired = init_v self.a_desired = init_a - self.alpha = np.exp(-DT_MDL/2.0) + self.alpha = np.exp(-DT_MDL / 2.0) self.v_desired_trajectory = np.zeros(CONTROL_N) self.a_desired_trajectory = np.zeros(CONTROL_N) self.j_desired_trajectory = np.zeros(CONTROL_N) - - def update(self, sm, CP): + def update(self, sm): v_ego = sm['carState'].vEgo a_ego = sm['carState'].aEgo @@ -93,7 +92,7 @@ class Planner(): self.a_desired_trajectory = np.interp(T_IDXS[:CONTROL_N], T_IDXS_MPC, self.mpc.a_solution) self.j_desired_trajectory = np.interp(T_IDXS[:CONTROL_N], T_IDXS_MPC[:-1], self.mpc.j_solution) - #TODO counter is only needed because radar is glitchy, remove once radar is gone + # TODO counter is only needed because radar is glitchy, remove once radar is gone self.fcw = self.mpc.crash_cnt > 5 if self.fcw: cloudlog.info("FCW triggered") @@ -101,7 +100,7 @@ class Planner(): # Interpolate 0.05 seconds and save as starting point for next iteration a_prev = self.a_desired self.a_desired = float(interp(DT_MDL, T_IDXS[:CONTROL_N], self.a_desired_trajectory)) - self.v_desired = self.v_desired + DT_MDL * (self.a_desired + a_prev)/2.0 + self.v_desired = self.v_desired + DT_MDL * (self.a_desired + a_prev) / 2.0 def publish(self, sm, pm): plan_send = messaging.new_message('longitudinalPlan') diff --git a/selfdrive/controls/plannerd.py b/selfdrive/controls/plannerd.py index 88734b3c13..02f1c19a77 100755 --- a/selfdrive/controls/plannerd.py +++ b/selfdrive/controls/plannerd.py @@ -36,9 +36,9 @@ def plannerd_thread(sm=None, pm=None): sm.update() if sm.updated['modelV2']: - lateral_planner.update(sm, CP) + lateral_planner.update(sm) lateral_planner.publish(sm, pm) - longitudinal_planner.update(sm, CP) + longitudinal_planner.update(sm) longitudinal_planner.publish(sm, pm) diff --git a/selfdrive/test/longitudinal_maneuvers/plant.py b/selfdrive/test/longitudinal_maneuvers/plant.py index ac19d27540..cefc2166ec 100755 --- a/selfdrive/test/longitudinal_maneuvers/plant.py +++ b/selfdrive/test/longitudinal_maneuvers/plant.py @@ -42,8 +42,7 @@ class Plant(): from selfdrive.car.honda.values import CAR from selfdrive.car.honda.interface import CarInterface - self.CP = CarInterface.get_params(CAR.CIVIC) - self.planner = Planner(self.CP, init_v=self.speed) + self.planner = Planner(CarInterface.get_params(CAR.CIVIC), init_v=self.speed) def current_time(self): return float(self.rk.frame) / self.rate @@ -97,7 +96,7 @@ class Plant(): sm = {'radarState': radar.radarState, 'carState': car_state.carState, 'controlsState': control.controlsState} - self.planner.update(sm, self.CP) + self.planner.update(sm) self.speed = self.planner.v_desired self.acceleration = self.planner.a_desired fcw = self.planner.fcw From ee4a1ee7000605449cb8a8403e2a6fdac5228b82 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 26 Nov 2021 14:58:06 +0100 Subject: [PATCH 031/102] bump cereal --- cereal | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cereal b/cereal index 9b245b6023..8cbd71836e 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 9b245b60238b54867057c591b9ac2948b81a1794 +Subproject commit 8cbd71836e4170fa175070796396a91771624e82 From e376a621baa125063ffbf1fbd91560e25d45e8fd Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Fri, 26 Nov 2021 21:59:23 +0800 Subject: [PATCH 032/102] ui/device: change last_brightness from float to int (#23029) --- selfdrive/ui/ui.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/ui/ui.h b/selfdrive/ui/ui.h index fab68d3818..c341d06aa2 100644 --- a/selfdrive/ui/ui.h +++ b/selfdrive/ui/ui.h @@ -192,7 +192,7 @@ private: int awake_timeout = 0; float accel_prev = 0; float gyro_prev = 0; - float last_brightness = 0; + int last_brightness = 0; FirstOrderFilter brightness_filter; QTimer *timer; From a58d272ae4afa11624220b9392295ad6659db1df Mon Sep 17 00:00:00 2001 From: jimw Date: Fri, 26 Nov 2021 10:58:25 -0500 Subject: [PATCH 033/102] CARLA: send YUV and RGB over visionipc from bridge.py (#23012) * CARLA: send YUV and RGB over visionipc * CARLA: send YUV and RGB over visionipc-fix pipfile * CARLA: send YUV and RGB over visionipc-Camerad class * relock pipfile * small bridge cleanup * use tici camera resolution * update vof * HUD_SETTING has no counter * no loggerd Co-authored-by: jwolffe Co-authored-by: Willem Melching --- Pipfile | 1 + Pipfile.lock | 312 +++++++++++++++++++--------------- tools/sim/bridge.py | 162 +++++++++++------- tools/sim/launch_openpilot.sh | 3 +- tools/sim/lib/can.py | 2 +- 5 files changed, 276 insertions(+), 204 deletions(-) diff --git a/Pipfile b/Pipfile index 3fc26b363b..fdba040198 100644 --- a/Pipfile +++ b/Pipfile @@ -57,6 +57,7 @@ pycapnp = "==1.1.0" pycryptodome = "*" PyJWT = "*" pylint = "*" +pyopencl = "*" pyserial = "*" python-dateutil = "*" PyYAML = "*" diff --git a/Pipfile.lock b/Pipfile.lock index a1aaeb8766..81dc794b53 100644 --- a/Pipfile.lock +++ b/Pipfile.lock @@ -1,7 +1,7 @@ { "_meta": { "hash": { - "sha256": "c0f1a46ca2ccdc208a392c5ce78d9d928f82d40afd46a33da7b99b895798fce2" + "sha256": "6b23dd7136502655f1c18c37d55db33d77f1b85e0572aed69869401df936003a" }, "pipfile-spec": 6, "requires": { @@ -16,13 +16,20 @@ ] }, "default": { + "appdirs": { + "hashes": [ + "sha256:7d5d0167b2b1ba821647616af46a749d1c653740dd0d2415100fe26e27afdf41", + "sha256:a841dacd6b99318a741b166adb07e19ee71a274450e68237b4650ca1055ab128" + ], + "version": "==1.4.4" + }, "astroid": { "hashes": [ - "sha256:11f7356737b624c42e21e71fe85eea6875cb94c03c82ac76bd535a0ff10b0f25", - "sha256:abc423a1e85bc1553954a14f2053473d2b7f8baf32eae62a328be24f436b5107" + "sha256:5939cf55de24b92bda00345d4d0659d01b3c7dafb5055165c330bc7c568ba273", + "sha256:776ca0b748b4ad69c00bfe0fff38fa2d21c338e12c84aa9715ee0d473c422778" ], "markers": "python_version ~= '3.6'", - "version": "==2.8.5" + "version": "==2.9.0" }, "atomicwrites": { "hashes": [ @@ -141,11 +148,11 @@ }, "charset-normalizer": { "hashes": [ - "sha256:e019de665e2bcf9c2b64e2e5aa025fa991da8720daa3c1138cadd2fd1856aed0", - "sha256:f7af805c321bfa1ce6714c51f254e0d5bb5e5834039bc17db7ebe3a4cec9492b" + "sha256:735e240d9a8506778cd7a453d97e817e536bb1fc29f4f6961ce297b9c7a917b0", + "sha256:83fcdeb225499d6344c8f7f34684c2981270beacc32ede2e669e94f7fa544405" ], "markers": "python_version >= '3'", - "version": "==2.0.7" + "version": "==2.0.8" }, "click": { "hashes": [ @@ -167,29 +174,30 @@ }, "cryptography": { "hashes": [ - "sha256:07bb7fbfb5de0980590ddfc7f13081520def06dc9ed214000ad4372fb4e3c7f6", - "sha256:18d90f4711bf63e2fb21e8c8e51ed8189438e6b35a6d996201ebd98a26abbbe6", - "sha256:1ed82abf16df40a60942a8c211251ae72858b25b7421ce2497c2eb7a1cee817c", - "sha256:22a38e96118a4ce3b97509443feace1d1011d0571fae81fc3ad35f25ba3ea999", - "sha256:2d69645f535f4b2c722cfb07a8eab916265545b3475fdb34e0be2f4ee8b0b15e", - "sha256:4a2d0e0acc20ede0f06ef7aa58546eee96d2592c00f450c9acb89c5879b61992", - "sha256:54b2605e5475944e2213258e0ab8696f4f357a31371e538ef21e8d61c843c28d", - "sha256:7075b304cd567694dc692ffc9747f3e9cb393cc4aa4fb7b9f3abd6f5c4e43588", - "sha256:7b7ceeff114c31f285528ba8b390d3e9cfa2da17b56f11d366769a807f17cbaa", - "sha256:7eba2cebca600a7806b893cb1d541a6e910afa87e97acf2021a22b32da1df52d", - "sha256:928185a6d1ccdb816e883f56ebe92e975a262d31cc536429041921f8cb5a62fd", - "sha256:9933f28f70d0517686bd7de36166dda42094eac49415459d9bdf5e7df3e0086d", - "sha256:a688ebcd08250eab5bb5bca318cc05a8c66de5e4171a65ca51db6bd753ff8953", - "sha256:abb5a361d2585bb95012a19ed9b2c8f412c5d723a9836418fab7aaa0243e67d2", - "sha256:c10c797ac89c746e488d2ee92bd4abd593615694ee17b2500578b63cad6b93a8", - "sha256:ced40344e811d6abba00295ced98c01aecf0c2de39481792d87af4fa58b7b4d6", - "sha256:d57e0cdc1b44b6cdf8af1d01807db06886f10177469312fbde8f44ccbb284bc9", - "sha256:d99915d6ab265c22873f1b4d6ea5ef462ef797b4140be4c9d8b179915e0985c6", - "sha256:eb80e8a1f91e4b7ef8b33041591e6d89b2b8e122d787e87eeb2b08da71bb16ad", - "sha256:ebeddd119f526bcf323a89f853afb12e225902a24d29b55fe18dd6fcb2838a76" - ], - "index": "pypi", - "version": "==35.0.0" + "sha256:2049f8b87f449fc6190350de443ee0c1dd631f2ce4fa99efad2984de81031681", + "sha256:231c4a69b11f6af79c1495a0e5a85909686ea8db946935224b7825cfb53827ed", + "sha256:24469d9d33217ffd0ce4582dfcf2a76671af115663a95328f63c99ec7ece61a4", + "sha256:2deab5ec05d83ddcf9b0916319674d3dae88b0e7ee18f8962642d3cde0496568", + "sha256:494106e9cd945c2cadfce5374fa44c94cfadf01d4566a3b13bb487d2e6c7959e", + "sha256:4c702855cd3174666ef0d2d13dcc879090aa9c6c38f5578896407a7028f75b9f", + "sha256:52f769ecb4ef39865719aedc67b4b7eae167bafa48dbc2a26dd36fa56460507f", + "sha256:5c49c9e8fb26a567a2b3fa0343c89f5d325447956cc2fc7231c943b29a973712", + "sha256:684993ff6f67000a56454b41bdc7e015429732d65a52d06385b6e9de6181c71e", + "sha256:6fbbbb8aab4053fa018984bb0e95a16faeb051dd8cca15add2a27e267ba02b58", + "sha256:8982c19bb90a4fa2aad3d635c6d71814e38b643649b4000a8419f8691f20ac44", + "sha256:9511416e85e449fe1de73f7f99b21b3aa04fba4c4d335d30c486ba3756e3a2a6", + "sha256:97199a13b772e74cdcdb03760c32109c808aff7cd49c29e9cf4b7754bb725d1d", + "sha256:a776bae1629c8d7198396fd93ec0265f8dd2341c553dc32b976168aaf0e6a636", + "sha256:aa94d617a4cd4cdf4af9b5af65100c036bce22280ebb15d8b5262e8273ebc6ba", + "sha256:b17d83b3d1610e571fedac21b2eb36b816654d6f7496004d6a0d32f99d1d8120", + "sha256:d73e3a96c38173e0aa5646c31bf8473bc3564837977dd480f5cbeacf1d7ef3a3", + "sha256:d91bc9f535599bed58f6d2e21a2724cb0c3895bf41c6403fe881391d29096f1d", + "sha256:ef216d13ac8d24d9cd851776662f75f8d29c9f2d05cdcc2d34a18d32463a9b0b", + "sha256:f6a5a85beb33e57998dc605b9dbe7deaa806385fdf5c4810fb849fcd04640c81", + "sha256:f92556f94e476c1b616e6daec5f7ddded2c082efa7cee7f31c7aeda615906ed8" + ], + "index": "pypi", + "version": "==36.0.0" }, "cython": { "hashes": [ @@ -759,11 +767,23 @@ }, "pylint": { "hashes": [ - "sha256:0f358e221c45cbd4dad2a1e4b883e75d28acdcccd29d40c76eb72b307269b126", - "sha256:2c9843fff1a88ca0ad98a256806c82c5a8f86086e7ccbdb93297d86c3f90c436" + "sha256:4f4a52b132c05b49094b28e109febcec6bfb7bc6961c7485a5ad0a0f961df289", + "sha256:b4b5a7b6d04e914a11c198c816042af1fb2d3cda29bb0c98a9c637010da2a5c5" + ], + "index": "pypi", + "version": "==2.12.1" + }, + "pyopencl": { + "hashes": [ + "sha256:05ccbdc341f64f448bfdff173d1b1e79887129cb6c147605628bbd2e56bc3929", + "sha256:0e705b47733d1055c4d8f7478907222e5881519a0dbadd1bf288baebfc024999", + "sha256:51425e65ec49c738eefe21b1eeb1f39245b01cc0ddfd495fbe1f8df33dbc6c9e", + "sha256:59f9824426d823b544717cc25dee221e1a5c5143143efb8d94034cf4ef562913", + "sha256:662899ca2fb74f2d14c2d7ac0560d3cac07e6b0847a245694bb86a27a4d350ca", + "sha256:99e26fde9e5c418878a5a4a685b8ebca118f423bb09f33e7e24cfd8ef94aee30" ], "index": "pypi", - "version": "==2.11.1" + "version": "==2021.2.9" }, "pyserial": { "hashes": [ @@ -781,6 +801,13 @@ "index": "pypi", "version": "==2.8.2" }, + "pytools": { + "hashes": [ + "sha256:db6cf83c9ba0a165d545029e2301621486d1e9ef295684072e5cd75316a13755" + ], + "markers": "python_version ~= '3.6'", + "version": "==2021.2.9" + }, "pyyaml": { "hashes": [ "sha256:0283c35a6a9fbf047493e3a0ce8d79ef5030852c51e9d911a27badfde0605293", @@ -883,19 +910,19 @@ }, "scons": { "hashes": [ - "sha256:663f819e744ddadcdf4f46b03289a7210313b86041efe1b9c8dde81dba437b72", - "sha256:691893b63f38ad14295f5104661d55cb738ec6514421c6261323351c25432b0a" + "sha256:8c13911a2aa40552553488f7d625af4c0768fc8cdedab4a858d8ce42c8c3664d", + "sha256:d47081587e3675cc168f1f54f0d74a69b328a2fc90ec4feb85f728677419b879" ], "index": "pypi", - "version": "==4.2.0" + "version": "==4.3.0" }, "sentry-sdk": { "hashes": [ - "sha256:b9844751e40710e84a457c5bc29b21c383ccb2b63d76eeaad72f7f1c808c8828", - "sha256:c091cc7115ff25fe3a0e410dbecd7a996f81a3f6137d2272daef32d6c3cfa6dc" + "sha256:0db297ab32e095705c20f742c3a5dac62fe15c4318681884053d0898e5abb2f6", + "sha256:789a11a87ca02491896e121efdd64e8fd93327b69e8f2f7d42f03e2569648e88" ], "index": "pypi", - "version": "==1.4.3" + "version": "==1.5.0" }, "setproctitle": { "hashes": [ @@ -1187,11 +1214,11 @@ }, "charset-normalizer": { "hashes": [ - "sha256:e019de665e2bcf9c2b64e2e5aa025fa991da8720daa3c1138cadd2fd1856aed0", - "sha256:f7af805c321bfa1ce6714c51f254e0d5bb5e5834039bc17db7ebe3a4cec9492b" + "sha256:735e240d9a8506778cd7a453d97e817e536bb1fc29f4f6961ce297b9c7a917b0", + "sha256:83fcdeb225499d6344c8f7f34684c2981270beacc32ede2e669e94f7fa544405" ], "markers": "python_version >= '3'", - "version": "==2.0.7" + "version": "==2.0.8" }, "control": { "hashes": [ @@ -1255,29 +1282,30 @@ }, "cryptography": { "hashes": [ - "sha256:07bb7fbfb5de0980590ddfc7f13081520def06dc9ed214000ad4372fb4e3c7f6", - "sha256:18d90f4711bf63e2fb21e8c8e51ed8189438e6b35a6d996201ebd98a26abbbe6", - "sha256:1ed82abf16df40a60942a8c211251ae72858b25b7421ce2497c2eb7a1cee817c", - "sha256:22a38e96118a4ce3b97509443feace1d1011d0571fae81fc3ad35f25ba3ea999", - "sha256:2d69645f535f4b2c722cfb07a8eab916265545b3475fdb34e0be2f4ee8b0b15e", - "sha256:4a2d0e0acc20ede0f06ef7aa58546eee96d2592c00f450c9acb89c5879b61992", - "sha256:54b2605e5475944e2213258e0ab8696f4f357a31371e538ef21e8d61c843c28d", - "sha256:7075b304cd567694dc692ffc9747f3e9cb393cc4aa4fb7b9f3abd6f5c4e43588", - "sha256:7b7ceeff114c31f285528ba8b390d3e9cfa2da17b56f11d366769a807f17cbaa", - "sha256:7eba2cebca600a7806b893cb1d541a6e910afa87e97acf2021a22b32da1df52d", - "sha256:928185a6d1ccdb816e883f56ebe92e975a262d31cc536429041921f8cb5a62fd", - "sha256:9933f28f70d0517686bd7de36166dda42094eac49415459d9bdf5e7df3e0086d", - "sha256:a688ebcd08250eab5bb5bca318cc05a8c66de5e4171a65ca51db6bd753ff8953", - "sha256:abb5a361d2585bb95012a19ed9b2c8f412c5d723a9836418fab7aaa0243e67d2", - "sha256:c10c797ac89c746e488d2ee92bd4abd593615694ee17b2500578b63cad6b93a8", - "sha256:ced40344e811d6abba00295ced98c01aecf0c2de39481792d87af4fa58b7b4d6", - "sha256:d57e0cdc1b44b6cdf8af1d01807db06886f10177469312fbde8f44ccbb284bc9", - "sha256:d99915d6ab265c22873f1b4d6ea5ef462ef797b4140be4c9d8b179915e0985c6", - "sha256:eb80e8a1f91e4b7ef8b33041591e6d89b2b8e122d787e87eeb2b08da71bb16ad", - "sha256:ebeddd119f526bcf323a89f853afb12e225902a24d29b55fe18dd6fcb2838a76" - ], - "index": "pypi", - "version": "==35.0.0" + "sha256:2049f8b87f449fc6190350de443ee0c1dd631f2ce4fa99efad2984de81031681", + "sha256:231c4a69b11f6af79c1495a0e5a85909686ea8db946935224b7825cfb53827ed", + "sha256:24469d9d33217ffd0ce4582dfcf2a76671af115663a95328f63c99ec7ece61a4", + "sha256:2deab5ec05d83ddcf9b0916319674d3dae88b0e7ee18f8962642d3cde0496568", + "sha256:494106e9cd945c2cadfce5374fa44c94cfadf01d4566a3b13bb487d2e6c7959e", + "sha256:4c702855cd3174666ef0d2d13dcc879090aa9c6c38f5578896407a7028f75b9f", + "sha256:52f769ecb4ef39865719aedc67b4b7eae167bafa48dbc2a26dd36fa56460507f", + "sha256:5c49c9e8fb26a567a2b3fa0343c89f5d325447956cc2fc7231c943b29a973712", + "sha256:684993ff6f67000a56454b41bdc7e015429732d65a52d06385b6e9de6181c71e", + "sha256:6fbbbb8aab4053fa018984bb0e95a16faeb051dd8cca15add2a27e267ba02b58", + "sha256:8982c19bb90a4fa2aad3d635c6d71814e38b643649b4000a8419f8691f20ac44", + "sha256:9511416e85e449fe1de73f7f99b21b3aa04fba4c4d335d30c486ba3756e3a2a6", + "sha256:97199a13b772e74cdcdb03760c32109c808aff7cd49c29e9cf4b7754bb725d1d", + "sha256:a776bae1629c8d7198396fd93ec0265f8dd2341c553dc32b976168aaf0e6a636", + "sha256:aa94d617a4cd4cdf4af9b5af65100c036bce22280ebb15d8b5262e8273ebc6ba", + "sha256:b17d83b3d1610e571fedac21b2eb36b816654d6f7496004d6a0d32f99d1d8120", + "sha256:d73e3a96c38173e0aa5646c31bf8473bc3564837977dd480f5cbeacf1d7ef3a3", + "sha256:d91bc9f535599bed58f6d2e21a2724cb0c3895bf41c6403fe881391d29096f1d", + "sha256:ef216d13ac8d24d9cd851776662f75f8d29c9f2d05cdcc2d34a18d32463a9b0b", + "sha256:f6a5a85beb33e57998dc605b9dbe7deaa806385fdf5c4810fb849fcd04640c81", + "sha256:f92556f94e476c1b616e6daec5f7ddded2c082efa7cee7f31c7aeda615906ed8" + ], + "index": "pypi", + "version": "==36.0.0" }, "cycler": { "hashes": [ @@ -1343,11 +1371,11 @@ }, "fonttools": { "hashes": [ - "sha256:68071406009e7ef6a5fdcd85d95975cd6963867bb226f2b786bfffe15d1959ef", - "sha256:8c8f84131bf04f3b1dcf99b9763cec35c347164ab6ad006e18d2f99fcab05529" + "sha256:dca694331af74c8ad47acc5171e57f6b78fac5692bf050f2ab572964577ac0dd", + "sha256:eff1da7ea274c54cb8842853005a139f711646cbf6f1bcfb6c9b86a627f35ff0" ], "markers": "python_version >= '3.7'", - "version": "==4.28.1" + "version": "==4.28.2" }, "hexdump": { "hashes": [ @@ -1358,19 +1386,19 @@ }, "hypothesis": { "hashes": [ - "sha256:8f7318839b64bae1410704933fe01f3db5f80f20f2ba8d4ea3520443ae3a001d", - "sha256:f1627022f75306c653115fbd169ba6a4322804f60533a7b46625fd0eecba43d5" + "sha256:92005826894782cc57c47b98debe1bc889b716f0774e60f83536f14360a9199e", + "sha256:c4943d159f299a96b1c23277c4bcf0759a757888b67a6d73e9c70d853024aa15" ], "index": "pypi", - "version": "==6.24.5" + "version": "==6.27.2" }, "identify": { "hashes": [ - "sha256:4f85f9bd8e6e5e2d61b2f8de5ff5313d8a1cfac4c88822d74406de45ad10bd82", - "sha256:8cb609a671d2f861ae7fe583711a43fd2faab0c892f39cbc4568b0c51b354238" + "sha256:a33ae873287e81651c7800ca309dc1f84679b763c9c8b30680e16fbfa82f0107", + "sha256:eba31ca80258de6bb51453084bff4a923187cd2193b9c13710f2516ab30732cc" ], "markers": "python_full_version >= '3.6.1'", - "version": "==2.3.6" + "version": "==2.4.0" }, "idna": { "hashes": [ @@ -1682,47 +1710,47 @@ }, "opencv-python-headless": { "hashes": [ - "sha256:014e4a892f67043610521e673883da5ad98a6e61356a609c6502b9d22144f2f1", - "sha256:01a6411eb9eecf58db3a50fa761f0527bdd2b23b884b3bea44eb57e6d06e4767", - "sha256:067e4736cdc70712f43c064bfe53ba80492c20479ad3290849337f948572c392", - "sha256:09b21c48144a9dd82e435d66ccd834f3a391a2cd2b69f787aabbc7cd3576f2f1", - "sha256:113b8ce88f337ab3a1ee670b8c5afc3fbf0d8aafec7b2ee897ad5efd9926ce90", - "sha256:1162de92301d0d13642afe8e163593982d3159ef21eba95a56ba3f5ca8024861", - "sha256:1799ae397677bd3a68aff4eb4f5c122baf3ee73a26fe67391e0d618bd2b7d046", - "sha256:1e0498bc4a39d887e84801b82df5cc943a5ae4b596511da7e69df64b263f293b", - "sha256:27b9118b342dc464590ed233c7f468c8cb68ee0e5d9734d9b67fb0bc1b10abd6", - "sha256:32e1f478457adeea4e1a3d6baf33310331740cceffd83a2f34e00a7e5bae6407", - "sha256:37e20b1a0c623c7e01381668b83342387798d0f32ff8a7d7f3dd0ef127eb10fa", - "sha256:3e32018e65eabc9aab10c7a109be5f735cf2c3934a47025b6903dcec034d460b", - "sha256:4b9fa45f1b364e7585fd4a2781565667efed49124748fb3ec2a66e40b7398338", - "sha256:526417214a1cad27e3d2d064e535868ae05f5a07a0e344d54fe81078bbacfa57", - "sha256:540fa340b29dd86670e1f91bbcd2675df032b774f77d08909faf818696524617", - "sha256:64bfc55fe60ed9ad778ec73161f0cea58e425a3f2f06293756f82880319bffa9", - "sha256:685c41fce11c83a238ab40bd57d5b39c3fc4f87a898565cd27e4a521b5902a62", - "sha256:69c55e055e81a2eead40e6f2521ad27bdd11523dc0c1de5e5aea23041a0a49f0", - "sha256:6e0757762096158b803b366c386f25f24715662465c448ed70ce65ecd93e41a2", - "sha256:79ca8b8feab911a80692fa3871c02526844f112e0f8bf4749f78383696cfaa4c", - "sha256:807ac9d48c11b3f734d9de5eda69e1c4197204bac1e6db3d3d51859832df6fc1", - "sha256:84f037ba74482548c066ad5e341f77ebcd3d08d06a540a4a1182300045b8bde8", - "sha256:989d4817a2f22a601707ea36a3664a6c26cee155ed441363d5f29d73d9aec610", - "sha256:a148f8bdb54e03b1d899acb95aa6d870d6f10eed037d9b4700912068f3952c32", - "sha256:bb29a911c4a67f9710b53b94766be1bb22926b98460790091d4620a534329736", - "sha256:c8b595731b5c519daf2bf3c074ec2080eb51e8efef198a4493f930b5e4439bb0", - "sha256:d1735296d88e16379d001c4946c1a196b87e3c3ff4da0c10762918dded02f670", - "sha256:d73972a62d3e48ee01783d4eee01152c93348c70305c91f85fb668ddcc8907ad", - "sha256:dabf703efe12ec4341efd71c1dd384542e28fc49b7d2ea02f185ef22bb75a1c8", - "sha256:fdd80034749b8b2f211c2549293b34af691e4f90bf17b320a84b09b784275cc2" - ], - "index": "pypi", - "version": "==4.5.4.58" + "sha256:01f76ca55fdb7e94c3e7eab5035376d06518155e3d88a08096e4670e57a0cee4", + "sha256:03349d9fb28703b2eaa8b1f333a6139b9849596ae4445cb1d76e2a7f5e4a2cf8", + "sha256:29f5372dabdcd571074f0539bd294a2f5a245a00b871827af6d75a971b3f657e", + "sha256:30261b87477a718993fa7cd8a44b7de986b81f8005e23110978c58fd53eb5e43", + "sha256:33e534fbc7a417a05ef6b14812fe8ff6b6b7152c22d502b61536c50ad63f80cb", + "sha256:3a8457918ecbca57669f141e7dba92e56af370876d022d75d58b94174d11e26b", + "sha256:4ef93f338b16e95418b69293924745a36f23e3d05da5ee10dde76af72b0889e3", + "sha256:5009a183be7a6817ff216dcb63ef95022c74e360011fa52aa33bc833256693b5", + "sha256:5331ce17a094bea4f8132ee23b2eaade85904199c0d04501102c9bb889302c67", + "sha256:659107ea6059b5cc953e1a32136a54998540cefea47b01dd62f1e806d10cbe39", + "sha256:6d949ec3e10cffa915ab1853e490674b8c420ba29eb0aeea72785f3e254dc7a1", + "sha256:6e7710aff3a0717f39c9ade77fdd9111203b09589539655044e73cc5d9960666", + "sha256:7b4bd3c6a0d2601b2619ae406eb85a41dff538a7c9cb2a54fb1e90631bf33887", + "sha256:7da49405e163b7a2cf891bf54a877ff3e198bc0bfe55009c1d19eb5a0153921d", + "sha256:7f8dd594ea0b0049d1614d7bfba984ebd926b2f12670edf6ae3d9d5d6ff8f8f0", + "sha256:8f8a06f75dc69631404e0846038d30ff43c9a9d60fcffe07c7a88f8b8c8c776c", + "sha256:99e678db353102119cbfe9d17aef520bacf585a3a287c4278dd1ce6fcd3be8f7", + "sha256:a1f9d41c6afe86fdbe85ac31ff9a6ce893af2d0fce68fbd1581dbbc0e4dfcb25", + "sha256:a1fd5bbf5db00432fb368c73e7d70ead13f69619b33e01dabf2906426a1a9277", + "sha256:a5461ad9789c784e75713d6c213c0e34b709073c71ec8ed94129419ea0ce7c01", + "sha256:a6ba305364df31b8ac8471a719371d0c05e1e5f7cc5b8a2295e7e958f9bc39bb", + "sha256:bbf37d5de98b09e7513e61fca6ebf6466fd82c3c2f0475e51d2a3c80e0bc1a92", + "sha256:bc9502064e8c3ff6f40b74c8a68fb31d0c9eae18c1d3f52d4e3f0ccda986f7cb", + "sha256:cdea7ab1698b69274eb69b16efdd7b16944c5019c06f0ace9530f91862496cf4", + "sha256:cdfec5dedd44617d94725170446cbe77c0b45044188bdc97cd251e698aeee822", + "sha256:db112fe9ffde7af96df09befcefdd33c4338f3a34fbfe894e04e66e14f584d9e", + "sha256:db461f2f0bfac155d56be7688ab6b43c140ce8b944aa5e6cfcb754bfeeeca750", + "sha256:dc303a5e09089001fd4fd51bd18a6d519e81ad5cbc36bb4b5fc3388d22a64be1", + "sha256:eb9e571427b7f44b8d8f9a3b6b7b25e45bc8e8895ed3cf3ecd917c0125cf3477", + "sha256:f4fbd431b2b0014b7d99e870f428eebf50a0149e4be1a72b905569aaadf4b540" + ], + "index": "pypi", + "version": "==4.5.4.60" }, "packaging": { "hashes": [ - "sha256:096d689d78ca690e4cd8a89568ba06d07ca097e3306a4381635073ca91479966", - "sha256:14317396d1e8cdb122989b916fa2c7e9ca8e2be9e8060a6eff75b6b7b4d8a7e0" + "sha256:dd47c42927d89ab911e606518907cc2d3a1f38bbd026385970643f9c5b8ecfeb", + "sha256:ef103e05f519cdc783ae24ea4e2e0f508a9c99b2d4969652eed6a2e1ea5bd522" ], "markers": "python_version >= '3.6'", - "version": "==21.2" + "version": "==21.3" }, "parameterized": { "hashes": [ @@ -1923,11 +1951,11 @@ }, "pyparsing": { "hashes": [ - "sha256:c203ec8783bf771a155b207279b9bccb8dea02d8f0c9e5f8ead507bc3246ecc1", - "sha256:ef9d7589ef3c200abe66653d3f1ab1033c3c419ae9b9bdb1240a85b024efc88b" + "sha256:04ff808a5b90911829c55c4e26f75fa5ca8a2f5f36aa3a51f68e27033341d3e4", + "sha256:d9bdec0013ef1eb5a84ab39a3b3868911598afa494f5faa038647101504e2b81" ], - "markers": "python_version >= '2.6' and python_version not in '3.0, 3.1, 3.2, 3.3'", - "version": "==2.4.7" + "markers": "python_version >= '3.6'", + "version": "==3.0.6" }, "pyprof2calltree": { "hashes": [ @@ -2007,33 +2035,35 @@ }, "scipy": { "hashes": [ - "sha256:1437073f1d4664990879aa8f9547524764372e0fef84a077be4b19e82bba7a8d", - "sha256:17fd991a275e4283453f89d404209aa92059ac68d76d804b4bc1716a3742e1b5", - "sha256:1ea6233f5a365cb7945b4304bd06323ece3ece85d6a3fa8598d2f53e513467c9", - "sha256:2d25272c03ee3c0fe5e0dff1bb7889280bb6c9e1766fa9c7bde81ad8a5f78694", - "sha256:30bdda199667e74b50208a793eb1ba47a04e5e3fa16f5ff06c6f7969ae78e4da", - "sha256:359b60a0cccd17723b9d5e329a5212a710e771a3ddde800e472fb93732756c46", - "sha256:39f838ea5ce8da868785193d88d05cf5a6d5c390804ec99de29a28e1dcdd53e6", - "sha256:4d175ba93e00d8eef8f7cd70d4d88a9106a86800c82ea03cf2268c36d6545483", - "sha256:5273d832fb9cd5724ee0d335c16a903b923441107dd973d27fc4293075a9f4e3", - "sha256:54951f51d731c832b1b8885e0a92e89f33d087de7e40d02078bf0d49c7cbdbb5", - "sha256:74f518ce542533054695f743e4271cb8986b63f95bb51d70fcee4f3929cbff7d", - "sha256:7b1d0f5f524518f1a86f288443528e4ff4a739c0966db663af4129b7ac7849f8", - "sha256:82c5befebf54d799d77e5f0205c03030f57f69ba2541baa44d2e6ad138c28cd3", - "sha256:8482c8e45857ab0a5446eb7460d2307a27cbbe659d6d2257820c6d6eb950fd0f", - "sha256:87cf3964db0f1cce17aeed5bfc1b89a6b4b07dbfc48e50d21fa3549e00456803", - "sha256:8b5726a0fedeaa6beb1095e4466998bdd1d1e960b28db9b5a16c89cbd7b2ebf1", - "sha256:97eb573e361a73a553b915dc195c6f72a08249964b1a33f157f9659f3b6210d1", - "sha256:a80eb01c43fd98257ec7a49ff5cec0edba32031b5f86503f55399a48cb2c5379", - "sha256:cac71d5476a6f56b50459da21f6221707e0051ebd428b2137db32ef4a43bb15e", - "sha256:d86abd1ddf421dea5e9cebfeb4de0d205b3dc04e78249afedba9c6c3b2227ff2", - "sha256:dc2d1bf41294e63c7302bf499973ac0c7f73c93c01763db43055f6525234bf11", - "sha256:e08b81fcd9bf98740b58dc6fdd7879e33a64dcb682201c1135f7d4a75216bb05", - "sha256:e3efe7ef75dfe627b354ab0af0dbc918eadee97cc80ff1aabea6d3e01114ebdd", - "sha256:fa2dbabaaecdb502641b0b3c00dec05fb475ae48655c66da16c9ed24eda1e711" - ], - "index": "pypi", - "version": "==1.7.2" + "sha256:033ce76ed4e9f62923e1f8124f7e2b0800db533828c853b402c7eec6e9465d80", + "sha256:173308efba2270dcd61cd45a30dfded6ec0085b4b6eb33b5eb11ab443005e088", + "sha256:21b66200cf44b1c3e86495e3a436fc7a26608f92b8d43d344457c54f1c024cbc", + "sha256:2c56b820d304dffcadbbb6cbfbc2e2c79ee46ea291db17e288e73cd3c64fefa9", + "sha256:304dfaa7146cffdb75fbf6bb7c190fd7688795389ad060b970269c8576d038e9", + "sha256:3f78181a153fa21c018d346f595edd648344751d7f03ab94b398be2ad083ed3e", + "sha256:4d242d13206ca4302d83d8a6388c9dfce49fc48fdd3c20efad89ba12f785bf9e", + "sha256:5d1cc2c19afe3b5a546ede7e6a44ce1ff52e443d12b231823268019f608b9b12", + "sha256:5f2cfc359379c56b3a41b17ebd024109b2049f878badc1e454f31418c3a18436", + "sha256:65bd52bf55f9a1071398557394203d881384d27b9c2cad7df9a027170aeaef93", + "sha256:7edd9a311299a61e9919ea4192dd477395b50c014cdc1a1ac572d7c27e2207fa", + "sha256:8499d9dd1459dc0d0fe68db0832c3d5fc1361ae8e13d05e6849b358dc3f2c279", + "sha256:866ada14a95b083dd727a845a764cf95dd13ba3dc69a16b99038001b05439709", + "sha256:87069cf875f0262a6e3187ab0f419f5b4280d3dcf4811ef9613c605f6e4dca95", + "sha256:93378f3d14fff07572392ce6a6a2ceb3a1f237733bd6dcb9eb6a2b29b0d19085", + "sha256:95c2d250074cfa76715d58830579c64dff7354484b284c2b8b87e5a38321672c", + "sha256:ab5875facfdef77e0a47d5fd39ea178b58e60e454a4c85aa1e52fcb80db7babf", + "sha256:ca36e7d9430f7481fc7d11e015ae16fbd5575615a8e9060538104778be84addf", + "sha256:ceebc3c4f6a109777c0053dfa0282fddb8893eddfb0d598574acfb734a926168", + "sha256:e2c036492e673aad1b7b0d0ccdc0cb30a968353d2c4bf92ac8e73509e1bf212c", + "sha256:eb326658f9b73c07081300daba90a8746543b5ea177184daed26528273157294", + "sha256:eb7ae2c4dbdb3c9247e07acc532f91077ae6dbc40ad5bd5dca0bb5a176ee9bda", + "sha256:edad1cf5b2ce1912c4d8ddad20e11d333165552aba262c882e28c78bbc09dbf6", + "sha256:eef93a446114ac0193a7b714ce67659db80caf940f3232bad63f4c7a81bc18df", + "sha256:f7eaea089345a35130bc9a39b89ec1ff69c208efa97b3f8b25ea5d4c41d88094", + "sha256:f99d206db1f1ae735a8192ab93bd6028f3a42f6fa08467d37a14eb96c9dd34a3" + ], + "index": "pypi", + "version": "==1.7.3" }, "setuptools-scm": { "hashes": [ diff --git a/tools/sim/bridge.py b/tools/sim/bridge.py index 2873aa7223..ed129db6ee 100755 --- a/tools/sim/bridge.py +++ b/tools/sim/bridge.py @@ -1,19 +1,25 @@ #!/usr/bin/env python3 import argparse -import carla # pylint: disable=import-error import math -import numpy as np -import time import threading -from cereal import log +import time +import os from multiprocessing import Process, Queue from typing import Any +import carla # pylint: disable=import-error +import numpy as np +import pyopencl as cl +import pyopencl.array as cl_array +from lib.can import can_function + import cereal.messaging as messaging -from common.params import Params +from cereal import log +from cereal.visionipc.visionipc_pyx import VisionIpcServer, VisionStreamType # pylint: disable=no-name-in-module, import-error +from common.basedir import BASEDIR from common.numpy_fast import clip -from common.realtime import Ratekeeper, DT_DMON -from lib.can import can_function +from common.params import Params +from common.realtime import DT_DMON, Ratekeeper from selfdrive.car.honda.values import CruiseButtons from selfdrive.test.helpers import set_params_enabled @@ -21,18 +27,18 @@ parser = argparse.ArgumentParser(description='Bridge between CARLA and openpilot parser.add_argument('--joystick', action='store_true') parser.add_argument('--low_quality', action='store_true') parser.add_argument('--town', type=str, default='Town04_Opt') -parser.add_argument('--spawn_point', dest='num_selected_spawn_point', - type=int, default=16) +parser.add_argument('--spawn_point', dest='num_selected_spawn_point', type=int, default=16) args = parser.parse_args() -W, H = 1164, 874 +W, H = 1928, 1208 REPEAT_COUNTER = 5 PRINT_DECIMATION = 100 STEER_RATIO = 15. pm = messaging.PubMaster(['roadCameraState', 'sensorEvents', 'can', "gpsLocationExternal"]) -sm = messaging.SubMaster(['carControl','controlsState']) +sm = messaging.SubMaster(['carControl', 'controlsState']) + class VehicleState: def __init__(self): @@ -40,8 +46,9 @@ class VehicleState: self.angle = 0 self.bearing_deg = 0.0 self.vel = carla.Vector3D() - self.cruise_button= 0 - self.is_engaged=False + self.cruise_button = 0 + self.is_engaged = False + def steer_rate_limit(old, new): # Rate limiting to 0.5 degrees per step @@ -53,21 +60,56 @@ def steer_rate_limit(old, new): else: return new -frame_id = 0 -def cam_callback(image): - global frame_id - img = np.frombuffer(image.raw_data, dtype=np.dtype("uint8")) - img = np.reshape(img, (H, W, 4)) - img = img[:, :, [0, 1, 2]].copy() - - dat = messaging.new_message('roadCameraState') - dat.roadCameraState = { - "frameId": image.frame, - "image": img.tobytes(), - "transform": [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0] - } - pm.send('roadCameraState', dat) - frame_id += 1 + +class Camerad: + def __init__(self): + self.frame_id = 0 + self.vipc_server = VisionIpcServer("camerad") + + # TODO: remove RGB buffers once the last RGB vipc subscriber is removed + self.vipc_server.create_buffers(VisionStreamType.VISION_STREAM_RGB_BACK, 4, True, W, H) + self.vipc_server.create_buffers(VisionStreamType.VISION_STREAM_YUV_BACK, 40, False, W, H) + self.vipc_server.start_listener() + + # set up for pyopencl rgb to yuv conversion + self.ctx = cl.create_some_context() + self.queue = cl.CommandQueue(self.ctx) + cl_arg = f" -DHEIGHT={H} -DWIDTH={W} -DRGB_STRIDE={W*3} -DUV_WIDTH={W // 2} -DUV_HEIGHT={H // 2} -DRGB_SIZE={W * H} -DCL_DEBUG " + + # TODO: move rgb_to_yuv.cl to local dir once the frame stream camera is removed + kernel_fn = os.path.join(BASEDIR, "selfdrive", "camerad", "transforms", "rgb_to_yuv.cl") + prg = cl.Program(self.ctx, open(kernel_fn).read()).build(cl_arg) + self.krnl = prg.rgb_to_yuv + self.Wdiv4 = W // 4 if (W % 4 == 0) else (W + (4 - W % 4)) // 4 + self.Hdiv4 = H // 4 if (H % 4 == 0) else (H + (4 - H % 4)) // 4 + + def cam_callback(self, image): + img = np.frombuffer(image.raw_data, dtype=np.dtype("uint8")) + img = np.reshape(img, (H, W, 4)) + img = img[:, :, [0, 1, 2]].copy() + + # convert RGB frame to YUV + rgb = np.reshape(img, (H, W * 3)) + rgb_cl = cl_array.to_device(self.queue, rgb) + yuv_cl = cl_array.empty_like(rgb_cl) + self.krnl(self.queue, (np.int32(self.Wdiv4), np.int32(self.Hdiv4)), None, rgb_cl.data, yuv_cl.data).wait() + yuv = np.resize(yuv_cl.get(), np.int32((rgb.size / 2))) + eof = self.frame_id * 0.05 + + # TODO: remove RGB send once the last RGB vipc subscriber is removed + self.vipc_server.send(VisionStreamType.VISION_STREAM_RGB_BACK, img.tobytes(), self.frame_id, eof, eof) + self.vipc_server.send(VisionStreamType.VISION_STREAM_YUV_BACK, yuv.data.tobytes(), self.frame_id, eof, eof) + + dat = messaging.new_message('roadCameraState') + dat.roadCameraState = { + "frameId": image.frame, + "transform": [1.0, 0.0, 0.0, + 0.0, 1.0, 0.0, + 0.0, 0.0, 1.0] + } + pm.send('roadCameraState', dat) + self.frame_id += 1 + def imu_callback(imu, vehicle_state): vehicle_state.bearing_deg = math.degrees(imu.compass) @@ -83,6 +125,7 @@ def imu_callback(imu, vehicle_state): dat.sensorEvents[1].gyroUncalibrated.v = [imu.gyroscope.x, imu.gyroscope.y, imu.gyroscope.z] pm.send('sensorEvents', dat) + def panda_state_function(exit_event: threading.Event): pm = messaging.PubMaster(['pandaStates']) while not exit_event.is_set(): @@ -97,6 +140,7 @@ def panda_state_function(exit_event: threading.Event): pm.send('pandaStates', dat) time.sleep(0.5) + def peripheral_state_function(exit_event: threading.Event): pm = messaging.PubMaster(['peripheralState']) while not exit_event.is_set(): @@ -112,20 +156,21 @@ def peripheral_state_function(exit_event: threading.Event): pm.send('peripheralState', dat) time.sleep(0.5) + def gps_callback(gps, vehicle_state): dat = messaging.new_message('gpsLocationExternal') # transform vel from carla to NED # north is -Y in CARLA velNED = [ - -vehicle_state.vel.y, # north/south component of NED is negative when moving south - vehicle_state.vel.x, # positive when moving east, which is x in carla + -vehicle_state.vel.y, # north/south component of NED is negative when moving south + vehicle_state.vel.x, # positive when moving east, which is x in carla vehicle_state.vel.z, ] dat.gpsLocationExternal = { "timestamp": int(time.time() * 1000), - "flags": 1, # valid fix + "flags": 1, # valid fix "accuracy": 1.0, "verticalAccuracy": 1.0, "speedAccuracy": 0.1, @@ -141,8 +186,9 @@ def gps_callback(gps, vehicle_state): pm.send('gpsLocationExternal', dat) + def fake_driver_monitoring(exit_event: threading.Event): - pm = messaging.PubMaster(['driverState','driverMonitoringState']) + pm = messaging.PubMaster(['driverState', 'driverMonitoringState']) while not exit_event.is_set(): # dmonitoringmodeld output dat = messaging.new_message('driverState') @@ -160,16 +206,16 @@ def fake_driver_monitoring(exit_event: threading.Event): time.sleep(DT_DMON) + def can_function_runner(vs: VehicleState, exit_event: threading.Event): i = 0 while not exit_event.is_set(): can_function(pm, vs.speed, vs.angle, i, vs.cruise_button, vs.is_engaged) time.sleep(0.01) - i+=1 + i += 1 def bridge(q): - # setup CARLA client = carla.Client("127.0.0.1", 2000) client.set_timeout(10.0) @@ -209,11 +255,12 @@ def bridge(q): blueprint = blueprint_library.find('sensor.camera.rgb') blueprint.set_attribute('image_size_x', str(W)) blueprint.set_attribute('image_size_y', str(H)) - blueprint.set_attribute('fov', '70') + blueprint.set_attribute('fov', '40') blueprint.set_attribute('sensor_tick', '0.05') transform = carla.Transform(carla.Location(x=0.8, z=1.13)) camera = world.spawn_actor(blueprint, transform, attach_to=vehicle) - camera.listen(cam_callback) + camerad = Camerad() + camera.listen(camerad.cam_callback) vehicle_state = VehicleState() @@ -244,7 +291,6 @@ def bridge(q): brake_ease_out_counter = REPEAT_COUNTER steer_ease_out_counter = REPEAT_COUNTER - vc = carla.VehicleControl(throttle=0, steer=0, brake=0, reverse=False) is_openpilot_engaged = False @@ -253,12 +299,11 @@ def bridge(q): throttle_manual = steer_manual = brake_manual = 0 old_steer = old_brake = old_throttle = 0 - throttle_manual_multiplier = 0.7 #keyboard signal is always 1 - brake_manual_multiplier = 0.7 #keyboard signal is always 1 - steer_manual_multiplier = 45 * STEER_RATIO #keyboard signal is always 1 - + throttle_manual_multiplier = 0.7 # keyboard signal is always 1 + brake_manual_multiplier = 0.7 # keyboard signal is always 1 + steer_manual_multiplier = 45 * STEER_RATIO # keyboard signal is always 1 - while 1: + while True: # 1. Read the throttle, steer and brake from op or manual controls # 2. Set instructions in Carla # 3. Send current carstate to op via can @@ -282,7 +327,6 @@ def bridge(q): brake_manual = float(m[1]) is_openpilot_engaged = False elif m[0] == "reverse": - #in_reverse = not in_reverse cruise_button = CruiseButtons.CANCEL is_openpilot_engaged = False elif m[0] == "cruise": @@ -302,19 +346,16 @@ def bridge(q): steer_out = steer_manual * steer_manual_multiplier brake_out = brake_manual * brake_manual_multiplier - #steer_out = steer_out - # steer_out = steer_rate_limit(old_steer, steer_out) old_steer = steer_out old_throttle = throttle_out old_brake = brake_out - # print('message',old_throttle, old_steer, old_brake) - if is_openpilot_engaged: sm.update(0) + # TODO gas and brake is deprecated - throttle_op = clip(sm['carControl'].actuators.accel/1.6, 0.0, 1.0) - brake_op = clip(-sm['carControl'].actuators.accel/4.0, 0.0, 1.0) + throttle_op = clip(sm['carControl'].actuators.accel / 1.6, 0.0, 1.0) + brake_op = clip(-sm['carControl'].actuators.accel / 4.0, 0.0, 1.0) steer_op = sm['carControl'].actuators.steeringAngleDeg throttle_out = throttle_op @@ -325,24 +366,24 @@ def bridge(q): old_steer = steer_out else: - if throttle_out==0 and old_throttle>0: - if throttle_ease_out_counter>0: + if throttle_out == 0 and old_throttle > 0: + if throttle_ease_out_counter > 0: throttle_out = old_throttle throttle_ease_out_counter += -1 else: throttle_ease_out_counter = REPEAT_COUNTER old_throttle = 0 - if brake_out==0 and old_brake>0: - if brake_ease_out_counter>0: + if brake_out == 0 and old_brake > 0: + if brake_ease_out_counter > 0: brake_out = old_brake brake_ease_out_counter += -1 else: brake_ease_out_counter = REPEAT_COUNTER old_brake = 0 - if steer_out==0 and old_steer!=0: - if steer_ease_out_counter>0: + if steer_out == 0 and old_steer != 0: + if steer_ease_out_counter > 0: steer_out = old_steer steer_ease_out_counter += -1 else: @@ -350,28 +391,27 @@ def bridge(q): old_steer = 0 # --------------Step 2------------------------------- - steer_carla = steer_out / (max_steer_angle * STEER_RATIO * -1) - steer_carla = np.clip(steer_carla, -1,1) + steer_carla = np.clip(steer_carla, -1, 1) steer_out = steer_carla * (max_steer_angle * STEER_RATIO * -1) old_steer = steer_carla * (max_steer_angle * STEER_RATIO * -1) - vc.throttle = throttle_out/0.6 + vc.throttle = throttle_out / 0.6 vc.steer = steer_carla vc.brake = brake_out vehicle.apply_control(vc) # --------------Step 3------------------------------- vel = vehicle.get_velocity() - speed = math.sqrt(vel.x**2 + vel.y**2 + vel.z**2) # in m/s + speed = math.sqrt(vel.x**2 + vel.y**2 + vel.z**2) # in m/s vehicle_state.speed = speed vehicle_state.vel = vel vehicle_state.angle = steer_out vehicle_state.cruise_button = cruise_button vehicle_state.is_engaged = is_openpilot_engaged - if rk.frame%PRINT_DECIMATION == 0: + if rk.frame % PRINT_DECIMATION == 0: print("frame: ", "engaged:", is_openpilot_engaged, "; throttle: ", round(vc.throttle, 3), "; steer(c/deg): ", round(vc.steer, 3), round(steer_out, 3), "; brake: ", round(vc.brake, 3)) rk.keep_time() @@ -385,6 +425,7 @@ def bridge(q): camera.destroy() vehicle.destroy() + def bridge_keep_alive(q: Any): while 1: try: @@ -393,6 +434,7 @@ def bridge_keep_alive(q: Any): except RuntimeError: print("Restarting bridge...") + if __name__ == "__main__": # make sure params are in a good state set_params_enabled() diff --git a/tools/sim/launch_openpilot.sh b/tools/sim/launch_openpilot.sh index e10d688c2f..b94a453b7b 100755 --- a/tools/sim/launch_openpilot.sh +++ b/tools/sim/launch_openpilot.sh @@ -5,8 +5,7 @@ export NOBOARD="1" export SIMULATION="1" export FINGERPRINT="HONDA CIVIC 2016" -# TODO: remove this once the bridge uses visionipc -export BLOCK="loggerd" +export BLOCK="camerad,loggerd" DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null && pwd )" cd ../../selfdrive/manager && ./manager.py diff --git a/tools/sim/lib/can.py b/tools/sim/lib/can.py index 97754ab0b8..4873947d4b 100755 --- a/tools/sim/lib/can.py +++ b/tools/sim/lib/can.py @@ -62,7 +62,7 @@ def can_function(pm, speed, angle, idx, cruise_button, is_engaged): msg.append(packer.make_can_msg("CRUISE", 0, {}, idx)) msg.append(packer.make_can_msg("SCM_FEEDBACK", 0, {"MAIN_ON": 1}, idx)) msg.append(packer.make_can_msg("POWERTRAIN_DATA", 0, {"ACC_STATUS": int(is_engaged)}, idx)) - msg.append(packer.make_can_msg("HUD_SETTING", 0, {}, idx)) + msg.append(packer.make_can_msg("HUD_SETTING", 0, {})) # *** cam bus *** msg.append(packer.make_can_msg("STEERING_CONTROL", 2, {}, idx)) From 50cd8588a27834bfd01d95ed452cf8ac247cb584 Mon Sep 17 00:00:00 2001 From: George Hotz Date: Sat, 27 Nov 2021 00:28:33 -0500 Subject: [PATCH 034/102] boardd: be careful with paren order in assert --- selfdrive/boardd/panda.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/boardd/panda.cc b/selfdrive/boardd/panda.cc index 6dc458a8c3..9315ebe6d0 100644 --- a/selfdrive/boardd/panda.cc +++ b/selfdrive/boardd/panda.cc @@ -384,7 +384,7 @@ void Panda::pack_can_buffer(const capnp::List::Reader &can_data } auto can_data = cmsg.getDat(); uint8_t data_len_code = len_to_dlc(can_data.size()); - assert(can_data.size() <= (hw_type == cereal::PandaState::PandaType::RED_PANDA) ? 64 : 8); + assert(can_data.size() <= ((hw_type == cereal::PandaState::PandaType::RED_PANDA) ? 64 : 8)); assert(can_data.size() == dlc_to_len[data_len_code]); can_header header; From c6f62ebc4f661c4b597e8bde971aa8617cfc5bcb Mon Sep 17 00:00:00 2001 From: George Hotz Date: Sat, 27 Nov 2021 00:57:30 -0500 Subject: [PATCH 035/102] Revert "boardd: be careful with paren order in assert" This reverts commit 50cd8588a27834bfd01d95ed452cf8ac247cb584. --- selfdrive/boardd/panda.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/boardd/panda.cc b/selfdrive/boardd/panda.cc index 9315ebe6d0..6dc458a8c3 100644 --- a/selfdrive/boardd/panda.cc +++ b/selfdrive/boardd/panda.cc @@ -384,7 +384,7 @@ void Panda::pack_can_buffer(const capnp::List::Reader &can_data } auto can_data = cmsg.getDat(); uint8_t data_len_code = len_to_dlc(can_data.size()); - assert(can_data.size() <= ((hw_type == cereal::PandaState::PandaType::RED_PANDA) ? 64 : 8)); + assert(can_data.size() <= (hw_type == cereal::PandaState::PandaType::RED_PANDA) ? 64 : 8); assert(can_data.size() == dlc_to_len[data_len_code]); can_header header; From b2a018643fb3caa30e7baa5b6be61b8ec4b734f1 Mon Sep 17 00:00:00 2001 From: Igor Biletskyy Date: Sat, 27 Nov 2021 12:22:54 -0800 Subject: [PATCH 036/102] Extra check for tail_size length (#23047) --- selfdrive/boardd/panda.cc | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/boardd/panda.cc b/selfdrive/boardd/panda.cc index 6dc458a8c3..efe8555999 100644 --- a/selfdrive/boardd/panda.cc +++ b/selfdrive/boardd/panda.cc @@ -478,6 +478,7 @@ bool Panda::unpack_can_buffer(uint8_t *data, int size, std::vector &o } else { // Keep partial CAN packet until next USB packet tail_size = (chunk_len - pos); + assert(tail_size <= CANPACKET_MAX_SIZE); memcpy(tail, &chunk[pos], tail_size); break; } From 8160cf3c1b2726709db58219c33d1616b4a8acb5 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sat, 27 Nov 2021 21:58:21 -0800 Subject: [PATCH 037/102] camerad: remove camera frame stream (#23045) * camerad: remove camera frame stream * fix release files --- SConstruct | 3 +- release/files_common | 2 - selfdrive/camerad/SConscript | 17 ++-- .../camerad/cameras/camera_frame_stream.cc | 92 ------------------- .../camerad/cameras/camera_frame_stream.h | 30 ------ tools/sim/Dockerfile.sim | 2 +- 6 files changed, 9 insertions(+), 137 deletions(-) delete mode 100644 selfdrive/camerad/cameras/camera_frame_stream.cc delete mode 100644 selfdrive/camerad/cameras/camera_frame_stream.h diff --git a/SConstruct b/SConstruct index 30bb425461..a66290aabf 100644 --- a/SConstruct +++ b/SConstruct @@ -60,7 +60,6 @@ if arch == "aarch64" and TICI: arch = "larch64" USE_WEBCAM = os.getenv("USE_WEBCAM") is not None -USE_FRAME_STREAM = os.getenv("USE_FRAME_STREAM") is not None lenv = { "PATH": os.environ['PATH'], @@ -352,7 +351,7 @@ if GetOption("clazy"): qt_env['ENV']['CLAZY_IGNORE_DIRS'] = qt_dirs[0] qt_env['ENV']['CLAZY_CHECKS'] = ','.join(checks) -Export('env', 'qt_env', 'arch', 'real_arch', 'SHARED', 'USE_WEBCAM', 'USE_FRAME_STREAM') +Export('env', 'qt_env', 'arch', 'real_arch', 'SHARED', 'USE_WEBCAM') SConscript(['selfdrive/common/SConscript']) Import('_common', '_gpucommon', '_gpu_libs') diff --git a/release/files_common b/release/files_common index 2ef34106c3..527c87be66 100644 --- a/release/files_common +++ b/release/files_common @@ -368,8 +368,6 @@ selfdrive/camerad/snapshot/* selfdrive/camerad/include/* selfdrive/camerad/cameras/camera_common.h selfdrive/camerad/cameras/camera_common.cc -selfdrive/camerad/cameras/camera_frame_stream.cc -selfdrive/camerad/cameras/camera_frame_stream.h selfdrive/camerad/cameras/camera_qcom.cc selfdrive/camerad/cameras/camera_qcom.h selfdrive/camerad/cameras/camera_replay.cc diff --git a/selfdrive/camerad/SConscript b/selfdrive/camerad/SConscript index 5a2b73c61f..85bc756bc1 100644 --- a/selfdrive/camerad/SConscript +++ b/selfdrive/camerad/SConscript @@ -1,4 +1,4 @@ -Import('env', 'arch', 'cereal', 'messaging', 'common', 'gpucommon', 'visionipc', 'USE_WEBCAM', 'USE_FRAME_STREAM') +Import('env', 'arch', 'cereal', 'messaging', 'common', 'gpucommon', 'visionipc', 'USE_WEBCAM') libs = ['m', 'pthread', common, 'jpeg', 'OpenCL', 'yuv', cereal, messaging, 'zmq', 'capnp', 'kj', visionipc, gpucommon] @@ -18,15 +18,12 @@ else: env.Append(CFLAGS = '-DWEBCAM') env.Append(CPPPATH = ['/usr/include/opencv4', '/usr/local/include/opencv4']) else: - if USE_FRAME_STREAM: - cameras = ['cameras/camera_frame_stream.cc'] - else: - libs += ['avutil', 'avcodec', 'avformat', 'bz2', 'ssl', 'curl', 'crypto'] - # TODO: import replay_lib from root SConstruct - cameras = ['cameras/camera_replay.cc', - env.Object('camera-util', '#/selfdrive/ui/replay/util.cc'), - env.Object('camera-framereader', '#/selfdrive/ui/replay/framereader.cc'), - env.Object('camera-filereader', '#/selfdrive/ui/replay/filereader.cc')] + libs += ['avutil', 'avcodec', 'avformat', 'bz2', 'ssl', 'curl', 'crypto'] + # TODO: import replay_lib from root SConstruct + cameras = ['cameras/camera_replay.cc', + env.Object('camera-util', '#/selfdrive/ui/replay/util.cc'), + env.Object('camera-framereader', '#/selfdrive/ui/replay/framereader.cc'), + env.Object('camera-filereader', '#/selfdrive/ui/replay/filereader.cc')] if arch == "Darwin": del libs[libs.index('OpenCL')] diff --git a/selfdrive/camerad/cameras/camera_frame_stream.cc b/selfdrive/camerad/cameras/camera_frame_stream.cc deleted file mode 100644 index 8e6c69e361..0000000000 --- a/selfdrive/camerad/cameras/camera_frame_stream.cc +++ /dev/null @@ -1,92 +0,0 @@ -#include "selfdrive/camerad/cameras/camera_frame_stream.h" - -#include -#include - -#include - -#include "cereal/messaging/messaging.h" -#include "selfdrive/common/util.h" - -#define FRAME_WIDTH 1164 -#define FRAME_HEIGHT 874 - -extern ExitHandler do_exit; - -namespace { - -// TODO: make this more generic -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, - }, - [CAMERA_ID_OV8865] = { - .frame_width = 1632, - .frame_height = 1224, - .frame_stride = 2040, // seems right - .bayer = false, - .bayer_flip = 3, - .hdr = false - }, -}; - -void camera_init(VisionIpcServer * v, CameraState *s, int camera_id, unsigned int fps, cl_device_id device_id, cl_context ctx, VisionStreamType rgb_type, VisionStreamType yuv_type) { - assert(camera_id < std::size(cameras_supported)); - s->ci = cameras_supported[camera_id]; - assert(s->ci.frame_width != 0); - - s->camera_num = camera_id; - s->fps = fps; - s->buf.init(device_id, ctx, s, v, FRAME_BUF_COUNT, rgb_type, yuv_type); -} - -void run_frame_stream(CameraState &camera, const char* frame_pkt) { - SubMaster sm({frame_pkt}); - - size_t buf_idx = 0; - while (!do_exit) { - sm.update(1000); - if(sm.updated(frame_pkt)) { - auto msg = static_cast(sm[frame_pkt]); - auto frame = msg.get(frame_pkt).as(); - camera.buf.camera_bufs_metadata[buf_idx] = { - .frame_id = frame.get("frameId").as(), - .timestamp_eof = frame.get("timestampEof").as(), - .timestamp_sof = frame.get("timestampSof").as(), - }; - - cl_command_queue q = camera.buf.camera_bufs[buf_idx].copy_q; - cl_mem yuv_cl = camera.buf.camera_bufs[buf_idx].buf_cl; - - auto image = frame.get("image").as(); - clEnqueueWriteBuffer(q, yuv_cl, CL_TRUE, 0, image.size(), image.begin(), 0, NULL, NULL); - camera.buf.queue(buf_idx); - buf_idx = (buf_idx + 1) % FRAME_BUF_COUNT; - } - } -} - -} // namespace - -void cameras_init(VisionIpcServer *v, MultiCameraState *s, cl_device_id device_id, cl_context ctx) { - camera_init(v, &s->road_cam, CAMERA_ID_IMX298, 20, device_id, ctx, - VISION_STREAM_RGB_BACK, VISION_STREAM_YUV_BACK); - camera_init(v, &s->driver_cam, CAMERA_ID_OV8865, 10, device_id, ctx, - VISION_STREAM_RGB_FRONT, VISION_STREAM_YUV_FRONT); -} - -void cameras_open(MultiCameraState *s) {} -void cameras_close(MultiCameraState *s) {} -void camera_autoexposure(CameraState *s, float grey_frac) {} -void process_road_camera(MultiCameraState *s, CameraState *c, int cnt) {} - -void cameras_run(MultiCameraState *s) { - std::thread t = start_process_thread(s, &s->road_cam, process_road_camera); - set_thread_name("frame_streaming"); - run_frame_stream(s->road_cam, "roadCameraState"); - t.join(); -} diff --git a/selfdrive/camerad/cameras/camera_frame_stream.h b/selfdrive/camerad/cameras/camera_frame_stream.h deleted file mode 100644 index 0d4d8cfb42..0000000000 --- a/selfdrive/camerad/cameras/camera_frame_stream.h +++ /dev/null @@ -1,30 +0,0 @@ -#pragma once - -#define CL_USE_DEPRECATED_OPENCL_1_2_APIS -#ifdef __APPLE__ -#include -#else -#include -#endif - -#include "camera_common.h" - -#define FRAME_BUF_COUNT 16 - -typedef struct CameraState { - int camera_num; - CameraInfo ci; - - int fps; - float digital_gain; - - CameraBuf buf; -} CameraState; - -typedef struct MultiCameraState { - CameraState road_cam; - CameraState driver_cam; - - SubMaster *sm; - PubMaster *pm; -} MultiCameraState; diff --git a/tools/sim/Dockerfile.sim b/tools/sim/Dockerfile.sim index cff02565f1..f6cf0d9b0b 100644 --- a/tools/sim/Dockerfile.sim +++ b/tools/sim/Dockerfile.sim @@ -62,4 +62,4 @@ COPY ./selfdrive $HOME/openpilot/selfdrive COPY ./tools $HOME/openpilot/tools WORKDIR $HOME/openpilot -RUN USE_FRAME_STREAM=1 scons -j$(nproc) +RUN scons -j$(nproc) From a4ca8e4835949f5f8a5d6123142f9ffcb7e36245 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Sun, 28 Nov 2021 11:32:37 +0100 Subject: [PATCH 038/102] sim: improve carla performance (#23046) --- tools/sim/bridge.py | 12 +++++++++++- tools/sim/start_carla.sh | 2 +- 2 files changed, 12 insertions(+), 2 deletions(-) diff --git a/tools/sim/bridge.py b/tools/sim/bridge.py index ed129db6ee..dc948d0fd5 100755 --- a/tools/sim/bridge.py +++ b/tools/sim/bridge.py @@ -221,13 +221,20 @@ def bridge(q): client.set_timeout(10.0) world = client.load_world(args.town) + settings = world.get_settings() + settings.synchronous_mode = True # Enables synchronous mode + settings.fixed_delta_seconds = 0.05 + world.apply_settings(settings) + + world.set_weather(carla.WeatherParameters.ClearSunset) + if args.low_quality: world.unload_map_layer(carla.MapLayer.Foliage) world.unload_map_layer(carla.MapLayer.Buildings) world.unload_map_layer(carla.MapLayer.ParkedVehicles) - world.unload_map_layer(carla.MapLayer.Particles) world.unload_map_layer(carla.MapLayer.Props) world.unload_map_layer(carla.MapLayer.StreetLights) + world.unload_map_layer(carla.MapLayer.Particles) blueprint_library = world.get_blueprint_library() @@ -414,6 +421,9 @@ def bridge(q): if rk.frame % PRINT_DECIMATION == 0: print("frame: ", "engaged:", is_openpilot_engaged, "; throttle: ", round(vc.throttle, 3), "; steer(c/deg): ", round(vc.steer, 3), round(steer_out, 3), "; brake: ", round(vc.brake, 3)) + if rk.frame % 5 == 0: + world.tick() + rk.keep_time() # Clean up resources in the opposite order they were created. diff --git a/tools/sim/start_carla.sh b/tools/sim/start_carla.sh index df6e2a3fa3..6418dacaee 100755 --- a/tools/sim/start_carla.sh +++ b/tools/sim/start_carla.sh @@ -24,4 +24,4 @@ docker run \ -v /tmp/.X11-unix:/tmp/.X11-unix:rw \ -it \ carlasim/carla:0.9.12 \ - /bin/bash ./CarlaUE4.sh -opengl -nosound -RenderOffScreen -quality-level=Epic + /bin/bash ./CarlaUE4.sh -opengl -nosound -RenderOffScreen -benchmark -fps=20 -quality-level=High From a449b856cac746647ad994eb511600929d529498 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Mon, 29 Nov 2021 05:29:40 +0800 Subject: [PATCH 039/102] framereader: fix crash after fallback to cpu decoding (#23055) --- selfdrive/ui/replay/framereader.cc | 9 ++++++--- selfdrive/ui/replay/framereader.h | 1 + 2 files changed, 7 insertions(+), 3 deletions(-) diff --git a/selfdrive/ui/replay/framereader.cc b/selfdrive/ui/replay/framereader.cc index 29172a58b2..76e9ea7d66 100644 --- a/selfdrive/ui/replay/framereader.cc +++ b/selfdrive/ui/replay/framereader.cc @@ -27,8 +27,9 @@ enum AVPixelFormat get_hw_format(AVCodecContext *ctx, const enum AVPixelFormat * if (*p == *hw_pix_fmt) return *p; } printf("Please run replay with the --no-cuda flag!\n"); - assert(0); - return AV_PIX_FMT_NONE; + // fallback to YUV420p + *hw_pix_fmt = AV_PIX_FMT_NONE; + return AV_PIX_FMT_YUV420P; } } // namespace @@ -94,7 +95,7 @@ bool FrameReader::load(const std::string &url, bool no_cuda, std::atomic * width = (decoder_ctx->width + 3) & ~3; height = decoder_ctx->height; - if (!no_cuda) { + if (has_cuda_device && !no_cuda) { if (!initHardwareDecoder(AV_HWDEVICE_TYPE_CUDA)) { printf("No CUDA capable device was found. fallback to CPU decoding.\n"); } else { @@ -136,6 +137,8 @@ bool FrameReader::initHardwareDecoder(AVHWDeviceType hw_device_type) { int ret = av_hwdevice_ctx_create(&hw_device_ctx, hw_device_type, nullptr, nullptr, 0); if (ret < 0) { + hw_pix_fmt = AV_PIX_FMT_NONE; + has_cuda_device = false; printf("Failed to create specified HW device %d.\n", ret); return false; } diff --git a/selfdrive/ui/replay/framereader.h b/selfdrive/ui/replay/framereader.h index 7bb63d72f7..f6895c7be6 100644 --- a/selfdrive/ui/replay/framereader.h +++ b/selfdrive/ui/replay/framereader.h @@ -50,4 +50,5 @@ private: AVPixelFormat hw_pix_fmt = AV_PIX_FMT_NONE; AVBufferRef *hw_device_ctx = nullptr; std::vector nv12toyuv_buffer; + inline static std::atomic has_cuda_device = true; }; From 7237128a1d106ba1781cdcd33807ab155d875684 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 28 Nov 2021 13:33:46 -0800 Subject: [PATCH 040/102] script to apply patch from PR --- scripts/apply-pr.sh | 11 +++++++++++ 1 file changed, 11 insertions(+) create mode 100755 scripts/apply-pr.sh diff --git a/scripts/apply-pr.sh b/scripts/apply-pr.sh new file mode 100755 index 0000000000..65805b8485 --- /dev/null +++ b/scripts/apply-pr.sh @@ -0,0 +1,11 @@ +#!/bin/bash + +if [ $# -eq 0 ]; then + echo "usage: $0 " + exit 1 +fi + +BASE="https://github.com/commaai/openpilot/pull/" +PR_NUM="$(echo $1 | grep -o -E '[0-9]+')" + +curl -L $BASE/$PR_NUM.patch | git apply From 08f9316b56ffe2c36a5d9c23d0b4df49903ad52a Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 28 Nov 2021 14:02:06 -0800 Subject: [PATCH 041/102] remove dead + duplicate python code --- common/cython_hacks.py | 23 ----------------------- release/files_common | 1 - tools/lib/lazy_property.py | 12 ------------ 3 files changed, 36 deletions(-) delete mode 100644 common/cython_hacks.py delete mode 100644 tools/lib/lazy_property.py diff --git a/common/cython_hacks.py b/common/cython_hacks.py deleted file mode 100644 index d0e154746d..0000000000 --- a/common/cython_hacks.py +++ /dev/null @@ -1,23 +0,0 @@ -import os -import sysconfig -from Cython.Distutils import build_ext - -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) diff --git a/release/files_common b/release/files_common index 527c87be66..902242bcd7 100644 --- a/release/files_common +++ b/release/files_common @@ -36,7 +36,6 @@ common/filter_simple.py common/stat_live.py common/spinner.py common/text_window.py -common/cython_hacks.py common/SConscript common/kalman/.gitignore diff --git a/tools/lib/lazy_property.py b/tools/lib/lazy_property.py deleted file mode 100644 index 85c038f287..0000000000 --- a/tools/lib/lazy_property.py +++ /dev/null @@ -1,12 +0,0 @@ -class lazy_property(object): - """Defines a property whose value will be computed only once and as needed. - - This can only be used on instance methods. - """ - def __init__(self, func): - self._func = func - - def __get__(self, obj_self, cls): - value = self._func(obj_self) - setattr(obj_self, self._func.__name__, value) - return value From 920b751888a09192f055241c7db6cfdfc5f1bf57 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 28 Nov 2021 14:19:49 -0800 Subject: [PATCH 042/102] juggle: add demo flag and improve README --- tools/plotjuggler/README.md | 23 +++++++++++++++-------- tools/plotjuggler/juggle.py | 10 +++++++--- 2 files changed, 22 insertions(+), 11 deletions(-) diff --git a/tools/plotjuggler/README.md b/tools/plotjuggler/README.md index f462cadece..8ab150e821 100644 --- a/tools/plotjuggler/README.md +++ b/tools/plotjuggler/README.md @@ -1,10 +1,12 @@ # PlotJuggler -We've extended [PlotJuggler](https://github.com/facontidavide/PlotJuggler) to plot all of your openpilot logs. Check out our plugins: https://github.com/commaai/PlotJuggler. +[PlotJuggler](https://github.com/facontidavide/PlotJuggler) is a tool to quickly visualize time series data, and we've written plugins to parse openpilot logs. Check out our plugins: https://github.com/commaai/PlotJuggler. ## Installation -Once you've cloned and are in openpilot, download PlotJuggler and install our plugins with this command: +**NOTE: this is Ubuntu only for now. Pull requests for macOS support are welcome.** + +Once you've cloned and are in openpilot, this command will download PlotJuggler and install our plugins: `cd tools/plotjuggler && ./install.sh` @@ -12,9 +14,9 @@ Once you've cloned and are in openpilot, download PlotJuggler and install our pl ``` $ ./juggle.py -h -usage: juggle.py [-h] [--qlog] [--can] [--stream] [--layout [LAYOUT]] [route_name] [segment_number] [segment_count] +usage: juggle.py [-h] [--demo] [--qlog] [--can] [--stream] [--layout [LAYOUT]] [route_name] [segment_number] [segment_count] -PlotJuggler plugin for reading openpilot logs +A helper to run PlotJuggler on openpilot routes positional arguments: route_name The route name to plot (cabana share URL accepted) (default: None) @@ -23,9 +25,10 @@ positional arguments: optional arguments: -h, --help show this help message and exit + --demo Use the demo route instead of providing one (default: False) --qlog Use qlogs (default: False) --can Parse CAN data (default: False) - --stream Start PlotJuggler without a route to stream data using Cereal (default: False) + --stream Start PlotJuggler in streaming mode (default: False) --layout [LAYOUT] Run PlotJuggler with a pre-defined layout (default: None) ``` @@ -47,11 +50,15 @@ If streaming to PlotJuggler from a replay on your PC, simply run: `./juggle.py - For a quick demo, go through the installation step and run this command: -`./juggle.py "https://commadataci.blob.core.windows.net/openpilotci/d83f36766f8012a5/2020-02-05--18-42-21/0/rlog.bz2" --layout=layouts/demo.xml` +`./juggle.py --demo --qlog --layout=layouts/demo.xml` + +## Layouts + +If you create a layout that's useful for others, consider upstreaming it. -## Tuning +### Tuning -Use this layout to generate plots for tuning PRs. Also see tuning wiki and tuning PR template. +Use this layout to improve your car's tuning and generate plots for tuning PRs. Also see the tuning wiki and tuning PR template. `--layout layouts/tuning.xml` diff --git a/tools/plotjuggler/juggle.py b/tools/plotjuggler/juggle.py index 151e4a49c4..d488750701 100755 --- a/tools/plotjuggler/juggle.py +++ b/tools/plotjuggler/juggle.py @@ -16,6 +16,8 @@ from urllib.parse import urlparse, parse_qs juggle_dir = os.path.dirname(os.path.realpath(__file__)) +DEMO_ROUTE = "4cf7a6ad03080c90|2021-09-29--13-46-36" + def load_segment(segment_name): print(f"Loading {segment_name}") if segment_name is None: @@ -94,12 +96,13 @@ def juggle_route(route_name, segment_number, segment_count, qlog, can, layout): start_juggler(tempfile.name, dbc, layout) def get_arg_parser(): - parser = argparse.ArgumentParser(description="PlotJuggler plugin for reading openpilot logs", + parser = argparse.ArgumentParser(description="A helper to run PlotJuggler on openpilot routes", formatter_class=argparse.ArgumentDefaultsHelpFormatter) + parser.add_argument("--demo", action="store_true", help="Use the demo route instead of providing one") parser.add_argument("--qlog", action="store_true", help="Use qlogs") parser.add_argument("--can", action="store_true", help="Parse CAN data") - parser.add_argument("--stream", action="store_true", help="Start PlotJuggler without a route to stream data using Cereal") + parser.add_argument("--stream", action="store_true", help="Start PlotJuggler in streaming mode") parser.add_argument("--layout", nargs='?', help="Run PlotJuggler with a pre-defined layout") parser.add_argument("route_name", nargs='?', help="The route name to plot (cabana share URL accepted)") parser.add_argument("segment_number", type=int, nargs='?', help="The index of the segment to plot") @@ -116,4 +119,5 @@ if __name__ == "__main__": if args.stream: start_juggler(layout=args.layout) else: - juggle_route(args.route_name.strip(), args.segment_number, args.segment_count, args.qlog, args.can, args.layout) + route = DEMO_ROUTE if args.demo else args.route_name.strip() + juggle_route(route, args.segment_number, args.segment_count, args.qlog, args.can, args.layout) From 5abe293f614479071f016fbbc2c4d1bdc3d6ddbe Mon Sep 17 00:00:00 2001 From: Erich Moraga <33645296+ErichMoraga@users.noreply.github.com> Date: Sun, 28 Nov 2021 21:15:36 -0600 Subject: [PATCH 043/102] Fix comment typo: steerRation -> steerRatio (#23058) --- selfdrive/car/toyota/interface.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py index 0759c7bf95..59022bf0f3 100755 --- a/selfdrive/car/toyota/interface.py +++ b/selfdrive/car/toyota/interface.py @@ -215,7 +215,7 @@ class CarInterface(CarInterfaceBase): elif candidate == CAR.PRIUS_TSS2: stop_and_go = True ret.wheelbase = 2.70002 # from toyota online sepc. - ret.steerRatio = 13.4 # True steerRation from older prius + ret.steerRatio = 13.4 # True steerRatio from older prius tire_stiffness_factor = 0.6371 # hand-tune ret.mass = 3115. * CV.LB_TO_KG + STD_CARGO_KG set_lat_tune(ret.lateralTuning, LatTunes.PID_N) From f5e48678640bbde0f2616e955ced53f30d61ac6c Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Mon, 29 Nov 2021 18:13:30 +0800 Subject: [PATCH 044/102] replay: refactor http download (#23052) * refactor http download * use chunk_size instead of parts testcase:set chunksize to 5mb * use template space * cleanup * remove unused include * check buffer overfllow * simplify print download speed --- selfdrive/ui/replay/filereader.cc | 27 ++---- selfdrive/ui/replay/filereader.h | 6 +- selfdrive/ui/replay/route.cc | 2 +- selfdrive/ui/replay/tests/test_replay.cc | 18 ++-- selfdrive/ui/replay/util.cc | 109 ++++++++++++++--------- selfdrive/ui/replay/util.h | 4 +- 6 files changed, 87 insertions(+), 79 deletions(-) diff --git a/selfdrive/ui/replay/filereader.cc b/selfdrive/ui/replay/filereader.cc index d110255497..84dc76694b 100644 --- a/selfdrive/ui/replay/filereader.cc +++ b/selfdrive/ui/replay/filereader.cc @@ -1,12 +1,7 @@ #include "selfdrive/ui/replay/filereader.h" -#include - -#include -#include #include #include -#include #include "selfdrive/common/util.h" #include "selfdrive/ui/replay/util.h" @@ -31,7 +26,7 @@ std::string FileReader::read(const std::string &file, std::atomic *abort) } else if (is_remote) { result = download(file, abort); if (cache_to_local_ && !result.empty()) { - std::ofstream fs(local_file, fs.binary | fs.out); + std::ofstream fs(local_file, std::ios::binary | std::ios::out); fs.write(result.data(), result.size()); } } @@ -39,23 +34,13 @@ std::string FileReader::read(const std::string &file, std::atomic *abort) } std::string FileReader::download(const std::string &url, std::atomic *abort) { - std::string result; - size_t remote_file_size = 0; for (int i = 0; i <= max_retries_ && !(abort && *abort); ++i) { - if (i > 0) { - std::cout << "download failed, retrying" << i << std::endl; - } - if (remote_file_size <= 0) { - remote_file_size = getRemoteFileSize(url); + std::string result = httpGet(url, chunk_size_, abort); + if (!result.empty()) { + return result; } - if (remote_file_size > 0 && !(abort && *abort)) { - std::ostringstream oss; - result.resize(remote_file_size); - oss.rdbuf()->pubsetbuf(result.data(), result.size()); - int chunks = chunk_size_ > 0 ? std::max(1, (int)std::nearbyint(remote_file_size / (float)chunk_size_)) : 1; - if (httpMultiPartDownload(url, oss, chunks, remote_file_size, abort)) { - return result; - } + if (i != max_retries_) { + std::cout << "download failed, retrying " << i + 1 << std::endl; } } return {}; diff --git a/selfdrive/ui/replay/filereader.h b/selfdrive/ui/replay/filereader.h index 06ce14e9f2..34aa91e858 100644 --- a/selfdrive/ui/replay/filereader.h +++ b/selfdrive/ui/replay/filereader.h @@ -5,14 +5,14 @@ class FileReader { public: - FileReader(bool cache_to_local, int chunk_size = -1, int max_retries = 3) - : cache_to_local_(cache_to_local), chunk_size_(chunk_size), max_retries_(max_retries) {} + FileReader(bool cache_to_local, size_t chunk_size = 0, int retries = 3) + : cache_to_local_(cache_to_local), chunk_size_(chunk_size), max_retries_(retries) {} virtual ~FileReader() {} std::string read(const std::string &file, std::atomic *abort = nullptr); private: std::string download(const std::string &url, std::atomic *abort); - int chunk_size_; + size_t chunk_size_; int max_retries_; bool cache_to_local_; }; diff --git a/selfdrive/ui/replay/route.cc b/selfdrive/ui/replay/route.cc index 9ee1d387c4..caaef4de5c 100644 --- a/selfdrive/ui/replay/route.cc +++ b/selfdrive/ui/replay/route.cc @@ -121,7 +121,7 @@ void Segment::loadFile(int id, const std::string file) { frames[id] = std::make_unique(local_cache, 20 * 1024 * 1024, 3); success = frames[id]->load(file, flags & REPLAY_FLAG_NO_CUDA, &abort_); } else { - log = std::make_unique(local_cache, -1, 3); + log = std::make_unique(local_cache, 0, 3); success = log->load(file, &abort_); } diff --git a/selfdrive/ui/replay/tests/test_replay.cc b/selfdrive/ui/replay/tests/test_replay.cc index f2a2171c82..9efc55a610 100644 --- a/selfdrive/ui/replay/tests/test_replay.cc +++ b/selfdrive/ui/replay/tests/test_replay.cc @@ -1,7 +1,5 @@ #include #include -#include -#include #include "catch2/catch.hpp" #include "selfdrive/common/util.h" @@ -16,19 +14,15 @@ TEST_CASE("httpMultiPartDownload") { char filename[] = "/tmp/XXXXXX"; close(mkstemp(filename)); + const size_t chunk_size = 5 * 1024 * 1024; std::string content; - auto file_size = getRemoteFileSize(TEST_RLOG_URL); - REQUIRE(file_size > 0); - SECTION("5 connections, download to file") { - std::ofstream of(filename, of.binary | of.out); - REQUIRE(httpMultiPartDownload(TEST_RLOG_URL, of, 5, file_size)); + SECTION("download to file") { + REQUIRE(httpDownload(TEST_RLOG_URL, filename, chunk_size)); content = util::read_file(filename); } - SECTION("5 connection, download to buffer") { - std::ostringstream oss; - content.resize(file_size); - oss.rdbuf()->pubsetbuf(content.data(), content.size()); - REQUIRE(httpMultiPartDownload(TEST_RLOG_URL, oss, 5, file_size)); + SECTION("download to buffer") { + content = httpGet(TEST_RLOG_URL, chunk_size); + REQUIRE(!content.empty()); } REQUIRE(content.size() == 9112651); REQUIRE(sha256(content) == TEST_RLOG_CHECKSUM); diff --git a/selfdrive/ui/replay/util.cc b/selfdrive/ui/replay/util.cc index b4fcbf7e6b..27f0bd9cfd 100644 --- a/selfdrive/ui/replay/util.cc +++ b/selfdrive/ui/replay/util.cc @@ -4,8 +4,10 @@ #include #include +#include #include -#include +#include +#include #include #include #include @@ -22,21 +24,34 @@ struct CURLGlobalInitializer { ~CURLGlobalInitializer() { curl_global_cleanup(); } }; +template struct MultiPartWriter { + T *buf; + size_t *total_written; size_t offset; size_t end; - size_t written; - std::ostream *os; + + size_t write(char *data, size_t size, size_t count) { + size_t bytes = size * count; + if ((offset + bytes) > end) return 0; + + if constexpr (std::is_same::value) { + memcpy(buf->data() + offset, data, bytes); + } else if constexpr (std::is_same::value) { + buf->seekp(offset); + buf->write(data, bytes); + } + + offset += bytes; + *total_written += bytes; + return bytes; + } }; +template size_t write_cb(char *data, size_t size, size_t count, void *userp) { - MultiPartWriter *w = (MultiPartWriter *)userp; - w->os->seekp(w->offset); - size_t bytes = size * count; - w->os->write(data, bytes); - w->offset += bytes; - w->written += bytes; - return bytes; + auto w = (MultiPartWriter *)userp; + return w->write(data, size, count); } size_t dumy_write_cb(char *data, size_t size, size_t count, void *userp) { return size * count; } @@ -64,12 +79,12 @@ size_t getRemoteFileSize(const std::string &url) { CURLcode res = curl_easy_perform(curl); double content_length = -1; if (res == CURLE_OK) { - res = curl_easy_getinfo(curl, CURLINFO_CONTENT_LENGTH_DOWNLOAD, &content_length); + curl_easy_getinfo(curl, CURLINFO_CONTENT_LENGTH_DOWNLOAD, &content_length); } else { std::cout << "Download failed: error code: " << res << std::endl; } curl_easy_cleanup(curl); - return content_length > 0 ? content_length : 0; + return content_length > 0 ? (size_t)content_length : 0; } std::string getUrlWithoutQuery(const std::string &url) { @@ -81,30 +96,32 @@ void enableHttpLogging(bool enable) { enable_http_logging = enable; } -bool httpMultiPartDownload(const std::string &url, std::ostream &os, int parts, size_t content_length, std::atomic *abort) { +template +bool httpDownload(const std::string &url, T &buf, size_t chunk_size, size_t content_length, std::atomic *abort) { static CURLGlobalInitializer curl_initializer; - static std::mutex lock; - static uint64_t total_written = 0, prev_total_written = 0; - static double last_print_ts = 0; - os.seekp(content_length - 1); - os.write("\0", 1); + int parts = 1; + if (chunk_size > 0 && content_length > 10 * 1024 * 1024) { + parts = std::nearbyint(content_length / (float)chunk_size); + parts = std::clamp(parts, 1, 5); + } CURLM *cm = curl_multi_init(); - - std::map writers; + size_t written = 0; + std::map> writers; const int part_size = content_length / parts; for (int i = 0; i < parts; ++i) { CURL *eh = curl_easy_init(); writers[eh] = { - .os = &os, + .buf = &buf, + .total_written = &written, .offset = (size_t)(i * part_size), - .end = i == parts - 1 ? content_length - 1 : (i + 1) * part_size - 1, + .end = i == parts - 1 ? content_length : (i + 1) * part_size, }; - curl_easy_setopt(eh, CURLOPT_WRITEFUNCTION, write_cb); + curl_easy_setopt(eh, CURLOPT_WRITEFUNCTION, write_cb); curl_easy_setopt(eh, CURLOPT_WRITEDATA, (void *)(&writers[eh])); curl_easy_setopt(eh, CURLOPT_URL, url.c_str()); - curl_easy_setopt(eh, CURLOPT_RANGE, util::string_format("%d-%d", writers[eh].offset, writers[eh].end).c_str()); + curl_easy_setopt(eh, CURLOPT_RANGE, util::string_format("%d-%d", writers[eh].offset, writers[eh].end - 1).c_str()); curl_easy_setopt(eh, CURLOPT_HTTPGET, 1); curl_easy_setopt(eh, CURLOPT_NOSIGNAL, 1); curl_easy_setopt(eh, CURLOPT_FOLLOWLOCATION, 1); @@ -112,27 +129,22 @@ bool httpMultiPartDownload(const std::string &url, std::ostream &os, int parts, curl_multi_add_handle(cm, eh); } - int still_running = 1; size_t prev_written = 0; + double last_print = millis_since_boot(); + int still_running = 1; while (still_running > 0 && !(abort && *abort)) { curl_multi_wait(cm, nullptr, 0, 1000, nullptr); curl_multi_perform(cm, &still_running); - size_t written = std::accumulate(writers.begin(), writers.end(), 0, [=](int v, auto &w) { return v + w.second.written; }); - int cur_written = written - prev_written; - prev_written = written; - - std::lock_guard lk(lock); - double ts = millis_since_boot(); - total_written += cur_written; - if ((ts - last_print_ts) > 2 * 1000) { - if (enable_http_logging && last_print_ts > 0) { - size_t average = (total_written - prev_total_written) / ((ts - last_print_ts) / 1000.); + if (enable_http_logging) { + if (double ts = millis_since_boot(); (ts - last_print) > 2 * 1000) { + size_t average = (written - prev_written) / ((ts - last_print) / 1000.); int progress = std::min(100, 100.0 * (double)written / (double)content_length); - std::cout << "downloading " << getUrlWithoutQuery(url) << " - " << progress << "% (" << formattedDataSize(average) << "/s)" << std::endl; + std::cout << "downloading " << getUrlWithoutQuery(url) << " - " << progress + << "% (" << formattedDataSize(average) << "/s)" << std::endl; + last_print = ts; + prev_written = written; } - prev_total_written = total_written; - last_print_ts = ts; } } @@ -155,15 +167,32 @@ bool httpMultiPartDownload(const std::string &url, std::ostream &os, int parts, } } - for (auto &[e, w] : writers) { + for (const auto &[e, w] : writers) { curl_multi_remove_handle(cm, e); curl_easy_cleanup(e); } - curl_multi_cleanup(cm); + return complete == parts; } +std::string httpGet(const std::string &url, size_t chunk_size, std::atomic *abort) { + size_t size = getRemoteFileSize(url); + if (size == 0) return {}; + + std::string result(size, '\0'); + return httpDownload(url, result, chunk_size, size, abort) ? result : ""; +} + +bool httpDownload(const std::string &url, const std::string &file, size_t chunk_size, std::atomic *abort) { + size_t size = getRemoteFileSize(url); + if (size == 0) return false; + + std::ofstream of(file, std::ios::binary | std::ios::out); + of.seekp(size - 1).write("\0", 1); + return httpDownload(url, of, chunk_size, size, abort); +} + std::string decompressBZ2(const std::string &in) { if (in.empty()) return {}; diff --git a/selfdrive/ui/replay/util.h b/selfdrive/ui/replay/util.h index 30a26c4314..85d7af0125 100644 --- a/selfdrive/ui/replay/util.h +++ b/selfdrive/ui/replay/util.h @@ -1,7 +1,6 @@ #pragma once #include -#include #include std::string sha256(const std::string &str); @@ -10,4 +9,5 @@ std::string decompressBZ2(const std::string &in); void enableHttpLogging(bool enable); std::string getUrlWithoutQuery(const std::string &url); size_t getRemoteFileSize(const std::string &url); -bool httpMultiPartDownload(const std::string &url, std::ostream &os, int parts, size_t content_length, std::atomic *abort = nullptr); +std::string httpGet(const std::string &url, size_t chunk_size = 0, std::atomic *abort = nullptr); +bool httpDownload(const std::string &url, const std::string &file, size_t chunk_size = 0, std::atomic *abort = nullptr); From 5394fe1ae799e38d5c5433a2e530d5be84ee7e99 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Mon, 29 Nov 2021 18:14:34 +0800 Subject: [PATCH 045/102] DevicePanel: split long constructor into multiple functions (#23043) * begin refactor * split long constructor to multiple functions * one connection to signal * merge master --- selfdrive/ui/qt/offroad/settings.cc | 127 +++++++++++++++------------- selfdrive/ui/qt/offroad/settings.h | 7 +- 2 files changed, 74 insertions(+), 60 deletions(-) diff --git a/selfdrive/ui/qt/offroad/settings.cc b/selfdrive/ui/qt/offroad/settings.cc index ab2b0287f5..e5438f7c85 100644 --- a/selfdrive/ui/qt/offroad/settings.cc +++ b/selfdrive/ui/qt/offroad/settings.cc @@ -109,72 +109,53 @@ TogglesPanel::TogglesPanel(SettingsWindow *parent) : ListWidget(parent) { } } -DevicePanel::DevicePanel(QWidget* parent) : ListWidget(parent) { - setSpacing(50); +DevicePanel::DevicePanel(SettingsWindow *parent) : ListWidget(parent) { Params params = Params(); + + setSpacing(50); addItem(new LabelControl("Dongle ID", getDongleId().value_or("N/A"))); addItem(new LabelControl("Serial", params.get("HardwareSerial").c_str())); // offroad-only buttons auto dcamBtn = new ButtonControl("Driver Camera", "PREVIEW", - "Preview the driver facing camera to help optimize device mounting position for best driver monitoring experience. (vehicle must be off)"); + "Preview the driver facing camera to help optimize device mounting position for best driver monitoring experience. (vehicle must be off)"); connect(dcamBtn, &ButtonControl::clicked, [=]() { emit showDriverView(); }); + addItem(dcamBtn); - QString resetCalibDesc = "openpilot requires the device to be mounted within 4° left or right and within 5° up or down. openpilot is continuously calibrating, resetting is rarely required."; - auto resetCalibBtn = new ButtonControl("Reset Calibration", "RESET", resetCalibDesc); + auto resetCalibBtn = new ButtonControl("Reset Calibration", "RESET", " "); + connect(resetCalibBtn, &ButtonControl::showDescription, this, &DevicePanel::updateCalibDescription); connect(resetCalibBtn, &ButtonControl::clicked, [&]() { if (ConfirmationDialog::confirm("Are you sure you want to reset calibration?", this)) { params.remove("CalibrationParams"); } }); - connect(resetCalibBtn, &ButtonControl::showDescription, [&]() { - QString desc = resetCalibDesc; - std::string calib_bytes = params.get("CalibrationParams"); - if (!calib_bytes.empty()) { - try { - AlignedBuffer aligned_buf; - capnp::FlatArrayMessageReader cmsg(aligned_buf.align(calib_bytes.data(), calib_bytes.size())); - auto calib = cmsg.getRoot().getLiveCalibration(); - if (calib.getCalStatus() != 0) { - double pitch = calib.getRpyCalib()[1] * (180 / M_PI); - double yaw = calib.getRpyCalib()[2] * (180 / M_PI); - desc += QString(" Your device is pointed %1° %2 and %3° %4.") - .arg(QString::number(std::abs(pitch), 'g', 1), pitch > 0 ? "up" : "down", - QString::number(std::abs(yaw), 'g', 1), yaw > 0 ? "right" : "left"); - } - } catch (kj::Exception) { - qInfo() << "invalid CalibrationParams"; - } - } - resetCalibBtn->setDescription(desc); - }); + addItem(resetCalibBtn); - ButtonControl *retrainingBtn = nullptr; if (!params.getBool("Passive")) { - retrainingBtn = new ButtonControl("Review Training Guide", "REVIEW", "Review the rules, features, and limitations of openpilot"); + auto retrainingBtn = new ButtonControl("Review Training Guide", "REVIEW", "Review the rules, features, and limitations of openpilot"); connect(retrainingBtn, &ButtonControl::clicked, [=]() { if (ConfirmationDialog::confirm("Are you sure you want to review the training guide?", this)) { emit reviewTrainingGuide(); } }); + addItem(retrainingBtn); } - ButtonControl *regulatoryBtn = nullptr; if (Hardware::TICI()) { - regulatoryBtn = new ButtonControl("Regulatory", "VIEW", ""); + auto regulatoryBtn = new ButtonControl("Regulatory", "VIEW", ""); connect(regulatoryBtn, &ButtonControl::clicked, [=]() { const std::string txt = util::read_file("../assets/offroad/fcc.html"); RichTextDialog::alert(QString::fromStdString(txt), this); }); + addItem(regulatoryBtn); } - for (auto btn : {dcamBtn, resetCalibBtn, retrainingBtn, regulatoryBtn}) { - if (btn) { - connect(parent, SIGNAL(offroadTransition(bool)), btn, SLOT(setEnabled(bool))); - addItem(btn); + QObject::connect(parent, &SettingsWindow::offroadTransition, [=](bool offroad) { + for (auto btn : findChildren()) { + btn->setEnabled(offroad); } - } + }); // power buttons QHBoxLayout *power_layout = new QHBoxLayout(); @@ -183,34 +164,12 @@ DevicePanel::DevicePanel(QWidget* parent) : ListWidget(parent) { QPushButton *reboot_btn = new QPushButton("Reboot"); reboot_btn->setObjectName("reboot_btn"); power_layout->addWidget(reboot_btn); - QObject::connect(reboot_btn, &QPushButton::clicked, [&]() { - if (QUIState::ui_state.status == UIStatus::STATUS_DISENGAGED) { - if (ConfirmationDialog::confirm("Are you sure you want to reboot?", this)) { - // Check engaged again in case it changed while the dialog was open - if (QUIState::ui_state.status == UIStatus::STATUS_DISENGAGED) { - params.putBool("DoReboot", true); - } - } - } else { - ConfirmationDialog::alert("Disengage to Reboot", this); - } - }); + QObject::connect(reboot_btn, &QPushButton::clicked, this, &DevicePanel::reboot); QPushButton *poweroff_btn = new QPushButton("Power Off"); poweroff_btn->setObjectName("poweroff_btn"); power_layout->addWidget(poweroff_btn); - QObject::connect(poweroff_btn, &QPushButton::clicked, [&]() { - if (QUIState::ui_state.status == UIStatus::STATUS_DISENGAGED) { - if (ConfirmationDialog::confirm("Are you sure you want to power off?", this)) { - // Check engaged again in case it changed while the dialog was open - if (QUIState::ui_state.status == UIStatus::STATUS_DISENGAGED) { - params.putBool("DoShutdown", true); - } - } - } else { - ConfirmationDialog::alert("Disengage to Power Off", this); - } - }); + QObject::connect(poweroff_btn, &QPushButton::clicked, this, &DevicePanel::poweroff); setStyleSheet(R"( QPushButton { @@ -225,6 +184,56 @@ DevicePanel::DevicePanel(QWidget* parent) : ListWidget(parent) { addItem(power_layout); } +void DevicePanel::updateCalibDescription() { + QString desc = + "openpilot requires the device to be mounted within 4° left or right and " + "within 5° up or down. openpilot is continuously calibrating, resetting is rarely required."; + std::string calib_bytes = Params().get("CalibrationParams"); + if (!calib_bytes.empty()) { + try { + AlignedBuffer aligned_buf; + capnp::FlatArrayMessageReader cmsg(aligned_buf.align(calib_bytes.data(), calib_bytes.size())); + auto calib = cmsg.getRoot().getLiveCalibration(); + if (calib.getCalStatus() != 0) { + double pitch = calib.getRpyCalib()[1] * (180 / M_PI); + double yaw = calib.getRpyCalib()[2] * (180 / M_PI); + desc += QString(" Your device is pointed %1° %2 and %3° %4.") + .arg(QString::number(std::abs(pitch), 'g', 1), pitch > 0 ? "up" : "down", + QString::number(std::abs(yaw), 'g', 1), yaw > 0 ? "right" : "left"); + } + } catch (kj::Exception) { + qInfo() << "invalid CalibrationParams"; + } + } + qobject_cast(sender())->setDescription(desc); +} + +void DevicePanel::reboot() { + if (QUIState::ui_state.status == UIStatus::STATUS_DISENGAGED) { + if (ConfirmationDialog::confirm("Are you sure you want to reboot?", this)) { + // Check engaged again in case it changed while the dialog was open + if (QUIState::ui_state.status == UIStatus::STATUS_DISENGAGED) { + Params().putBool("DoReboot", true); + } + } + } else { + ConfirmationDialog::alert("Disengage to Reboot", this); + } +} + +void DevicePanel::poweroff() { + if (QUIState::ui_state.status == UIStatus::STATUS_DISENGAGED) { + if (ConfirmationDialog::confirm("Are you sure you want to power off?", this)) { + // Check engaged again in case it changed while the dialog was open + if (QUIState::ui_state.status == UIStatus::STATUS_DISENGAGED) { + Params().putBool("DoShutdown", true); + } + } + } else { + ConfirmationDialog::alert("Disengage to Power Off", this); + } +} + SoftwarePanel::SoftwarePanel(QWidget* parent) : ListWidget(parent) { gitBranchLbl = new LabelControl("Git Branch"); gitCommitLbl = new LabelControl("Git Commit"); diff --git a/selfdrive/ui/qt/offroad/settings.h b/selfdrive/ui/qt/offroad/settings.h index a2c7e01d8f..fe88180662 100644 --- a/selfdrive/ui/qt/offroad/settings.h +++ b/selfdrive/ui/qt/offroad/settings.h @@ -38,10 +38,15 @@ private: class DevicePanel : public ListWidget { Q_OBJECT public: - explicit DevicePanel(QWidget* parent = nullptr); + explicit DevicePanel(SettingsWindow *parent); signals: void reviewTrainingGuide(); void showDriverView(); + +private slots: + void poweroff(); + void reboot(); + void updateCalibDescription(); }; class TogglesPanel : public ListWidget { From 3fd02649601856b2780168d36c49940ff49f4de2 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Mon, 29 Nov 2021 18:19:08 +0800 Subject: [PATCH 046/102] refactor httprequest: emit single signals (#23039) * refactor httprequest * Trigger Build --- selfdrive/ui/qt/api.cc | 35 +++++++++++++------------- selfdrive/ui/qt/api.h | 12 ++++----- selfdrive/ui/qt/maps/map_settings.cc | 18 ++++++------- selfdrive/ui/qt/maps/map_settings.h | 3 +-- selfdrive/ui/qt/request_repeater.cc | 6 ++--- selfdrive/ui/qt/setup/setup.cc | 2 +- selfdrive/ui/qt/widgets/drive_stats.cc | 6 +++-- selfdrive/ui/qt/widgets/drive_stats.h | 2 +- selfdrive/ui/qt/widgets/prime.cc | 8 +++--- selfdrive/ui/qt/widgets/prime.h | 2 +- selfdrive/ui/qt/widgets/ssh_keys.cc | 29 +++++++++++---------- selfdrive/ui/replay/route.cc | 6 ++--- 12 files changed, 63 insertions(+), 66 deletions(-) diff --git a/selfdrive/ui/qt/api.cc b/selfdrive/ui/qt/api.cc index 6339884aec..98236e5014 100644 --- a/selfdrive/ui/qt/api.cc +++ b/selfdrive/ui/qt/api.cc @@ -70,10 +70,14 @@ HttpRequest::HttpRequest(QObject *parent, bool create_jwt, int timeout) : create connect(networkTimer, &QTimer::timeout, this, &HttpRequest::requestTimeout); } -bool HttpRequest::active() { +bool HttpRequest::active() const { return reply != nullptr; } +bool HttpRequest::timeout() const { + return reply && reply->error() == QNetworkReply::OperationCanceledError; +} + void HttpRequest::sendRequest(const QString &requestURL, const HttpRequest::Method method) { if (active()) { qDebug() << "HttpRequest is active"; @@ -110,29 +114,26 @@ void HttpRequest::requestTimeout() { reply->abort(); } -// This function should always emit something void HttpRequest::requestFinished() { - bool success = false; - if (reply->error() != QNetworkReply::OperationCanceledError) { - networkTimer->stop(); - QString response = reply->readAll(); - - if (reply->error() == QNetworkReply::NoError) { - success = true; - emit receivedResponse(response); - } else { - emit failedResponse(reply->errorString()); + networkTimer->stop(); + if (reply->error() == QNetworkReply::NoError) { + emit requestDone(reply->readAll(), true); + } else { + QString error; + if (reply->error() == QNetworkReply::OperationCanceledError) { + networkAccessManager->clearAccessCache(); + networkAccessManager->clearConnectionCache(); + error = "Request timed out"; + } else { if (reply->error() == QNetworkReply::ContentAccessDenied || reply->error() == QNetworkReply::AuthenticationRequiredError) { qWarning() << ">> Unauthorized. Authenticate with tools/lib/auth.py <<"; } + error = reply->errorString(); } - } else { - networkAccessManager->clearAccessCache(); - networkAccessManager->clearConnectionCache(); - emit timeoutResponse("timeout"); + emit requestDone(error, false); } - emit requestDone(success); + reply->deleteLater(); reply = nullptr; } diff --git a/selfdrive/ui/qt/api.h b/selfdrive/ui/qt/api.h index 1c7c333ea0..6890a7957d 100644 --- a/selfdrive/ui/qt/api.h +++ b/selfdrive/ui/qt/api.h @@ -27,7 +27,11 @@ public: explicit HttpRequest(QObject* parent, bool create_jwt = true, int timeout = 20000); void sendRequest(const QString &requestURL, const Method method = Method::GET); - bool active(); + bool active() const; + bool timeout() const; + +signals: + void requestDone(const QString &response, bool success); protected: QNetworkReply *reply = nullptr; @@ -40,10 +44,4 @@ private: private slots: void requestTimeout(); void requestFinished(); - -signals: - void requestDone(bool success); - void receivedResponse(const QString &response); - void failedResponse(const QString &errorString); - void timeoutResponse(const QString &errorString); }; diff --git a/selfdrive/ui/qt/maps/map_settings.cc b/selfdrive/ui/qt/maps/map_settings.cc index 60a7812265..e130a9a1ec 100644 --- a/selfdrive/ui/qt/maps/map_settings.cc +++ b/selfdrive/ui/qt/maps/map_settings.cc @@ -127,8 +127,7 @@ MapPanel::MapPanel(QWidget* parent) : QWidget(parent) { { QString url = CommaApi::BASE_URL + "/v1/navigation/" + *dongle_id + "/locations"; RequestRepeater* repeater = new RequestRepeater(this, url, "ApiCache_NavDestinations", 30, true); - QObject::connect(repeater, &RequestRepeater::receivedResponse, this, &MapPanel::parseResponse); - QObject::connect(repeater, &RequestRepeater::failedResponse, this, &MapPanel::failedResponse); + QObject::connect(repeater, &RequestRepeater::requestDone, this, &MapPanel::parseResponse); } // Destination set while offline @@ -137,8 +136,8 @@ MapPanel::MapPanel(QWidget* parent) : QWidget(parent) { RequestRepeater* repeater = new RequestRepeater(this, url, "", 10, true); HttpRequest* deleter = new HttpRequest(this); - QObject::connect(repeater, &RequestRepeater::receivedResponse, [=](QString resp) { - if (resp != "null") { + QObject::connect(repeater, &RequestRepeater::requestDone, [=](const QString &resp, bool success) { + if (success && resp != "null") { if (params.get("NavDestination").empty()) { qWarning() << "Setting NavDestination from /next" << resp; params.put("NavDestination", resp.toStdString()); @@ -183,7 +182,12 @@ void MapPanel::updateCurrentRoute() { current_widget->setVisible(dest.size() && !doc.isNull()); } -void MapPanel::parseResponse(const QString &response) { +void MapPanel::parseResponse(const QString &response, bool success) { + if (!success) { + stack->setCurrentIndex(1); + return; + } + QJsonDocument doc = QJsonDocument::fromJson(response.trimmed().toUtf8()); if (doc.isNull()) { qDebug() << "JSON Parse failed on navigation locations"; @@ -283,10 +287,6 @@ void MapPanel::parseResponse(const QString &response) { repaint(); } -void MapPanel::failedResponse(const QString &response) { - stack->setCurrentIndex(1); -} - void MapPanel::navigateTo(const QJsonObject &place) { QJsonDocument doc(place); params.put("NavDestination", doc.toJson().toStdString()); diff --git a/selfdrive/ui/qt/maps/map_settings.h b/selfdrive/ui/qt/maps/map_settings.h index ec409c4962..03720edee7 100644 --- a/selfdrive/ui/qt/maps/map_settings.h +++ b/selfdrive/ui/qt/maps/map_settings.h @@ -17,8 +17,7 @@ public: explicit MapPanel(QWidget* parent = nullptr); void navigateTo(const QJsonObject &place); - void parseResponse(const QString &response); - void failedResponse(const QString &response); + void parseResponse(const QString &response, bool success); void updateCurrentRoute(); void clear(); diff --git a/selfdrive/ui/qt/request_repeater.cc b/selfdrive/ui/qt/request_repeater.cc index c11698d6f1..d2c0f9bc30 100644 --- a/selfdrive/ui/qt/request_repeater.cc +++ b/selfdrive/ui/qt/request_repeater.cc @@ -15,10 +15,10 @@ RequestRepeater::RequestRepeater(QObject *parent, const QString &requestURL, con if (!cacheKey.isEmpty()) { prevResp = QString::fromStdString(params.get(cacheKey.toStdString())); if (!prevResp.isEmpty()) { - QTimer::singleShot(500, [=]() { emit receivedResponse(prevResp); }); + QTimer::singleShot(500, [=]() { emit requestDone(prevResp, true); }); } - QObject::connect(this, &HttpRequest::receivedResponse, [=](const QString &resp) { - if (resp != prevResp) { + QObject::connect(this, &HttpRequest::requestDone, [=](const QString &resp, bool success) { + if (success && resp != prevResp) { params.put(cacheKey.toStdString(), resp.toStdString()); prevResp = resp; } diff --git a/selfdrive/ui/qt/setup/setup.cc b/selfdrive/ui/qt/setup/setup.cc index a855813688..bd494327cc 100644 --- a/selfdrive/ui/qt/setup/setup.cc +++ b/selfdrive/ui/qt/setup/setup.cc @@ -169,7 +169,7 @@ QWidget * Setup::network_setup() { // setup timer for testing internet connection HttpRequest *request = new HttpRequest(this, false, 2500); - QObject::connect(request, &HttpRequest::requestDone, [=](bool success) { + QObject::connect(request, &HttpRequest::requestDone, [=](const QString &, bool success) { cont->setEnabled(success); if (success) { const bool cell = networking->wifi->currentNetworkType() == NetworkType::CELL; diff --git a/selfdrive/ui/qt/widgets/drive_stats.cc b/selfdrive/ui/qt/widgets/drive_stats.cc index bd1dc71766..f4c8f502a3 100644 --- a/selfdrive/ui/qt/widgets/drive_stats.cc +++ b/selfdrive/ui/qt/widgets/drive_stats.cc @@ -48,7 +48,7 @@ DriveStats::DriveStats(QWidget* parent) : QFrame(parent) { if (auto dongleId = getDongleId()) { QString url = CommaApi::BASE_URL + "/v1.1/devices/" + *dongleId + "/stats"; RequestRepeater* repeater = new RequestRepeater(this, url, "ApiCache_DriveStats", 30); - QObject::connect(repeater, &RequestRepeater::receivedResponse, this, &DriveStats::parseResponse); + QObject::connect(repeater, &RequestRepeater::requestDone, this, &DriveStats::parseResponse); } setStyleSheet(R"( @@ -76,7 +76,9 @@ void DriveStats::updateStats() { update(json["week"].toObject(), week_); } -void DriveStats::parseResponse(const QString& response) { +void DriveStats::parseResponse(const QString& response, bool success) { + if (!success) return; + QJsonDocument doc = QJsonDocument::fromJson(response.trimmed().toUtf8()); if (doc.isNull()) { qDebug() << "JSON Parse failed on getting past drives statistics"; diff --git a/selfdrive/ui/qt/widgets/drive_stats.h b/selfdrive/ui/qt/widgets/drive_stats.h index 40ecbdeaf2..9446294516 100644 --- a/selfdrive/ui/qt/widgets/drive_stats.h +++ b/selfdrive/ui/qt/widgets/drive_stats.h @@ -21,5 +21,5 @@ private: } all_, week_; private slots: - void parseResponse(const QString &response); + void parseResponse(const QString &response, bool success); }; diff --git a/selfdrive/ui/qt/widgets/prime.cc b/selfdrive/ui/qt/widgets/prime.cc index 665466df5e..ab6dc67d36 100644 --- a/selfdrive/ui/qt/widgets/prime.cc +++ b/selfdrive/ui/qt/widgets/prime.cc @@ -161,7 +161,7 @@ PrimeUserWidget::PrimeUserWidget(QWidget* parent) : QWidget(parent) { if (auto dongleId = getDongleId()) { QString url = CommaApi::BASE_URL + "/v1/devices/" + *dongleId + "/owner"; RequestRepeater *repeater = new RequestRepeater(this, url, "ApiCache_Owner", 6); - QObject::connect(repeater, &RequestRepeater::receivedResponse, this, &PrimeUserWidget::replyFinished); + QObject::connect(repeater, &RequestRepeater::requestDone, this, &PrimeUserWidget::replyFinished); } } @@ -291,14 +291,14 @@ SetupWidget::SetupWidget(QWidget* parent) : QFrame(parent) { QString url = CommaApi::BASE_URL + "/v1.1/devices/" + *dongleId + "/"; RequestRepeater* repeater = new RequestRepeater(this, url, "ApiCache_Device", 5); - QObject::connect(repeater, &RequestRepeater::failedResponse, this, &SetupWidget::show); - QObject::connect(repeater, &RequestRepeater::receivedResponse, this, &SetupWidget::replyFinished); + QObject::connect(repeater, &RequestRepeater::requestDone, this, &SetupWidget::replyFinished); } hide(); // Only show when first request comes back } -void SetupWidget::replyFinished(const QString &response) { +void SetupWidget::replyFinished(const QString &response, bool success) { show(); + if (!success) return; QJsonDocument doc = QJsonDocument::fromJson(response.toUtf8()); if (doc.isNull()) { diff --git a/selfdrive/ui/qt/widgets/prime.h b/selfdrive/ui/qt/widgets/prime.h index 6044f06104..f7470fe441 100644 --- a/selfdrive/ui/qt/widgets/prime.h +++ b/selfdrive/ui/qt/widgets/prime.h @@ -68,5 +68,5 @@ private: PrimeUserWidget *primeUser; private slots: - void replyFinished(const QString &response); + void replyFinished(const QString &response, bool success); }; diff --git a/selfdrive/ui/qt/widgets/ssh_keys.cc b/selfdrive/ui/qt/widgets/ssh_keys.cc index ca360a3054..7630e65731 100644 --- a/selfdrive/ui/qt/widgets/ssh_keys.cc +++ b/selfdrive/ui/qt/widgets/ssh_keys.cc @@ -41,23 +41,22 @@ void SshControl::refresh() { void SshControl::getUserKeys(const QString &username) { HttpRequest *request = new HttpRequest(this, false); - QObject::connect(request, &HttpRequest::receivedResponse, [=](const QString &resp) { - if (!resp.isEmpty()) { - params.put("GithubUsername", username.toStdString()); - params.put("GithubSshKeys", resp.toStdString()); + QObject::connect(request, &HttpRequest::requestDone, [=](const QString &resp, bool success) { + if (success) { + if (!resp.isEmpty()) { + params.put("GithubUsername", username.toStdString()); + params.put("GithubSshKeys", resp.toStdString()); + } else { + ConfirmationDialog::alert(QString("Username '%1' has no keys on GitHub").arg(username), this); + } } else { - ConfirmationDialog::alert(QString("Username '%1' has no keys on GitHub").arg(username), this); + if (request->timeout()) { + ConfirmationDialog::alert("Request timed out", this); + } else { + ConfirmationDialog::alert(QString("Username '%1' doesn't exist on GitHub").arg(username), this); + } } - refresh(); - request->deleteLater(); - }); - QObject::connect(request, &HttpRequest::failedResponse, [=] { - ConfirmationDialog::alert(QString("Username '%1' doesn't exist on GitHub").arg(username), this); - refresh(); - request->deleteLater(); - }); - QObject::connect(request, &HttpRequest::timeoutResponse, [=] { - ConfirmationDialog::alert("Request timed out", this); + refresh(); request->deleteLater(); }); diff --git a/selfdrive/ui/replay/route.cc b/selfdrive/ui/replay/route.cc index caaef4de5c..b3736fa75f 100644 --- a/selfdrive/ui/replay/route.cc +++ b/selfdrive/ui/replay/route.cc @@ -35,10 +35,8 @@ bool Route::load() { bool Route::loadFromServer() { QEventLoop loop; HttpRequest http(nullptr, !Hardware::PC()); - QObject::connect(&http, &HttpRequest::failedResponse, [&] { loop.exit(0); }); - QObject::connect(&http, &HttpRequest::timeoutResponse, [&] { loop.exit(0); }); - QObject::connect(&http, &HttpRequest::receivedResponse, [&](const QString &json) { - loop.exit(loadFromJson(json)); + QObject::connect(&http, &HttpRequest::requestDone, [&](const QString &json, bool success) { + loop.exit(success ? loadFromJson(json) : 0); }); http.sendRequest("https://api.commadotai.com/v1/route/" + route_.str + "/files"); return loop.exec(); From 35c0319f6c846c900098b5280652ab16424658c6 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Mon, 29 Nov 2021 18:19:38 +0800 Subject: [PATCH 047/102] boardd: new function sync_time (#23033) * sync_time * add direction * Update selfdrive/boardd/boardd.cc Co-authored-by: Willem Melching * enum class * rename * caps * lambda get_time_str * Revert "lambda get_time_str" This reverts commit 5eb6e19c5130b28963e9555f6c73835ac30d817d. * static Co-authored-by: Willem Melching --- selfdrive/boardd/boardd.cc | 62 ++++++++++++++++++++------------------ 1 file changed, 33 insertions(+), 29 deletions(-) diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index bbaf28ca67..3f66efc9fe 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -62,7 +62,7 @@ std::atomic pigeon_active(false); ExitHandler do_exit; -std::string get_time_str(const struct tm &time) { +static std::string get_time_str(const struct tm &time) { char s[30] = {'\0'}; std::strftime(s, std::size(s), "%Y-%m-%d %H:%M:%S", &time); return s; @@ -78,6 +78,35 @@ bool check_all_connected(const std::vector &pandas) { return true; } +enum class SyncTimeDir { TO_PANDA, FROM_PANDA }; + +void sync_time(Panda *panda, SyncTimeDir dir) { + if (!panda->has_rtc) return; + + setenv("TZ", "UTC", 1); + struct tm sys_time = util::get_time(); + struct tm rtc_time = panda->get_rtc(); + + if (dir == SyncTimeDir::TO_PANDA) { + if (util::time_valid(sys_time)) { + // Write time to RTC if it looks reasonable + double seconds = difftime(mktime(&rtc_time), mktime(&sys_time)); + if (std::abs(seconds) > 1.1) { + panda->set_rtc(sys_time); + LOGW("Updating panda RTC. dt = %.2f System: %s RTC: %s", + seconds, get_time_str(sys_time).c_str(), get_time_str(rtc_time).c_str()); + } + } + } else if (dir == SyncTimeDir::FROM_PANDA) { + if (!util::time_valid(sys_time) && util::time_valid(rtc_time)) { + const struct timeval tv = {mktime(&rtc_time), 0}; + settimeofday(&tv, 0); + LOGE("System time wrong, setting from RTC. System: %s RTC: %s", + get_time_str(sys_time).c_str(), get_time_str(rtc_time).c_str()); + } + } +} + bool safety_setter_thread(std::vector pandas) { LOGD("Starting safety setter thread"); @@ -171,19 +200,7 @@ Panda *usb_connect(std::string serial="", uint32_t index=0) { std::call_once(connected_once, &Panda::set_usb_power_mode, panda, cereal::PeripheralState::UsbPowerMode::CDP); #endif - if (panda->has_rtc) { - setenv("TZ","UTC",1); - struct tm sys_time = util::get_time(); - struct tm rtc_time = panda->get_rtc(); - - if (!util::time_valid(sys_time) && util::time_valid(rtc_time)) { - LOGE("System time wrong, setting from RTC. System: %s RTC: %s", - get_time_str(sys_time).c_str(), get_time_str(rtc_time).c_str()); - const struct timeval tv = {mktime(&rtc_time), 0}; - settimeofday(&tv, 0); - } - } - + sync_time(panda.get(), SyncTimeDir::FROM_PANDA); return panda.release(); } @@ -516,21 +533,8 @@ void peripheral_control_thread(Panda *panda) { } // Write to rtc once per minute when no ignition present - if ((panda->has_rtc) && !ignition && (cnt % 120 == 1)) { - // Write time to RTC if it looks reasonable - setenv("TZ","UTC",1); - struct tm sys_time = util::get_time(); - - if (util::time_valid(sys_time)) { - struct tm rtc_time = panda->get_rtc(); - double seconds = difftime(mktime(&rtc_time), mktime(&sys_time)); - - if (std::abs(seconds) > 1.1) { - panda->set_rtc(sys_time); - LOGW("Updating panda RTC. dt = %.2f System: %s RTC: %s", - seconds, get_time_str(sys_time).c_str(), get_time_str(rtc_time).c_str()); - } - } + if (!ignition && (cnt % 120 == 1)) { + sync_time(panda, SyncTimeDir::TO_PANDA); } } } From 113988ae31bd32db1576d88d5160be01faa63cb5 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 29 Nov 2021 04:29:32 -0600 Subject: [PATCH 048/102] longitudinal: only apply overshoot prevention when braking (#22986) * only if braking is desired * use v_target to determine stopping * more clear? --- selfdrive/controls/lib/longcontrol.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/controls/lib/longcontrol.py b/selfdrive/controls/lib/longcontrol.py index f59a6cc0d6..fcebf1b564 100644 --- a/selfdrive/controls/lib/longcontrol.py +++ b/selfdrive/controls/lib/longcontrol.py @@ -107,7 +107,7 @@ class LongControl(): # Toyota starts braking more when it thinks you want to stop # Freeze the integrator so we don't accelerate to compensate, and don't allow positive acceleration - prevent_overshoot = not CP.stoppingControl and CS.vEgo < 1.5 and v_target_future < 0.7 + prevent_overshoot = not CP.stoppingControl and CS.vEgo < 1.5 and v_target_future < 0.7 and v_target_future < v_target deadzone = interp(CS.vEgo, CP.longitudinalTuning.deadzoneBP, CP.longitudinalTuning.deadzoneV) freeze_integrator = prevent_overshoot From 00db14af6435ef789cd22d275855610f18be0011 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Mon, 29 Nov 2021 18:35:34 +0800 Subject: [PATCH 049/102] cameraview: fix frameskip (#23022) * fix frameskip * sync upload->render * cleanup * comment * rename to latest_texture_id --- selfdrive/ui/qt/widgets/cameraview.cc | 31 +++++++++++---------------- selfdrive/ui/qt/widgets/cameraview.h | 4 +--- 2 files changed, 13 insertions(+), 22 deletions(-) diff --git a/selfdrive/ui/qt/widgets/cameraview.cc b/selfdrive/ui/qt/widgets/cameraview.cc index 240e4c837d..6b25c49237 100644 --- a/selfdrive/ui/qt/widgets/cameraview.cc +++ b/selfdrive/ui/qt/widgets/cameraview.cc @@ -98,7 +98,6 @@ CameraViewWidget::CameraViewWidget(std::string stream_name, VisionStreamType typ stream_name(stream_name), stream_type(type), zoomed_view(zoom), QOpenGLWidget(parent) { setAttribute(Qt::WA_OpaquePaintEvent); connect(this, &CameraViewWidget::vipcThreadConnected, this, &CameraViewWidget::vipcConnected, Qt::BlockingQueuedConnection); - connect(this, &CameraViewWidget::vipcThreadFrameReceived, this, &CameraViewWidget::vipcFrameReceived); } CameraViewWidget::~CameraViewWidget() { @@ -152,7 +151,7 @@ void CameraViewWidget::initializeGL() { } void CameraViewWidget::showEvent(QShowEvent *event) { - latest_frame = nullptr; + latest_texture_id = -1; if (!vipc_thread) { vipc_thread = new QThread(); connect(vipc_thread, &QThread::started, [=]() { vipcThread(); }); @@ -200,18 +199,17 @@ void CameraViewWidget::updateFrameMat(int w, int h) { } void CameraViewWidget::paintGL() { - if (!latest_frame) { + if (latest_texture_id == -1) { glClearColor(bg.redF(), bg.greenF(), bg.blueF(), bg.alphaF()); glClear(GL_STENCIL_BUFFER_BIT | GL_COLOR_BUFFER_BIT); return; } - std::unique_lock lk(texture_lock); glViewport(0, 0, width(), height()); glBindVertexArray(frame_vao); glActiveTexture(GL_TEXTURE0); - glBindTexture(GL_TEXTURE_2D, texture[latest_frame->idx]->frame_tex); + glBindTexture(GL_TEXTURE_2D, texture[latest_texture_id]->frame_tex); glUseProgram(program->programId()); glUniform1i(program->uniformLocation("uTexture"), 0); @@ -239,17 +237,12 @@ void CameraViewWidget::vipcConnected(VisionIpcClient *vipc_client) { glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_SWIZZLE_B, GL_RED); assert(glGetError() == GL_NO_ERROR); } - latest_frame = nullptr; + latest_texture_id = -1; stream_width = vipc_client->buffers[0].width; stream_height = vipc_client->buffers[0].height; updateFrameMat(width(), height()); } -void CameraViewWidget::vipcFrameReceived(VisionBuf *buf) { - latest_frame = buf; - update(); -} - void CameraViewWidget::vipcThread() { VisionStreamType cur_stream_type = stream_type; std::unique_ptr vipc_client; @@ -298,8 +291,6 @@ void CameraViewWidget::vipcThread() { if (VisionBuf *buf = vipc_client->recv(nullptr, 1000)) { if (!Hardware::EON()) { - std::unique_lock lk(texture_lock); - void *texture_buffer = gl_buffer->map(QOpenGLBuffer::WriteOnly); memcpy(texture_buffer, buf->addr, buf->len); gl_buffer->unmap(); @@ -309,13 +300,15 @@ void CameraViewWidget::vipcThread() { glTexSubImage2D(GL_TEXTURE_2D, 0, 0, 0, buf->width, buf->height, GL_RGB, GL_UNSIGNED_BYTE, 0); glBindTexture(GL_TEXTURE_2D, 0); assert(glGetError() == GL_NO_ERROR); - - emit vipcThreadFrameReceived(buf); - - glFlush(); - } else { - emit vipcThreadFrameReceived(buf); + // use glFinish to ensure that the texture has been uploaded. + glFinish(); } + latest_texture_id = buf->idx; + // Schedule update. update() will be invoked on the gui thread. + QMetaObject::invokeMethod(this, "update"); + + // TODO: remove later, it's only connected by DriverView. + emit vipcThreadFrameReceived(buf); } } } diff --git a/selfdrive/ui/qt/widgets/cameraview.h b/selfdrive/ui/qt/widgets/cameraview.h index 5e0fc1300b..fb69fcae59 100644 --- a/selfdrive/ui/qt/widgets/cameraview.h +++ b/selfdrive/ui/qt/widgets/cameraview.h @@ -36,7 +36,7 @@ protected: void vipcThread(); bool zoomed_view; - VisionBuf *latest_frame = nullptr; + std::atomic latest_texture_id = -1; GLuint frame_vao, frame_vbo, frame_ibo; mat4 frame_mat; std::unique_ptr texture[UI_BUF_COUNT]; @@ -49,9 +49,7 @@ protected: std::atomic stream_type; QThread *vipc_thread = nullptr; - std::mutex texture_lock; protected slots: void vipcConnected(VisionIpcClient *vipc_client); - void vipcFrameReceived(VisionBuf *buf); }; From ba67c355dbd032e4f6dfd95aaef519aa78c7c52a Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 29 Nov 2021 02:49:04 -0800 Subject: [PATCH 050/102] manager: kill procs in parallel (#23010) * manager: kill procs in parallel * oops block --- selfdrive/manager/manager.py | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/selfdrive/manager/manager.py b/selfdrive/manager/manager.py index 6c71c2a377..c8950acbd3 100755 --- a/selfdrive/manager/manager.py +++ b/selfdrive/manager/manager.py @@ -102,8 +102,13 @@ def manager_prepare(): def manager_cleanup(): + # send signals to kill all procs for p in managed_processes.values(): - p.stop() + p.stop(block=False) + + # ensure all are killed + for p in managed_processes.values(): + p.stop(block=True) cloudlog.info("everything is dead") From 296c4076a2ae8dfdcae5f300c922eac7d1df69cc Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Mon, 29 Nov 2021 19:09:14 +0800 Subject: [PATCH 051/102] framereader: refactor seeking (#22926) * refactor seeking * ckeck packets.empty() Co-authored-by: Willem Melching --- selfdrive/ui/replay/framereader.cc | 48 ++++++++++++++---------------- selfdrive/ui/replay/framereader.h | 10 ++----- 2 files changed, 25 insertions(+), 33 deletions(-) diff --git a/selfdrive/ui/replay/framereader.cc b/selfdrive/ui/replay/framereader.cc index 76e9ea7d66..e42859fd4f 100644 --- a/selfdrive/ui/replay/framereader.cc +++ b/selfdrive/ui/replay/framereader.cc @@ -38,8 +38,8 @@ FrameReader::FrameReader(bool local_cache, int chunk_size, int retries) : FileRe } FrameReader::~FrameReader() { - for (auto &f : frames_) { - av_packet_unref(&f.pkt); + for (AVPacket *pkt : packets) { + av_packet_free(&pkt); } if (decoder_ctx) avcodec_free_context(&decoder_ctx); @@ -106,18 +106,20 @@ bool FrameReader::load(const std::string &url, bool no_cuda, std::atomic * ret = avcodec_open2(decoder_ctx, decoder, NULL); if (ret < 0) return false; - frames_.reserve(60 * 20); // 20fps, one minute + packets.reserve(60 * 20); // 20fps, one minute while (!(abort && *abort)) { - Frame &frame = frames_.emplace_back(); - ret = av_read_frame(input_ctx, &frame.pkt); + AVPacket *pkt = av_packet_alloc(); + ret = av_read_frame(input_ctx, pkt); if (ret < 0) { - frames_.pop_back(); + av_packet_free(&pkt); valid_ = (ret == AVERROR_EOF); break; } + packets.push_back(pkt); // some stream seems to contian no keyframes - key_frames_count_ += frame.pkt.flags & AV_PKT_FLAG_KEY; + key_frames_count_ += pkt->flags & AV_PKT_FLAG_KEY; } + valid_ = valid_ && !packets.empty(); return valid_; } @@ -151,35 +153,29 @@ bool FrameReader::initHardwareDecoder(AVHWDeviceType hw_device_type) { bool FrameReader::get(int idx, uint8_t *rgb, uint8_t *yuv) { assert(rgb || yuv); - if (!valid_ || idx < 0 || idx >= frames_.size()) { + if (!valid_ || idx < 0 || idx >= packets.size()) { return false; } return decode(idx, rgb, yuv); } bool FrameReader::decode(int idx, uint8_t *rgb, uint8_t *yuv) { - auto get_keyframe = [=](int idx) { - for (int i = idx; i >= 0 && key_frames_count_ > 1; --i) { - if (frames_[i].pkt.flags & AV_PKT_FLAG_KEY) return i; - } - return idx; - }; - int from_idx = idx; - if (idx > 0 && !frames_[idx].decoded && !frames_[idx - 1].decoded) { - // find the previous keyframe - from_idx = get_keyframe(idx); + if (idx != prev_idx + 1 && key_frames_count_ > 1) { + // seeking to the nearest key frame + for (int i = idx; i >= 0; --i) { + if (packets[i]->flags & AV_PKT_FLAG_KEY) { + from_idx = i; + break; + } + } } + prev_idx = idx; for (int i = from_idx; i <= idx; ++i) { - Frame &frame = frames_[i]; - if ((!frame.decoded || i == idx) && !frame.failed) { - AVFrame *f = decodeFrame(&frame.pkt); - frame.decoded = f != nullptr; - frame.failed = !frame.decoded; - if (frame.decoded && i == idx) { - return copyBuffers(f, rgb, yuv); - } + AVFrame *f = decodeFrame(packets[i]); + if (f && i == idx) { + return copyBuffers(f, rgb, yuv); } } return false; diff --git a/selfdrive/ui/replay/framereader.h b/selfdrive/ui/replay/framereader.h index f6895c7be6..8a3f404158 100644 --- a/selfdrive/ui/replay/framereader.h +++ b/selfdrive/ui/replay/framereader.h @@ -23,7 +23,7 @@ public: bool get(int idx, uint8_t *rgb, uint8_t *yuv); int getRGBSize() const { return width * height * 3; } int getYUVSize() const { return width * height * 3 / 2; } - size_t getFrameCount() const { return frames_.size(); } + size_t getFrameCount() const { return packets.size(); } bool valid() const { return valid_; } int width = 0, height = 0; @@ -34,12 +34,7 @@ private: AVFrame * decodeFrame(AVPacket *pkt); bool copyBuffers(AVFrame *f, uint8_t *rgb, uint8_t *yuv); - struct Frame { - AVPacket pkt = {}; - int decoded = false; - bool failed = false; - }; - std::vector frames_; + std::vector packets; std::unique_ptrav_frame_, hw_frame; AVFormatContext *input_ctx = nullptr; AVCodecContext *decoder_ctx = nullptr; @@ -50,5 +45,6 @@ private: AVPixelFormat hw_pix_fmt = AV_PIX_FMT_NONE; AVBufferRef *hw_device_ctx = nullptr; std::vector nv12toyuv_buffer; + int prev_idx = -1; inline static std::atomic has_cuda_device = true; }; From a2f32fd3e18455ca2750f4a0a940ced2ca933163 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Mon, 29 Nov 2021 12:30:28 +0100 Subject: [PATCH 052/102] Clear loggerd locks once on boot (#23060) * add test for clear_locks * move to bootlog * simplify test --- selfdrive/loggerd/bootlog.cc | 1 + selfdrive/loggerd/logger.cc | 13 +++++++++++++ selfdrive/loggerd/logger.h | 1 + selfdrive/loggerd/loggerd.cc | 14 -------------- selfdrive/loggerd/loggerd.h | 1 - selfdrive/loggerd/tests/test_loggerd.cc | 18 ++++++++++++++++++ 6 files changed, 33 insertions(+), 15 deletions(-) diff --git a/selfdrive/loggerd/bootlog.cc b/selfdrive/loggerd/bootlog.cc index 481b3ee47c..5209958377 100644 --- a/selfdrive/loggerd/bootlog.cc +++ b/selfdrive/loggerd/bootlog.cc @@ -56,6 +56,7 @@ static kj::Array build_boot_log() { } int main(int argc, char** argv) { + clear_locks(LOG_ROOT); const std::string path = LOG_ROOT + "/boot/" + logger_get_route_name() + ".bz2"; LOGW("bootlog to %s", path.c_str()); diff --git a/selfdrive/loggerd/logger.cc b/selfdrive/loggerd/logger.cc index a73fefb8c9..81cfd131f6 100644 --- a/selfdrive/loggerd/logger.cc +++ b/selfdrive/loggerd/logger.cc @@ -2,6 +2,7 @@ #include #include +#include #include #include @@ -266,3 +267,15 @@ void lh_close(LoggerHandle* h) { } pthread_mutex_unlock(&h->lock); } + +int clear_locks_fn(const char* fpath, const struct stat *sb, int tyupeflag) { + const char* dot = strrchr(fpath, '.'); + if (dot && strcmp(dot, ".lock") == 0) { + unlink(fpath); + } + return 0; +} + +void clear_locks(const std::string log_root) { + ftw(log_root.c_str(), clear_locks_fn, 16); +} diff --git a/selfdrive/loggerd/logger.h b/selfdrive/loggerd/logger.h index bdda9d6917..e85d7810e0 100644 --- a/selfdrive/loggerd/logger.h +++ b/selfdrive/loggerd/logger.h @@ -96,3 +96,4 @@ void logger_log(LoggerState *s, uint8_t* data, size_t data_size, bool in_qlog); void lh_log(LoggerHandle* h, uint8_t* data, size_t data_size, bool in_qlog); void lh_close(LoggerHandle* h); +void clear_locks(const std::string log_root); diff --git a/selfdrive/loggerd/loggerd.cc b/selfdrive/loggerd/loggerd.cc index 40065b5859..e3444f3315 100644 --- a/selfdrive/loggerd/loggerd.cc +++ b/selfdrive/loggerd/loggerd.cc @@ -149,18 +149,6 @@ void encoder_thread(LoggerdState *s, const LogCameraInfo &cam_info) { } } -int clear_locks_fn(const char* fpath, const struct stat *sb, int tyupeflag) { - const char* dot = strrchr(fpath, '.'); - if (dot && strcmp(dot, ".lock") == 0) { - unlink(fpath); - } - return 0; -} - -void clear_locks() { - ftw(LOG_ROOT.c_str(), clear_locks_fn, 16); -} - void logger_rotate(LoggerdState *s) { { std::unique_lock lk(s->rotate_lock); @@ -190,8 +178,6 @@ void rotate_if_needed(LoggerdState *s) { } void loggerd_thread() { - clear_locks(); - // setup messaging typedef struct QlogState { int counter, freq; diff --git a/selfdrive/loggerd/loggerd.h b/selfdrive/loggerd/loggerd.h index b3e45adfae..448927ff8a 100644 --- a/selfdrive/loggerd/loggerd.h +++ b/selfdrive/loggerd/loggerd.h @@ -1,6 +1,5 @@ #pragma once -#include #include #include diff --git a/selfdrive/loggerd/tests/test_loggerd.cc b/selfdrive/loggerd/tests/test_loggerd.cc index d84185cbba..849b350ee4 100644 --- a/selfdrive/loggerd/tests/test_loggerd.cc +++ b/selfdrive/loggerd/tests/test_loggerd.cc @@ -91,3 +91,21 @@ TEST_CASE("trigger_rotate") { REQUIRE(frame_id == start_frame_id + encoder_seg * (SEGMENT_LENGTH * MAIN_FPS)); } } + +TEST_CASE("clear_locks") { + std::vector dirs; + for (int i = 0; i < 10; ++i) { + std::string &path = dirs.emplace_back(LOG_ROOT + "/" + std::to_string(i)); + REQUIRE(util::create_directories(path, 0775)); + std::ofstream{path + "/.lock"}; + REQUIRE(util::file_exists(path + "/.lock")); + } + + clear_locks(LOG_ROOT); + + for (const auto &dir : dirs) { + std::string lock_file = dir + "/.lock"; + REQUIRE(util::file_exists(lock_file) == false); + rmdir(dir.c_str()); + } +} From dbec761941c7599591fb59e9bb9f74b4f8cab2f7 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Mon, 29 Nov 2021 21:10:24 +0800 Subject: [PATCH 053/102] logreader: support reading from corrupt log (#23050) * catch exception outside loop * print decompress error * add test case for corrupt log * fix decompressbz2 stuck if log is corrupt * recovered from corrupt data * add output * ass space * std::endl * override load(), load from buffer * override FrameReader::load to load from the buffer * replace NULL with nullptr * fix test case for corrupt log * Trigger Build * check bzerror too Co-authored-by: Willem Melching --- selfdrive/camerad/cameras/camera_replay.cc | 2 +- selfdrive/ui/replay/framereader.cc | 24 ++++++++------ selfdrive/ui/replay/framereader.h | 7 ++-- selfdrive/ui/replay/logreader.cc | 38 +++++++++++++++++----- selfdrive/ui/replay/logreader.h | 7 ++-- selfdrive/ui/replay/route.cc | 8 ++--- selfdrive/ui/replay/tests/test_replay.cc | 11 +++++++ selfdrive/ui/replay/util.cc | 21 +++++++++--- selfdrive/ui/replay/util.h | 1 + 9 files changed, 85 insertions(+), 34 deletions(-) diff --git a/selfdrive/camerad/cameras/camera_replay.cc b/selfdrive/camerad/cameras/camera_replay.cc index 6bc53d8c94..731aab2a29 100644 --- a/selfdrive/camerad/cameras/camera_replay.cc +++ b/selfdrive/camerad/cameras/camera_replay.cc @@ -23,7 +23,7 @@ std::string get_url(std::string route_name, const std::string &camera, int segme } void camera_init(VisionIpcServer *v, CameraState *s, int camera_id, unsigned int fps, cl_device_id device_id, cl_context ctx, VisionStreamType rgb_type, VisionStreamType yuv_type, const std::string &url) { - s->frame = new FrameReader(true); + s->frame = new FrameReader(); if (!s->frame->load(url)) { printf("failed to load stream from %s", url.c_str()); assert(0); diff --git a/selfdrive/ui/replay/framereader.cc b/selfdrive/ui/replay/framereader.cc index e42859fd4f..32af922f1f 100644 --- a/selfdrive/ui/replay/framereader.cc +++ b/selfdrive/ui/replay/framereader.cc @@ -34,8 +34,7 @@ enum AVPixelFormat get_hw_format(AVCodecContext *ctx, const enum AVPixelFormat * } // namespace -FrameReader::FrameReader(bool local_cache, int chunk_size, int retries) : FileReader(local_cache, chunk_size, retries) { -} +FrameReader::FrameReader() {} FrameReader::~FrameReader() { for (AVPacket *pkt : packets) { @@ -52,17 +51,22 @@ FrameReader::~FrameReader() { } } -bool FrameReader::load(const std::string &url, bool no_cuda, std::atomic *abort) { - std::string content = read(url, abort); - if (content.empty()) return false; +bool FrameReader::load(const std::string &url, bool no_cuda, std::atomic *abort, bool local_cache, int chunk_size, int retries) { + FileReader f(local_cache, chunk_size, retries); + std::string data = f.read(url, abort); + if (data.empty()) return false; + + return load((std::byte *)data.data(), data.size(), no_cuda, abort); +} +bool FrameReader::load(const std::byte *data, size_t size, bool no_cuda, std::atomic *abort) { input_ctx = avformat_alloc_context(); if (!input_ctx) return false; struct buffer_data bd = { - .data = (uint8_t *)content.data(), + .data = (const uint8_t*)data, .offset = 0, - .size = content.size(), + .size = size, }; const int avio_ctx_buffer_size = 64 * 1024; unsigned char *avio_ctx_buffer = (unsigned char *)av_malloc(avio_ctx_buffer_size); @@ -70,11 +74,11 @@ bool FrameReader::load(const std::string &url, bool no_cuda, std::atomic * input_ctx->pb = avio_ctx_; input_ctx->probesize = 10 * 1024 * 1024; // 10MB - int ret = avformat_open_input(&input_ctx, url.c_str(), NULL, NULL); + int ret = avformat_open_input(&input_ctx, nullptr, nullptr, nullptr); if (ret != 0) { char err_str[1024] = {0}; av_strerror(ret, err_str, std::size(err_str)); - printf("Error loading video - %s - %s\n", err_str, url.c_str()); + printf("Error loading video - %s\n", err_str); return false; } @@ -103,7 +107,7 @@ bool FrameReader::load(const std::string &url, bool no_cuda, std::atomic * } } - ret = avcodec_open2(decoder_ctx, decoder, NULL); + ret = avcodec_open2(decoder_ctx, decoder, nullptr); if (ret < 0) return false; packets.reserve(60 * 20); // 20fps, one minute diff --git a/selfdrive/ui/replay/framereader.h b/selfdrive/ui/replay/framereader.h index 8a3f404158..d572b727e5 100644 --- a/selfdrive/ui/replay/framereader.h +++ b/selfdrive/ui/replay/framereader.h @@ -15,11 +15,12 @@ struct AVFrameDeleter { void operator()(AVFrame* frame) const { av_frame_free(&frame); } }; -class FrameReader : protected FileReader { +class FrameReader { public: - FrameReader(bool local_cache = false, int chunk_size = -1, int retries = 0); + FrameReader(); ~FrameReader(); - bool load(const std::string &url, bool no_cuda = false, std::atomic *abort = nullptr); + bool load(const std::string &url, bool no_cuda = false, std::atomic *abort = nullptr, bool local_cache = false, int chunk_size = -1, int retries = 0); + bool load(const std::byte *data, size_t size, bool no_cuda = false, std::atomic *abort = nullptr); bool get(int idx, uint8_t *rgb, uint8_t *yuv); int getRGBSize() const { return width * height * 3; } int getYUVSize() const { return width * height * 3 / 2; } diff --git a/selfdrive/ui/replay/logreader.cc b/selfdrive/ui/replay/logreader.cc index 7e7a943f88..8e2836a4ff 100644 --- a/selfdrive/ui/replay/logreader.cc +++ b/selfdrive/ui/replay/logreader.cc @@ -1,6 +1,7 @@ #include "selfdrive/ui/replay/logreader.h" #include +#include #include "selfdrive/ui/replay/util.h" Event::Event(const kj::ArrayPtr &amsg, bool frame) : reader(amsg), frame(frame) { @@ -26,7 +27,7 @@ Event::Event(const kj::ArrayPtr &amsg, bool frame) : reader(a // class LogReader -LogReader::LogReader(bool local_cache, int chunk_size, int retries, size_t memory_pool_block_size) : FileReader(local_cache, chunk_size, retries) { +LogReader::LogReader(size_t memory_pool_block_size) { #ifdef HAS_MEMORY_RESOURCE const size_t buf_size = sizeof(Event) * memory_pool_block_size; pool_buffer_ = ::operator new(buf_size); @@ -39,19 +40,32 @@ LogReader::~LogReader() { for (Event *e : events) { delete e; } + #ifdef HAS_MEMORY_RESOURCE delete mbr_; ::operator delete(pool_buffer_); #endif } -bool LogReader::load(const std::string &file, std::atomic *abort) { - raw_ = decompressBZ2(read(file, abort)); - if (raw_.empty()) return false; +bool LogReader::load(const std::string &url, std::atomic *abort, bool local_cache, int chunk_size, int retries) { + FileReader f(local_cache, chunk_size, retries); + std::string data = f.read(url, abort); + if (data.empty()) return false; + + return load((std::byte*)data.data(), data.size(), abort); +} + +bool LogReader::load(const std::byte *data, size_t size, std::atomic *abort) { + raw_ = decompressBZ2(data, size); + if (raw_.empty()) { + std::cout << "failed to decompress log" << std::endl; + return false; + } + + try { + kj::ArrayPtr words((const capnp::word *)raw_.data(), raw_.size() / sizeof(capnp::word)); + while (words.size() > 0) { - kj::ArrayPtr words((const capnp::word *)raw_.data(), raw_.size() / sizeof(capnp::word)); - while (words.size() > 0) { - try { #ifdef HAS_MEMORY_RESOURCE Event *evt = new (mbr_) Event(words); #else @@ -62,20 +76,26 @@ bool LogReader::load(const std::string &file, std::atomic *abort) { if (evt->which == cereal::Event::ROAD_ENCODE_IDX || evt->which == cereal::Event::DRIVER_ENCODE_IDX || evt->which == cereal::Event::WIDE_ROAD_ENCODE_IDX) { + #ifdef HAS_MEMORY_RESOURCE Event *frame_evt = new (mbr_) Event(words, true); #else Event *frame_evt = new Event(words, true); #endif + events.push_back(frame_evt); } words = kj::arrayPtr(evt->reader.getEnd(), words.end()); events.push_back(evt); - } catch (const kj::Exception &e) { - return false; } + } catch (const kj::Exception &e) { + std::cout << "failed to parse log : " << e.getDescription().cStr() << std::endl; + if (events.empty()) return false; + + std::cout << "read " << events.size() << " events from corrupt log" << std::endl; } + std::sort(events.begin(), events.end(), Event::lessThan()); return true; } diff --git a/selfdrive/ui/replay/logreader.h b/selfdrive/ui/replay/logreader.h index 5bb613d9de..33d7ea82f2 100644 --- a/selfdrive/ui/replay/logreader.h +++ b/selfdrive/ui/replay/logreader.h @@ -46,11 +46,12 @@ public: bool frame; }; -class LogReader : protected FileReader { +class LogReader { public: - LogReader(bool local_cache = false, int chunk_size = -1, int retries = 0, size_t memory_pool_block_size = DEFAULT_EVENT_MEMORY_POOL_BLOCK_SIZE); + LogReader(size_t memory_pool_block_size = DEFAULT_EVENT_MEMORY_POOL_BLOCK_SIZE); ~LogReader(); - bool load(const std::string &file, std::atomic *abort = nullptr); + bool load(const std::string &url, std::atomic *abort = nullptr, bool local_cache = false, int chunk_size = -1, int retries = 0); + bool load(const std::byte *data, size_t size, std::atomic *abort = nullptr); std::vector events; diff --git a/selfdrive/ui/replay/route.cc b/selfdrive/ui/replay/route.cc index b3736fa75f..23c27073cb 100644 --- a/selfdrive/ui/replay/route.cc +++ b/selfdrive/ui/replay/route.cc @@ -116,11 +116,11 @@ void Segment::loadFile(int id, const std::string file) { const bool local_cache = !(flags & REPLAY_FLAG_NO_FILE_CACHE); bool success = false; if (id < MAX_CAMERAS) { - frames[id] = std::make_unique(local_cache, 20 * 1024 * 1024, 3); - success = frames[id]->load(file, flags & REPLAY_FLAG_NO_CUDA, &abort_); + frames[id] = std::make_unique(); + success = frames[id]->load(file, flags & REPLAY_FLAG_NO_CUDA, &abort_, local_cache, 20 * 1024 * 1024, 3); } else { - log = std::make_unique(local_cache, 0, 3); - success = log->load(file, &abort_); + log = std::make_unique(); + success = log->load(file, &abort_, local_cache, 0, 3); } if (!success) { diff --git a/selfdrive/ui/replay/tests/test_replay.cc b/selfdrive/ui/replay/tests/test_replay.cc index 9efc55a610..5b9b7cdeb7 100644 --- a/selfdrive/ui/replay/tests/test_replay.cc +++ b/selfdrive/ui/replay/tests/test_replay.cc @@ -50,6 +50,17 @@ TEST_CASE("FileReader") { } } +TEST_CASE("LogReader") { + SECTION("corrupt log") { + FileReader reader(true); + std::string corrupt_content = reader.read(TEST_RLOG_URL); + corrupt_content.resize(corrupt_content.length() / 2); + LogReader log; + REQUIRE(log.load((std::byte *)corrupt_content.data(), corrupt_content.size())); + REQUIRE(log.events.size() > 0); + } +} + TEST_CASE("Segment") { auto flags = GENERATE(REPLAY_FLAG_DCAM | REPLAY_FLAG_ECAM, REPLAY_FLAG_QCAMERA); Route demo_route(DEMO_ROUTE); diff --git a/selfdrive/ui/replay/util.cc b/selfdrive/ui/replay/util.cc index 27f0bd9cfd..d6791465f2 100644 --- a/selfdrive/ui/replay/util.cc +++ b/selfdrive/ui/replay/util.cc @@ -194,19 +194,32 @@ bool httpDownload(const std::string &url, const std::string &file, size_t chunk_ } std::string decompressBZ2(const std::string &in) { - if (in.empty()) return {}; + return decompressBZ2((std::byte *)in.data(), in.size()); +} + +std::string decompressBZ2(const std::byte *in, size_t in_size) { + if (in_size == 0) return {}; bz_stream strm = {}; int bzerror = BZ2_bzDecompressInit(&strm, 0, 0); assert(bzerror == BZ_OK); - strm.next_in = (char *)in.data(); - strm.avail_in = in.size(); - std::string out(in.size() * 5, '\0'); + strm.next_in = (char *)in; + strm.avail_in = in_size; + std::string out(in_size * 5, '\0'); do { strm.next_out = (char *)(&out[strm.total_out_lo32]); strm.avail_out = out.size() - strm.total_out_lo32; + + const char *prev_write_pos = strm.next_out; bzerror = BZ2_bzDecompress(&strm); + if (bzerror == BZ_OK && prev_write_pos == strm.next_out) { + // content is corrupt + bzerror = BZ_STREAM_END; + std::cout << "decompressBZ2 error : content is corrupt" << std::endl; + break; + } + if (bzerror == BZ_OK && strm.avail_in > 0 && strm.avail_out == 0) { out.resize(out.size() * 2); } diff --git a/selfdrive/ui/replay/util.h b/selfdrive/ui/replay/util.h index 85d7af0125..726e65cb94 100644 --- a/selfdrive/ui/replay/util.h +++ b/selfdrive/ui/replay/util.h @@ -6,6 +6,7 @@ std::string sha256(const std::string &str); void precise_nano_sleep(long sleep_ns); std::string decompressBZ2(const std::string &in); +std::string decompressBZ2(const std::byte *in, size_t in_size); void enableHttpLogging(bool enable); std::string getUrlWithoutQuery(const std::string &url); size_t getRemoteFileSize(const std::string &url); From b2bcacf590f0206f7b608c4cc48afe61393dd007 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Mon, 29 Nov 2021 21:49:53 +0800 Subject: [PATCH 054/102] ui: singleton networkAccessManager (#22994) --- selfdrive/ui/qt/api.cc | 16 ++++++++++------ selfdrive/ui/qt/api.h | 2 +- 2 files changed, 11 insertions(+), 7 deletions(-) diff --git a/selfdrive/ui/qt/api.cc b/selfdrive/ui/qt/api.cc index 98236e5014..8ac9b41313 100644 --- a/selfdrive/ui/qt/api.cc +++ b/selfdrive/ui/qt/api.cc @@ -4,6 +4,7 @@ #include #include +#include #include #include #include @@ -62,8 +63,6 @@ QString create_jwt(const QJsonObject &payloads, int expiry) { } // namespace CommaApi HttpRequest::HttpRequest(QObject *parent, bool create_jwt, int timeout) : create_jwt(create_jwt), QObject(parent) { - networkAccessManager = new QNetworkAccessManager(this); - networkTimer = new QTimer(this); networkTimer->setSingleShot(true); networkTimer->setInterval(timeout); @@ -101,9 +100,9 @@ void HttpRequest::sendRequest(const QString &requestURL, const HttpRequest::Meth } if (method == HttpRequest::Method::GET) { - reply = networkAccessManager->get(request); + reply = nam()->get(request); } else if (method == HttpRequest::Method::DELETE) { - reply = networkAccessManager->deleteResource(request); + reply = nam()->deleteResource(request); } networkTimer->start(); @@ -122,8 +121,8 @@ void HttpRequest::requestFinished() { } else { QString error; if (reply->error() == QNetworkReply::OperationCanceledError) { - networkAccessManager->clearAccessCache(); - networkAccessManager->clearConnectionCache(); + nam()->clearAccessCache(); + nam()->clearConnectionCache(); error = "Request timed out"; } else { if (reply->error() == QNetworkReply::ContentAccessDenied || reply->error() == QNetworkReply::AuthenticationRequiredError) { @@ -137,3 +136,8 @@ void HttpRequest::requestFinished() { reply->deleteLater(); reply = nullptr; } + +QNetworkAccessManager *HttpRequest::nam() { + static QNetworkAccessManager *networkAccessManager = new QNetworkAccessManager(qApp); + return networkAccessManager; +} diff --git a/selfdrive/ui/qt/api.h b/selfdrive/ui/qt/api.h index 6890a7957d..8f74678109 100644 --- a/selfdrive/ui/qt/api.h +++ b/selfdrive/ui/qt/api.h @@ -37,7 +37,7 @@ protected: QNetworkReply *reply = nullptr; private: - QNetworkAccessManager *networkAccessManager = nullptr; + static QNetworkAccessManager *nam(); QTimer *networkTimer = nullptr; bool create_jwt; From 7c8044d2dbb2ce74c0c622b468caec185e590d48 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Mon, 29 Nov 2021 15:51:27 +0100 Subject: [PATCH 055/102] Add LastPowerDropDetected and create bootlog before clearing params (#23062) * Add LastControlledShutdown and create bootlog before clearing params * update param name * sorting --- selfdrive/common/params.cc | 1 + selfdrive/manager/manager.py | 7 +++---- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/selfdrive/common/params.cc b/selfdrive/common/params.cc index ebb37344ef..ea09ee0705 100644 --- a/selfdrive/common/params.cc +++ b/selfdrive/common/params.cc @@ -130,6 +130,7 @@ std::unordered_map keys = { {"JoystickDebugMode", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_OFF}, {"LastAthenaPingTime", CLEAR_ON_MANAGER_START}, {"LastGPSPosition", PERSISTENT}, + {"LastPowerDropDetected", CLEAR_ON_MANAGER_START}, {"LastUpdateException", PERSISTENT}, {"LastUpdateTime", PERSISTENT}, {"LiveParameters", PERSISTENT}, diff --git a/selfdrive/manager/manager.py b/selfdrive/manager/manager.py index c8950acbd3..4c70a38518 100755 --- a/selfdrive/manager/manager.py +++ b/selfdrive/manager/manager.py @@ -25,10 +25,12 @@ from selfdrive.version import dirty, get_git_commit, version, origin, branch, co sys.path.append(os.path.join(BASEDIR, "pyextra")) def manager_init(): - # update system time from panda set_time(cloudlog) + # save boot log + subprocess.call("./bootlog", cwd=os.path.join(BASEDIR, "selfdrive/loggerd")) + params = Params() params.clear_all(ParamKeyType.CLEAR_ON_MANAGER_START) @@ -117,9 +119,6 @@ def manager_thread(): cloudlog.info("manager start") cloudlog.info({"environ": os.environ}) - # save boot log - subprocess.call("./bootlog", cwd=os.path.join(BASEDIR, "selfdrive/loggerd")) - params = Params() ignore = [] From f7c46c694985456e569ce2313b29e43607c62a12 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Mon, 29 Nov 2021 19:38:55 +0100 Subject: [PATCH 056/102] Do not run code on version.py import (#23063) * Do not run code on version.py import * fix athena --- common/api/__init__.py | 8 +- selfdrive/athena/athenad.py | 10 +-- selfdrive/athena/manage_athenad.py | 4 +- selfdrive/car/car_helpers.py | 4 +- selfdrive/crash.py | 4 +- selfdrive/loggerd/tests/test_loggerd.py | 4 +- selfdrive/manager/build.py | 4 +- selfdrive/manager/manager.py | 23 ++--- selfdrive/test/process_replay/model_replay.py | 4 +- selfdrive/test/process_replay/update_refs.py | 4 +- selfdrive/thermald/thermald.py | 4 +- selfdrive/tombstoned.py | 16 ++-- selfdrive/version.py | 90 ++++++++++++------- 13 files changed, 103 insertions(+), 76 deletions(-) diff --git a/common/api/__init__.py b/common/api/__init__.py index 5b1d66cf77..8b83dfc641 100644 --- a/common/api/__init__.py +++ b/common/api/__init__.py @@ -3,7 +3,7 @@ import os import requests from datetime import datetime, timedelta from common.basedir import PERSIST -from selfdrive.version import version +from selfdrive.version import get_version API_HOST = os.getenv('API_HOST', 'https://api.commadotai.com') @@ -34,13 +34,13 @@ class Api(): if isinstance(token, bytes): token = token.decode('utf8') return token - + def api_get(endpoint, method='GET', timeout=None, access_token=None, **params): headers = {} if access_token is not None: - headers['Authorization'] = "JWT "+access_token + headers['Authorization'] = "JWT " + access_token - headers['User-Agent'] = "openpilot-" + version + headers['User-Agent'] = "openpilot-" + get_version() return requests.request(method, API_HOST + "/" + endpoint, timeout=timeout, headers=headers, params=params) diff --git a/selfdrive/athena/athenad.py b/selfdrive/athena/athenad.py index 779045bf97..5e462a42f3 100755 --- a/selfdrive/athena/athenad.py +++ b/selfdrive/athena/athenad.py @@ -30,7 +30,7 @@ from selfdrive.hardware import HARDWARE, PC from selfdrive.loggerd.config import ROOT from selfdrive.loggerd.xattr_cache import getxattr, setxattr from selfdrive.swaglog import cloudlog, SWAGLOG_DIR -from selfdrive.version import version, get_version, get_git_remote, get_git_branch, get_git_commit +from selfdrive.version import get_version, get_origin, get_short_branch, get_commit ATHENA_HOST = os.getenv('ATHENA_HOST', 'wss://athena.comma.ai') HANDLER_THREADS = int(os.getenv('HANDLER_THREADS', "4")) @@ -176,9 +176,9 @@ def getMessage(service=None, timeout=1000): def getVersion(): return { "version": get_version(), - "remote": get_git_remote(), - "branch": get_git_branch(), - "commit": get_git_commit(), + "remote": get_origin(), + "branch": get_short_branch(), + "commit": get_commit(), } @@ -551,7 +551,7 @@ def main(): except socket.timeout: try: r = requests.get("http://api.commadotai.com/v1/me", allow_redirects=False, - headers={"User-Agent": f"openpilot-{version}"}, timeout=15.0) + headers={"User-Agent": f"openpilot-{get_version()}"}, timeout=15.0) if r.status_code == 302 and r.headers['Location'].startswith("http://u.web2go.com"): params.put_bool("PrimeRedirected", True) except Exception: diff --git a/selfdrive/athena/manage_athenad.py b/selfdrive/athena/manage_athenad.py index 7bb717e078..fa95eacd8e 100755 --- a/selfdrive/athena/manage_athenad.py +++ b/selfdrive/athena/manage_athenad.py @@ -6,7 +6,7 @@ from multiprocessing import Process from common.params import Params from selfdrive.manager.process import launcher from selfdrive.swaglog import cloudlog -from selfdrive.version import version, dirty +from selfdrive.version import get_version, get_dirty ATHENA_MGR_PID_PARAM = "AthenadPid" @@ -14,7 +14,7 @@ ATHENA_MGR_PID_PARAM = "AthenadPid" def main(): params = Params() dongle_id = params.get("DongleId").decode('utf-8') - cloudlog.bind_global(dongle_id=dongle_id, version=version, dirty=dirty) + cloudlog.bind_global(dongle_id=dongle_id, version=get_version(), dirty=get_dirty()) try: while 1: diff --git a/selfdrive/car/car_helpers.py b/selfdrive/car/car_helpers.py index 980b207fa7..786b00fa2b 100644 --- a/selfdrive/car/car_helpers.py +++ b/selfdrive/car/car_helpers.py @@ -1,7 +1,7 @@ import os from common.params import Params from common.basedir import BASEDIR -from selfdrive.version import comma_remote, tested_branch +from selfdrive.version import get_comma_remote, get_tested_branch from selfdrive.car.fingerprints import eliminate_incompatible_cars, all_legacy_fingerprint_cars from selfdrive.car.vin import get_vin, VIN_UNKNOWN from selfdrive.car.fw_versions import get_fw_versions, match_fw_to_car @@ -14,7 +14,7 @@ EventName = car.CarEvent.EventName def get_startup_event(car_recognized, controller_available, fw_seen): - if comma_remote and tested_branch: + if get_comma_remote() and get_tested_branch(): event = EventName.startup else: event = EventName.startupMaster diff --git a/selfdrive/crash.py b/selfdrive/crash.py index f85d7c0e6d..e42b7532b0 100644 --- a/selfdrive/crash.py +++ b/selfdrive/crash.py @@ -1,6 +1,6 @@ """Install exception handler for process crash.""" from selfdrive.swaglog import cloudlog -from selfdrive.version import version +from selfdrive.version import get_version import sentry_sdk from sentry_sdk.integrations.threading import ThreadingIntegration @@ -24,4 +24,4 @@ def bind_extra(**kwargs) -> None: def init() -> None: sentry_sdk.init("https://a8dc76b5bfb34908a601d67e2aa8bcf9@o33823.ingest.sentry.io/77924", default_integrations=False, integrations=[ThreadingIntegration(propagate_hub=True)], - release=version) + release=get_version()) diff --git a/selfdrive/loggerd/tests/test_loggerd.py b/selfdrive/loggerd/tests/test_loggerd.py index 7ee97f5118..021eea5c83 100755 --- a/selfdrive/loggerd/tests/test_loggerd.py +++ b/selfdrive/loggerd/tests/test_loggerd.py @@ -18,7 +18,7 @@ from selfdrive.hardware import PC, TICI from selfdrive.loggerd.config import ROOT from selfdrive.manager.process_config import managed_processes from selfdrive.test.helpers import with_processes -from selfdrive.version import version as VERSION +from selfdrive.version import get_version from tools.lib.logreader import LogReader SentinelType = log.Sentinel.SentinelType @@ -95,7 +95,7 @@ class TestLoggerd(unittest.TestCase): initData = lr[0].initData self.assertTrue(initData.dirty != bool(os.environ["CLEAN"])) - self.assertEqual(initData.version, VERSION) + self.assertEqual(initData.version, get_version()) if os.path.isfile("/proc/cmdline"): with open("/proc/cmdline") as f: diff --git a/selfdrive/manager/build.py b/selfdrive/manager/build.py index c4fd4746ef..04769526ff 100755 --- a/selfdrive/manager/build.py +++ b/selfdrive/manager/build.py @@ -12,7 +12,7 @@ from common.spinner import Spinner from common.text_window import TextWindow from selfdrive.hardware import TICI from selfdrive.swaglog import cloudlog, add_file_handler -from selfdrive.version import dirty +from selfdrive.version import get_dirty MAX_CACHE_SIZE = 2e9 CACHE_DIR = Path("/data/scons_cache" if TICI else "/tmp/scons_cache") @@ -98,4 +98,4 @@ def build(spinner, dirty=False): if __name__ == "__main__" and not PREBUILT: spinner = Spinner() spinner.update_progress(0, 100) - build(spinner, dirty) + build(spinner, get_dirty()) diff --git a/selfdrive/manager/manager.py b/selfdrive/manager/manager.py index 4c70a38518..66de8eccc3 100755 --- a/selfdrive/manager/manager.py +++ b/selfdrive/manager/manager.py @@ -18,12 +18,13 @@ from selfdrive.manager.process import ensure_running from selfdrive.manager.process_config import managed_processes from selfdrive.athena.registration import register, UNREGISTERED_DONGLE_ID from selfdrive.swaglog import cloudlog, add_file_handler -from selfdrive.version import dirty, get_git_commit, version, origin, branch, commit, \ - terms_version, training_version, comma_remote, \ - get_git_branch, get_git_remote +from selfdrive.version import get_dirty, get_commit, get_version, get_origin, get_branch, \ + terms_version, training_version, get_comma_remote + sys.path.append(os.path.join(BASEDIR, "pyextra")) + def manager_init(): # update system time from panda set_time(cloudlog) @@ -69,12 +70,12 @@ def manager_init(): print("WARNING: failed to make /dev/shm") # set version params - params.put("Version", version) + params.put("Version", get_version()) params.put("TermsVersion", terms_version) params.put("TrainingVersion", training_version) - params.put("GitCommit", get_git_commit(default="")) - params.put("GitBranch", get_git_branch(default="")) - params.put("GitRemote", get_git_remote(default="")) + params.put("GitCommit", get_commit(default="")) + params.put("GitBranch", get_branch(default="")) + params.put("GitRemote", get_origin(default="")) # set dongle id reg_res = register(show_spinner=True) @@ -85,16 +86,16 @@ def manager_init(): raise Exception(f"Registration failed for device {serial}") os.environ['DONGLE_ID'] = dongle_id # Needed for swaglog - if not dirty: + if not get_dirty(): os.environ['CLEAN'] = '1' - cloudlog.bind_global(dongle_id=dongle_id, version=version, dirty=dirty, + cloudlog.bind_global(dongle_id=dongle_id, version=get_version(), dirty=get_dirty(), device=HARDWARE.get_device_type()) - if comma_remote and not (os.getenv("NOLOG") or os.getenv("NOCRASH") or PC): + if get_comma_remote() and not (os.getenv("NOLOG") or os.getenv("NOCRASH") or PC): crash.init() crash.bind_user(id=dongle_id) - crash.bind_extra(dirty=dirty, origin=origin, branch=branch, commit=commit, + crash.bind_extra(dirty=get_dirty(), origin=get_origin(), branch=get_branch(), commit=get_commit(), device=HARDWARE.get_device_type()) diff --git a/selfdrive/test/process_replay/model_replay.py b/selfdrive/test/process_replay/model_replay.py index 3b03bc8408..16ffea3c73 100755 --- a/selfdrive/test/process_replay/model_replay.py +++ b/selfdrive/test/process_replay/model_replay.py @@ -17,7 +17,7 @@ from selfdrive.manager.process_config import managed_processes 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 +from selfdrive.version import get_commit from tools.lib.framereader import FrameReader from tools.lib.logreader import LogReader @@ -169,7 +169,7 @@ if __name__ == "__main__": print("Uploading new refs") - new_commit = get_git_commit() + new_commit = get_commit() log_fn = get_log_fn(new_commit) save_log(log_fn, log_msgs) try: diff --git a/selfdrive/test/process_replay/update_refs.py b/selfdrive/test/process_replay/update_refs.py index fe5212d2c6..96feb0d534 100755 --- a/selfdrive/test/process_replay/update_refs.py +++ b/selfdrive/test/process_replay/update_refs.py @@ -6,7 +6,7 @@ from selfdrive.test.openpilotci import upload_file, get_url 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 -from selfdrive.version import get_git_commit +from selfdrive.version import get_commit from tools.lib.logreader import LogReader if __name__ == "__main__": @@ -16,7 +16,7 @@ if __name__ == "__main__": process_replay_dir = os.path.dirname(os.path.abspath(__file__)) ref_commit_fn = os.path.join(process_replay_dir, "ref_commit") - ref_commit = get_git_commit() + ref_commit = get_commit() if ref_commit is None: raise Exception("couldn't get ref commit") with open(ref_commit_fn, "w") as f: diff --git a/selfdrive/thermald/thermald.py b/selfdrive/thermald/thermald.py index 114110891e..eb3e594269 100755 --- a/selfdrive/thermald/thermald.py +++ b/selfdrive/thermald/thermald.py @@ -22,7 +22,7 @@ from selfdrive.hardware import EON, TICI, PC, HARDWARE from selfdrive.loggerd.config import get_available_percent from selfdrive.swaglog import cloudlog from selfdrive.thermald.power_monitoring import PowerMonitoring -from selfdrive.version import tested_branch, terms_version, training_version +from selfdrive.version import get_tested_branch, terms_version, training_version ThermalStatus = log.DeviceState.ThermalStatus NetworkType = log.DeviceState.NetworkType @@ -343,7 +343,7 @@ def thermald_thread(): last_update_exception = params.get("LastUpdateException", encoding='utf8') if update_failed_count > 15 and last_update_exception is not None: - if tested_branch: + if get_tested_branch(): extra_text = "Ensure the software is correctly installed" else: extra_text = last_update_exception diff --git a/selfdrive/tombstoned.py b/selfdrive/tombstoned.py index fb7a1a2c99..a301725bae 100755 --- a/selfdrive/tombstoned.py +++ b/selfdrive/tombstoned.py @@ -15,7 +15,7 @@ from common.file_helpers import mkdirs_exists_ok from selfdrive.hardware import TICI, HARDWARE from selfdrive.loggerd.config import ROOT from selfdrive.swaglog import cloudlog -from selfdrive.version import branch, commit, dirty, origin, version +from selfdrive.version import get_branch, get_commit, get_dirty, get_origin, get_version MAX_SIZE = 100000 * 10 # mal size is 40-100k, allow up to 1M if TICI: @@ -109,7 +109,7 @@ def report_tombstone_android(fn): clean_path = executable.replace('./', '').replace('/', '_') date = datetime.datetime.now().strftime("%Y-%m-%d--%H-%M-%S") - new_fn = f"{date}_{commit[:8]}_{safe_fn(clean_path)}"[:MAX_TOMBSTONE_FN_LEN] + new_fn = f"{date}_{get_commit(default='nocommit')[:8]}_{safe_fn(clean_path)}"[:MAX_TOMBSTONE_FN_LEN] crashlog_dir = os.path.join(ROOT, "crash") mkdirs_exists_ok(crashlog_dir) @@ -183,7 +183,7 @@ def report_tombstone_apport(fn): clean_path = path.replace('/', '_') date = datetime.datetime.now().strftime("%Y-%m-%d--%H-%M-%S") - new_fn = f"{date}_{commit[:8]}_{safe_fn(clean_path)}"[:MAX_TOMBSTONE_FN_LEN] + new_fn = f"{date}_{get_commit(default='nocommit')[:8]}_{safe_fn(clean_path)}"[:MAX_TOMBSTONE_FN_LEN] crashlog_dir = os.path.join(ROOT, "crash") mkdirs_exists_ok(crashlog_dir) @@ -203,14 +203,14 @@ def main(): sentry_sdk.utils.MAX_STRING_LENGTH = 8192 sentry_sdk.init("https://a40f22e13cbc4261873333c125fc9d38@o33823.ingest.sentry.io/157615", - default_integrations=False, release=version) + default_integrations=False, release=get_version()) dongle_id = Params().get("DongleId", encoding='utf-8') sentry_sdk.set_user({"id": dongle_id}) - sentry_sdk.set_tag("dirty", dirty) - sentry_sdk.set_tag("origin", origin) - sentry_sdk.set_tag("branch", branch) - sentry_sdk.set_tag("commit", commit) + sentry_sdk.set_tag("dirty", get_dirty()) + sentry_sdk.set_tag("origin", get_origin()) + sentry_sdk.set_tag("branch", get_branch()) + sentry_sdk.set_tag("commit", get_commit()) sentry_sdk.set_tag("device", HARDWARE.get_device_type()) while True: diff --git a/selfdrive/version.py b/selfdrive/version.py index 7a2234e3ec..2ddfc93c69 100644 --- a/selfdrive/version.py +++ b/selfdrive/version.py @@ -2,6 +2,7 @@ import os import subprocess from typing import List, Optional +from functools import lru_cache from common.basedir import BASEDIR from selfdrive.swaglog import cloudlog @@ -9,9 +10,16 @@ from selfdrive.swaglog import cloudlog TESTED_BRANCHES = ['devel', 'release2-staging', 'release3-staging', 'dashcam-staging', 'release2', 'release3', 'dashcam'] +training_version: bytes = b"0.2.0" +terms_version: bytes = b"2" + + +def cache(user_function, /): + return lru_cache(maxsize=None)(user_function) + def run_cmd(cmd: List[str]) -> str: - return subprocess.check_output(cmd, encoding='utf8').strip() + return subprocess.check_output(cmd, encoding='utf8').strip() def run_cmd_default(cmd: List[str], default: Optional[str] = None) -> Optional[str]: @@ -21,19 +29,23 @@ def run_cmd_default(cmd: List[str], default: Optional[str] = None) -> Optional[s return default -def get_git_commit(branch: str = "HEAD", default: Optional[str] = None) -> Optional[str]: +@cache +def get_commit(branch: str = "HEAD", default: Optional[str] = None) -> Optional[str]: return run_cmd_default(["git", "rev-parse", branch], default=default) -def get_git_branch(default: Optional[str] = None) -> Optional[str]: +@cache +def get_short_branch(default: Optional[str] = None) -> Optional[str]: return run_cmd_default(["git", "rev-parse", "--abbrev-ref", "HEAD"], default=default) -def get_git_full_branchname(default: Optional[str] = None) -> Optional[str]: +@cache +def get_branch(default: Optional[str] = None) -> Optional[str]: return run_cmd_default(["git", "rev-parse", "--abbrev-ref", "--symbolic-full-name", "@{u}"], default=default) -def get_git_remote(default: Optional[str] = None) -> Optional[str]: +@cache +def get_origin(default: Optional[str] = None) -> Optional[str]: try: local_branch = run_cmd(["git", "name-rev", "--name-only", "HEAD"]) tracking_remote = run_cmd(["git", "config", "branch." + local_branch + ".remote"]) @@ -42,55 +54,68 @@ def get_git_remote(default: Optional[str] = None) -> Optional[str]: return run_cmd_default(["git", "config", "--get", "remote.origin.url"], default=default) -def get_version(): +@cache +def get_version() -> str: with open(os.path.join(os.path.dirname(os.path.abspath(__file__)), "common", "version.h")) as _versionf: version = _versionf.read().split('"')[1] return version -version = get_version() -prebuilt = os.path.exists(os.path.join(BASEDIR, 'prebuilt')) -training_version: bytes = b"0.2.0" -terms_version: bytes = b"2" +@cache +def get_prebuilt() -> bool: + return os.path.exists(os.path.join(BASEDIR, 'prebuilt')) -dirty: bool = True -comma_remote: bool = False -tested_branch: bool = False -origin = get_git_remote() -branch = get_git_full_branchname() -commit = get_git_commit() -if (origin is not None) and (branch is not None): - try: - comma_remote = origin.startswith('git@github.com:commaai') or origin.startswith('https://github.com/commaai') - tested_branch = get_git_branch() in TESTED_BRANCHES +@cache +def get_comma_remote() -> bool: + origin = get_origin() + if origin is None: + return False + + return origin.startswith('git@github.com:commaai') or origin.startswith('https://github.com/commaai') - dirty = False +@cache +def get_tested_branch() -> bool: + return get_short_branch() in TESTED_BRANCHES + + +@cache +def get_dirty() -> bool: + origin = get_origin() + branch = get_branch() + if (origin is None) or (branch is None): + return True + + dirty = False + try: # Actually check dirty files - if not prebuilt: + if not get_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: + if dirty and get_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=commit, origin_commit=get_git_commit(branch)) + cloudlog.event("dirty comma branch", version=get_version(), dirty=dirty, origin=origin, branch=branch, + dirty_files=dirty_files, commit=get_commit(), origin_commit=get_commit(branch)) except subprocess.CalledProcessError: pass - dirty = dirty or (not comma_remote) + dirty = dirty or (not get_comma_remote()) dirty = dirty or ('master' in branch) except subprocess.CalledProcessError: - dirty = True cloudlog.exception("git subprocess failed while checking dirty") + dirty = True + + return dirty if __name__ == "__main__": @@ -100,8 +125,9 @@ if __name__ == "__main__": params.put("TermsVersion", terms_version) params.put("TrainingVersion", training_version) - print("Dirty: %s" % dirty) - print("Version: %s" % version) - print("Remote: %s" % origin) - print("Branch: %s" % branch) - print("Prebuilt: %s" % prebuilt) + print("Dirty: %s" % get_dirty()) + print("Version: %s" % get_version()) + print("Origin: %s" % get_origin()) + print("Branch: %s" % get_branch()) + print("Short branch: %s" % get_short_branch()) + print("Prebuilt: %s" % get_prebuilt()) From 29a8fe272cc60a80a000cdb9a921a38a4298c501 Mon Sep 17 00:00:00 2001 From: Vehicle Researcher Date: Mon, 29 Nov 2021 13:41:48 -0800 Subject: [PATCH 057/102] fix pmic temp scale on comma two --- selfdrive/hardware/eon/hardware.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/hardware/eon/hardware.py b/selfdrive/hardware/eon/hardware.py index 4ba85d2f8c..fa275c5a9c 100644 --- a/selfdrive/hardware/eon/hardware.py +++ b/selfdrive/hardware/eon/hardware.py @@ -369,7 +369,7 @@ class Android(HardwareBase): os.system('LD_LIBRARY_PATH="" svc power shutdown') def get_thermal_config(self): - return ThermalConfig(cpu=((5, 7, 10, 12), 10), gpu=((16,), 10), mem=(2, 10), bat=(29, 1000), ambient=(25, 1), pmic=((22,), 1)) + return ThermalConfig(cpu=((5, 7, 10, 12), 10), gpu=((16,), 10), mem=(2, 10), bat=(29, 1000), ambient=(25, 1), pmic=((22,), 1000)) def set_screen_brightness(self, percentage): with open("/sys/class/leds/lcd-backlight/brightness", "w") as f: From 01b99eae35906ba95c25c2498b19a53a0e8fc591 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 29 Nov 2021 13:44:20 -0800 Subject: [PATCH 058/102] logreader: remove log path print --- tools/lib/logreader.py | 1 - 1 file changed, 1 deletion(-) diff --git a/tools/lib/logreader.py b/tools/lib/logreader.py index 01c666fd16..2b571753f9 100755 --- a/tools/lib/logreader.py +++ b/tools/lib/logreader.py @@ -26,7 +26,6 @@ class MultiLogIterator(object): def _log_reader(self, i): if self._log_readers[i] is None and self._log_paths[i] is not None: log_path = self._log_paths[i] - print("LogReader:%s" % log_path) self._log_readers[i] = LogReader(log_path) return self._log_readers[i] From 048cc3ac9f86ed2b3b9fe82cb28ec243cc8e7bac Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Mon, 29 Nov 2021 15:22:02 -0800 Subject: [PATCH 059/102] Longcontrol : pid error should be 0 when plan is followed (#23066) * v_pid error should be 0 when plan is followed * update ref --- selfdrive/controls/lib/longcontrol.py | 17 +++++++---------- selfdrive/test/process_replay/ref_commit | 2 +- 2 files changed, 8 insertions(+), 11 deletions(-) diff --git a/selfdrive/controls/lib/longcontrol.py b/selfdrive/controls/lib/longcontrol.py index fcebf1b564..beacc518d0 100644 --- a/selfdrive/controls/lib/longcontrol.py +++ b/selfdrive/controls/lib/longcontrol.py @@ -10,20 +10,20 @@ LongCtrlState = car.CarControl.Actuators.LongControlState STOPPING_TARGET_SPEED_OFFSET = 0.01 # As per ISO 15622:2018 for all speeds -ACCEL_MIN_ISO = -3.5 # m/s^2 -ACCEL_MAX_ISO = 2.0 # m/s^2 +ACCEL_MIN_ISO = -3.5 # m/s^2 +ACCEL_MAX_ISO = 2.0 # m/s^2 -def long_control_state_trans(CP, active, long_control_state, v_ego, v_target, v_pid, +def long_control_state_trans(CP, active, long_control_state, v_ego, v_target_future, v_pid, output_accel, brake_pressed, cruise_standstill, min_speed_can): """Update longitudinal control state machine""" stopping_target_speed = min_speed_can + STOPPING_TARGET_SPEED_OFFSET stopping_condition = (v_ego < 2.0 and cruise_standstill) or \ (v_ego < CP.vEgoStopping and - ((v_pid < stopping_target_speed and v_target < stopping_target_speed) or + ((v_pid < stopping_target_speed and v_target_future < stopping_target_speed) or brake_pressed)) - starting_condition = v_target > CP.vEgoStarting and not cruise_standstill + starting_condition = v_target_future > CP.vEgoStarting and not cruise_standstill if not active: long_control_state = LongCtrlState.off @@ -75,13 +75,10 @@ class LongControl(): v_target_upper = interp(CP.longitudinalActuatorDelayUpperBound, T_IDXS[:CONTROL_N], long_plan.speeds) a_target_upper = 2 * (v_target_upper - long_plan.speeds[0])/CP.longitudinalActuatorDelayUpperBound - long_plan.accels[0] - - v_target = min(v_target_lower, v_target_upper) a_target = min(a_target_lower, a_target_upper) v_target_future = long_plan.speeds[-1] else: - v_target = 0.0 v_target_future = 0.0 a_target = 0.0 @@ -103,11 +100,11 @@ class LongControl(): # tracking objects and driving elif self.long_control_state == LongCtrlState.pid: - self.v_pid = v_target + self.v_pid = long_plan.speeds[0] # Toyota starts braking more when it thinks you want to stop # Freeze the integrator so we don't accelerate to compensate, and don't allow positive acceleration - prevent_overshoot = not CP.stoppingControl and CS.vEgo < 1.5 and v_target_future < 0.7 and v_target_future < v_target + prevent_overshoot = not CP.stoppingControl and CS.vEgo < 1.5 and v_target_future < 0.7 and v_target_future < self.v_pid deadzone = interp(CS.vEgo, CP.longitudinalTuning.deadzoneBP, CP.longitudinalTuning.deadzoneV) freeze_integrator = prevent_overshoot diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index b179c09e16..5fff750105 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -eb82d8fc821da3488dffe85f191211ee1fad5904 \ No newline at end of file +e32613484a42234bf896f1205039e9becc91ea3b \ No newline at end of file From 65ca9be82a18115a5dd0556c4b1f8cd9705743d9 Mon Sep 17 00:00:00 2001 From: Igor Biletskyy Date: Mon, 29 Nov 2021 15:34:33 -0800 Subject: [PATCH 060/102] boardd: split usbprotocol unittest and fix paren order in data length assert (#23065) --- selfdrive/boardd/panda.cc | 2 +- .../boardd/tests/test_boardd_usbprotocol.cc | 25 +++++++++++++++---- 2 files changed, 21 insertions(+), 6 deletions(-) diff --git a/selfdrive/boardd/panda.cc b/selfdrive/boardd/panda.cc index efe8555999..78e32716cf 100644 --- a/selfdrive/boardd/panda.cc +++ b/selfdrive/boardd/panda.cc @@ -384,7 +384,7 @@ void Panda::pack_can_buffer(const capnp::List::Reader &can_data } auto can_data = cmsg.getDat(); uint8_t data_len_code = len_to_dlc(can_data.size()); - assert(can_data.size() <= (hw_type == cereal::PandaState::PandaType::RED_PANDA) ? 64 : 8); + assert(can_data.size() <= ((hw_type == cereal::PandaState::PandaType::RED_PANDA) ? 64 : 8)); assert(can_data.size() == dlc_to_len[data_len_code]); can_header header; diff --git a/selfdrive/boardd/tests/test_boardd_usbprotocol.cc b/selfdrive/boardd/tests/test_boardd_usbprotocol.cc index 58cea3c681..f1fd2ef902 100644 --- a/selfdrive/boardd/tests/test_boardd_usbprotocol.cc +++ b/selfdrive/boardd/tests/test_boardd_usbprotocol.cc @@ -16,7 +16,7 @@ int random_int(int min, int max) { } struct PandaTest : public Panda { - PandaTest(uint32_t bus_offset, int can_list_size); + PandaTest(uint32_t bus_offset, int can_list_size, cereal::PandaState::PandaType hw_type); void test_can_send(); void test_can_recv(); @@ -27,9 +27,11 @@ struct PandaTest : public Panda { capnp::List::Reader can_data_list; }; -PandaTest::PandaTest(uint32_t bus_offset_, int can_list_size) : can_list_size(can_list_size), Panda(bus_offset_) { +PandaTest::PandaTest(uint32_t bus_offset_, int can_list_size, cereal::PandaState::PandaType hw_type) : can_list_size(can_list_size), Panda(bus_offset_) { + this->hw_type = hw_type; + int data_limit = ((hw_type == cereal::PandaState::PandaType::RED_PANDA) ? std::size(dlc_to_len) : 8); // prepare test data - for (int i = 0; i < std::size(dlc_to_len); ++i) { + for (int i = 0; i < data_limit; ++i) { std::random_device rd; std::independent_bits_engine rbe(rd()); @@ -101,10 +103,23 @@ void PandaTest::test_can_recv() { } } -TEST_CASE("send/recv can packets") { +TEST_CASE("send/recv CAN 2.0 packets") { auto bus_offset = GENERATE(0, 4); auto can_list_size = GENERATE(1, 3, 5, 10, 30, 60, 100, 200); - PandaTest test(bus_offset, can_list_size); + PandaTest test(bus_offset, can_list_size, cereal::PandaState::PandaType::DOS); + + SECTION("can_send") { + test.test_can_send(); + } + SECTION("can_receive") { + test.test_can_recv(); + } +} + +TEST_CASE("send/recv CAN FD packets") { + auto bus_offset = GENERATE(0, 4); + auto can_list_size = GENERATE(1, 3, 5, 10, 30, 60, 100, 200); + PandaTest test(bus_offset, can_list_size, cereal::PandaState::PandaType::RED_PANDA); SECTION("can_send") { test.test_can_send(); From 8b2cb7130526baa69508b2355ca1d2240ff738ee Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 29 Nov 2021 17:42:18 -0800 Subject: [PATCH 061/102] script to verify release and staging branches are the same --- release/verify.sh | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) create mode 100755 release/verify.sh diff --git a/release/verify.sh b/release/verify.sh new file mode 100755 index 0000000000..1c51eaff09 --- /dev/null +++ b/release/verify.sh @@ -0,0 +1,16 @@ +#!/bin/bash + +set -e + +RED="\033[0;31m" +GREEN="\033[0;32m" +CLEAR="\033[0m" + +BRANCHES="release2 release3 dashcam dashcam3" +for b in $BRANCHES; do + if git diff --quiet origin/$b origin/$b-staging && [ "$(git rev-parse origin/$b)" = "$(git rev-parse origin/$b-staging)" ]; then + printf "%-10s $GREEN ok $CLEAR\n" "$b" + else + printf "%-10s $RED mismatch $CLEAR\n" "$b" + fi +done From 9a87f684b58e51b2e64575452d068b4f868f026d Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 29 Nov 2021 17:50:10 -0800 Subject: [PATCH 062/102] add devel --- release/verify.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/release/verify.sh b/release/verify.sh index 1c51eaff09..2ebd50a29d 100755 --- a/release/verify.sh +++ b/release/verify.sh @@ -6,7 +6,7 @@ RED="\033[0;31m" GREEN="\033[0;32m" CLEAR="\033[0m" -BRANCHES="release2 release3 dashcam dashcam3" +BRANCHES="devel dashcam dashcam3 release2 release3" for b in $BRANCHES; do if git diff --quiet origin/$b origin/$b-staging && [ "$(git rev-parse origin/$b)" = "$(git rev-parse origin/$b-staging)" ]; then printf "%-10s $GREEN ok $CLEAR\n" "$b" From 348d2d2b0d169b0d181a51eb0e23b1f9b8fc6793 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Tue, 30 Nov 2021 10:14:59 +0800 Subject: [PATCH 063/102] rename yuv streams (#23071) * rename yuv streams * bump cereal Co-authored-by: Adeeb Shihadeh --- cereal | 2 +- selfdrive/camerad/cameras/camera_qcom.cc | 4 ++-- selfdrive/camerad/cameras/camera_qcom2.cc | 6 +++--- selfdrive/camerad/cameras/camera_replay.cc | 4 ++-- selfdrive/camerad/cameras/camera_webcam.cc | 4 ++-- selfdrive/loggerd/loggerd.h | 6 +++--- selfdrive/modeld/dmonitoringmodeld.cc | 2 +- selfdrive/modeld/modeld.cc | 2 +- selfdrive/test/process_replay/model_replay.py | 8 ++++---- selfdrive/test/process_replay/regen.py | 4 ++-- selfdrive/ui/replay/camera.h | 6 +++--- tools/sim/bridge.py | 4 ++-- 12 files changed, 26 insertions(+), 26 deletions(-) diff --git a/cereal b/cereal index 8cbd71836e..d6f233bf7b 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 8cbd71836e4170fa175070796396a91771624e82 +Subproject commit d6f233bf7bd6d1ee3508b17667e44420ce38de0d diff --git a/selfdrive/camerad/cameras/camera_qcom.cc b/selfdrive/camerad/cameras/camera_qcom.cc index 33b5d00c95..11383de668 100644 --- a/selfdrive/camerad/cameras/camera_qcom.cc +++ b/selfdrive/camerad/cameras/camera_qcom.cc @@ -211,12 +211,12 @@ void cameras_init(VisionIpcServer *v, MultiCameraState *s, cl_device_id device_i /*fps*/ 20, #endif device_id, ctx, - VISION_STREAM_RGB_BACK, VISION_STREAM_YUV_BACK); + VISION_STREAM_RGB_BACK, VISION_STREAM_ROAD); camera_init(v, &s->driver_cam, CAMERA_ID_OV8865, 1, /*pixel_clock=*/72000000, /*line_length_pclk=*/1602, /*max_gain=*/510, 10, device_id, ctx, - VISION_STREAM_RGB_FRONT, VISION_STREAM_YUV_FRONT); + VISION_STREAM_RGB_FRONT, VISION_STREAM_DRIVER); s->sm = new SubMaster({"driverState"}); s->pm = new PubMaster({"roadCameraState", "driverCameraState", "thumbnail"}); diff --git a/selfdrive/camerad/cameras/camera_qcom2.cc b/selfdrive/camerad/cameras/camera_qcom2.cc index 03138e353a..3ea065ae73 100644 --- a/selfdrive/camerad/cameras/camera_qcom2.cc +++ b/selfdrive/camerad/cameras/camera_qcom2.cc @@ -709,13 +709,13 @@ static void camera_open(CameraState *s) { void cameras_init(VisionIpcServer *v, MultiCameraState *s, cl_device_id device_id, cl_context ctx) { camera_init(s, v, &s->road_cam, CAMERA_ID_AR0231, 1, 20, device_id, ctx, - VISION_STREAM_RGB_BACK, VISION_STREAM_YUV_BACK); // swap left/right + VISION_STREAM_RGB_BACK, VISION_STREAM_ROAD); // swap left/right printf("road camera initted \n"); camera_init(s, v, &s->wide_road_cam, CAMERA_ID_AR0231, 0, 20, device_id, ctx, - VISION_STREAM_RGB_WIDE, VISION_STREAM_YUV_WIDE); + VISION_STREAM_RGB_WIDE, VISION_STREAM_WIDE_ROAD); printf("wide road camera initted \n"); camera_init(s, v, &s->driver_cam, CAMERA_ID_AR0231, 2, 20, device_id, ctx, - VISION_STREAM_RGB_FRONT, VISION_STREAM_YUV_FRONT); + VISION_STREAM_RGB_FRONT, VISION_STREAM_DRIVER); printf("driver camera initted \n"); s->sm = new SubMaster({"driverState"}); diff --git a/selfdrive/camerad/cameras/camera_replay.cc b/selfdrive/camerad/cameras/camera_replay.cc index 731aab2a29..8ff1b6aacc 100644 --- a/selfdrive/camerad/cameras/camera_replay.cc +++ b/selfdrive/camerad/cameras/camera_replay.cc @@ -98,9 +98,9 @@ void process_road_camera(MultiCameraState *s, CameraState *c, int cnt) { void cameras_init(VisionIpcServer *v, MultiCameraState *s, cl_device_id device_id, cl_context ctx) { camera_init(v, &s->road_cam, CAMERA_ID_LGC920, 20, device_id, ctx, - VISION_STREAM_RGB_BACK, VISION_STREAM_YUV_BACK, get_url(road_camera_route, "fcamera", 0)); + VISION_STREAM_RGB_BACK, VISION_STREAM_ROAD, get_url(road_camera_route, "fcamera", 0)); // camera_init(v, &s->driver_cam, CAMERA_ID_LGC615, 10, device_id, ctx, - // VISION_STREAM_RGB_FRONT, VISION_STREAM_YUV_FRONT, get_url(driver_camera_route, "dcamera", 0)); + // VISION_STREAM_RGB_FRONT, VISION_STREAM_DRIVER, get_url(driver_camera_route, "dcamera", 0)); s->pm = new PubMaster({"roadCameraState", "driverCameraState", "thumbnail"}); } diff --git a/selfdrive/camerad/cameras/camera_webcam.cc b/selfdrive/camerad/cameras/camera_webcam.cc index ff63257bd3..47da56042c 100644 --- a/selfdrive/camerad/cameras/camera_webcam.cc +++ b/selfdrive/camerad/cameras/camera_webcam.cc @@ -141,9 +141,9 @@ void driver_camera_thread(CameraState *s) { void cameras_init(VisionIpcServer *v, MultiCameraState *s, cl_device_id device_id, cl_context ctx) { camera_init(v, &s->road_cam, CAMERA_ID_LGC920, 20, device_id, ctx, - VISION_STREAM_RGB_BACK, VISION_STREAM_YUV_BACK); + VISION_STREAM_RGB_BACK, VISION_STREAM_ROAD); camera_init(v, &s->driver_cam, CAMERA_ID_LGC615, 10, device_id, ctx, - VISION_STREAM_RGB_FRONT, VISION_STREAM_YUV_FRONT); + VISION_STREAM_RGB_FRONT, VISION_STREAM_DRIVER); s->pm = new PubMaster({"roadCameraState", "driverCameraState", "thumbnail"}); } diff --git a/selfdrive/loggerd/loggerd.h b/selfdrive/loggerd/loggerd.h index 448927ff8a..977e03b8d3 100644 --- a/selfdrive/loggerd/loggerd.h +++ b/selfdrive/loggerd/loggerd.h @@ -44,7 +44,7 @@ const int SEGMENT_LENGTH = LOGGERD_TEST ? atoi(getenv("LOGGERD_SEGMENT_LENGTH")) const LogCameraInfo cameras_logged[] = { { .type = RoadCam, - .stream_type = VISION_STREAM_YUV_BACK, + .stream_type = VISION_STREAM_ROAD, .filename = "fcamera.hevc", .frame_packet_name = "roadCameraState", .fps = MAIN_FPS, @@ -58,7 +58,7 @@ const LogCameraInfo cameras_logged[] = { }, { .type = DriverCam, - .stream_type = VISION_STREAM_YUV_FRONT, + .stream_type = VISION_STREAM_DRIVER, .filename = "dcamera.hevc", .frame_packet_name = "driverCameraState", .fps = MAIN_FPS, // on EONs, more compressed this way @@ -72,7 +72,7 @@ const LogCameraInfo cameras_logged[] = { }, { .type = WideRoadCam, - .stream_type = VISION_STREAM_YUV_WIDE, + .stream_type = VISION_STREAM_WIDE_ROAD, .filename = "ecamera.hevc", .frame_packet_name = "wideRoadCameraState", .fps = MAIN_FPS, diff --git a/selfdrive/modeld/dmonitoringmodeld.cc b/selfdrive/modeld/dmonitoringmodeld.cc index 6ae6e780c8..c85c05c9d1 100644 --- a/selfdrive/modeld/dmonitoringmodeld.cc +++ b/selfdrive/modeld/dmonitoringmodeld.cc @@ -39,7 +39,7 @@ int main(int argc, char **argv) { DMonitoringModelState model; dmonitoring_init(&model); - VisionIpcClient vipc_client = VisionIpcClient("camerad", VISION_STREAM_YUV_FRONT, true); + VisionIpcClient vipc_client = VisionIpcClient("camerad", VISION_STREAM_DRIVER, true); while (!do_exit && !vipc_client.connect(false)) { util::sleep_for(100); } diff --git a/selfdrive/modeld/modeld.cc b/selfdrive/modeld/modeld.cc index 3d3e435909..9013e63617 100644 --- a/selfdrive/modeld/modeld.cc +++ b/selfdrive/modeld/modeld.cc @@ -153,7 +153,7 @@ int main(int argc, char **argv) { model_init(&model, device_id, context); LOGW("models loaded, modeld starting"); - VisionIpcClient vipc_client = VisionIpcClient("camerad", wide_camera ? VISION_STREAM_YUV_WIDE : VISION_STREAM_YUV_BACK, true, device_id, context); + VisionIpcClient vipc_client = VisionIpcClient("camerad", wide_camera ? VISION_STREAM_WIDE_ROAD : VISION_STREAM_ROAD, true, device_id, context); while (!do_exit && !vipc_client.connect(false)) { util::sleep_for(100); } diff --git a/selfdrive/test/process_replay/model_replay.py b/selfdrive/test/process_replay/model_replay.py index 16ffea3c73..32a5717852 100755 --- a/selfdrive/test/process_replay/model_replay.py +++ b/selfdrive/test/process_replay/model_replay.py @@ -50,10 +50,10 @@ def process_frame(msg, pm, sm, log_msgs, vipc_server, spinner, frs, frame_idxs, img = frs[msg.which()].get(frame_idxs[msg.which()], pix_fmt="yuv420p")[0] if msg.which == "roadCameraState": - vipc_server.send(VisionStreamType.VISION_STREAM_YUV_BACK, img.flatten().tobytes(), f.roadCameraState.frameId, + vipc_server.send(VisionStreamType.VISION_STREAM_ROAD, img.flatten().tobytes(), f.roadCameraState.frameId, f.roadCameraState.timestampSof, f.roadCameraState.timestampEof) else: - vipc_server.send(VisionStreamType.VISION_STREAM_YUV_FRONT, img.flatten().tobytes(), f.driverCameraState.frameId, + vipc_server.send(VisionStreamType.VISION_STREAM_DRIVER, img.flatten().tobytes(), f.driverCameraState.frameId, f.driverCameraState.timestampSof, f.driverCameraState.timestampEof) with Timeout(seconds=15): log_msgs.append(messaging.recv_one(sm.sock[packet_from_camera[msg.which()]])) @@ -73,8 +73,8 @@ def model_replay(lr_list, frs): spinner.update("starting model replay") vipc_server = VisionIpcServer("camerad") - vipc_server.create_buffers(VisionStreamType.VISION_STREAM_YUV_BACK, 40, False, *(tici_f_frame_size if TICI else eon_f_frame_size)) - vipc_server.create_buffers(VisionStreamType.VISION_STREAM_YUV_FRONT, 40, False, *(tici_d_frame_size if TICI else eon_d_frame_size)) + vipc_server.create_buffers(VisionStreamType.VISION_STREAM_ROAD, 40, False, *(tici_f_frame_size if TICI else eon_f_frame_size)) + vipc_server.create_buffers(VisionStreamType.VISION_STREAM_DRIVER, 40, False, *(tici_d_frame_size if TICI else eon_d_frame_size)) vipc_server.start_listener() pm = messaging.PubMaster(['roadCameraState', 'driverCameraState', 'liveCalibration', 'lateralPlan']) diff --git a/selfdrive/test/process_replay/regen.py b/selfdrive/test/process_replay/regen.py index 0e8a0eaf11..5326075240 100755 --- a/selfdrive/test/process_replay/regen.py +++ b/selfdrive/test/process_replay/regen.py @@ -39,8 +39,8 @@ def replay_service(s, msgs): vs = None def replay_cameras(lr, frs): cameras = [ - ("roadCameraState", DT_MDL, eon_f_frame_size, VisionStreamType.VISION_STREAM_YUV_BACK), - ("driverCameraState", DT_DMON, eon_d_frame_size, VisionStreamType.VISION_STREAM_YUV_FRONT), + ("roadCameraState", DT_MDL, eon_f_frame_size, VisionStreamType.VISION_STREAM_ROAD), + ("driverCameraState", DT_DMON, eon_d_frame_size, VisionStreamType.VISION_STREAM_DRIVER), ] def replay_camera(s, stream, dt, vipc_server, fr, size): diff --git a/selfdrive/ui/replay/camera.h b/selfdrive/ui/replay/camera.h index 8b1fa7620b..21e02292d5 100644 --- a/selfdrive/ui/replay/camera.h +++ b/selfdrive/ui/replay/camera.h @@ -32,9 +32,9 @@ protected: void cameraThread(Camera &cam); Camera cameras_[MAX_CAMERAS] = { - {.type = RoadCam, .rgb_type = VISION_STREAM_RGB_BACK, .yuv_type = VISION_STREAM_YUV_BACK}, - {.type = DriverCam, .rgb_type = VISION_STREAM_RGB_FRONT, .yuv_type = VISION_STREAM_YUV_FRONT}, - {.type = WideRoadCam, .rgb_type = VISION_STREAM_RGB_WIDE, .yuv_type = VISION_STREAM_YUV_WIDE}, + {.type = RoadCam, .rgb_type = VISION_STREAM_RGB_BACK, .yuv_type = VISION_STREAM_ROAD}, + {.type = DriverCam, .rgb_type = VISION_STREAM_RGB_FRONT, .yuv_type = VISION_STREAM_DRIVER}, + {.type = WideRoadCam, .rgb_type = VISION_STREAM_RGB_WIDE, .yuv_type = VISION_STREAM_WIDE_ROAD}, }; std::atomic publishing_ = 0; std::unique_ptr vipc_server_; diff --git a/tools/sim/bridge.py b/tools/sim/bridge.py index dc948d0fd5..9924a40b11 100755 --- a/tools/sim/bridge.py +++ b/tools/sim/bridge.py @@ -68,7 +68,7 @@ class Camerad: # TODO: remove RGB buffers once the last RGB vipc subscriber is removed self.vipc_server.create_buffers(VisionStreamType.VISION_STREAM_RGB_BACK, 4, True, W, H) - self.vipc_server.create_buffers(VisionStreamType.VISION_STREAM_YUV_BACK, 40, False, W, H) + self.vipc_server.create_buffers(VisionStreamType.VISION_STREAM_ROAD, 40, False, W, H) self.vipc_server.start_listener() # set up for pyopencl rgb to yuv conversion @@ -98,7 +98,7 @@ class Camerad: # TODO: remove RGB send once the last RGB vipc subscriber is removed self.vipc_server.send(VisionStreamType.VISION_STREAM_RGB_BACK, img.tobytes(), self.frame_id, eof, eof) - self.vipc_server.send(VisionStreamType.VISION_STREAM_YUV_BACK, yuv.data.tobytes(), self.frame_id, eof, eof) + self.vipc_server.send(VisionStreamType.VISION_STREAM_ROAD, yuv.data.tobytes(), self.frame_id, eof, eof) dat = messaging.new_message('roadCameraState') dat.roadCameraState = { From 5040427cb739fad364319070a0f87ab03031cd99 Mon Sep 17 00:00:00 2001 From: Vivek Aithal Date: Mon, 29 Nov 2021 19:30:14 -0800 Subject: [PATCH 064/102] Mesh3D: Add accelerometer bias to loc_kf (#22880) * add accel-bias to mesh3d * remove acc scale --- selfdrive/locationd/models/loc_kf.py | 23 ++++++++++++++++------- 1 file changed, 16 insertions(+), 7 deletions(-) diff --git a/selfdrive/locationd/models/loc_kf.py b/selfdrive/locationd/models/loc_kf.py index 2739494225..c6a92f1683 100755 --- a/selfdrive/locationd/models/loc_kf.py +++ b/selfdrive/locationd/models/loc_kf.py @@ -49,6 +49,7 @@ class States(): 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 + ACCELEROMETER_BIAS = slice(30, 33) # bias of mems accelerometer # Error-state has different slices because it is an ESKF ECEF_POS_ERR = slice(0, 3) @@ -66,6 +67,7 @@ class States(): GLONASS_FREQ_SLOPE_ERR = slice(26, 27) CLOCK_ACCELERATION_ERR = slice(27, 28) ACCELEROMETER_SCALE_ERR = slice(28, 29) + ACCELEROMETER_BIAS_ERR = slice(29, 32) class LocKalman(): @@ -82,7 +84,8 @@ class LocKalman(): 0, 0, 0, 0, 0, 0, - 1], dtype=np.float64) + 1, + 0, 0, 0], dtype=np.float64) # state covariance P_initial = np.diag([1e16, 1e16, 1e16, @@ -97,7 +100,8 @@ class LocKalman(): (0.01)**2, (0.01)**2, (0.01)**2, 10**2, 1**2, 0.2**2, - 0.05**2]) + 0.05**2, + 0.05**2, 0.05**2, 0.05**2]) # process noise Q = np.diag([0.03**2, 0.03**2, 0.03**2, @@ -112,7 +116,8 @@ class LocKalman(): (0.05 / 60)**2, (0.05 / 60)**2, (0.05 / 60)**2, (.1)**2, (.01)**2, 0.005**2, - (0.02 / 100)**2]) + (0.02 / 100)**2, + (0.005 / 100)**2, (0.005 / 100)**2, (0.005 / 100)**2]) # measurements that need to pass mahalanobis distance outlier rejector maha_test_kinds = [ObservationKind.ORB_FEATURES] # , ObservationKind.PSEUDORANGE, ObservationKind.PSEUDORANGE_RATE] @@ -154,7 +159,8 @@ class LocKalman(): 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, :] + # accel_scale = state[States.ACCELEROMETER_SCALE, :] + accel_bias = state[States.ACCELEROMETER_BIAS, :] dt = sp.Symbol('dt') @@ -290,7 +296,8 @@ class LocKalman(): pos = sp.Matrix([x, y, z]) # 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_acc_sym = imu_rot * (gravity + acceleration + accel_bias) + h_acc_stationary_sym = acceleration h_phone_rot_sym = sp.Matrix([vroll, vpitch, vyaw]) speed = sp.sqrt(vx**2 + vy**2 + vz**2) @@ -320,7 +327,8 @@ class LocKalman(): [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], - [h_orb_point_sym, ObservationKind.ORB_POINT, orb_epos_sym]] + [h_orb_point_sym, ObservationKind.ORB_POINT, orb_epos_sym], + [h_acc_stationary_sym, ObservationKind.NO_ACCEL, None]] # MSCKF configuration if N > 0: @@ -368,7 +376,8 @@ class LocKalman(): 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.0025**2, 0.0025**2, 0.0025**2]), - ObservationKind.ECEF_POS: np.diag([5**2, 5**2, 5**2])} + ObservationKind.ECEF_POS: np.diag([5**2, 5**2, 5**2]), + ObservationKind.NO_ACCEL: np.diag([0.0025**2, 0.0025**2, 0.0025**2])} # MSCKF stuff self.N = N From 700b1bcce7ef0618cd4b04c5723faf27a1d8aa98 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 29 Nov 2021 22:57:13 -0800 Subject: [PATCH 065/102] jenkins: build releases in parallel (#23070) --- Jenkinsfile | 83 ++++++++++++----------------------------------------- 1 file changed, 18 insertions(+), 65 deletions(-) diff --git a/Jenkinsfile b/Jenkinsfile index 6004849726..1feb482900 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -1,7 +1,7 @@ def phone(String ip, String step_label, String cmd) { withCredentials([file(credentialsId: 'id_rsa', variable: 'key_file')]) { def ssh_cmd = """ -ssh -tt -o StrictHostKeyChecking=no -i ${key_file} -p 8022 'comma@${ip}' /usr/bin/bash <<'EOF' +ssh -tt -o StrictHostKeyChecking=no -i ${key_file} 'comma@${ip}' /usr/bin/bash <<'EOF' set -e @@ -47,7 +47,7 @@ def phone_steps(String device_type, steps) { } pipeline { - agent none + agent { docker { image 'ghcr.io/commaai/alpine-ssh'; args '--user=root' } } environment { TEST_DIR = "/data/openpilot" SOURCE_DIR = "/data/openpilot_source/" @@ -57,38 +57,27 @@ pipeline { } stages { - - stage('Build release2') { - agent { - docker { - image 'python:3.7.3' - args '--user=root' - } - } + stage('build releases') { when { branch 'devel-staging' } - steps { - phone_steps("eon-build", [ - ["build release2-staging & dashcam-staging", "PUSH=1 $SOURCE_DIR/release/build_release.sh"], - ]) - } - } - stage('Build release3') { - agent { - docker { - image 'python:3.7.3' - args '--user=root' + parallel { + stage('release2') { + steps { + phone_steps("eon-build", [ + ["build release2-staging & dashcam-staging", "PUSH=1 $SOURCE_DIR/release/build_release.sh"], + ]) + } + } + + stage('release3') { + steps { + phone_steps("tici", [ + ["build release3-staging & dashcam3-staging", "PUSH=1 $SOURCE_DIR/release/build_release.sh"], + ]) + } } - } - when { - branch 'devel-staging' - } - steps { - phone_steps("tici", [ - ["build release3-staging & dashcam3-staging", "PUSH=1 $SOURCE_DIR/release/build_release.sh"], - ]) } } @@ -105,43 +94,7 @@ pipeline { } stages { - - /* - stage('PC tests') { - agent { - dockerfile { - filename 'Dockerfile.openpilotci' - args '--privileged --shm-size=1G --user=root' - } - } - stages { - stage('Build') { - steps { - sh 'scons -j$(nproc)' - } - } - } - post { - always { - // fix permissions since docker runs as another user - sh "chmod -R 777 ." - } - } - } - */ - stage('On-device Tests') { - agent { - docker { - /* - filename 'Dockerfile.ondevice_ci' - args "--privileged -v /dev:/dev --shm-size=1G --user=root" - */ - image 'python:3.7.3' - args '--user=root' - } - } - stages { stage('parallel tests') { parallel { From 91f87e367527c607724711914142851bf0ea7238 Mon Sep 17 00:00:00 2001 From: grekiki Date: Tue, 30 Nov 2021 14:15:42 +0100 Subject: [PATCH 066/102] Replace list by generator (#23077) --- 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 8975b3e832..f9b57130b1 100755 --- a/selfdrive/debug/cpu_usage_stat.py +++ b/selfdrive/debug/cpu_usage_stat.py @@ -66,7 +66,7 @@ if __name__ == "__main__": for p in psutil.process_iter(): if p == psutil.Process(): continue - matched = any(l for l in p.cmdline() if any([pn for pn in monitored_proc_names if re.match(r'.*{}.*'.format(pn), l, re.M | re.I)])) + matched = any(l for l in p.cmdline() if any(pn for pn in monitored_proc_names if re.match(r'.*{}.*'.format(pn), l, re.M | re.I))) if matched: k = ' '.join(p.cmdline()) print('Add monitored proc:', k) From f65e9b4c67611fd347d57b092941b92e6da544da Mon Sep 17 00:00:00 2001 From: Erich Moraga <33645296+ErichMoraga@users.noreply.github.com> Date: Tue, 30 Nov 2021 12:49:54 -0600 Subject: [PATCH 067/102] docs/CARS: Add 2021 C-HR (#23078) `@eFini#8426` confirmed... https://discord.com/channels/469524606043160576/524327905937850394/914925655228031017 [my inquiry] https://discord.com/channels/469524606043160576/524327905937850394/915131655679791144 [his confirmation] Still stuck w/ stock longitudinal, despite being TSS2.5. He's been using it for many months, as seen in one of his early posts that came to Adeeb's attention for route analysis... https://discord.com/channels/469524606043160576/524327905937850394/827038344742699008 [`88551059c417a545|2021-03-29--23-34-50`] --- docs/CARS.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/CARS.md b/docs/CARS.md index d88ee6c65f..43ed2ae3ae 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -50,7 +50,7 @@ | Toyota | Camry 2021-22 | All | openpilot | 0mph4 | 0mph | | Toyota | Camry Hybrid 2018-20 | All | Stock | 0mph4 | 0mph | | Toyota | Camry Hybrid 2021-22 | All | openpilot | 0mph | 0mph | -| Toyota | C-HR 2017-20 | All | Stock | 0mph | 0mph | +| Toyota | C-HR 2017-21 | All | Stock | 0mph | 0mph | | Toyota | C-HR Hybrid 2017-19 | All | Stock | 0mph | 0mph | | Toyota | Corolla 2017-19 | All | Stock3| 20mph1 | 0mph | | Toyota | Corolla 2020-22 | All | openpilot | 0mph | 0mph | From eda69930430da564251581814fd3962ca7af0372 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Tue, 30 Nov 2021 10:50:06 -0800 Subject: [PATCH 068/102] Toyota pedal rewrite (#23067) * pedal redo * add offset to compensate for creep and windbrake * offset in standard units * wrong size * better creep values * update ref --- selfdrive/car/toyota/carcontroller.py | 55 ++++++++---------------- selfdrive/car/toyota/tunes.py | 10 +---- selfdrive/car/toyota/values.py | 3 +- selfdrive/test/process_replay/ref_commit | 2 +- 4 files changed, 20 insertions(+), 50 deletions(-) diff --git a/selfdrive/car/toyota/carcontroller.py b/selfdrive/car/toyota/carcontroller.py index fdbf5cc8d5..c445528a83 100644 --- a/selfdrive/car/toyota/carcontroller.py +++ b/selfdrive/car/toyota/carcontroller.py @@ -5,35 +5,18 @@ from selfdrive.car.toyota.toyotacan import create_steer_command, create_ui_comma create_accel_command, create_acc_cancel_command, \ create_fcw_command, create_lta_steer_command from selfdrive.car.toyota.values import CAR, STATIC_DSU_MSGS, NO_STOP_TIMER_CAR, TSS2_CAR, \ - MIN_ACC_SPEED, PEDAL_HYST_GAP, PEDAL_SCALE, CarControllerParams + MIN_ACC_SPEED, PEDAL_TRANSITION, CarControllerParams from opendbc.can.packer import CANPacker VisualAlert = car.CarControl.HUDControl.VisualAlert -def accel_hysteresis(accel, accel_steady, enabled): - - # for small accel oscillations within ACCEL_HYST_GAP, don't change the accel command - if not enabled: - # send 0 when disabled, otherwise acc faults - accel_steady = 0. - elif accel > accel_steady + CarControllerParams.ACCEL_HYST_GAP: - accel_steady = accel - CarControllerParams.ACCEL_HYST_GAP - elif accel < accel_steady - CarControllerParams.ACCEL_HYST_GAP: - accel_steady = accel + CarControllerParams.ACCEL_HYST_GAP - accel = accel_steady - - return accel, accel_steady - - class CarController(): def __init__(self, dbc_name, CP, VM): self.last_steer = 0 - self.accel_steady = 0. self.alert_active = False self.last_standstill = False self.standstill_req = False self.steer_rate_limited = False - self.use_interceptor = False self.packer = CANPacker(dbc_name) @@ -43,25 +26,22 @@ class CarController(): # *** compute control surfaces *** # gas and brake - interceptor_gas_cmd = 0. - pcm_accel_cmd = actuators.accel - - if CS.CP.enableGasInterceptor: - # handle hysteresis when around the minimum acc speed - if CS.out.vEgo < MIN_ACC_SPEED: - self.use_interceptor = True - elif CS.out.vEgo > MIN_ACC_SPEED + PEDAL_HYST_GAP: - self.use_interceptor = False - - if self.use_interceptor and active: - # only send negative accel when using interceptor. gas handles acceleration - # +0.18 m/s^2 offset to reduce ABS pump usage when OP is engaged - MAX_INTERCEPTOR_GAS = interp(CS.out.vEgo, [0.0, MIN_ACC_SPEED], [0.2, 0.5]) - interceptor_gas_cmd = clip(actuators.accel / PEDAL_SCALE, 0., MAX_INTERCEPTOR_GAS) - pcm_accel_cmd = 0.18 - max(0, -actuators.accel) - - pcm_accel_cmd, self.accel_steady = accel_hysteresis(pcm_accel_cmd, self.accel_steady, enabled) - pcm_accel_cmd = clip(pcm_accel_cmd, CarControllerParams.ACCEL_MIN, CarControllerParams.ACCEL_MAX) + if CS.CP.enableGasInterceptor and enabled: + MAX_INTERCEPTOR_GAS = 0.5 + # RAV4 has very sensitive has pedal + if CS.CP.carFingerprint in [CAR.RAV4, CAR.RAV4H, CAR.HIGHLANDER, CAR.HIGHLANDERH]: + PEDAL_SCALE = interp(CS.out.vEgo, [0.0, MIN_ACC_SPEED, MIN_ACC_SPEED + PEDAL_TRANSITION], [0.15, 0.3, 0.0]) + elif CS.CP.carFingerprint in [CAR.COROLLA]: + PEDAL_SCALE = interp(CS.out.vEgo, [0.0, MIN_ACC_SPEED, MIN_ACC_SPEED + PEDAL_TRANSITION], [0.3, 0.4, 0.0]) + else: + PEDAL_SCALE = interp(CS.out.vEgo, [0.0, MIN_ACC_SPEED, MIN_ACC_SPEED + PEDAL_TRANSITION], [0.4, 0.5, 0.0]) + # offset for creep and windbrake + pedal_offset = interp(CS.out.vEgo, [0.0, 2.3, MIN_ACC_SPEED + PEDAL_TRANSITION], [-.4, 0.0, 0.2]) + pedal_command = PEDAL_SCALE * (actuators.accel + pedal_offset) + interceptor_gas_cmd = clip(pedal_command, 0., MAX_INTERCEPTOR_GAS) + else: + interceptor_gas_cmd = 0. + pcm_accel_cmd = clip(actuators.accel, CarControllerParams.ACCEL_MIN, CarControllerParams.ACCEL_MAX) # steer torque new_steer = int(round(actuators.steer * CarControllerParams.STEER_MAX)) @@ -88,7 +68,6 @@ class CarController(): self.standstill_req = False self.last_steer = apply_steer - self.last_accel = pcm_accel_cmd self.last_standstill = CS.out.standstill can_sends = [] diff --git a/selfdrive/car/toyota/tunes.py b/selfdrive/car/toyota/tunes.py index 3f210d48a7..15c8bbfcc6 100644 --- a/selfdrive/car/toyota/tunes.py +++ b/selfdrive/car/toyota/tunes.py @@ -1,6 +1,5 @@ #!/usr/bin/env python3 from enum import Enum -from selfdrive.car.toyota.values import MIN_ACC_SPEED, PEDAL_HYST_GAP class LongTunes(Enum): @@ -29,15 +28,8 @@ class LatTunes(Enum): ###### LONG ###### def set_long_tune(tune, name): - if name == LongTunes.PEDAL: - tune.deadzoneBP = [0.] - tune.deadzoneV = [0.] - tune.kpBP = [0., 5., MIN_ACC_SPEED, MIN_ACC_SPEED + PEDAL_HYST_GAP, 35.] - tune.kpV = [1.2, 0.8, 0.765, 2.255, 1.5] - tune.kiBP = [0., MIN_ACC_SPEED, MIN_ACC_SPEED + PEDAL_HYST_GAP, 35.] - tune.kiV = [0.18, 0.165, 0.489, 0.36] # Improved longitudinal tune - elif name == LongTunes.TSS2: + if name == LongTunes.TSS2 or name == LongTunes.PEDAL: tune.deadzoneBP = [0., 8.05] tune.deadzoneV = [.0, .14] tune.kpBP = [0., 5., 20.] diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 32923b43ab..4b3f82fbc0 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -6,9 +6,8 @@ from selfdrive.config import Conversions as CV Ecu = car.CarParams.Ecu MIN_ACC_SPEED = 19. * CV.MPH_TO_MS +PEDAL_TRANSITION = 10. * CV.MPH_TO_MS -PEDAL_HYST_GAP = 3. * CV.MPH_TO_MS -PEDAL_SCALE = 3.0 class CarControllerParams: ACCEL_HYST_GAP = 0.06 # don't change accel command for small oscilalitons within this value diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 5fff750105..41f2296dec 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -e32613484a42234bf896f1205039e9becc91ea3b \ No newline at end of file +e0926a8b9f7cffc35808109a710648a7f57c0b71 \ No newline at end of file From b57f55088e4a4054ba4b86d7cce9b2a20704db61 Mon Sep 17 00:00:00 2001 From: Vivek Aithal Date: Tue, 30 Nov 2021 10:51:32 -0800 Subject: [PATCH 069/102] add a note in loc_kf (#23082) --- selfdrive/locationd/models/loc_kf.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/selfdrive/locationd/models/loc_kf.py b/selfdrive/locationd/models/loc_kf.py index c6a92f1683..48e309d9c6 100755 --- a/selfdrive/locationd/models/loc_kf.py +++ b/selfdrive/locationd/models/loc_kf.py @@ -50,6 +50,8 @@ class States(): CLOCK_ACCELERATION = slice(28, 29) # clock acceleration in light-meters/s**2, ACCELEROMETER_SCALE = slice(29, 30) # scale of mems accelerometer ACCELEROMETER_BIAS = slice(30, 33) # bias of mems accelerometer + # We curently do not use ACCELEROMETER_SCALE to avoid instability due to too many free variables (ACCELEROMETER_SCALE, ACCELEROMETER_BIAS, IMU_OFFSET). + # From experiments we see that ACCELEROMETER_BIAS is more correct than ACCELEROMETER_SCALE # Error-state has different slices because it is an ESKF ECEF_POS_ERR = slice(0, 3) @@ -159,7 +161,6 @@ class LocKalman(): 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, :] accel_bias = state[States.ACCELEROMETER_BIAS, :] dt = sp.Symbol('dt') From eb0724d7e3bff078f803d45d5d305b5f793c8f22 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Wed, 1 Dec 2021 03:31:46 +0800 Subject: [PATCH 070/102] soundd: fix test case (#23075) * init sound_stats * send deviceState msg --- selfdrive/ui/tests/test_sound.cc | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/selfdrive/ui/tests/test_sound.cc b/selfdrive/ui/tests/test_sound.cc index 62aa35cb2b..43599f3828 100644 --- a/selfdrive/ui/tests/test_sound.cc +++ b/selfdrive/ui/tests/test_sound.cc @@ -9,6 +9,7 @@ class TestSound : public Sound { public: TestSound() : Sound() { for (auto i = sounds.constBegin(); i != sounds.constEnd(); ++i) { + sound_stats[i.key()] = {0, 0}; QObject::connect(i.value().first, &QSoundEffect::playingChanged, [=, s = i.value().first, a = i.key()]() { if (s->isPlaying()) { sound_stats[a].first++; @@ -23,7 +24,11 @@ public: }; void controls_thread(int loop_cnt) { - PubMaster pm({"controlsState"}); + PubMaster pm({"controlsState", "deviceState"}); + MessageBuilder deviceStateMsg; + auto deviceState = deviceStateMsg.initEvent().initDeviceState(); + deviceState.setStarted(true); + const int DT_CTRL = 10; // ms for (int i = 0; i < loop_cnt; ++i) { for (auto &[alert, fn, loops] : sound_list) { @@ -34,6 +39,7 @@ void controls_thread(int loop_cnt) { cs.setAlertSound(alert); cs.setAlertType(fn.toStdString()); pm.send("controlsState", msg); + pm.send("deviceState", deviceStateMsg); QThread::msleep(DT_CTRL); } } From bc57ffd16ff2154a9c9126648233c8439dcffe9c Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 30 Nov 2021 14:51:31 -0800 Subject: [PATCH 071/102] increase scons cache size for CI devices --- selfdrive/manager/build.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/manager/build.py b/selfdrive/manager/build.py index 04769526ff..d6429092ea 100755 --- a/selfdrive/manager/build.py +++ b/selfdrive/manager/build.py @@ -14,7 +14,7 @@ from selfdrive.hardware import TICI from selfdrive.swaglog import cloudlog, add_file_handler from selfdrive.version import get_dirty -MAX_CACHE_SIZE = 2e9 +MAX_CACHE_SIZE = 4e9 if "CI" in os.environ else 2e9 CACHE_DIR = Path("/data/scons_cache" if TICI else "/tmp/scons_cache") TOTAL_SCONS_NODES = 2405 From b3b5beb6277ba0889a74ac56178596727519f1b1 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 30 Nov 2021 18:18:12 -0800 Subject: [PATCH 072/102] process replay: set full env in cpp replay --- .../test/process_replay/process_replay.py | 25 +++++++++++-------- 1 file changed, 14 insertions(+), 11 deletions(-) diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index b5be15f253..ccdbc2754f 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -341,6 +341,15 @@ def replay_process(cfg, lr, fingerprint=None): else: return cpp_replay_process(cfg, lr, fingerprint) +def setup_env(): + params = Params() + params.clear_all() + params.put_bool("OpenpilotEnabledToggle", True) + params.put_bool("Passive", False) + params.put_bool("CommunityFeaturesToggle", True) + + os.environ['NO_RADAR_SLEEP'] = "1" + os.environ["SIMULATION"] = "1" def python_replay_process(cfg, lr, fingerprint=None): sub_sockets = [s for _, sub in cfg.pub_sub.items() for s in sub] @@ -356,15 +365,7 @@ def python_replay_process(cfg, lr, fingerprint=None): all_msgs = sorted(lr, key=lambda msg: msg.logMonoTime) pub_msgs = [msg for msg in all_msgs if msg.which() in list(cfg.pub_sub.keys())] - params = Params() - params.clear_all() - params.put_bool("OpenpilotEnabledToggle", True) - params.put_bool("Passive", False) - params.put_bool("CommunityFeaturesToggle", True) - - os.environ['NO_RADAR_SLEEP'] = "1" - os.environ["SIMULATION"] = "1" - + setup_env() # TODO: remove after getting new route for civic & accord migration = { @@ -384,7 +385,7 @@ def python_replay_process(cfg, lr, fingerprint=None): if msg.which() == 'carParams': car_fingerprint = migration.get(msg.carParams.carFingerprint, msg.carParams.carFingerprint) if len(msg.carParams.carFw) and (car_fingerprint in FW_VERSIONS): - params.put("CarParamsCache", msg.carParams.as_builder().to_bytes()) + Params().put("CarParamsCache", msg.carParams.as_builder().to_bytes()) else: os.environ['SKIP_FW_QUERY'] = "1" os.environ['FINGERPRINT'] = car_fingerprint @@ -402,7 +403,7 @@ def python_replay_process(cfg, lr, fingerprint=None): can_sock = None cfg.init_callback(all_msgs, fsm, can_sock, fingerprint) - CP = car.CarParams.from_bytes(params.get("CarParams", block=True)) + CP = car.CarParams.from_bytes(Params().get("CarParams", block=True)) # wait for started process to be ready if 'can' in list(cfg.pub_sub.keys()): @@ -447,6 +448,8 @@ def cpp_replay_process(cfg, lr, fingerprint=None): pub_msgs = [msg for msg in all_msgs if msg.which() in list(cfg.pub_sub.keys())] log_msgs = [] + setup_env() + managed_processes[cfg.proc_name].prepare() managed_processes[cfg.proc_name].start() From e679d05d9e98e267047c21c0b6b67fe9d61f8ed6 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 30 Nov 2021 19:47:33 -0800 Subject: [PATCH 073/102] New sounds (#22652) * new engage/disengage + amp config * first family * cleanup audible alerts * tici isn't special * fix up debug cycle alerts * these were better * extend range * use distracted sound * log scaling * getting closer * slightly louder * prompt * update tests * update refs * fix c2 test * resolve todo * adjust tolerance * revert for now * should work Co-authored-by: Comma Device --- cereal | 2 +- release/files_tici | 1 - selfdrive/assets/sounds/disengage.wav | Bin 0 -> 155804 bytes selfdrive/assets/sounds/disengaged.wav | Bin 40662 -> 0 bytes selfdrive/assets/sounds/engage.wav | Bin 0 -> 92172 bytes selfdrive/assets/sounds/engaged.wav | Bin 40654 -> 0 bytes selfdrive/assets/sounds/error.wav | Bin 40650 -> 0 bytes selfdrive/assets/sounds/prompt.wav | Bin 0 -> 127172 bytes selfdrive/assets/sounds/refuse.wav | Bin 0 -> 209238 bytes selfdrive/assets/sounds/warning_1.wav | Bin 21468 -> 0 bytes selfdrive/assets/sounds/warning_2.wav | Bin 124708 -> 0 bytes selfdrive/assets/sounds/warning_immediate.wav | Bin 0 -> 133412 bytes selfdrive/assets/sounds/warning_repeat.wav | Bin 62760 -> 0 bytes selfdrive/assets/sounds/warning_soft.wav | Bin 0 -> 76108 bytes selfdrive/assets/sounds_tici/disengaged.wav | Bin 50316 -> 0 bytes selfdrive/assets/sounds_tici/engaged.wav | Bin 50288 -> 0 bytes selfdrive/assets/sounds_tici/error.wav | Bin 50304 -> 0 bytes selfdrive/assets/sounds_tici/warning_1.wav | Bin 31094 -> 0 bytes selfdrive/assets/sounds_tici/warning_2.wav | Bin 134392 -> 0 bytes .../assets/sounds_tici/warning_repeat.wav | Bin 70114 -> 0 bytes selfdrive/controls/lib/alertmanager.py | 21 ++-- selfdrive/controls/lib/events.py | 65 ++++++------ selfdrive/debug/cycle_alerts.py | 93 ++++++++++-------- selfdrive/hardware/tici/amplifier.py | 15 +-- selfdrive/hardware/tici/hardware.h | 4 +- selfdrive/test/process_replay/ref_commit | 2 +- selfdrive/ui/soundd/sound.cc | 14 ++- selfdrive/ui/soundd/sound.h | 17 ++-- selfdrive/ui/tests/test_soundd.py | 19 ++-- selfdrive/ui/ui.h | 2 +- 30 files changed, 136 insertions(+), 119 deletions(-) create mode 100644 selfdrive/assets/sounds/disengage.wav delete mode 100644 selfdrive/assets/sounds/disengaged.wav create mode 100644 selfdrive/assets/sounds/engage.wav delete mode 100644 selfdrive/assets/sounds/engaged.wav delete mode 100644 selfdrive/assets/sounds/error.wav create mode 100644 selfdrive/assets/sounds/prompt.wav create mode 100644 selfdrive/assets/sounds/refuse.wav delete mode 100644 selfdrive/assets/sounds/warning_1.wav delete mode 100644 selfdrive/assets/sounds/warning_2.wav create mode 100644 selfdrive/assets/sounds/warning_immediate.wav delete mode 100644 selfdrive/assets/sounds/warning_repeat.wav create mode 100644 selfdrive/assets/sounds/warning_soft.wav delete mode 100644 selfdrive/assets/sounds_tici/disengaged.wav delete mode 100644 selfdrive/assets/sounds_tici/engaged.wav delete mode 100644 selfdrive/assets/sounds_tici/error.wav delete mode 100644 selfdrive/assets/sounds_tici/warning_1.wav delete mode 100644 selfdrive/assets/sounds_tici/warning_2.wav delete mode 100644 selfdrive/assets/sounds_tici/warning_repeat.wav diff --git a/cereal b/cereal index d6f233bf7b..9ce45916c6 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit d6f233bf7bd6d1ee3508b17667e44420ce38de0d +Subproject commit 9ce45916c6c27e8cfbbe2aa6b796fac41eeeba00 diff --git a/release/files_tici b/release/files_tici index 29c8353b81..59cc41918f 100644 --- a/release/files_tici +++ b/release/files_tici @@ -4,7 +4,6 @@ selfdrive/timezoned.py selfdrive/assets/navigation/* selfdrive/assets/training_wide/* -selfdrive/assets/sounds_tici/* selfdrive/camerad/cameras/camera_qcom2.cc selfdrive/camerad/cameras/camera_qcom2.h diff --git a/selfdrive/assets/sounds/disengage.wav b/selfdrive/assets/sounds/disengage.wav new file mode 100644 index 0000000000000000000000000000000000000000..9f4a16e627e74b747fe786167fc6f1472d842ea7 GIT binary patch literal 155804 zcmX6@1yoy2(+=+L9^BpC-5rWcp-_qy3T=_%PJxy}TM86+DDLhM5}e@f?wb7h-v2yj zW_M?H_da)ac5lwjHPTd5`)-d6Fjq8Fb$RCpBm@8eNCgfQQ_c>44jv}R0BQgkfEGXkpajq$>OcT9fDym}U`5o}5JC^2 zLwKkVesV-fj1Y1}iyG0F3NeZn;iX4t`u}XS2rI*X00Nj0^ROWF|NK;lD-Zy%0jLO; z5AX~48T=5wkB|fS3H%s=Q$%?IKS$UP5cW+3))2A<--hoXEW3yv2mg)OLs*v)z6JO^ zden01OU?|4;s3BLUC>7>FqRF9P(4`{Ds`1NZ?#01<#7Knx&? zfH*)BAcueoKpmh1FaQ_=ECJSlR{$$SX$dexzyx761?VF@1^}b~V2G&y&uRqFLX6P_ zC?iHIAm)$;$N*#!B7)@sE zKk#IDEIbhI4R?Z@!gb(Ea4|RsoEDA`M~6Scj$rFB2&@-Y4=aV`z*1qcun<@n>@xyi zU=grr*jHFKtN>OG>x4}rdfvfs;0$nixE1^}JR1?sLpTXQ3Sa|>0u%v;0Y?B_Bwi#_ zq)$lYNJ~gW$mYm7$k)gQD6J^`s5PjHXe(%O=$aT9ms2UL1S+z~mr8GmbqW}A<})%=H4q4(XFhjae&0t~MV)3G_Us6+TP}mi@%UJ?SkTOPD5KTwiV22-pPO^#<-YTJ#v#g1)b7yU z)Oq#I%)4M;mJi~A;(-wVUT<8tL0feri1M}Y3^O~)N96L$wymJq=Apl>YE@f#o0&gT z)Z^8oYa_FwR$>K`wbJ|l0E<&=s$0f-T!-mF)!--aEofwFW04 zx?H2*Xqg%rIzL&m+X~04ui9!x8W!yLmG9vgeiWf>2O?jU;`C3gd|h39?gI0JKZZg> z3W7R6vIM;LpYXHrANuewu=W#4kZ+LbXaB&z@B2JXo#ZXAb>7S02n;d4Ck{ioxR%^Y zUG$%*?@esttDMNM_)VE^o6?;WmX!Jx@{QsbTb^^dTEkH%WXK)NG+VI%h6XM4&zwzI z50!O(Xz;91Eco_kD>L;6W`^0Xce!k({PiR~Z@}%V;ion*9DG|kS{_!Zdi4vFG=~`v zi2wR$;?VZczagNYwNGguKYwKW^yjlp@LEW5C`TwxFzH9J_bzWo98%3rHTh&}cysBM z2=o99m*v~M3tz@9d#W18D)#clv+mO~Q_a49_==LY{$ue^W6^5O?>7EH42bbU#cK5? z=l0bm&l)}yX|idksiUVZq3my7de%&4WroYo^FQ>316AKzv4*SWM0SyG2hcRh)L1fv zLKHalw5&*7Grc7O_&)y*G7pmcjQYvwqyNWGpNN9`gQ-HJLcfJcj zTrF6FoXecX95?Qz~r<9ihgDOR?P7#e5`D1mKva&-rL~2 zNCV6eWYdrH#7aG?Z<(apOS_x;%=(K4J_a5JHUvTfKYtwf0A->glf$Tc5Ik|(xR_-agLVICBCT#LuJ|kTC*l|QC-?8*?B@LF zvcI(&ZD)OKMlh$a&DOGq~}(%DCh_k2lBSPw^kF+|vR`d0l-} z*W#E3w0!T&?H4p9(jX>TflOIFtr^o;J2Y1hMAH4S}eii;70@6Q%K2HX7g?#%}@XP z@vmzBK+$cvS?&9l!S1S|bx_Gv z6$^vPe*KGSB_Du8kXAR23?G*<*(oSkON3J7)wShJ*=*3A_01L2uGX|y+e@)qtcyDqNJ&CzYl&01`hoxOW`ixWrX&7L5_t8k||Y~86-&#VqE8!Y_wS0;P*cl@s}zbbx9W>e?67UNVsHmG*hkFd?gZKHFhuQ+l#7 z2{Xw_t7qutn#@}^*?x11c=P3*gYWW(=1;$a6+>e}O+sov*9W-zQhC6fjckle1$EI? zp)x;29C&)7PYO;*jpL2EkD`wL z7}*+b8@e5c>{IEMZ7*)htu?E>FYd{^_>=dO_D9&a%~ZQoKw90m&p%%Ovdei_=u_cW zAJUOHR6g}{)#2#=9t8tRI?ia%>n2X1P^q4$r(?Qf_0jR{4USiWAIr!5pp}q6q1z$d zLHZv%{G`2*-1Hrdtkg^-bk)?}$+t?V3T<%%SuyCDD3%G1FxKIi_i5)H2hCf5R|6KA z=R;;Rrwk#^69(fuBg8{(eS=+GZFG%|HQeR-g(kW0e=}#Kf7?wF{~DjXm@Js$k(QU< z_7jrbSCC$ASVz%*I}d9`TKX`Xjx1)>LfHzGXnr#ql+y@9GmxXiU+Gkff(O?px4O!9FeECGTp{Qf|&#L~(h`OPb276N>lbJkOSUde044_YHeyRSMN ziQJ35r9XW8lo~7&`Z|;|r1`T%An1LAC#{>5lcbG^xvXJ`_J-;!1vcqA(JB56PAz5& z+ICVQyeYJKnB9HYCC7>Ke)X2_+R>u_+}z~-_{vaNZ*hB4qd?7AX>@+fALLBtZvnz6V>e^GVh7{y64sJ`r4eShWd-D!l>+}^w;uOZO&BgV?|!*r0T|-;Q+#2{;V}?v zmp|6nG5r3j-%-&WaM@uHTtG}p#SLoDdSV^$CUsXe{^3B zPf7Qa*O3miHZvB#O>7NBb$B&2m8WGjBus>cxaV1j=q)JP2$`|tP{7YuH=C!0d$Q|| z3k;KCBZoakt%J3Z<;ev&*;tuXX++5y@fI;6QCksC5k(Pok^a%wv22M9DVN`~e%<8) zOB8F=TMl}$KyC9)n;j>$_Yo*E__vhB%o=>15<5zNbZSjuHfFECzb)|o+)~?lR%ly)q(12KnQaxD_ONK-&hQEUYi^+)QJ82hQH+meL z>HgDs{(j;5_XR(Q!?08LyXKA>*V2GI;w*t5=&6~BFR|>=)R7C}rs2QBe@7TbL1Lcb zZ<80lW&DKY2o$?k8#nj& zfX4E*eZC9m?WWhB@4nxaKg)-7e+R!h-)wIQ&u?$1-t4{JcKmBcZvEB5%!F4zR&!ms zOBPd{Pk@UP#+XZuPa=&YiSqaudwF>vyAiZ71J)Wk?A&UUuVyIu_}A|DMml=xVdCew zrs&*A(TLCC{^4{HVUY#V;c=Qt*lE8qX8v3joK^TWSa$v#5}m|YLf#QOD}QiAH6?JR z4rDbIn3n2PInq@!E3(0Gc6S?mN9z;v{?0Go|F{3G-|Tw>-*?`Mo~Lh(-4b2iI33y< zTZ7Es7!~S_sQDN$Nh{-{Tz8UaCo-C0JVcm4aIgvHo>dUN=)z(PBVkP877->kXgc4DFm_L|Lxyq2wYX0I{a$KQ2&@B7;ON%*JwzxAK> zTYaD6yXC#$Y44%$R`!Y%;%)ZD+-hEacdO30`{B|_17x(M%qtwk} z=n_PI7}kZ^9A4vII+@p)C6J+-hLo%qFCNnyc^zMH!2cc$)Iz$G@za zeA9B}I`1~p{+DsVx$d?41N`ejSO?Y&=^Vo!t_P6;xgB*0g9dXGTQujTH&Y&uUhcje ze&+sw51b!%{JH$8{o;HRypcV7-Jf0B9W`t?%n1yOwU(9t$~cHV^9HcB(L>1d@MX|5 zUIwqHj-Z@(dap2H(uFY=1eK zzLE8C_geMoe2?xA@n`&S zDklOd92j=_B_j+N;T+``8vqKqRJ!|1|r!xqCrBW9xRVri4^QZ+Md{umYvl{eK%wi^vxPoP4hw@gp% z9=uS!2zaTZSZw$*#aR??)L--@P5-@evU6~1cKP5|@z(xbsb`Sao)?;TuNSEomS?6% zhY>f^@Wa%wo9Ud)~EgEtXI93UO<1YQ=e#>d`08%jYuamuz zt}3f&C@1A7@ptX7{0YM`NKr@OX<^r2Fv4JAeG$UZVR4Y8zBH-K*zCGOr^>X3*PTN{ zd6TD0@w@gHde4FwJ47bc>$b~wLvP_VhNa5B-*f3GQ}{6$7z^e3+uD};86BozA;z<;NA@@6X) zx(ap~wCL!rZ>-QL{F)t@3H%n8oE)zcQySTY;7Ao_85R}pABh)}8Bg(5`1{Jwce#_r z4b|k$z@GBaoSF00kOThfUDzkAev*1RHg*gF6$yxZp<1&JjnSal_$w(}phLP--fIij zo;Qnb-R|~p3*TnGm40jL-unjZQswOK;9_H7xoFa(f23KhyeCs2y2P8#x=uSnVuf7= z0NqX;&ukto2!JOC*4q8*vnpH*7qcHT`@boEwNKzgto8Q@hw!y9x^UeHuBiSP%Y=ik zDCvX0LjFFKJl4du)b^T>+s*x3mpq!ju?93@_mjHO$FS1~Jc)*0tSoaY!ooYp zLP2{)9E>#p-?}+ILf#Z#XqZSta0J(jRO%L8=ji+rN*_wON^Fj!jNy$sjqr&WjQ~U) zN9V;kB@v}*X2|@ZF6b#=sf%f^8PEbtLmjp%Pmb=0k)Lsr$(rdM*gg4o#mZy{mBlns z_2i5$Ooc4TtP5-p?av)+oh4l2T)p4mxM{o5x~aVBa>04M=NM=A(<;pz&v;80S))X; zN6J?CBR4Ix2{k`a3kEuj@7n4xbDeO08ALWP+zzWBtz;@D{+s!`^oM2I_hk2ktrTO3K7{zF#W22E{1V5>3#qr{Rz(iDlYd{PXLFauh~91@cRJ4t5aV zoT!Wps*-^Exb~iYg7KW$sO2Z?ZCgBtYsWliEEgo#3fFtrKGzi&KgtrsWAWa3d_d8&cT7zDc$+^Yk8Ll7k(GE*U?V> z4k~t)R@LSS#v6J`h-@^F4HV<#f5)!E&`iF7*MRErL~}W_-@SG;_jW>QFr`zi$-joW zOr~Ht8|ha~`f2JwvTkBf{QEe$IOO=q1ZWabs&9J0FWOw+qMFLr4PhP619KCH^9&mf zhgnw*&jo0D_`k`&(C@K=csPXN5_)p1%HPzpwXO9*M$e{a7P(evw*2;Jj=oO*&LpoD zUiUhGcUp8nve&fvX_;l}X4s%(t{$f-BONDV#@ohPMW;oUf?J64<1zl?$3AFHXC4d8 zI8@m6rFr3BYWYavhurett{IKr@>7(P;}Y`|z9oE0BukD>S^s91Y4+zlPqx&&X0xfK z>ux9sq7UWYq&|AN8hLg`YsYIQGp75uv}(IWr%9Woc7j zm*fC&!gBuY-0Y0&TQY|nhIM)+xm6{y#DdLhI)isM2bv%%k+^mkzY{MLrPB`s?4ats&lFz zXxwGiYUynawjHpScT{m2avE^DbqsaLvWvEHc;#*8YecFis`*cOQr1_zT;L67E8{;Z zbD}9s5x}=Q?6cxsztyn0nThv99^I2I(RDSIN+mk^YuVesk~5~ikEgv&Jxq~KeVwN9 z9s0xj*FyHceAH6P>Y0Z5cH#c#v8QRCW#8@5W0D)$7b&z;Tnkbs8Z0Jl4tBmm;Sq^q zSy`nlwQj9SJxilu(@l$ZD{fmx`=1UOj%ZG2j!2Gg?UQWntjR1XOvw$)b=uS!lo(}7 zMEm*PvNti5Q}_~)U=+hNZjnzncWzeX<{%SAL$lrPtp@ekRW_xu1+uxXv&4TE{TTS3 z{!RQ_-M6Rjhd*L}GXDwwD_G=I?)Yz`sju^5z#k+z%elh3BXq)ZgZxr~N{cH)f=~Sg zn8)VAvn@y_P9!s@;H=uEd8#{a7+^YT(P1TS%WI$O5aGD$nCJM_Va)ExCf*9q;>LJJ zUs;<=%|Ss{>Zfoj4=bxD-4`+!JXti-m)q;xW6GU3E2p!~6JtYSJ@>7|4awC$WfO(j ze{cVs{0h$;{n4Htkxu!;Kg0DWURGhwZhlzF-^%#9gO=Rxh9P2b?wrml(eBhq=ndA3 z2WkqAH!(VuE`u5?fICE>M|44IKt4i+N;60|+0fi{z+%Ko&Q{d^yMv2kg`<`ufdjvt zpiTCxW3y%>U%d)VD-{94;wwZ40|<) zFo$FNRJ#J3A6By#&nANgW;*Wbn~D%=ebG03{OpYkxRh#y?=k-XChjROJ|Ez0PApDM z(}J1@E4%kvLmND62Fkw|Pv=+U5@xeyt^QK_<^9X<_hS}g4tgH6kfm&)io719)uQ`s za1;cZ*;~Tj57m#UehvMV<$VIUODZOMX47eTg%r-7aeL%WMU zW8B|c--6OkXO9OCW_6>sO*EX=gj7VApcK;O_2$rL6aQ(>qWPndjh<_n=T>N4T37kD zwz?^%qqdKFv>M_#&$4>C-E|auDf0k@8>9cmZ6+?K^r0tV`OW#jrzGMcX^l7|^VLVS z|L9{HW1GcUB)=lJMzis=d1sSgjc&zciEU15!ecb2}L?TNrUMFzFdBxO7V?;WE ztAJMjB5>P#8n9=v{vHaN`Y`S>Slg}G#?t8fPq@;xl&{D?-|p{y4qFah&hH$+-=#dY z!uKU!6|FTE4cVR_&CV?xU+G%)S+!YhzxrU=WZr7pYjmmiqV-*^P!TQ-7ft3L z^apR634A297^Zc}Jn{()PumFtc6u9R^^%Sq@ zHkb@JvU&T32E>zPh!nL{#WWXmXbtX+UYXjM&sua@D!!6`~+r70u}E| zHHy0nrwalK1_~+*)r%EMyUMSt%4&Z$F16-$)%D|!egiAb(k@YK@b4L&1YRXQWWp2B z+;RAc7Rmi+PZ>4YV|mgAL&SKcGvx=BOVl;AqxCEdyN!EHMa@|(>MU9<9?c8PI8DWj zISqVtk~ElASmgsG-w5CEh_VSW;7|?|e!>z$hCR+)L61>)o!8KzJ5%_em?6vFppK*F z^?JE~>{W^7A*F;R;>8C={KX_CDW%rs6_r&r6!kStO>NTMj|h%dVCc-(Mb~w^-PgzO zF8%L4VAiOz*m#6vWbbJ1fR1d1+yesjqJC1Rh>T=X2Wye&9T`{{+nIvR`phjX%q>#P zrOi4_{uzbpw`kX@b1I|DDN8U5RdAoMpwK^(LkT)Dvysvse_VAPlkEOnbB4N3cY>UU z9s7zpRa?y(cWSSyLn>p+h01J72})ZdCB3SZPXqE4k!ON=4dn#C~@M~&n(;9l4!`sWdsR#B( zP{B4c$I#-nupO_X_ZLBT-(HGP8n7A&a>;yX*cm(7_<4K;lf)dQujOS_#54xA7xiKd z+l)V&{xMTG&oyT>KQt9L(K1TapU|#WmshryJCpzl6Z1~8c>+(V97({q66mFH_J@|s zcgHHbI_qJJ*E2=nywRh9gdVSsk(Ttv>AJ{&Mb)}hj+N^b3l)x)a#ioDrT>-HSv5Me zT(uMS*bX3%0>DZ$wNUdlmL1F^{0r7QjTbMJG^{*=VzML}D@IiI7@jRbWbtKbcZE`w zM2&Op9X)45U*jv24O3gQFtaLCNfT=$83Scq6HRf|A%$z{Ut&0dlH78vlnl$1al~A> zU1&CNz(eb0!g0uM&idtI@T@w-er$L!tT(5Vp$(_mrh&drL&cwKOI#)#{(&&U%-tsjEk*nu{%CTA1^ZQ+F$ljaIqN(naS~J*BIm3@p+wv z-iwRNR4RZ~A~ia+lk~O?Kt}W?`zHFPs-_Aic}BGc9(r=x@`zmQle>|u6p`YOSq59*HG0Q zRP)tz)Kva^RTtlY*L>RQ+v(VwF~~Va3K5^pUKCn~?VKFlUy$D`!8}mEVrLT;k|)xd zGTpIz@>U4_6<3w{t&pKYry;1lqDyA5Vn}4%XH09dW87ziVMwUoqT{3KtLm#rFY6{D zDm=q0#PNpd9jy&HC*d_#HHy!R>>bSo#gXbx!J6u#(5x>6b^LUQzrU}$sROmGusOT& zroObUq!y`m{vTa!S?%9CvxbPK=a!Xr$8Pq1#o@Z~50f9}s+WKp?Ym!&Ute0^Tf{}E=2rY%<}h&kYIOj*HRA}88h05!=hx%rZnbD0ZA@xjnU*Fj9t|_(Up>3>_yB9LhIC2k)m@=BTT>iF!viIlM z;X>lF756)Vb3UISeXR6WCzqvz23Gnrx-2>enq_L3%F^;=(jUZ}1xb0L*;;|^)Za)|@V7BOBQZQJUxQ9x_CvPx zRzsoavpWzX(AN>O!8d(v-Ts~K?Io?EEyT?dP2k4mM(rk~X1NxsHuaABuE5^B0g{o9 z@oLENj1QE5m1oO(zxzb-YW+SECXIT46;D7*_LX{>0iPAl+0LgToFV>8`jvdY(t&EL z2D$c?j*K3reuzG~{+X_gPL-C02DWODVw>z=NgPp9fi*4%))IzVszeesynXa|fczuX zHQ#B^L_JJ3rib%hger) zk8Hp4Q0gez#OmbztkvSv>gv|*zUXQ873o7BObB%VOPipNl!e-jA(bVVQ=V^1h+AAz z`bo}DDP7f2M4Rv?UpuEhO9p)rWfZXl z?lxK~+~UFbD((ble{BoYkC3LSMH%I>G`-RQ#Y^luk#lW)y$32T{a@ou$i zn{99Ioa$!p>mR5XUK&#ZUr$}nsV%LqHEeeu+@9)Ow>^l!TTrF3y9oryQmNM&P+1>2 z`}u5y>&5G&-^vdu4XLVW7;BAc=jqVua_Fk-%xVd0nyPoIcqrn@1xS4qdlZ!BW#;H( zBBW!bz#;-+$D$g+}K2-`j;Ixgm7-hl0?0T zjzAfA6`Ly~h~|#$f?yV_8Kv;0{SNao>DXrP{pQq4Ak<+tZ4w4*7%dyR=#S`i>8|Zm z=}>AiHTdnjD(_8rkYNYN0C4N^}ai zvdB`6VsN1jK5;HXRtDg2>SfX!{Ci9k6owavyOoQ?0 z0p32=p2#kR&Q~21?WOIH?L{4bI}f}3d(`{P2U3PmMu*3jz~a+ubK8p|Yv8Sn{j`(% z%kw*(mr7(h%ox0FViC%>blyyg>`UCT0@@+~2~%k+xpM^q<#v@T)vszJYG5^WHFDLT z%Ir$s3j4CC(m;tj5o;J zsk4civ8G|l!HK@59^-Ccmu2T!$6AL<=XvL4mwZo4@2CC`gSo>vW8rv$*TF}jhTgKzuOdU<*%yKTG3x){46yX3nSdxCpU`$`AWhuTL3#-Aqm zrs`+Ip%p8%o0GexN2TYW8~CF-AQNpF8%U^1W=<`}Fvl#*;mKntuq2Exel6)I6D!BB z;H{{vl%w=dsYnS~X%UR^Fxk4(Y_2-3_T-MgMV)rdiR4=vf9G=6F3edZ7CJ4I_yIO=HhZ)2U;tt@S6-ElJS!(miJRwRzOuGSBy}Imv@j;k*$_CkZcn}6WJD!=Vjq+VR>Odp_wL&BxJy8 zLURC6Jni2spFbXH?e%U3t~xEo&)rS^19y(ok1h}G4(Rq1^fC9w_bB&h^%V7J^fL7E z_a_dB46%*8A7h%}pDdjTTu4~nSbx96b%=R(clB_O0i#6W!DPcDBHkqbLUYUjWTE0% z=QiOF5Hb~A5yz8SkT#VKmQ$5)ls}UvREU%RCHFYhy%pCnR3PcRlKAJV$F(^Fn(nrx3+AGk@ z-5cJE-#6K}+pjl>G)ys?Iqn0loid-(T?}5`+zi+gImW!$znOm=gSVpQVR_;+kTXVsxc-p-?9##9PKFL5_ckywAQ`IaNR0-l^WGUO9$(%n3{@L9#&FV@e~Rhu{OV z{SSS%eE46TVE3f(((6w3nHuQ?tqR+e zV2ebbGLAML_y!TjNbVB8R6!|`OtAt9SE(&&TG=z%cXIu5>vF1cva*CSJyKN?tD;vz z-TZVsr|j{}oAj8}7-Yu;qu7;b`G{;>xMjY~I*~je*df@^T_(%L9`}l#zjY? zhiQk92Kfh4`o;VC`#t;D`>O{w2Hy;ujW&&c0%uI2%ymFJRyH=ccGC`N&zi5S?=fCl zkQ~ur*ii&mBya@%sJazb*LvaQlm zQXAq>ksd*FzGyCPwtU82S|mys@hRRaCKTlaM)&A`vvdCCSZ`l-`@{O$as zSvQe4J~t{eayYa(NIe)aATS^{;4|<%usD+y#`nP6Aoe$VG4$SLw$tXm>oie1J2O$TrA2=r{-)gbnG8V2;s&lEHdYcC&>G9LuX~ zJzLFtb4L{C-q(xw`Y-cHrsy-+x&)0RD3lxsj*Kj$>=N8wd|raAB45P{B|N2eq>*Hc zWshYs}2Hz^2q0Zoj39CaCq8QvMn7>Xa7844Qq8|fVN9`~K-fY?o| z%$Y(9mf6=Ax61djj{45fu5Ir@&)P^}G!yJ;d^M8q6kRm447JRr>@8epyt@La!l$Bl z;#HE^(gZR;WCjpWkU^Jrm+Teq7u^@i;Wyz~;J{^F2IkSKQErjEA-KZ+f=-1z{1W%z zd}Dp#bJBFcyxY5(w3fO&1QnbgoJpHXgfvZ1fqKXCN4rKiM`ngW!@!Z=k?PUIu>_Da zIB^nVrgN?w3SQ=2AK8l9^FB&C16_&Smpt<$wV|nEPv8rYe4xmr`N3ete8?ut<;1Hh zFpoG;(8Tj3_9Ta;grv2k`K6Pk6eV-SuSHLU$px2r8@L?V2bqT%Ks0p}u_U?#csLOB zOyoB({YT|n!^_aqg+qhAyRFgnk(K*J(}l&^U(*SbRbbMIj`6=^kWtl9*a-5d^XSv) z>KG7IG~ojIFtsq_J}3 zKqSosIXIyhE+__YttY)Zud9+Xl;f~{&YkOx<5jF>3+VJ*(oE!3HG~;F4}y%7kEe|p zj5&?9j46!+L3$J2V2{bS)Bk397xoqxSMWEYw*~fLM=xjG*S`1t&!k9hXpLA$c+W(q zWFu4&bhwP}EI--5ajEha^LGe_37?BliY<$YiR+20ix-FmieicU7Mc=J<@>@t%>ic} zXVPZqroo|9AhjU0#kI$@Lv;kWKZo8|Tpyk5o(vv1?=o*;uam93TAZ2xI-4*(HmMH5 z2h&ctgSN*@#v8`($KQdJCal2~5Zx(}8T+}}g{UQ;)$9$Totpjk$Cl?_*D3ey&uahx z8Wk1=-W}lxX(S~N?JtHCCN#E7jx_E)-dp~Eg3Q9EB3z=`qVuB1qE4cAA{4@lf`S4) zyh7Y%9H*@POb!g|G?J7bNHYlwaBDDYQ5yig&(M3c8;y&?6UM{t-RP}=^_&&JQr<%B z+`k#J>4wQnNI#eWoG_s`p)v7pVs;`C91dxol%2+yC7JhvVlOYRUT&!GfcCwQ#m*V8 zf%i1ev;cBc9Ly`6eu7jID+*MaNcuHKY*sjXF&8#3kpE2JqfnD@t_Yi`pXg6fd{H8i zWuXee2mVxEeC{}oPS!Xk7KSXE8ww6mHNsc8uP_}^odEBilkS_ZVdoAf>j#McowvN# zTUL~paG?zIKC?H|MN@^7qYxZOBv=Ye4;BEYfW;yBlL}KU)84aw^P^CUWu`Um%?~?A z`(KV_&q=OP?(d!s;YTQ27?U^+1bHO>6kIe_^n^@OtU!)7E-GF&{!;-jp$g$>k!KNk zQ9aR8krZKDAqGJs{&gNVu61@A)@{aQdSaRYiguDc0#sa5Oa@eLfa0^`edhHJVy)*7 zQg=UZ<*Wl%vzIFz3YJg5w770sedmxIkUUoWyM-%pf(OoTd?B@L;lIrQt~Dn&j!@ z^Ang8d=jb_#uSkfVHR-|Ru*CwJmn|i`^W9TdCMltLczFB=S#gu&QD@T;D_@GBN!zF z9`lraH+e;V9(T-kaJTcaDY0I@Vzwj#HJi_vMVYCc`Z4(%asc)MGl79%AMhc#5;8l< zKMk7cnR{IDTH;*=ZYXd6-D5ujokm@n+)6%jz{rr%(KoT$@ZyOS$Uv0*w7v`xOpdHD zb_cFho;Q4$0_KADLNFl}VHaU};rBu|f*Jx0{93$^Tq7I-Y*6L_U>==1^$5S$x zl8KE8dGG=F6e2a%H(f9bomW^qUp`qw+0xnVI50lBKF_(=|00wo(h@q}}4eLZ}xe{z1%xLdf@g4i=bOM+0^d9B&%X`Lz2 zNqa~WSO+Wyb^tenJs_VZ+oyDA6y}^4MixJ<*sQy4{n>p!@I3)sq+HY7H$UmY*O5)p zr?8Chh6ou+-6%?_N9cNiQOs0q{)mip<3Z-r=eHC<7xWhF5Udm=666F-c7RVKV3n&Vb3wjBJ@>lUC z@c!iX<1}GMVU=TIWjLgHOSws^Mbv~xhn<3sf)Wl#d(OD$xtX{KKQ%ZK*q7UJ-|Smc zU3pwQSOCnc&JItUKx#{oNS#Dy0o-F!WwmCP;+*B;<5A%y{8hIpoIRZsuHL-(u}!c42I%-=aaHLL-M09}tY={>Ab{=SSItXFO{? zJm2(Qrk{l$ryjKLl5Qt#2(96*U@wV6bLM5{2xqxwVx}3VU#29cOQ!8-JZHP-R2Qfh z#g-#i(Kgz*e(gpdL?8b+tG$HY;6La;7sClr!qIQA%<&2cAtW2*Jyd?QXY?wJubB;4 z(b$7IdN{kdqPUTG%yR%=Xkq##;1B#?m&_ZGmAPZ%%Wze#UObawdC*Y<7P3 zbWU`k9h$V1wKBb?yt%QRx@U7Jazb-XdBu6F_weO;01iY6K!;%A;_(woldzCODcxuw zbVNW#CN!2NR(|#m98sJmT>D%m-0|G6xYxKux!!UzayYOBvjj590jucHX>=$9$&!hq z2|RG6v0l)ck?r9W&*S%*H=i#9&(e>l4y5+Fw!JrX*7a9|mNyptprQ-X^C5Gmv!%1u zv!}D~<|OB}7UH4!OKZ#1s}JjDTYWov`)7y0Pt4DGu4rzV9|WJR;c3XzXlPhWxJ(2j z#4DuX6j;>mv=#JSz$zvemOEB$_V*mGI8nGFxyHFlx%jzKIEOg`*qc~4n0FZ)8N}&I zs9_YcWY)y52@G)gu zD(6|}&*xs|B<8#46BkmUBa6n%sH+=mR~x`>m)-7tiKCViy>qOqotxSF>8BGIC9)ct z4W5Z*JUcg=H%k>0 z2v|pNL3>E$MgbxvB$g)7#?{4=M5jkV1spstK1|<2ub$5(Pm_-@53+V&ZHsTpuluh; zm)|bQE*e5(7qAz$=MUz27J3)HK~onOmMm6K)@IjdH}|*E_p}d+kI+vO&jqgFH*5Eh zr#aX;5&-QH;{baQ?<=7k$uyZZWfAo5KgQ=X!m}!_%jL{#c&wxw6Mq5N9MV(7|OU_FsM*<{T!uQ49#*)Se zL@h;{f&rez9)fPyu1qgZPfLzJAAa61+P&I#+Ctl0SRY%vU$t4?UnyKESQ%dd{vShU z;g)tAMqv{h5fMbNyA`mzYtHGMHFd_+xpX~eZTr^U>B^Yh-L0U4-K~U_Ew+AKzklGl z9u9AwbHCHs(-&q;W=-ZI=L;4jNjc<;ivhH|jMgRF)%o>o*5jS%eeWY|ln(m_2O~m}Nz%7u9A%efBjp<8cI23H$#SxCX|h`~o6^(BSwx4_JvguA zO=vZwA6yHH1A>L03Cshuc&>039d7KM*r{RJZcMNKUcSw|M*l>eqF9mf#D@!^^AU4t zvqH06Y01a%4yh>w0r^|{xJ;i6TK2Z=O<6O3nlaL`Ruu?bAEH4bC2fw=M3lT=5H*x5?x90Mf=!J_?D1;$Wh1T`2uv&hI7e=x_0CuB;uds4ZV(&d{T1 zl2jUHj7%mekP?V13ojSk7i1Rr7vKw43)dIs7Gj8UB!03C<@_Rg~I&W05 zEOt8gJPxrOrrc?~n|vriKj8?V7f2S|A?_|w3f+Lo!d0b25o3s(NG8%lI!gMqv;n(^ z?MP+h4Me>Z7XCm|5EdX2D;_DPDT)_9EjYm!%says$-#YCw0C{y*DYSd61|km2N~Bso$m@jB6-s7q8OIubt;c}V|A_sQ=lghdY;KZDNPUB;~4 z-ypMsc1HJH4l6m7xgYTM^YIF*3TpsCAcEKh@dbz_^frubRfAuX(m~W9l#y}Bx5xx! z2+|!%N7y6YOSQu5B|~9@5;71IuqKETSSu7RAk0_Hc}alfbB@XVWUE#6^Y0NJ=-^j$BQ0Bdrtjh!2R5iPc0XsgU%F{FO4c7)?`Q2rkL3 zoLMW}fNy=-k=%cK2;jWQJ;AHQ?<;sgI1s1~>Jjr6FNd%s5HM*;0K6N1S!zMb9`OwE z1Mv`X6A^;gk@AvCg?CFfz=EJd5GC>BVxFRQB5)xJe?H(gk29Ad2jAh*p5U&=b`-06 z1GV0`8nq&~yu%z~G}0Ss!_>7!sl_l#F8P3Tm0jZpVh}Nu_=31XOeQ@g|D_01b7>D4 z|1FiR@ULIkoZpJrrSFFv4R9LqJOY&PHwzXD#{v=S*LQ6}LA7Fc@;P~cWJ)S0`V-BG$BFNWND`B@K{j4& zrQWAsW4>DMSykJ3$Ku<0u(y8T%aO%J{5m`qeh(fE2f!mF%V9+5l*BWLwD?;wil_|Gfvv`9{+oaYJa4%&INA@_ z_O8><$s{LXR$gO($org-EXsC3%DD;Uvx<00C7w6ittVIzYvrY{v@&rGz5i+T?OA1_kpNM zOiIK<`C<2AD==rtYmyHoUq~iON=n{?%|H=Qd5LN9_h5wBJ5iE|rf`VhGyXh4H_sB6 zIH&c|?Sq;<(cR12Q!LL-?7HJx|4Q)k7Bi1=gI%LN)obw@rJSrtE+9pb0!jao`bfcK zU5ff*5EV-cV#qEDt$^218-c7h+bz4~{Uf#-SGhWP?gQlcvjyNnH-zg%mVsg*gcuBb z2p$ms2yvF6O5B2S!XjXKuwEDwwgLMNgTUTErzN%^BjSI+4r1M+C}4tcogkeb$fwEc z#(jbF^AYYqX#eDH-nQu0)y=VW&o%st54*-rT(((NUWaW;Zb|I$@6q;a4j*vna^bj7^7aA@`QHgl3n~eFiQEHz z5zPi=izR~}i3dXDCHf`qKv__4*drJ_$P0^tQK6C0a*07mwfKKvb+K|$Dd1({e8Cxh z0X{9>liW$1c}MgE)c*b5(QVAuyUnfj3v2Y1Tg#eD%M2{NkG4WpqCQ%LEY?zxrm?ZOS-5q1M|H1jKm2g>=mzH^moHBvuM%Gz|A2t3 zP`L09k#69!D7P3G%p=YeuY^QN0HF7vSm-Jg4C99VgQ`K3C6*z=kPUFF*kur>=w*>k zAt^y`{!f5T9ssu^=ZmAM1H=8dyBpg9TP>TW8;xu3tNY7MOP`o;8F};>8k&|zb)#}q z$&1U2P--Z3mYPI!pqns!m~WRD%TcS#YY7|Tth_CUovvNy{ni81qf8EAu4~*QJSKoo ze5?Epf?tGYg^|FMqPIb>#9n}}iJL%3kVFZJgd)@u>H{@~4oi4Sv_jwzU2z0>4U{Qr z3#<~>5_%;-Z)dVhHrv*(tZA-pE{`ltG7lIi#&fz5 z{U0rmW=XT61<=xH5c+R=0K=N;ycE5hy8>9dv_8CH&#K;1-+8mk*kj*ZAM$gAbGC3P z@;v8V1^DyV3CIY=3%831iJF5v#azHD;#1;xA-fO{i5n94C7w%!use7jGAXVmZUNR6 z;{nwJLqy0z=LARj9r-GGb$BwlbUDk9oDK)~BlgyI61G8Ge>TlF$ZP4VmsY%&&nzV{ z3m6c_8@dvmOlzjq&<1HpdJ>(FQN#Gie6aL&xpjqi?ZkTO#_p#7R>3ycuIFC*{^7yN zqdX2#t~=aJo-n`=pNBvlTa$N1>VS))o1i(dJg~3$jJPl4Go%`VgA774A$E`+@e|?& z;2yC7P@U*2prZ&?=%FA?Ad}A;FwT?6tU^QYbWqonOfR(h>y$#w8*vn?u z=yz1Xq0IH28_D|(AjSVlfKMnwxKLyqxFk9W$`T6z&w#ze^Vr>7V}Bdswc>8#1K{J} z-(q#3M$s(bemWO^8nGBQ2;vqbSAq`~BKZU! zA~hkkDfLw9B0LjjEuja#3j_;p@|Ya0ZilZC=-)^iGyD@`BRYdY{qOo}`ilC`vG0Yx zkC7+;%)TdPECQK7Rxzx@-Gd_+-hRQypgsvpsaw*4vRrZS^u``w5Tr^$jKBG7yB=3%uVel% z&KR8?j*N^lj2sK+4h;*w68P|R!)cBn*qO9Yle0;YJm+H0J&uA!NQNey4)n&mt=jAv zLN#B=JQPFnl&~tO$EF5vF$Aj^=GQL%azKM%M>cq*_QcRSna;0aetEj ziq4)Wpb)et)u$w;Gi_*UCFJzzIMfFpWD=2jAuI-Vef+xRb<)*qF$q_0U3n7o?b`X9 zukZYc6HSawx{=hDV0O3R#_3C%XJh;F->B(BcGyBSWd9<}KnY;-Gc%~el} zPwxJNdW(P2{nYA-(UXp+lP^xa-TCw^IU{vF8&Nz~IaM#h_6*+dTE&;MX(=(i%LM6e zb8LUhqlV3z_NvIL!|HeS0eem)6yNWkKZxY^$eE@#(PR>u6$@)-q zu8P&T+#y8>9(XbGZ@hUDI9)jXcG`bxd|Y-UzW)lo6uZ`%-|W%6-ICdX!1E1qPZkk> zGH6S6B!s1 z-gW-qs?i;K{Ntp&B<+OF+cGhxw_nq}2Nl|~$MVVR5*UWc}Cp3G? z)O_KT=jiEyGd=y?yIot|B|ZBCiDRUhHu4m+cOz!+H>WLMh%lF!v4jSkPZ}$CU+IZ#X(SUvquxKI{43H#m4G;>;!g8!C6j5{Hw(Nk8IZZ%$nVggKuA zIyD-#sh)?a@R@8aQyz^ucE4|oDJSMF|GW0r{-@>lh_5|gUVlyb4*oTm(x2I0aIPY} z!M|gZFgR21H9^Rjc>)1M}3W97qB{oe@cowIE`&4=}hb+>DmYaiAhHk!23 zJ4U;DdU6K>MzG`iQ+#tAL=K86t(N(CwRJON_bLZB9~fvL0Y-)?Sg0Lp^I`H$m29uM z2A_Nr_$z|%vgOU*yBFA;rNzX|IImlvE4q=OKq=2;hgFl)I!cO9B>w?(cq}am4m{)U4Fhld(HP8hu^eH?WGW%?%zko8?`_Tm^$UXR=x{gfpBn&SY9#XE(oYPw4!QP}#3H!aM0a#~_O`XV!1+z2_zf^@t}RdKD<@yL#@%0Bd7s z{E7Ge`e6a*Q?6#+){S3DoJ?9^6L5xZ1FnHDV8UAh4n37zBCS`AMs$_c*5ocr#Y0p@ zF9-qvc+T{L?j1+g#@fuXJyU`1Ouaz4L%O|SKUX}RHDNM(aqwg>tLsUJW=jvd!>`Lf z7vu9ibL=v)=?AGBDJ3b6slU@o|HWh#<%SlXEB#Z+s`YHjZi96u6PyM#N4=-!=KB{_ zmk&4Z96aD{7MYazBQ2rqsg;0kGWD^wbiL?R6F><|Isfcxz-?SydSYLaeG(|aEmrJC z&84Ks=fPS&Meeo^+ve*SH*H=Oj4WAFQM^^8oqvtn?CATh8!LD%eMyI|yO>OJTv(q? zoMuhfjF}IQ_p9`1b?vlgHb>O!R!fu-__%8|)TPA^KmltTThm?D=-NYltbWWUJ^ zEQ&2_tx06Sz(Z^y{}v)a|jy} zLkn*KkX*3`8{2<2@>dYdD(Vw*G5aQ|VcL4~)mYVV-N4OWMz>UCP`IzqZ3eG5ag*X>%9NGD}`E-@R%%=UJbP{dmw`ZEC zq9*X82SaQ9zk4{lmD!4hHo|N5E6`c;6;!OyM^|%4Qyb&pP2Jd5h{F8&I1r{@}bxZlZjFaRq z@H-J2e=^Tsj=_E8&dW{zwQI{6j5(?yC7UQPuRC)z@qLtQNV`uFzlCjT{nPle_Dy9& zsd7c$&0Ti;>7caQX*8bXg> znc*ZM=)J2)+YdM_`9(lIu*b4as;0X4*zBwU=L*l*08-eW^VhDzZl8`5PLxY}m-rx_ zE7s}8^~;@6??N{HG(AIInr)&?FQP}auqtNq`pCC1Rq-9*z953nj{E(QKD&Ae*4`Rr zd5n=qH6Wj!x145-1q`M2_H{{g+-W|n%c*)@R$XM8FP(EUGw|O)+FWXUYFg^4wAl2$ ze|?#2*~jt*3gU{7m)TT?)MV6aH8a~JJIe^o1MXw7Gfw1WrtPNsfdTIsku(W}%$&-$ zZm7wo?bBn7Q^Ua=Q976PZV>L!;;ttoB#6cP#Kzow9z!}`cvdR-nD5;aI2RW?DGNuV zS$&3I09GcRC;CrlfKQL-K1cd~*>*4cj{HByIt8`hGHo~p7$guHarjnR zgMLj$`Pt%|`NZtT3|KlN#qlrV&z0X6ziUUs+lg@^iDpUiNmB_g<3jFSy|Hmc;sQ0|LkQ}0 z=c$+z`ff-^1Dh-6^+vMj1f6PirjoRrDq>Rt2g(%+19WkK_fBqJS`MVb7Ahv)hNpU- zoO}0ibeA5Ga0GCKiSFHZ#TXae7gM+`yuti{s-*Gy-%ONy#6-*BktGrzs+fv zGm~<63&~}tYa*I>u_irx!yYq|i`uK_b{n}-BF)fqa*7&EbdJSwr}Ps~{c)k@(XCg^ z*#yA6`0t6Ql2#KRC7|P^?)co`iE+Q+6{#B9e>%`-@kFAVoFksyaSOwFy(rBNWjVPk zQgM(oz?1yZT$lDOSkM(=8W-_kYGY)nkGI>hy|B@z#;E*a(Rwa6b2shF-;`fc$vo^; zqw|+vpU;2J{OtSX+}D9`DL=Y@p7^7h8vJh~YbWn~v3o^PZECX?&c2s60-nuUOkVBW z<>0Xq`2szVy{*21iZX9^pdHWlC7y|llDIs0J@(E<+=;}bq-RMF67R%+k6pR>`)cRK z7g5`x%7Gd_;wN@p7VMTR0LI3sTUxa$J90XRhY|~-vVyie?+&GRlGg!CNsE#T4O7vh zq63xqJJ_I>OZDkhVrAIErre#(N9i#sO}}sb{Q1M|yVtj|ul-+5z6pFs|0qxX^sDdB z*;LPeDOmw|uZs-J!)v6PE_Zkl#)go!q#6Hk(v1X(AybF7D3b8?-A;=g|@VXO8=8o&>lv94XeqW}yZXx_316 zm07aoQr9H>LH0tNfOL+ldzV?~R&5!Y6qR}HDZ^2d0T;qe9JbY_ajqu6qOxSSAU4+` z%jX{wV*JUKf5MlKK)_Z?^NAXmDE?MfoX5j zB{Kk7VL6idCPkH{zbe;j^P7g-&vgg&=Z;3rTqOTsA7T6Lw{pt}MT48+8uG8y7IYCt zNXsF6Nw=93`==rUM1mJX7Q;YiW6p}6-3qe`T@Tg|6!ianYQt0QxT~wbW29}o%=!Lt2_M?*gl)twKcK~tF3pBdoF9JK*WHc6;#yuc zysa6oxLO)f)Rq4!w=4U6*6qx>jO2`x42jI<%!;i2>^Hgb`Avo1B~In(Rafg$nk?HL zyXt#0hi50f7Y?Z_E8N?fM>hZ~BHtw&&sBjDSqvXz$GvUhbb=2oB3O+?IPL{RThu^|e2!O)8>gi4vp|C%$?a)1TmB|j=MY8{&0u>?ZiP}ih7v4@_v{%r3X_plHK zl8F>kKCK;LAa8NOUfa#nv&ZM@>4#@B!Z;$HM|wwHh#HFg6EPp25z2dpKd{Nq^3*HO z2KND%Q3t$Djzx?K%AixvLyMq#MNyKib2OBFPAkGK;Ky_2=*q6eX8W=hEsJR^4UVjN`-I>Ac z4EzBqn?asGPr?Wp~; z;$c0(#-}}fK_|Z*pLUtDe`f_U4ZvK{306C;5RLSM%7T^zNZdUKf46*A#pqb#$LXli zu>SkqZS6KqjGDo6$>Qp~x-64_s;S9;9{i#tH~*0QG5uZSN7j%0Wcgn#wh?e5jh=BP zN2?&TWV>R$)}@)$LBNX)z8bflQ(QD#e$3iEc*LtF!h#GT+mwp5o?|S{tL(;H-+4Cq z`UIJUMMdJG{Vz&g23@hb^6zr^rMnjx=SCx}!mNVl{Pj6nZ>{Qtac}Ud@|6l~Ig=AMb=H&3@!5?ukDNZc5Ec>= z7_{f_>J#c^b)3`nuY-ooS96Au8roauv3irzob0xgEi_+DNJNi6f;;69yVJgrzI>6U zMIz1o8b33n*$eD~w0kwx*FLEHTPjtwpLZ;WFH1F}I6Xg2GHp3kD{VTB|6h7Wah86r zUcvj~@bc%?A`O%l2<|>XWsqlFY}Stam_b@D}$q_3sauIPDlH9~gJqH=x0<-Y3+%#IyeRe{LY>F#AO72y>|MUo=2B zLZelAUk-`93!{ULfk6WIcruSlcT+ZFR?O%dq}ti<6Ay>q_O*AbV+UJW8ep{@mAz%I zB`QVN3uN=P^Zw<==a%N$=ArVF3S`;)c*inA#i#0Tb^VQQt(;g=*G`YuAY-(6Ds3J| z5oX?9gKSS6G;%iyEQ?w}vyk$NFVu&0*9|(&JZvsG!rd?)RbFYQsJ>7A;{vb&cLRR; zTlt;!QTBe}`R(|5w>2jldvA8;m~M0nP0|U{7*kf3zk}R@rHHGEz8B;G#Bg@*i*4Jk zUs(D=#SuZXmnL?HOZy85E1mHjr&{keE!F4LrdJay{VD+Ll(cN=^Ae2`u@du=%o4v+ zr?Lm-+?AbGBQ<*Ui;Y_?;T`C%u%69> z@A1>}gZpNknm^g=dBp>NY{O;AvD7ZodfPn4WZobGHLQcwv{Q{$OqNYTNWzl9wIW#l z4DMrxecN{HznR+<_j$tPoskp$XYtk8fL8m)TeWMIjb*dNK84cxPPu*Am08=FzcT-2 z3TJg>jc0r1YUPI)ZWnKtovpH|OKMVTSM9pjiy6jDo}Zsw{IGn7m3Z)jr%Q-W++506 z-bRhCV{c$;)@0r7;OFXjywvkQ?2xsJ5`A*<1Kkn7?OWCcQHFVt2t9Qb0qTUi?J9434*A# z;9quH&txZYy_E@Hd^N8!#TZ%aS0QBJF19^r>aR<_?5UI z;PyFe z#|Yn`gFIGW9 zc0BDK>$@}JH+6TRjf!4rWL-GW;#m>f=r$>nEEk_8f5isbYZZit?^Cq_4PGwRj>-fvQH&e#nx=t zr*C0&;Y49w(LwR|(!b?`RZ}%Q4ROsU+wXJ^6K)PTjJi!-pKqtwFniY?Y)7)m5YGg& zK%Gz`a$Mn?8bap;TH83+yv{n<{;89etIx50cZf%+N54msNAdCd?liYUmu{zUhb~(o zYds4aQyU{wjJCdjPP4{!RVk&ra?g+nk^vANP>fJHfXpd$Ah&I@?y+=<`h!TEahMnw ze%Jq;(ADYPfoctFny$~R?Wwk_5~@U2#FUGdbCv6r|0@rxxLY|?m00tvZld9N^Xs-L z?EUWO-fx3EW7$&=<{wk)7|^v(Teb&$+;jZpzy}ahsb*QIvaH6qjv3n0Xw+29a>Clk zPSqjLvBT-MbDuN8`HpkH6VWl>!PfqpZM$`wUz?#jf zkxHS;?-el>DHV#90##1c!!_7C-o_uzPugm*`rVYC-huTIo5||gGbBwKVp(+~WGClP zj3-fm4)lR!!zX3virs2gwdeJZ4Ejw>EiA2jZ8z-yIQBbza;7_vIA3(ma{A*K;Xtvo zusv@bZE0mbV{*x86my`@(CO3sp{Af5DF0qMAD$u+A+|4kgTIek^2lxX=H~a62Kpx1 zaz1y;VGK9~=?lP5<1*UoTHsBU^&e_`tB+M7EA1;9%3qY{m8({;DrBo3R$H^P{QotI zwhXlOVS(L`dh7aC1T{c6eaV43R zwqM6J$Il@uE^#PTC+DE@Kr==UV4!buVD4pYW>?|R=@jcy@A}hC<(Stoy<<&oB5p|6 z73UXDOAZKofNh19gT-6Zdq!565j|(^Aa!MBoSZB23oH+uDe{E>G`GqjYrAp%^HL)9 zCh^%!<2Y>iSDzOijq_;BZ8~0$skv6kSH553Rm@+6Dl93;DA*~eDC{e8Dgl=nR1{S` zto_{}*wWHo#U|gp8t@$rn))#hT+CpGtQ+iT9O>~I2-%8R!nCA06bsapbpp_)#^vUn z)@STvonWq7$7DYm5u*+kocn5pCZfkwZ|IA((pElq?z0+CO z5K^Toe2@{B3X-@A@)nW=lyDgCWo?SByrzLk%`>0J{|-@mZ*?EXCbsT2*4M36M^!qO z-zgO?*(@?EA{I^;niNrr7{z9#Gi5CmyH&BZS`8}AciMz;#BPDUhePh;K{K7iI9kNY zeOAl93ilU*Em03>67qq9lUkED9hGi$Xf|VY%+A`ez&YDh<(Q6ph5LkiiaWyHqIrsz7d?Y?5insl8eKx{_J`w=B7oQS!1Rp`^aVztp2FwcMlfWOZrn z<%ZbiskRTe*Z9FczhT7*)!ATD2Q6qtfQ8%p!FiqUxCmUlRnkYMOmR%DM%xqh!tjPE zhozp)uART5i!HCTo?5t?dX`!;I8XmPz zt5vI{D{oYwD_kl{EACZ3t)f=Hsl8GEtC6=Qv+WV~SJw{VRe#{{mGPQsn+3te1BSxd z&8><3vs~Q##Uf|KS0&HMF@YLav1KQ!OeVJXR zZHx`b`n4s|9BF1~f;6IFUZX_x0<>c_LR8^OMRG7{Be?;)F7#_soP zI*a^p{@AqB_|sw0fw3M&w|(b$M`>Gci+XcQ7v&{y?xv{N)Z zRr}dFrc1~RlE)!RpjDv?zWdy+N3wf|Eauwg5|Hjh`LlqWt(r_4yD%I(kl!mx_|kO> z=h$(+4cl_L`FPW{MrK1!Lqh|iajK;<&D}F;BIS!6} z#@6Ke&@!3MzvxW-GYg+89lJSve&AIv34gWA0%zBe*tXu1+WfMqq*1o9y&ed`X=h^7yXpyA{VPL4<5#B<3ml6ers3N4t&079PBfpFu!EQ=^oJB(W>cX= zMPDOW+fI*wLKr}d@W$q*m(4Di>svHgNLuPzidz<2$XPg>JDBmArW*4aDHeu zG;0p4H7JKGw9D*D3B&fm!@!?{;Q)Cq#zE^&&Sv^*IdhCENOqh5GQB%~dE|)Q@%#8Y zoj*G^S`(U&H-^_Y*FLEETn(t6uac;)u5PO_t%Ej1HGx{iI+8l=2+sX)hs7s4XZ{ht zQU5Mwua|At9u#uD;X5U~4vLV-hqp-=%imDuR6nEjO7|{G%iy2UjLDGMe-@jT^4457 zA8jUW#%x~N>{?4(b690tz|4(JMU1-){LnA;?rJ-0FjdYerpwkMs$jpwFN(?vwF1Jp z)(;-Ug_gKpAUeuW!Q``9gT;F*VH>n9z%J45pWS^sDZ4n^WSf`P?p8z#7xUAm7~^$= ztLVpiuG$Ogjw+D~ZZb#kj}pRSSA^U6klfb~hj!dH2UemOu*I>3vYDKT#*v+YfZoOK z6x_%5>J~&(M}286x%zSyn|D+Jt>CC|s@Sd&t9n&^ySBgnLsL;J8Y|l!(n}dk9s4`o zwjf9iUTR&}+IfCB&MhHe2viZL!mc43oHGOFwVYzH&V54U{ zWov17!VYeiYP(=Vwa&6qw!CScV5)5V(_jk)&}-CkP)}2yli!u5!rLTXi8-@R*ot`0 zaER~MZrxf}SstgoCp*srr{~59L$iGd!ply>4#n2MriJ>J+U@FxRdJQw6)!4sE7U5v zs~oE-HLSYRjS4L`?Zvpe_|JX&LvP1jXH<#ORM--D9lXuS=06kyt_VRuDG+|RhxBFn zP-Pu;yq2DxH`>q;Z!BuYVUcV(Y*l4#V{_H!G+Q4ht?yW!vs7V|Dv+ju#!-f97@WSR z?pv*Q>Zes$3K6m?Y>lLe-xAdongYagK@JPp-CkSy%y3@hA>wDMCYssZ4(|owSvZxB z&#kAMFE+N+zo`3Ndr(tXGg9MRD_W;k|EA$YlYdJ^+huHcR~kX7e|>15&A@syFG9(q z2dzkLQg+G?Z*!~jw+P#ceUxZ|mq_1`KT`5jyP}ix4nP1A9)UxiBM!g; za7TVqd)0#JNxeY&G&eA1I9@e;g{_l&cyi}^Y*Kqpt3u066S2{(ak!zSfw%E*GCz$M+U`#blDJGXq>W$}(h76MpEHEXgO+5}>s#dy& zp4v<0B86Pp|B&YJ5s3hB15jG%JYNR)+>!7;YTIoiVC5X+-r`pxZdP*Y)tLUU@PK^p zZ9JrF8>`guuPvtaT?=4ponGOh(L*=U~3RR2Nh<}HyJHoJ#9cd*{Cp8yP~{k1!}CUg#!!|i8jn1=zNMfIsV z@3i*SZa1HGZOvv0LE|Gs=B=hbjZ2RV4`6%u z@z=W0ILnToZBDJ$EpOOwT7jBfn}?gzT3TA6?O7c+adBNGcxZ2O|H&cyQQwK=Y2o<- z(i7@4X3^^I=E>dmLp$ykJ}2Qiki5i2_;cxp@;1tiYP?#zI{)-JF+jt1BYl%orfOzo zW}M~{<_xpfW-F$uraC6;M)8I;j4+z0_gP0%>#2IG%6G-4As;D?cbiLR-jSr+?IQn>k^S+*I{?2PGMlW=1}qk9HZ=tcc3 zT{rC!4Oum`vaG_AOfo`2@-?Ivv@6UdK;x<4xVSIAU9j%5yh!^@_L)ad8;pkyxAjN& zcy&Kvzj3wFs@#&_^s2F|A+W)&;cf+iHx}m67m}`at#-1i#ra-g* z%&N=^&CZ#TP4!K!P4tYH49^-gp^x+#x~bZpn)7NHb~@Zc4k_IVH-yH4-vMt5Y65CG zbq=0w&#qf97tu_~Yjb04CQj%uctEr_6wlwqjq~hSZ<}cawZ3d|Z}D#V)}qw9*1F5? zGZy<_XJq#cLUAu_;L{LhlIhb{nJyn-U5EkM zzltc;TN;v1AoZ@bM1lD*3P!Gl%9He-iu{~KohElGpA z&RALz-Spe3IMC%P0APgDMY$jbl14~QxmSvvD$VK_wc2$Ede2cTw79{NL84)g;e=tS z;W5K}gINp_U5C1(&!HElQ>8`Km{O}&d9QRrVL>)fI$w$ejfqVaq|cAeC4Rx z$8C>pP*%j4Uet1u-TcAy$^?+joZ=kp@0;$CA$;z3?=ogHe!8%?u%XzmSRf9I!*_zZ z-{5t61p1%@{zG*m-s5UhhO;pXqvU9s<`Q@f#xmW#eptY@0+1K76g3g&g#D2^l19q2 z6kn+fs|{$p(&ErT>7w;^^q%W8_0>=oC{5J1eu}=X{!cxUu7EB`XG^O{Q$ypfT8>Jw zQi1|lE&#lr(oY(T%?8n%MNXNI{~SRL9rgqI zEP4v@A>GbhF`W~*H@Js59L}|qzYExX3|~wz>s{>|9v}}Xj6NDyoMO%F%`1}cQTdsL zE3q3P+b8$kIIMUy`45CjMeW4%p$zykvQ0Krp%JZNw%Xxav!yYEatf zOXwuDA6f{VgzC}X)T8PC(m`rRYd%!Jpen8WSz%0;j_iiVLN~zXq9=r`_{6zK4*%@l zV1=#SS}LZ&DOC&4X5UQpj~^S|92y*$?33($NzlQIbgQ$uO2AGsj=S?rC!@2mtGSzu z*Y7Fp4PbL@%!hA{Qpdkf-JkusFhf2=<6I)FHf&bxG#?CdPVr6%bc%cvJ0>w8i9!a* z9#arheyKX9&eZJJ{!f=j{{-q9IvAs9P+-7msA$N`R*N*7XcLXrMV0Dtv-b?s8u!## z%KD1ta&YMuxFhrjxD|*OtOg`=#j4xJq^=rit# z!Be}EJ740Ou^8-1$4Z9=HWllQv+F$F^`~2gFx*4v;~Km)EITGVX+86A-hm9EvGZ+f zeyp#%BZmlX557x6*F}BAC19yif--1%loCtjnL1IES7%SRRNo5y3X^K^z);rcp;3m> zOCwXGbi)AyDy9YPjjGXG)1hePX`EIYS5{H9k&~6~hFd{n!Owt~1x*2)oRtR;cOo{! zR}-1dR8?~2{KXlUNr$nk!;J$DeFub{%vuI(1LxUzmH>02InLfuTguObEH*_$N!DONY_4RcRwNf+?YG;(g z6bxj05N!SjBpT!>EW+QxX118`iEizz@ht1n?^4zmUeBJKvK&7-@_7)@U(oXfU(qGg zS%LlDQQxl6-qY65w$>Ka4(izIkj1_1)a#ZY*!4E`Ck@4o7EEZ)jLlb&%V<4IqU+vU zDSOl-1s-?)U}0B~7$gG*Lb%Cz%WEnPtDI8LVryhbH&fpkU5FVsXg0iHL@;6)4I14u zT4z^{F;K>|qcHjpbU$hPXs)V7sjweKl=G4vf~!I8!InT7K{{^%XVQVsj>D$Q>Lq3= z6-@p)?>r+jDLG~{oIIe*?zRBlyK4gX7n{|w)&8X2xBW&tp*^a@4C{>h(P`LyfEViZ z?I#cBjbx1vOj*qJ5#O^3NYN|LHp;i@Y}%Ct6RN{&&yEzL9~* zVcju}$BADDpt2Kpw61TBS%WUE{pg zp7t5tFM99wgHYS3F!UStcM&ateu|pV=V8-`Qgzg|Z)@ICS63}n5>QZ+6-2g6dP;PN zsR8c@wgMpBXOEiqbhe8&j;(Sn_0j4n%|z;)-ptoYmGPmGqM^Eh)jt2;RYEPkqY-u04VFfv5S5+eg2kVU zW(jriEpa0`y!TVKk2Y?x`&~ebq4*I)=blf`O@xdIj4TY2`X&0#_fYU}x`VnrIyO+u>Ajo z!$APZBiNi2Qbt1_s)SbwQE%2<(q7fAW{)T7m?ndCLl>h;BdXDiQHl}DDAw?%fi-3v zC8aN@TdyUjVWx^uYLHWwJ`aB(@m(xg zRX%=V6ga##z}0Ww`;j1pZ|r*0`2tsf6~?A_Jm^SfkAivFBAj4XdiM(gw%26GF;;%~Eo(81W)eijWe2 z0MBoZmHp#vR*S{jz)}L;Y!OC+%xlb?o9r12903hc`boWF==Kes>an8N-~(pNw?m3CcUk0(u2cXz7z;66BmySux)6xYGs9R_#TmI5txcW>Ip zbNxTx`>!r&SQOUIx%=5?pL3I){mDC1{`{JmHZ)^Xc4gl7qH$#ttB%!GHuf{UwYBE% zA~JHAY`to)cCK@j`ztRWzy5)JLNwvWB5PaNV}8fYPWaL?tJQQ0sGTBHNsS zUiqr!+yo)6Uu?H%G-_-3%aB)r2mLyGC%LzCIpCP1)+vTacH zot8Eyqj&bGybFcCrQa*=);wz{Zw>@@f8iam0n{@28ub)MKbME@&fY!zx&+EX&WG_4 zQ7wXE^s(#Wvl1-Ob@sN#+H`Kyw~bSqyWmfHw{mUyEIu->PmD*42NBvZ-(WQ0wa;MB zRM!?x>mA-HS!qjhDf*0;f)h+P4rywvzgM%n@@U!j;^@M!c{_5JWbMfK@W&->-*4Yv z87Vh^JWtjq%>oVgO`4q~Cc&iqV?Ma5*tDtX`I(0y8}NP+Rd%X!Qtdzbv4&-qbMz11 zjyh2RaxXQbed_#=`%5pzmkKNkP7E_eM7HpcDTUMz%K@#DTM@0*t#evUZuPOH zH6bg0QCxXUWOQg$Mfi@;svwU5e_szT*6pkFX2&?qAH_nclst>Z!8Pd+?sx6a%PD7mBqg^?Zc5T8bx2N6zVqWtO8Z}i z-<4^~j3rq?xenl{u9S7Ial?AW+;NI&Zy-zFZ3KNA-mws#`)uxoy8&f}~T85jQ~ zr3U@J2>yHIk3Gp`@|UFaq*lqr$r(RXKd=1SpZe&JbLPkFr+L+d|CHud9Isj1Ft>S% zd9-~9*9wsk?MGcaJ;;SzfQB55%;JeHp8T zM6}kB=k+7DbL@tgW6^V3h>@dUW*8D;3LN8q*5`@mZMQYf(T-o#Jru7bUc@$}nj1`K zSY{X<0C!4FRwYv22a@n2^S|V*%^IFD^3RUchF@C%_tqZ`$ybxlCD$kK{4qOaBXszs zsiXhQ&A6H6pPQclx+uAnsTf;RSU6V zem;Q{gI9*m3=fWc7Zn&iB4!+9xuwN*iC-1JEq+G4EPip^_1F{8<3B_pkwkcM$cUil z{w5#F%i@;gyw1@bayd29Wkd$jnm<81T8|q$HwpDcH6@i)`4C8J?2|9#WM=)&u>a|n z_Tu-rUvWRXrX2j?^`k7=o;>7-{m0Lg+Mh#yE7F)hZkb!N0`M=UDD+cB}V%>j3kg__%}# z36m3I6O!ZO$-N;3DQ&q-VO`_@mtl#Jvo$Yy>0{q*|CmiDn8$hV z-F}1MWDXA78j%>)J31pKAg*n^OTshogri%IZRykUZUO>hg&2D*MrhF`s$WD@SaI;O zzzV+vpE;h(-KIOoJLalqE6OFkiQBN#oKB}&dKkQz%^a4~Hh*Bzfl{I3-UOua+&6_W0`Xu zWKy2>Y486sP!bXy77$S#xx7VcbW=<=O!G`!LVT-uGX79pMXYnIHs(W%R#Ar|zJz@X zxfnDypviY4Y#?%6E1Z65PpbPX^pYh6i>%}s$QF{B&NOvx5I{}dmSq(?7Ou*ZX3R$f^$yGU11mRpsr&03Vf{`r*lHI@Cn*()9r z=s(YQzIPAEx;y5gcABBRqW-4HmS&JYuvg+`?f|{Py27-odAI&{gw)dIkXlOp2~JxF>4wJN+SHk;s;4 z)|MLaU&QhVdBocAtT6Ae_|Sk5ThRT$9s#fYl)mk}JA3-N=eW#uD%B=vW-E8d_D~z~ znMgO@m*F6T>Q{5RzN*flW=dsp*{BkyBDBCKZ&41Kot*h21J78Ju1?SYlkvy+r+507 z^c5K+GpA==%68BFl6Sq}Ws$99Nx5@Xbxlrvb7PosH6*yT=B|iJd^Yu1rdP@w2wjHr zVz+V+cW-ZBgWtgbF0fnhxR8FKu3^u@+J+wj{CVMj!cT;^3jY`u6Sg39XULl1enAZZ zv;80Y{_%e4xzL?+ndEdr`$+wt;+S+c*%~9nZ1%1Fxh2Es)I399UAL{~uPVn1yi8rv zzGzc{K5tcSbPknGWhG?p%#de1O+S%-C*6|1Hlt%^`>c7{ML9?FwinzeVoP?EcdiPk zb#I7knq|CgX|Q+Tc8DpMjA|lMB%d|mkTaG&tIVSZstLhpqn2d4yG z3>*?r;n&M|qxS~S;qIc#7N=@$xMrkszHANTS8YR%@wb?Co3mw>F~4b{-mSj8=4;i5 zirg}^v}f^|LdSwDc|&spa-6eUWG%?d%~+k$JEL#L-VE2wqRh&yh@6MHoAduI%qkvK zMpo8W+v`FbR~t&reeJK<5OFh>3R#4KN^gx#d&Mc#b+!9h&;8zi`{wv11WXT{5i}rJ z9&$ex@To% z9?RU7c?T+eFl$ow)SOGX&iS7T9u{Sk_?Dlj>{27Cuh;9FIg_(3hUv>sLZ;v&sE#tJ z@}qj3Hc!{VWvSa9kF{RyeUg2n{bxa9-H0Hk;2XidAxlCo0sadi%R^d(ybq2D-W2pE z@N>Wk|Mq@QeF$$?Pt5&^OE0H~T3+2oIYzde+K!(x!d`utFx^A%9rjLeo}eJxIVR+sP0xHh>z^Bm)y>l5WS&VO3K zfI#P9+oNJyqAc=6IF0VorHe>F$zV#qLGQLjQu1`FHce z^U`up<{r&`nXAitkasZuRsmUbzIbKn?()x-aW!x1X6U1uIb){fk^L~cQW%5=5k~5{ zY^D;^tkS0Iq%Jx)qx&gOU+;N7hkSSXjqqpuHwWYgxCh1th6geM4+BO76#KXFU*UJt z_nXfH?~PvZo?qQNy6toM3r&XV>Y%CvEmRGX2xLZ+7Vb6li`IUJ~@?!FQ^V;X_%2Vg30Iy1~ z!``7j|M>*?9`IaJoJlrJtTDk&rj`xd;- zAC(`K-zI;3J_m`Bj|-cM#+O)2-#oCc<=KW<}3HR?5Fde;eXEmwf}YhiT+J~ z(b#s>L@*U2rhbgVH(~_2CCbkUm6*3^jZLY1KrIo3LA-buH zenS1fwdK{ltCB0`l}DCIO4TJ{#q)|X3P%+x3Tq13f)0gu3kMg46}K)~SejNgs)DG> ztNvd5r9KxD=VFbs%r~r@eH{Cik3^1R5^|>G9WcD5x}!s!Bkpw9xtr@fH{7GE=Qyv) z-raqqzW06GL6xihH2xm`a{ups6a7+ry?wj-bn@1DeexLK{>jzFrJvJm$Jq{p)gj6< z*)d5+NXXlPv=sF0OZv2Jw`Hg4xZ%I1e7#G<=(>9~KGo+dTUAt*-6=g#vbXqlQFY<) z!m5JH1;+|r7kC!_SGb{QXYn`4zsxJYQ+c;KrIu*;r}1%fnCV}OgZ(h0;5Uhl=m_E_ z)g*OOM5=r>W``?|ZJcg86OfuV(|wu80?$!i{@&@{t9<0X+k7j0Bm74C&Gh@nPvv*U zm-dPCY3)sV-SF^p-{AVdIaT*Z`%!aIwNQ~DYo@Ld6ESBbo4?9#p=a7gTZWiM7-lqW z(%+~rtPQAHU!|{DR_<7qT5`MiVNqUTLg9yk9R-^U-WRkhG!zyVAtj?q%gT0E^s9=i zX;s&|VN&Cv=8s0v+|IV1e#u(+Fl02goj6V1klvObR!&t1IDFL(*QGhNcRB2u=_c{; z_Vo6Wc&B-<_EGt6@cr#;_m%oJ`9AX<>-*iu*{8F2XD_YiWA_ej7hGzbbh-eohelMU z%8vlM&GUhQ;qp%n>BzQ%^u+k#9(YDahb}H zn&gbKOnuv7sAImar}F`q&#u{SIqq*g_Ivh&^u&$ccJHx1mmra{$mf^OHJ_nAzq|vz zM|(~7jPuBH8|r$;xkP8uR%u?UHYg%xf2gH|8}=3w;d--yw5Ki5($}=nklNI;@xO+4 z^<}kZYZg|IsTx(exZ+BAO@^?FyaBqC$IQK6Z+DPW_Rl%3mpWtGhWAXvgV3Iw@Sbx{h)i=l+jJ zpl7}3DX$3co8FkuUp~WpI{HX`o_NQ2FY?;&xzA&UyTOPM}M$2TVl*xjn&QLAZu@JLs)%P?Teag)t9Q?Rn}I-R~#zWmftN~ zS~jX|dfCY`3nXc}SL9bDSEg23tGm=*uZwL+g>1k%hGC|`mf5yM`aWC62O=Y|J;YKpa=U z=eRYxmblz?9`9suoUVPPv8z0kvGNG154>2$j24T3`0s2cU2pTV&NKfs_A`_<9c&z` zk7#hMcd84m?N+l0(iVlv$&eDbtRk|4DQ_spD%w=+ub?U~SI(;HTRplav9_dcR0FMl z({##k*mTYE!-g@fxRt^~qztnYBGoK?FJGv{)hje#9cZmmhdb3cJ#b#?66Tuby1)&0 z-|LP->f#3v+QY%q(bMd4(<9nrpZg!T3fEMZL(Wl7mmFz_HkwhY`HDrdg_4=%RD3Er zUtG^$V+-kM`vI$?<*I3n(ZgVDDsD{G7c?}~TY%maf=51`{T4o z*Qo97kf?sF{4Fn)Hc|-bh_^&%i#K?Noy(Z)yKL>PX7dNr3FA`3nC2c$?Hi-@aSa{n z``0a~JyTOu9aH^pmAdM3<)BKBO0v?ua!loi$}v^J)jp8jmsn@3KcOGkF#XgzMY>)gjcR^x7$Mb53A@*L-DOEqoOiOLu92C0K28WILqL&9JK--CO=w51Dd z`>kUwtP)3W<%No=6~ii4K+Stq3YB$L zWKGxF+jYGf(8i*sKZXjE%-YI6lex;J2-S!QYbHKZ+oi$s+X{thkb0RW(P5Kzq2oYZ zsFT&{Eo4h3xTd=ALQj} zXK%7Tv1~VwG9?(b22)d7<4gUShHdo=>t@!@uGvt1 zwW_*uKxHPRiLR(PR8e0sr_!eiuXd>!QhTE=u;HVAQ&V3YN517)<>~h`COH*F40stlxfQxGjvH#kDL#?jCIwz-EoU>Pjr6+X{ayU*SWWF zf8eHd>*YEPsy!HV`-!%L!vnQcHAJyT_F7U!x)B4g!$^hDm;b_!WbF1kwguMq7M;1- zm}B_Re7)&J<1YQ?hV}KE>-N{)0iFa_@2PUEdR=+6@I!gZX>Jm)D+vAP27Y=>fXchxyXl`KL!o4QAE z*dX+|7$rRCMzJa;-G0@!)wo53ZY6d#LM)OrQM42S-D*I33OC2Bxd>g7mZV3Z;jC;rIqsQ9Y*?g=Li`7(NOfkG@ zzR`3PDxL_biudaBYolrp)P&UJRll!Js%Am^vTIh=wykro_h@LPU)1=csh#1Yai-bb znr=HrPh-RQGGQN*fPKL`k+&#J+C#QLzDIFVc~Z4Uy-G95p`BLgm{hMz&8vQrid&--G%gZ-lvg zAXmw}qz~Fx*``B^Y7cWOQxK@3vYBkc8eKtCX4F5d^RBy9I|fn=!)yE3?yA+-&aIQy zzo|diuwI|oc)zKxxs&mhDaP`~+S^`AuVHb1n?Q^6(JU;OSVg|0?2=$vKlx0>TICj1 zqI#2Np~E0;sAGfUMO_!CUrs%ok2_~O+nx2!ADmY>dpe(XqIGe)5zuYMI<(Yqswc|n z3aR|Ew1Xs*oI}X)o9Hk^B7WufLOx_X<49X=CDs(nEAvg$dE+U=ndV!N3R6x^85BYW=hZ2mK%Y%f@F-znT$aKhtw_xb?EFCH;=+&HaKj z%QU1rb{&_J6R5M2e5q0%qv)+1t{S8M2U0hkwWZpVj$L$rbc3AkIyF1_ILABtJJ&f~ za_Zrftc%gDbiAki>5#8UQQuQ-Q1(!8vfI+35-WL{=!09(2gow9o8ZplTpd$J=h#zi zN!Hhvd*%zKgU0=a#O9+-cN^37YW=u|r20Yi&2{$x_0GBrb%k~D^|$J~G&DB6(cb~w zsm%)Gc++chnDvy+oj%F9amRRPaX(^0$KcNhjOr*^A-yE~D9=+=DH~Pg>ff3N4jZ*? z919)i=_+;IoYpvA(A?Xw()iM(u#C5Uvc=IC7$vujXN9TAPc#}&B$7x{ z(nUH=wn=_WaZPzkbxyrYGs_`PTcO?RDA6s}z0uX_NI*>M(sailq0{cT6L62yK5%Hz zIA~ndGF6S@nS8A*PFhawCgX`*Y$F+J{={5~A>?7|J0!?zfGM4oeN}zb?KNHwW{2C_5so#EV|5R87M-h8C?v<~ zb=P&hbQzAl9WQEg9Y}{zO{CgKB`9*_H)IQ?2@(_efLM;lVS41gxK!xC%eZXjHsGFV z8))rhX>0Ck8g5)^xY}IR)S>B0V^HI3{UUw5-bGL7mHJ?PKYgM;U;kI*{l@l9IZgYT z#~9igTbeqVhgvpUU)k*TF3di*ii;O^hy_R+Y&%{+w51M7N~Lk~)rtqoOjVh>K=aID zp;qd+&9T7IUDsOIQ5UI`0NzB$Ajc=#PTD69t`3tmSJZhbyHc*C6n0sqG)Z!qT1);z z_~J(NEpk+xE%e|6I2miEYwT6FMk{6wvGh0ZFeMp1jLQtg&7+#jnl?2BHI+18Xk6Ji zwy|GhpT-G|TN__BVog(;a+_u}I~Y<8PmT9XU(KAQtL>DXU{9 zBV->hlAV^nP`p##P_0+D)ud^LJG^j^X}fBtYnNyjYDa0?Y1P^khqVq~4sSJmHDA4#2j{U$TWCv=BWUKV7?7aMdVumtA^+Pp6{aqcRnWs6c`L4;< z6lnfvk~GgW`!y3Z!J0DlQFTl8dsSypKwsrz#S6Jv<|pee9VMAU%^=4RgYcG^7m6cA z!dLz>m&h(>rqbgf9eKKSmF2uS!{lRHZLBuTGmwUR&C{A&Gz(4TO&Lw8O@&QtQ(*Iy z=7-HLh64sq<16C|(_dy6i`=TPIoiYM{!s5LTpsTxjzA7W#T|$~2UeqjG;) z8)-L5J1UBFCQR5*^a`?C93^z*gCH$AlIc#*v7fb7TRU3MTQrt^W}W%Esl6%PxYX!q zd}N0tsc#gluKBC`{RIxy)<5Av&>&h--&ePd;oqd$; zf>m$nYB^=*Ow&zy#!<$6!+b#fuz4=vl{bTRZ1QX#(tNI&H0(D-8q1(t9yIT=?6aP= zeYIQZV0Jopmp2Kmkag%A%!d1ueW-DgY100(1UWB%q!_8xE2pcHRRQYx>MQEs>UuS! zMl@!1w)(bui8@?epjxj|sE#U~l!*$XyubXMtV-%F9VA&mZ6kLR+wdjWP&5H?5S#dH zE{RQIvS_P4$UejN$f^ad)R?E5YfURmQqxsqZ)2n3ieaK5%zzlGn~Rz&nkhqj!wN&1 zp^NdGag0d@AEkZAa>9Da_R-!*w_w+BseFjI4Ec_#@Xo|caxJwEaJQ40Was3Oiu(#* zK1BI^;R`SWmT?L)++u|td?Juy_9~DyrUkF zCx~_UM63fEh^RzNz<3Q8&yHiR&<6W3`+Hk^+e>R-YoTSW#m(~EJkHFTPMg}8vWzQ? zLB>qO5yMnNf5QO7EW;T?vtfp@(Rjo(%p7a+w0hav*(cKnnIu-u|1E45A0bt!fT;*4 z5~pgYN0PXb(m zlwz9vzN}8_ERC0Rr@E7!;Dt8+m>i`LN^}wu_(|MF*2oNCp3`CU8M}x5j4jOe*xJpS zZJBKm%ty`9=AWk7CY|Y{ahW`kYPxP-Vi|1hZ<}OaLtlZM zXeYjputvOuq@ZP39bQGGlh>%Z5`XD?>EE&svIzM$dA8h7Fzeo@va z6)H!Si%PC)R(?`$QU)qtDcUJ6$W5{qvN6&HlJ(R|ayBs#Z;kn(N<=QY1Mb<}Emq1d zVD$82T0!5o54Ll*TeiVAi*>Kn+j`9sYPo3kHlHztnBEx28@-HXL#4rL2!tz8VVrC7 zGMAdaTHaZ6Z3rF4jAu`CKY`t9#2wXPP1rMh1>sKKA=^-|s5r@aiCVf&S|=SYOObV! zKa~3`4k%2D0m{?LT4jLhZ`C;9&KOm!s#>{4NhoJ49?2_Yf)tmER0Ekoe8L}Kx6r4^ z4^a?035R(bHacX54GMY%DTH1M{QJS>|JwS=J%8zV;q;SEeu9pXw2cy(9*_3G-Zze3yEo-g4Y{7PfE(7;{ zfnCdWBzL5RHmm+osZ|e^@yhcGtGuIph3usCxg?z`A!$NIMB~G;BWNDd5;-ms;yQ>u-@wcG zL!3Kzl?`W~F>RQqbToazuCy<+m0Jf}zgT)%(#`YD0p>E(8`FQL2d1AU+SJ8-&}=g= zx7aL+)(BgwZHN6Y+DgA?HnROVH@<;?CM1d@5kIsRy@f5rBZz!rKiP?Dg3lM|Casn3 zlZDA&K(!w#bjoSU^UB}KN@cb32QYnBSB1)FD^Kbt#QK3gVQ<+jhZZT9}OFH_4rVmEO;d71E8SS!XOrN}|F16G3_z*`Z; z@QDNMsA`yi`b$~q1z89AcX@BnbA_^xa)ELyDE3g$zvqg9iX?fAe4{K)>IkSeP*2GQ zB9>T%|H9(2tEfNv5b253i-*LvVx_QKh!axyX}pD7&egHQ*$0e_8B1Tc3%2pLuhuTs z-k6=w_LXuMWmKWT3ZOxeanvbpSDE`cxOj|#m+ zD}4UI6x1IpfPDY)gb!IlUZN&ST%>QM6J=GhDS+HXF-Wmou~V^Mu~som;i1Tu@0JHa ztz%?YrB2d?lJAr|HJ5xtxB&7pYzUTvjzOD{Er=)bOdKLM2pa__;T#{#U*&wbBP`D> zU<&CW^l$qhdx33eU&TnpYQ;Xq z7R6*ml%hg@NFD~~(NnfVS|@2I*+pfNzT|Qu4R4KK#lo=%=m1oYoJ9H~B=TBZA;yS> z!gj%5c*J+$pK(##X_jCYGevZN`k6i2e$nP`J8KQMezeT8_*v@AKY=4@X1&?pGSl+i z5^KFU{S31_l~d`_*FL`i>1$I5bK zo#gxEzvMQ#TA@{tidy+I`3iZ6JWV!D)+n7O&5?AM+@u_-HDnVpov`4Wa6kMzwjS8h zfZjwWp>F6`WFewLE{H+m89^@0B-!pJ?K4l4E7YXb*)ulJq>5n4s1DQ z-fZ4sK5719Rsr&C%Q!0y^ZW$6FWo?YU=Ff#xz4<+P%C^Ck06uLD9j8UXgLu_R+9Uu zaLETr59v#3sBFC~NruZq<-O&D)a6hFY|iBJ+3i4|65>?lG3vmN4rzYXT_BEV~2!lAgslv!B`3Ts&XJUlgW_fk-)W z8J&Yg;HCH}q917@k5W;Rmy%A>r_vzVR#~>pQ$AF_TE1U?P`+6{4(eSdOO$!b&P!dS zJ0(_X8kI)&AU_b@i4=SiZo!UX?XVJbI~s{*AuA9U0I;842fdf#s~F+|t&1%Ia)80~-F(K9N>2kC~Zl z5SP!L_A6ip?E$1l$cBUQ(vgjl5)v-={KprY`W|Wc$R!wv8+_~Q}$T4 zOEyxblYN)YmCB^YCBc%1R9osD`8SzI%qLLd0^S|3!T!bm!Ya`{Xf*m0nSsz^qUazV z6`X~Cc^!X*lXC0WCT1M-1N#0IsQ5mc!gd~}3ccl?Wrt;+WwB+G<%Xrq5^ddVZLp5F z<=V#D8|;a61e3ySXFGEO_mST%3=`dv0^}k(9&^S&;|mETd6A5uZc%=cU4XryOLyK*($5x$qe3fINahzfm*PQVEK65f$WCjKEa$==ip z%0seP@?L^VyGoZy&wyLZk(NsfrD?$YlhQ@fR#IB>NHSZZkvygbQT5~|(t*50v?Si) z1MvcE3Ra8GL+g>bNR2o{EEc8-75p4t&n@8?c0Eh6yBIBVj*g(;+9%q1+kM*%TcFKg z{b79!oW5;+Z>_XC+4|ZJ+sbWiK*4c(72QNHXC&-dwjEc&?dCfOHNq)z0Ky}8fGa3| z9+0OJh{a3n4I!oFeTwt!`tYnBp z1XlH@YRRpn8%&seiDG;$?u6gL`oQU2gF2u$kxodOI8&sBJ%XEXiI3#(f*M|Cb!;MI zp{KwGae)1&Z8%KM2duq85gUQq%@!#zexo(h8gIL73$#D7_oi#;Gt5AiUL%76_iU^Rn~dk-eTnDbYxjV%45sc-gk(6>wM?Ruc9xC>#51Jhq&=iTQoH1< zWFP1tOqqMe>rU%F>s9L?D`o3rJ8d(8i+yAdqz};wWQ*iPywfDXZWC*G5IL4*PlmK;Mpp%ju4lGBo0iCh{D>=-T` zEgd24B@LH~l5dh7l9rM@YB{B*&XFz17epUGJry@%TQC>kNn7*-G8oB&YFmUY(C;tv z?fDJrX9)kbGHeiuhD!LB!guUAY#3~*a zW5plf5zYKoUc>*(Idg|t6}ttPvXE}HuLeE*U`qs#*xU9u=*w!`Ra=qG-@d^9%^pne zp^fxdCKI^*l5NG^<0AN*@N%!qf(QJsI^;0;l)W&!9l#v%{WwajCF((0o{_H9OzIgW zP#pl}8OaMtvLqGi{1`YgQsN=WpmtJ!ftp+-N0VAIh1g1TAe!(~csINhTZSRn9#o0$ zgI<3?bP`VqLBfAf@nmio%x^PU8?zSN;TgI$oon9@(`TR^w;OHsHiOM-)4>&(Xg?0; zF^FCP-lQXQoAG6jvp(Eu&VxV4dkRMcnYa;L%48%B>4e@x-LP#~Gq{y+csy~DP>?Ig zaKS)AKo z{?OiNZ%wbKztMrrMka^p#NK3`xpiDEH=O^-hYQC96wXbtI2cJr+M&fHF)i2=tO9U1a#Q(q=sjVL`iFjT2e?|q2^GbR6e;<7rpA(*E3j z7TB`We!zat{>=WzZU^r=ivAZk62WX^s+hs-Yc`ZS%CX!`{s$i-Y!ym`*5U!NQtXVJ zK^XX~wRE&MmW1`e)A7kf1F@3i$dyzD)fE^G?>PgOU{b3jM{-xPLeffN1_n)}6x1Vf z7}*G&-i5e^N8>NB9@uYmGHOK*A#unbag7)V)t)EFgo}Iv|CWP$Ozar8j@inD!xV9a zUPce2yVHNcS9f|4Jqfzwe)=|@LO0T0%phhb^PACvkG#*?*uLBu&cOBOFY%}_Q}``( z7N5YJd>@HL-=Y0s`k9X-#9l&2o*+qT9`%u;BprYk%Op#nv-gukN)X9U>L@jm@}>&N z^W-Q}2@}r@n2m4Zz43fFkuvN8+5s&>HX;#74mhi}VwG@6Xe(s%OMxe6VSf0;j$=jU zJ~M}jV<@HqSp0;(NuQ^W(MRFyIDM6VMrY9o6VEJX-ZDydF8dwa;6ARI8_j=!etAH! z36sRHVoT%_@MIJ4WD(YY%>Y+B3g(|Eavxbt22kUvZPZ2T5%qw&O6{i>QhlfZs+oKP z-Dx=KO_mVniP40P_=2y%gYa~0E7lq-Lr(y^1>_NULN)SA94#7!oq`TDJQVgSow-y% zqGmsWru@zLGd#=%`QV;X=)FFt!Cd2{iCKD}{fzlS}8k_$B;r zP?W>q3+IYepoQhgT(lWoj`7$U*kg?+-V+%UKGYDZAAI+v2&xpcJrUeg z6!@uk#1@zvMEn?6t+uXj0m9PI--cpDjqD3GU68MXLW7%kwiofrt)iR-YPaOHB@ z%j`0?6YI#e69BvsXpW{BADE2hG8dR%j1xPEJ;dffzuXA8Tk=PEk)JK( z2m{4$VmIUy@;CYu9S%KnICT3q#7Ux#h$N?x`^oF%EAj*RmV6G6PLP|)#pEQi7a0w` z#sbdwJh6aCAZYw8z7Fq-Q+Nt?2pf*MVY%pjV0j6$7I8(cit#Y_{4M10GlAjPx&9o< zy=FJE16fzL8Zhqz%-sO9g5hYImN9P3U(5{Ha{YjMcV#!Q?^%Q!#GQgu*@wT!I|*yR z5%z~u>4PL9jmU8H4QwTL0K@y>S8xm7ok%1;5KV+5xQ{N-Sw@oM$cf|xat1k{TtLnv z=aQ4jeo%9s_(AL-+7os7VZ0rlgKfq_u&?MWltj-XvB)=ZlvppU6Fh~Nuzl0;U%5Td zGlMxBo6g<=pJ8OL6VNz2E2bTr9ta zPvL!pl|rTvD;^aQWHyqE^n}h60`;P?arhhD8RoB-1WI-z*O9l#9I}~|f`?K8PxRz3 z@+R=RJ!vIw5@QIAxQ!2k`SKDdH;?{@&PILEe9*yO2rJ$Zr-&|MGVCL|2q?J1z5Gz# zk8k20aqGDr9K~g@XV_VQ(3NGGQsxhn%zOjJXD~Gk3&`Wykx=hjY!U0hjo~hWqIBU; z@do}M;h7L39u(!!lO^C$oWP@~V5?Ar_aOEYKM9ryAUi{?r$BZ8uf~(eq2ym=0Lc-V z#5H0W(FP{VxA5~FaS?kD*Qy_Q!24=Z<_>db5}d@#%t_`vbBB4!WHSbEuN~Nh>}fWOb>${gv_%Rl2a z!b0J@5GHOAbH&!kzlaf>_ybgfEy8|aLHHVQhAN^TxTTjw1 z1TS8~9RY=)*+=YJwmVeY2+ESod}Y2fSxh6NVOz7~*?sIQwuW`&I&m|&{oFIIoYU|< zfhiw&37qn0f+zgHc5yLMhs;JR(Q#M?)&qYGJFJDE76i<_i^xO3i-+WY1i1$D+C|hA+lkq+(fAWwLiC5;{fa0eM8bjeAl*r4QbF2@65=CqmRL%3 zBh*9@ehps?GrShB!#-o@;Y7{^ro>@ttPcHz{tMeeFW4;~fL*6ayebY8aq*!r7MOAe zIBo=2`WIIN^FV)A&gL+;Knd5uc4Y;#i@C(ShApfPuET10R@H0(H<`P_RdeC|GX5=W z!Y2#Q1y`sOxz;2 z5o2Kv#)%B5_eOjO9*WagCUyguG8}7xq1Z3<96AFHMk|mLNFT%~o)Wvlw6;}<1eUDf z-aQ*!CKP$-wZT$Pdty*Jumu0w%{7;$Lx3Vk&VNcH;yY4rg-!oXEa#CVfD)Q;1`r zBECc^ej8r|bAk#l!5)Km9{~youPy+`&;>FFR1vAfKsJ0*6m3_dk z;5))zKMT;$=32o%D3AS*-3w=MIMld3Y+3&As|!0Ay8I^g9Q%#s*jP})7o41*!hhzY zgyVun+y*MR98TqIn2!fwuP|?zZGYgd!~i&xS3$uuh(cgX4)F^fUjwC{3OgP-Ol2qW z$#@vvguQ{y!xY%{xWjHR3%Gq4)TAfsgjOQYkxj?|#0|Fjcg2;^?Iqx7_X$G;HE7Cq zzAbFVuY$VixSwnyAP!)0=$ysiN@^J%wB#>9eHiwF2&nf;n2A;VBv2D4VYN^QUFSJ$ z3HSa_OCF*KT;;P^B^HcNfqCsCUIsIpjtC&4i3pfw+`)r1!(Ej}_*vk_6uc)M30nsQ zuZD^GEp`n%h^>HsABQQheDpfH0F419ybIf(Af!Y*CJqv%;%i}r5Gs`MC-_mYcgx^T za#Oe#9KvO>580FK4p5fm>?(E}boJ}NpCZ=I`f|OvrQ9Vhn{(v*@(1}`V8{j`3#NvX zqD>qF=iUL>{Rp+7ZLuYA*C!S3S$TshkAqqF0Dc314ZS}bRJ|Opf;~$HOct;3yZBMS zKMU`N$KV>+4SvSpGd-{b%ntw0eCRys$TlP%c2=jwiK4GqEj$&r0Z$SHsZb2AZWmN9 znrFEbIG+nZ5q+Td*8|qyY%2Q$dTBme#adV`xZVL!?JHafII79~9bVuE3-`bcP67To zAah`kqD7~|&W%O8L;rXSxFhi4;5p6%<}5&K!fBj??%#}8Ld`$p&+v12B0d*Thv6KY z$!k#Uu9zH4LrTp;v;El>^r6m+}~ujO;O zbAY@P=fX8Zhj|XQJ_r0b3`%njSf9k!vpQ}dm&j#+p6r0TQ=^3>p`CbJbVW8Jl}Kmw zG+Kv7L)W>16~ewS6ne>c@YIP=)wB3j`~v)b9N&qr2dv`&ZF^8{Ph19=>p*{AW0$dw z*cdDtv!d_OjWDH==ttn+V8k0L{z^P7&V|n7E82t~!UbWD&_-bSm;5Ha3sn3Aw~gxw zEH4GN9D=hslKmUpR4@2GAFzL91-1wGFHFS!;5_@o=8F>+i`imN9VDz7>N&t1=K@(Ask_Thgcx)&U!gO~&S8 z%dyq4!Px{@cEMKrG;sb2IFKB87Cfc}r`;Ow0&`hE=sK-&Z&2@4IMEX^Z!8-8Hl~3l+^NXQxyYqG2Ywj2~A39|5khjA6!u^h^*gR}0 zAYYH|#*SgBU>=||hn}v16Fzh=xvq7MMMc}B`AVXmv zt47RX0WkcrcwXEgE(A~8Qq+mH!b@S7FdV!}J^zqj$9LxyuphqwEbqg4aX6=Ei`hc9 z685huE}okXDqqdD0ySymhl4u{68FKqz!At3m@OxOhbxCJ-xU;LGdPX2uzf!P-?zhQ zn}baQ<_?4Ve8b@T7|`k&a6RS$r>4R48w`j;FbS|D3B3iA-W;?y+--0|Iiwo-iTsD0 zLRKMTkambWViSMCK616#SM(A~K@%1WF@m1I4jxYjd#psLww5brKY-&t!5)Ea_kX|} zI~xN$c?o`M4%EAYa8qytFJ%x%A+JD3CZd@|x{0H<~j+P&4p(tE+7zZ#4kn1p4EDD~{5MaZ4 zz<3)}G6k5P2fxy=Pq5*-0M}?XJlhEP=?c)3qtG$ipcI+}?syd9k5q{d#8qNXP{Kmt z0rZUla8J_!4(Sj-6?TSNzL`sdnqKD)b30%swG@~>3)nFa9_{CDa=$o)Zw0RA8}9k7$NK^I4e%oG zuHJnR9<CTw?U9$JD^Z8Gyp7Rfg;!zi8Mt#cdbZq}ihS8h5)|C&GzNpZQT(;fH1p4~{=?X5P%=VYU}f z|8e^GAl*lT8*iL``SgoZfxa>f<~`vtCj{vqm|ksWzaY^6b4`kt%uJ^u#Zp`BilP z=FF2zDn@m5FIQ*aV0*}n&3&Hf$7d;YQ^3E`-C$gvQTQdu0_8A|WiSa(E zqvnscOz+^or!JX#cxw6Z=(X}#W!AFsk*B8~ik|PDx_xT?)U{KWC3621fB8`?@}KER zeJh`j%W=o2uXg;@ckATz&D>?%9p9%+y1pOVTm@^62fO-IIgnCwIPgy!&|3 z%vm#^jkZ^vxjtI{Kv>FJsoO4!m;Xn4X`hQ`0(lD!d};#c}uLcFrMaK8<^@6y2Ozo2n*@5Bx9tTamBHr`9sV}DTJUM=R_tav+#BJg! zFN+1<8&v#sqWH+f#NqLn=gwMr*1hrlA56VJ5xUmY1JV7bV#}3BH;jJ}5JmSKc4JE znZRx_UT3^q_FpZUd0^(&NO0QBiCM>oX8vww>v;KP(?1Bl9GEy=EYsy17F`^TU%cqL zFu_^V8>O%KspOtHGp~<#%}&Shx9R!3a`gStO{2M)sUMYGeML}wm3a0+(c*if%}=Ke z`+TN*M+C#)l05(7%vJXaW^Nbmw_^HJcSOfO4s!qF)FIgku}b=x^GD~7ex2UQ2ZDgR zj#kM`?b7jYg5e*^RPeCWnp=<8Ol^Nxx;Oum9JpU(J|p|ccAFk&()ab`n^&aD*?-Z? z7ri|`^Xqg?)=z#qDLs?JXHHGl`DErgyNr$=T|HVQZ0KY0+Owvvi#I=(m>dP2pNhBN zH?<%+{<3KPkBQfx<#AHb?!x%{Q&THO?rmd@?X%NoZu0AbMCl1rpNP(P$gKFzFo>^> z{&BSTXocj-_y^Rnr!)A77-(N&Aii|ps+ z>jSBQcT9!zAJbP&ubk=7cW3UL*>U{Q@fpFvJrnmQ1WE25EipAOjCr?s_x@p_`v=c_ zJvc1mRjGpBooM@N)zaX#wWw2!Z@#~_2v&IjOR~>C1wECB1h#y8nSEoW=DJ$3~ znDCxt!T$(SoSYmpKXciYqSr%$g`Z9~{aM)fZ)W{u)-hp=d(2vF)&;@O1E&^GXYGrr zaptDR`Q7*n*$uHzraLQ-Q!u0=Ts0G_J;P-GDgJU~x_keUJ$t*1=Y+HTB>mOr&#W+W z!}PC$*Y8d@>qX(^FBlN~qtoA*J~h?ZdNXfGEL=acZhZUulviFT`KZjI57O&B@+|O@kmi#v8Uve%~PYI6M7@`SFRL#|H0>cDI>YE_ioQYWHKq zb>1FUa^UFssVui1Z8BOv{B^Y;%F6MUIitnXO}T4)`S=%M(60|Oe0=6l>C+xOv+~S! z(eV3{JJ+8cg=O89j`1_;@$8g+EB`fpO_<V`Rq zsDmT%k-@xg2Z_I%&tHzskC=LE{PobRX5Xp3(#<&_uR1Kgb9kcgpJR~^OnoG={K=`0 z=ezez{X{E;U6{Q2{p`4UTkw13R6akO`L}duF{=~9 z3*R^Wcgc|Zr5m*G^r6#lNGC=)W*A0GrJ2lS6IqrYPw~gne`}I%pjqi+pHacl^ z^5~54e>gyW_`~ODX}&I)UX-l9{mhFJ0pFbYW4b(x2SE>xG4fpI(?b<=j;MuTO6M>C6q0e#e~Y%gLAbM&^T33H~(N zofVxP9IrSc-tm=4dtAKbxNxQ8;xj)OSk?)V@W=V?`}ylJ!OeHZU-nLae#J1U8%Aem z3iZ{nk~gGpyxwTZOp31w_c?uhTB`5U#-{`cPadB*K0YY^@mziHAmYQxp2uY(yMOkL z-5c)oi}=Q8gX15`=dY&MeE#(P@$8o*0{${HJ+n(Hk6(`O98u|gtuyZB5I^40PD{e#vUM)v90 z>FUwxk^bw6&UcMoJK8tXopnb`$6Kz8ZGRU0IwA?nVRa|Xd^s||F#9BC&n!so z_~)?kA4gi)cSZ1H+2qjI1uuUybH~go;}^x-PRi78t?-7UMn8#HJTh82+;iJt_s)@E z({!wtiT>_M&buge?O)>ge~H&$k=T7A6VCPXxmd@ON#a60v) z>>T_>cF6u+I&3RO=NBbUem%JN)_BOy@sE|p(=+#HhId|ShaYB&{PCH0%=~>2WzV4a z=JE9nW;UAHa%P9%^{dja_*}f`%%JutXu4lK?u$9wRbeGtCVD=UxIcOD>c_J~Y|&^Y zn!R^)>*%_~=cRdE7m1%5ts1m@Nj&4oc+by*=%*z<&rAhzV&wk!@Tk|MQdlv)wbMrb zo(b2!*}w5beEbhVkYl2$ca7hYneofUFGT5JScd3_M)Gh+UpzX93GL$ z>?>vtoY`q+o5;V>%qG$I&RNl$WYJ&kZb-gaI^BZ} z;^mu7ZJxMXJ07xPka@ZMc3wPT`*_VE@twotQSS@}zAI7tj#SgH3#-{Pb;laf_5I1c zzs}x@4+q0{i|pg&d#*IIMt<5ZdOtk*^~c!@Haijhk!WI3xXJs1f;SEPZ?AajVL{)6GEZ7B`*a?N z1^yHc@Xc`NFC^Z+lTOZQ@!$J{H5-TRzB-eqk4Mwk_xJMo=+t^|3c{~5^+Xu=@$vA3 zQ^!9VsgECjD%w6Yb>)`n53Ue-XTqazpSdnO8cxk@>G){-GczAa_wDb~33^HL{tMF~ ze?_$a{+VMU@!8>ybH^`;ul+pr@T#Nz($)A{`Z8zdj)Ch^r(BYl`c=62r}O()2W9pQ z)89KB<4y6_6XM~IRsT@C}0_$e$!by*G?z{lvxDS?Sw?tBa4W z3Pb)}eDcs>$M&hwHjUgHjyE2!9~@sZJ*zqC;?K-HooUBI@!;EMZVs=#GHW@1=7Kyf znYlD8n;-9ZI{3F9vj zMRa_{=%GQ!yT=}HjwgR4KK{vkeqX%g^|6u)eyOQ@6T`nu<@Ccz!{;E8m#;*v#94B(I3( z4~v(4Ahp@aS=nmAl%v9W?#tf67Y|YS`_VbckJsdRNzmh0;a6Xc^dAX({y_NuXQRR6 zQ@NZMo7|VZHA}^l*9!C6IvDiaM8dqOm9k^wfgFEYFz_q!y;sFn8wO3LQ%^mZ>pVDq zB;SoQA9ym~-!{G^IR5o?Bwm*NOS98)JALLm@$t8%3feo7xP5A&{WG0>Px8_4k}H=B za=t4%I6p_PoBa5Wwq zSM<1G$yuq+?jAoqULtI5-Si8#$#u5L<2j?v^V~Y%U+A6!J|2qD!#Qs~N(H8{y4vKHSK05nAeB~Rd zG=CZt{!J|Y>&S6@W)YuHt^DfouEChm__iSXZ^G2S6zo1K==kM)|HrV`QR3sJsTzJ5 zYb^|i-DP|Nb>K#Jl3> zFHg?gG9L2i=(0q?=Mo=#WWUA}$&BX&t9~8qJ2|?!GE8DRb>O^ktc~OM>xIwGP9Oiq zyz1v+8t;oN+l-gay(g#6{8y%%??@eSSTN2l7420!5<~APE3dCPtotWiLxt#GPmckAbDp&^3cuUFxUKzEnXLPupnIVp?Je#t$SjUz^(U+-Ucw=~y*R-ry|wbo}CA`R?I* zE5~bS`gb!YgaIBMU4K5g^m~yy?|L$`RQ7wmK3MXLtapic!@==`Pb3D9OI7@z!NkvJ zC)dA)-M%A8_K(^5_x_;Ev59~`MXH5Ej^88r@s{xH4+l{`nOy(&V9XBD`dwM?XM;)` zMdRnkmY<4OydjdkJXz+|$?@+Ft{fe?kB@)+U#2Ffgm0Z3IliCz;otJQJ%V(z#`lD^ zoSlipDdD-NgmYb;igG-&V%GJ-aLEq^e}0zgk_{gpFP?79s)_zB;@{Bv9myEqi=;Ot z=WiG;`-(8c4<^HWB0dfK-jyoiz{KVH+3j#o82gWdov%$iEIqn?d}e0wy!Dfj`?J~I z_pNa6pCu-LA1?Tp`1~b#Tod%YHTmO?@q%dYilFfcdF8vqw{}akjw1VIVSguuxBejd z{%-imFTzkRNk?;;;Qz}KHUFJ6JvyEnUwKQ=?zkZXT@$2xX0%*9dXvbu+thwRiUX3x zw@>b0EhznXeCFcB-zj+Z{y<^#wYKI zhNe=f!GH}@y={={ZJF5ShUor358gMPNxs~8 zv~$q>4bj^%k^SVv-aYY=m4egj4BTqDsc~ZOrbOx~iQFHCseB{Zr;WW6KLdxKRA6P1tT^Mlzpyf8UuQFZ|=o$ltc@yq3-?Q#Bob^QDX*&p!E zp_>KOpPsoV+5PfJer_IrN#4IIk+~?lHg<|HeI%ZDb~4xOME;(^-1kKeS^bRUjT>7E@w`meGrM_wA~^3;DyOXFAW;(GukOyUom)iWsvRIs?`L{*er)FaI zt02iAX3m+pBDrW3zuz^{{l3KIPh!oRa?a)AZM)=L?}+xk6+byMx%}SIqoZ*;5{pId zC-eO+VS#6*=KpCleRO7H{}SJLQCQjYa_nl+;B>rU!SJ{{nteQ4T`DNO<`C;!Yxvhz@fpl(E z8&-8xvf1y`#aI}*H;W$rA=*1G9&&k*c-GX)VI1p+gUp$FGTwYf^5tj3mR_FgZkniC zHIG%|q4SbMHXnReM%gewZIs6*Ip5~-;!Trd)=C~)Dk#1v(SLs;^Y+;H*6}To`R4fO z)v1KeiDiDBI6f{B_sMAe?LovB4t4X!k#_arv3Az6bEJM#Si*OPxEv*__YO<_X#DjT zLvFk_wb|Wy+!-cvP4dXek@>6n`#;7T4vglu801?k()Tep@~<4(7EAs9P`vfNJRgdb z&x{uvJb9I@ac-nvBd=N}ubPRb?n*|zG(P(0;P^?&nLi5d{4ieo{Yd|f$p5)?vfiJ( z|JF!)c(To_lA-=S9fW}3W zm&e~vOQ!jKo~QiH`>#s`FAPJP$tq`OP0wWAHzY!S6=eKa(Bt4l;zse9xp{7p>h9G8 zJGm&{y;-jCq0x8az1IcfmPrSg#7l*9Tpx*#i^PY->eGpY)03sY9mafYkn4o-kMnbd zhr$$Ah%VQUe{4N4v7O_=JB@aXyc@(zmJh-_7Fljhez`sw=9+xHHEUQHi_D~_x_o%& zDtW9FTTBJZ?}!~vjZTh@AHOYmcAxmibHiSC2zI|Rad31z>Vh1-VsPLUL9$~qk2xuR zd}XA+CCG7I5bsaPgI|puULGF1Qm%ewB>#CN{$3*E2eIw{<>!mzrFX_=qr76ByiT_L zyYQ>GCtlv1j`{&v!A6m89NBLiUlxs@k)zItmCj2px-Oo6cUJIp@Nu!A(R3mjmpMDq zeKVbsH^$RspF!W7>aeKxuUJ_Yf6HS;yZJ*z+94$VS z*Iki3bXFuL??Ee-j?` z^E`hWA3Zysa#{RmL8KoiBd!q~*(Qi{K#n*#kA36mI|OIeNn9)wsh-U1V9J8%w2ylu z!<~uJ8{!e(l5Z0XUu?ujF374+O3pYTeDH)^|F_ZHc|k({ep~z+F8(#X_rsk3 zh#<);20Y&<^~TE+pC5~+PmE{Xmn^wnWO`Yc$%k_#wc0PE-{0nmbsU}S`I<37;s~mc*aKY=H22$2M@mSx_I@Ql5<}lWI8B5y>X6vDzCmKvYZjr`F-U4 zQ$C*(>?7~FS;tlR>-;>RI{n`~;Q8snsUOB0zmR z5wTq4-z~ZKUE$eZ3kUysGUhMy_+I$`XOb5WAF|DMS;4x|>}t{e3h~JmhYtKQ!LDV4 z-OK0q^MdQo$y)L+Oop7ZMttk(M4f0nKVExA%R05mWc1GfHn&5tTAZkzDV@P zMExg|dk#uGZaSWqUd7sp%AHbMyfxDQAnTqVnb(fSU!Sb~_3+Wt!%B3#FHNpFDd=)c z5b*H$>NYw1Qi;pEa=mM!qpR{2f-DN>STk4MDu}dW{Mck+)5tI{$g*sraU6u4PSnoM zgki<3be%jl$}6@C5E@^nYj8eQh*waWsEn zV*9W0`%~iiKaDnzO&{^2$%^kxHT@5%``;5C9}^7wS>!%Hmb)+7niI`zmFpc8>ED)m z>?4u+)2SVfOmw{?zuPZ=T`dydlYDV;V*M}C%0;=}U6FZCbhUM2`q06v-yLuI=RDq$ zqh6HXZk-j+2_tzR@peu0baga(LnM|_SB|%BJH*9aiH#kDRI6t_cSS0b&5tIhzaU*H z%w&yBXEzJW;vq*Sl26YWmX8k}7S#SikmRR%{3Oiu^O5__e~YQrW8G(Bm;3VCyN1X8 zLv~m^cw67V@b-#6_ZT`C>kS^dL}Yy|I(;h0JUc!xH4>6nfJ}a8n+~uVX`O0KRy@Scw6|>fvGTeiN<$H zKk;Spmruoe&W`q0is!yA-te8oo<97wiNmvkecz6Mye%HNL9*@qAQ{5VYSQ}O0Q;x}syes=Ys-QPtEC+3VN2W`)Z#<7TJk`Y(SIi43A9}=y;D(in) zbbUZPW~)fCd@S^MB)lVX!sLhI&$uk4#MbG1ZfvxAe1FN<^4_fMg4pnv(daj$nNP-x zKa}UE6N&$s{B%kzd&dw<8$}}rMOW{QZod?XznjN5^WDcI`K#hPo965o*=6yD-)FVQ zN6X)h_d)wpbB(K$M;?#fR!Q7#G9dMCS;O9W>=(YUODwTT{9*Y>HO}=ON=NEPK>tZr}kevI(cO>puQQ_ zXF_>Ks)Q5LeSB{sbk}J6>AdnUL7d}qjw6$!{wZCXcZ7c(k#l`3JnGcgePOy~8w?2g z@*v6U@_1#A-alu5ZhU#oparS0=%=$nXo;0Pok)FZ`2O*%;Qsi~wLzw{5;G@-$Nw~J z=U3r)rzDGB5v|R{Gu95mKR^EXy7=z9W-}7)*vLm(yzEbuf%7U%QZGm1neA*yg1zQwejvZ zCh}hyuiQUAvr*2!SnBE9ht>Z!Jn#6(`K?I%rO13t^!}B2+V`XDKSc72gCY;)tSd&c zZNl{S3u`?rsP@`u{#7}r8vTF)N4858$cAgiqgIOFn8~l0D`BdS#B*+stXD=8I#-tj zQ?8CBZ_X<2j`uu1Fw5n#_V$N&%XJP)937Tx9G2MMZO9I@Mh_<9&x*BvoY*)fsB>iW zePsGDpHHV6kNI8l8S5=fwp<~8yz=eI?#*F@%v5-k@b*IW|muO2jhZ}P)*ths6;WQ$mCuW0t*T;avh#|!h* zPSL~~S^2#=!#R=a$I1OFfv-i+onQPW7(!MoMtU%M)(gBS(TH7Lou40!-%kZ^pv^k5qv!g0 ztUWx|h{f1!g>ZyfVV4VoYr0`)Cf0tN*!XQ8`ZO2BW-2Ebz+STwW6KN}koSqpkyF9; zaXe+o;YzFK+#6&C&xzOQ_vfEpM^kza>*X)48CQybD-t{79Y; z<+Gn2i?;dplUc>$19Il=jkAh%DbIK^7!9i=c7+GQ1>^zsr_shlymWU?&Zkc?)d?cNl>ueF}cTB~$SEBWRAmsC7 zhb{Aa{{2`yc>bXCD|4l5qPtrXpR`2&rz7){gUl=Dilp5jk97vFvqbRu{&?9H$@y6P zNkPgJlU+`a?XHR!-#2)LcwTGp2E1dHXlfjNh$sC1uEDyqBJJvtXOrl8heXRB@$0?v z+&u`jb7b8v(r%QqtdbRul8^3A99)g6JJb9Ht?>HrE{Lu2R&>M z88?b;^yRi3B4zW)ymqd%)ac3B|C&g4a&kyJS>{>C2mMZuPv4R=E|yiVJ5*WN>E4lh zk0EbwmNSUva$0_(hNZ20BCm}2bnL@AJYV$LK}CZiVor{noxhS^2l=T)`jYv*F8Fie zU65$&=y|QYda2mv>8wv~dU&wK<3p@29Q;$wd|4hB201PtEOt+H1&fxBKiIeBin`Nt zV&|D$OT0U_eLt^$H1aMQBoLc$Lw?l#BeNry$=N)X%XjL~6^1kNVAYfLEtMynSs{AG zZN<}?d9FS9wmNT_tm2uhVSX~wge9Amg}{{`FK`%U)H-IadS^r{Z#BSC$HQf+;RKlEmQwp z291l~dATl4nI=DyP=44;?0cvigS;-JaRvG#qDgO!)em6pxwW#r`tea+7A zRJBhHUU^?$d3T=qmn?bp(vePgO80n^#5*Q372Pb1bT>yk*T;+Q3}!tTZQ&YAW+f{R zTGeCTEK+Zi=eF^a&9a8o^EaLZ)o~Z=yf@VIvW9iC{+07vR#o3U9Eo8$9g!LjmYr07i}E0g?8lz+AWpnQo>s6}&Y@ms z<$Hz)E1SF0J2scPw~I;#PHY`=B2P@^s|Z16(ySSKC`B7PpDD zVEdZ+%k1dk@nN-hCJ{j{=!`Qi2;EiE4HC;>ljh~M2>r6(9aXOjv58W*B!Oa zXCkxi^b%RA8kgCAKj-6A$Oz%MXzQ(Uu=1vDSyPQV&vN@+(A3JQ8DAEw7vt9g2Pa zC~ov~9*WLo$Ko#!$8;9UYgdg|Y?{2X?Z6wiPE>Z!tOy~qtV*k_#!Dt=b>6!M$?Nqz z2R=0BMHwH2s4EW|#|Ts_yk&`;8S>&!ka?-Z2E?i#IfEMP@vMQ&uC3#8TXc@^V5*}W zhgWYDc~wf=4gAGkkqx7XHDkHjjjucyxp9K)lU=a$OY`~iX#eJ%kL8xktJlbxXhD`; zFB-wwp3If+$rV}o?#S{?ylCaT5)N#VS8tH0l$(}_^l%c^s$Z_k6)p(Qo-t&H)53o) z2;SZqNmPrQ2d@tdb9hy1qt~R?cxk#WyT(^G$(fgnj_d$h5YMoN`%rP9ji`!$Sq4}C7t%IA8pNx&dgvQ&$@0-PS77dZRiF4DPPZs%oij# zTov8WvwrJJ(ThI*fss^2_v+MJhhzmiWc_n<-Nj?I$Ma|mVLbQ%Kj$avPgY|ynPYZj zT_gJ4BwENnP0r^H@{^qFJoJ5kEQP_{7768nJBP2PjyHtoTosMz`CS`p>WAMo_(w4t zVu}gebcw8T&FFgLaB_aVL%d`AJf9m*Vg_1{t81!W;NfcMt^!)iSaP@iG!D9X&hwn% zxmkX*ZZxV-eSf67JS>7d3#PR7JRKWM z5NN^R)we{ycSjzz<@AuH7SAiE^YepQ+l|rp1zC|AQC+91y(JHs`2N^Nrhu-C^EVV*CDWCsjC?VFmV zb%5!_+;}@)V4e;y;n?-@$%}&!=Y-$dTW*TUE=0y#_nL9?QCJ8_?{E$Y`|}MM^V~HtOS*YO z?&r(6yQ*mI=(f9Uwv32jDK$+C|m3Q2xpB&TWpEPtOK3kELPcS zUj2e2@uq9zd6(zvS495nV{Lm2mW(fN6MY^Q?V8|xKJtD!pO4DEv$rSPnn;?H-I192 zT{Qa5^tX>nm-_?hXMQ0X|L^GjFY)OG@wcVo6PpkHrx!-khYsWJ`5`DAXayJT!qed`mRlZP&l9`)ThW~IDpr(ETY!@T_H z>}mK`Chf;W+wY0CUXbgq9xS;j*ECVqhyC2}_)@+gv>o}8DvA<)qtJ}Rx zykecm^JIMMl6d~_h8+gK%vbw4ZW{dG{;y32WZNsAbYPzLe{B0@8o%GCP+s_>H~7^<ug>Zq?dh@2*?H(Dn7k~P*xo5w2@Cz|M*_~OSz@}DWEtCfX{=b#mPDiB8q?q%OKQ-qihsO9zYQWtF?cI)_Hz zZ_LE{Et#agc3``v>@(5hWzq9bh927&;~Pgu`fn#c+GTJ<;$~LPVS2Ssj(JtA^SZ>~ zVL9Ip(fjQ5%&&@nuD);9`HErgb6CDRAQ|Pk zLA6z4DGd0=tWb`-Fp}v07G0N(Ew@PietxjzMd9fO=bC#4@iq#UkFty8miW@e(dr*_ zeQe|W0e|#y)dv`^{?VFQqu!B@jv5kr-5bn+U4Kqi`t5-1=MA=j1Nte?%UbuzRS(K% zw!yL2PF`6u+Il3?nMIk5h{N*|!RP1btNz9t7EiowGOYMz!Dt#kJnMdWq~9s_nm5>Z zL44|>;DuS%uLeG1mIXntjAZr>&57KbMn}8EOZLjD$*^HofX6%(Z@>u4zi-QGOgGdR zD`v&|JNooGPqV^Obc1v#bc5^(yL@@WmvQuD>c=KUd@!?tX8wU?FzgjOC@_2M( zO8SdOC-wVa@5ta)Me3@-PgBA+J%vKu|$j`dDqU-FJ5M@w|&l_;+!6^>%7>9 z#NW+&|2sR`P7Eeol5^MLWS=z)G z2R%3OaB@8B#MtbV!Kd!Y(X(^J#*z4WvB@s+#qA=m3SCUtmrP&sBQ}3c9#F#$tuuH`*$i;m_=zsYOuXXJ$l57X`(}1FwKmvw z$Z0!g#!hg=9vYs# zK~}3X&|Vbp#+OY$Fy$q~C?3w4y7R|AQ*4!|s2lAvRTt}(wx(M>Yf;tUzB9=uVwybI zxh^KwW{-kytgfJGH0`LFdG=F@hkJ6h8}cxdz9=@kB;TpB%wx?c?C>_LvNLAW$l0l# zE9*Zk5&u+Csi!gQdn2vtL!V6FlipPGa;u}&Avm#_$uhwqjM5p%ZC97?t>Vdi?(PZ| ztqR|KMy30#wI0ru^#1LCF$udNo_%Yy$9nMSq3BJ&R!@A+pnp@3d6C9^&CFAGd@2&C zIdwq&)Si2*3Z2L5%#6d#6iVn*>Nw~QW5OasAJ2r=MA)iSnkF?~ZQ>_`_|9ZqH6o%f z3wECq3_EAYb2>h^50S}R)mEeyDQo3Hd%CV${*;+O@hldcHn#%XYBHK4|rUz8#76Zp?`{ zNmQ!LcM3Y}8f@^?FW!8xJrwU=h+AX3D|4QUg5a0uJGHA`zkba#Srz{=Ju+vS8@q|U z_2Ns=+04syPW^4#q=U;6`q!qB<`X*ccSSxCH9t=?8`{Q=gc1`NV zCuGr=(c4}jR}z`6b!2>!UOiMg`VyB$Cp2?&JktJk(Y{*FxmLVg1>L#CD*3G`10Qd< z`L5&zcP@Ft^M@iE#$i%rhrbz_X?b(fy7`VTkjH$!lLEftD6<#+=y|!O9#v;JtL0q! zy!S^3H%4OJxbyS4Aen&FS4C>wUpulM8P1|B&tE-EPkERM+C-9ESA9O}{jUVn5543M&>&U5^=_J8?ng5HFhl3jU zoX(#~_7ekknAqr^>acePr7NhSwBvrOoOkE2$bI7HJH_9(&g$o7MT_N(_eEkm1OAW< zc6{m-dyBrA&vq33K9bwn;67FRiS``&2CoUPeeJ;SUKH-KTh6y(u3@&?X@{RWD?GuQ=UpWLp|z&82aI`IZOhv*BZ^pHVKHsQ1xkZBMm za7TV)a%lQv+F<67?TI@6v~K(!)7Fpd9)l-xw#SAwTlYQDu4&Ap@k<{tyEy{BLaitA z*M-BCZ_lecYt@B?D0-thwq|Z-cUT@TKw?2VqCS5EqWc%B{7&l}KT z{lU{m*^Q|)cSCfjmvCu3RdxHoaO{fFjXQj?*&e$?*12(fe$A|L@pPFUh(_!+x-cB= z)Yw43{oI_z&M;OsW3~?kZp-6h%Px!NtTF@Zk>AXQiV*f+;05l%#&pfM>|HeDGR1u$ z8pX);eV2_U?A+ZvGVV6;XBFD+u`OPw$F0KCo95SW`B8|v~3xE?eRB{*)=-YHvZyWYt&LAMR!04raV`H^*p{PsDy0;D!0#3D^&otYP4bGO8**F>L}o}foHLx7&+23SF1~K}+KO3M z?|t1p^6isIRs-q%Y!fLr$hs$!3wc&I)3n^I)Tb9hS{Q?1#7Ey?2wcLA+N}h191UN9K+~NyXII`fXPAU@vPLHn5}zd z8@cxWoX69w7-E{(LLoWZOs*V5KO1|~F}BYE0>FTq^7+=tVt=`56h>+_t4DKlhq$m0 z5eAt2u_m54nbeAWdoQ||;n7@G{_E_5-51YeI`))%Ox?}KY0Qon`M4de?#*bI2k%~( z*uO27ygU|l&(UdloIdy=>)P+X!P{uXuDW=;lKN^TeJEnh76z@z(lvtS@y`e_8Vl}DOb_&vm>cHDdeD9>Va4u>X>^j z$g26H*#kC)H^T4bavUC@OKX?i27?D;P@Vhn4qRHzAWl?US4OsTf;l>h=R|TG^7{Nm z@5Al_mcoYYuv2w;n0DH+wL<&^>o*J2-z(>iC_`Ly=Z*a<_CD(T=$@z=)B)|%EVZ*CRPoi*4t+dliD>#trAnK-Hl5{oh+B*(bbX=dG!fgh{WRB!62?hu0*Y7aTf z-yqHkk<9K0JJU>_?c(XgM*N8zS<^lm9Po+(SI&>M&yN@J%Iji_`|>JxdaG2{OblYh zWo7dQY*{YX>i#Y~SbZ!%ielVAbs@^^(v*jE2GyvOX{|dcbPert5!p~$K2whu|4c*d zIi|H|Vi#9|+-i=i2AMC6-0e8ogQXK|8X=#%3VH2w+$5_n1I3X^OxL}m1;2wiG_K-g zZM8sa)b)~;R4qE#mS}|*~1FBQ2?!&Q5;NbyZS*UddF6*gY**a^-p7q=HP|Qwm z%~jP`P{$<49uGT9$|kTNI|yYDJ1wDY_lwDN_NdJdQkm(v!^F<|2L`NKDzAiAI*PQj zY-F`F4GOFJb!beJ^UM6joNlSSUcKpRI&11UzR~^KE5=HC?6MVRs8VZ{AiL<@i00O= zI-2V6?)T_!LfUJMqsn1tUegJ_=rX~_<>dmL$t=J90M)r1Ec>eE?Q;{sY$`87CVMpH z4l`LD|8~i`U(1e4dqa2ze(Sz**;dwd1{JIbh9W96akYLP-CMI!{MCd3qGR^h<8_0k z;kVukNmbOM%4FQWa*VC_ps+A+#)efaSii1`eMTg#ipicK73`dxLFcHuT_HP$FB(YE9f78t-SOaB-OcLnc)Jdf z%x#aINEd-i#N%-QS)j88zS5oPI@We+SvjuZ9FSJumUlUd_llmCh6u7Ft7t>xtL1?k zxr<8;Z^fpSSgfqhR{S+@cAm(Asw&n;vYztgRu87+JmZN$N4iA%nBo=I&5Ne#Ys106 z%|q&0c01uN-O&fJXo|*YpdGUAKva)dgL^)!}rp=YS`byZWPZ-9^6&mNdwtct`i8vN?mK6)YIxP1&T6BjV!b7XJj1KRylS;Ob4Bv} zV6~kBH|P9%Bk~(hm7)0~p5417pf{bm2LsPgg>X}b+OJ4!vYsi24jG0IQK7OvG|n)ctD6*IC^Co~(0BY$!9YiTT#my(#4Jx+ zJ@Sh;6_&__PhNU-W;vlTVE6tBaP?o-BuytnD)5Irlvu3tCPTUe5VW9yEFA3 zdNsLLtlXGKcN6h*ok)8N-NV0iVt1F+2=1laH=kAOcAu^onQ;{FS7KUhUi;hZ1^V4^ z&#rs$-C+fFWCxKZ7R z(@WFR=bDgKC!Vd=fpyFe^qJF52unrRFC>Lc5C%L3MP{Q zRkM1-dyGLj8OS{)@)*o2hNu1DCP!O8t*p z2fWaEg4mth-jK807kxW=gV=T3^dojjXTqd=%h=fdwpNDh+IKtQC93>peA4Uk)JtRy zn5{;GHnd%KgR``bmTz%^$^L~Ryc~n&v60NgMp&#nJ?%)iE?;{ud^@*harA7uV0H;L zH;o3&$FT@ZPuHBb@XBZV6W%X`rOXc}(}eX0{8n3gCn^47$0{p9!}dDbS1q$ErZzrX z?aDrCcUHm-cv#8Q`W=8v+ux!x45d_ z^R)xBaF=Q4kFxFLo**+Rv%KC{$yO=}yJy`Kq^ICL6Z8@6OR$^x!CYUKkzK@+*UKo@ zYA<&2PBhcE-Tvk;va_gioSlWw8{%Sze6~ke|4MD=40?g4g}v9o{veFft^(ev*RnxY zZKo^m5*M9LyDO)?8*!ya$6C0ah<0zCyIbtW>T}rv^?T>w?YSn5zj5#kwL3I?EH+aA z+as>$sFx=?U;$LHvq1%dfr&~Us@j^M_GH4XF2^Thklt*If=O z0BlN*G~-l>lU~P1RVxnpff^A{;mt6Fb;~UHw)<0b^-N;Si`*Bud%BQ2rABZkX8WVh zMA|zNOP8nPs=swXtbAk6rqjA)R_u-kQx11<>h*NLU#Bs>O9KzQEwO0Nk68xEdq<9X zy!|;+yPN-(TsC45-5RaPSxYryhUxAz)t|aZzH#T3X*x`i#rU$dwPuus#H;R?Ie<=x ziBa>8Zk9f#hYxihzi7SZvz{a*bKff;he+^Gb%R%8Zj)}JuDg9Y?)m8Cag*3#a@V+f zOw4ul-Oo?G;9h-u{Jo!y`d*FIJ3dQHunTiG@8)K5FJFj8@5igVX7`)3m`n3&_q(`{M^8~a^3lHg3cIV2F$hml zrgrmcdY^DR9U66?>9@`YPU7`ge($!Q%=mQ1M6CUJR*K!L?PXcL0A7L%nR&w!ojg-s zynE;9+PhBm-3HVNdR)CD*^WiK_e>=&Pi1yx{Eh}XYjm#iD!FcQcY4>aR>4Yi``l|| ze#oCZ#I?IqO`Rcx3QSi5cQjYE8`b^ljiy;cWVn~+dEpay_g+IpyU*PJBGPSgcZCkZ zg<;*NXBzF^3=`>#V{PwRWfo@E-+KdPWmTZNDOx3{t>_wx!bKBf$VpQ8QybyRDkyo) zZW(N^6DIjt-=)Y&%S%Nnh`CvG41??@u&br-lV#o50MwKjc?TS}`>#6`V0Y0$M6r19 z5yVPGpP0c*bL>XY4fe@#VZPpG-o zRXLX$$8^WN#;%U7H`6y~6(4vIjKQiqW!Ham#H>8bZA@)2Mcpy16BpWUujfox@FN3D#FPq{l<2GKt@3&O;l&%C#HN_&qgcRRLf z(APERA*K2jV}THN4>ESv!TQccK9eNtD?1a>aLZ>qs#IXs%&&ZP=OWbenLp`QtE6QW zcvK!&EKu9>O<8i%_2zFRHJj%N*n3_U`&R_>N9TR-m`UGFPgSJ&ng6i?O--_hUV)B* zd{F6i{8-PrD=U4g7feod>0lH5S6jnEUZSGcWx_o04PIB~;%xM2iqB(AN7V2>vkL#| zRDy=#6(qnAiv2LZyAC@s!yREB)aZ1A|KUa5;{`4JL`I!t_oQQ{{G`ate<8D7McsLz zD>vDxrH@JnEJp+Gr<(XT)TBeU8Dx?0stn(}`xWXNLU6ll$%&bXRRS zV^NsayW7BD`pz5e{Hw)z2@Ucl=Tv9vkMUS20!i(esQtW(cG(fC^Wl1N&&`MXE{t}n z_Wp5Mtqe_ft1+bC36FR%*{q;*4ShMk?b%7oqwT(fO`Xi@;MyPTHNEQ@mgvLiz4U(m z_ApqpT*v%$QZMQo!l}N8jraHPUfViIvS@wI%B{Z>^fuJ!1E-?3J;*!lUFxnXz3= z%pW&_n7yA}mj`Fi1y&p5;E%;S`i@Vc+)DM%#e}%VYOoFW{qSekDw2G?7_PSL7EFSf_G#Z(?WYdNN~%86d@vn6>)Egw2^%={e&$cJz7oM~uwfLS`d6&vsYB zpyEcOk;P2*Wr4}=FDzbnt$CEhJOTG*2_G!Pzl$5b^6?3>s3p|~`aF6JuZZa! zKUN*lapyVuf@%iYnjiGtm&_sTweGA$EZQ;e?s7ZZ)t4&7_Mh2@C+Mqnw~3X>^WvCY z8WGi;Xmo_nW}>DuFrt+JYgr#Y=30#$T9F_1Ykc1+wJr;L$y}cFh~M@7f~*-+k?k-$ zC_zeDNaZ0?$yuZkyKEtfCa5d|$e@#H%~neSa}BnkcOEG6i`33g#4}SYCxTKY?y7)E ze%HmoUiHc3XZ~m9aytx^XH2L>2?jjbCrEysnerugU;pjB*JWp-(b{Q2Zh_jZy^7Gz zW!BP;gB%03Ak{b$ssL28c55^e`E+;o*dh4f;FES%+GFfpYx+J9_MVylskF>-@B&i8 z{Z{pMtYH3~%J$uF#5J$sx81WWPpPpmQL@oTQK~-JiiJKOikzKhnx5)9szV{2z5#zR z&%ljj@Ag_W_GlgXlBFH#DWZ~7iyMnEwXv*P@GqF zk1g?2>{N~vU(PEF)$-7$bG1e!l$P|uM;o`(a5>giLaY_t=wp)$q z-&n6aV_lBM2CxwCVri#M-)NC9nEW-nZ&Xj zKqpd72T!bI^MCo?-XWla(BGAi$|}vM2WC!e0E}9@H&&4QahF9?IW-MR5iVY#AOkp)*ov*eQplR1oRdk{a zMO*FTCAwp+U*wK*D7mBfXfKp%%8?U4>O17XE^N<3T_BF&zP=OIhbyROTIZ=op>#V= zd=X2~0U)n)6jR_e^wN{lukO2=nc+?3R~bM-^?|dtH{g6Y7jNa`&48ql*|5X*(8_XP zm8wQQwoeIj(6i`-&O4uUADSq#cG1kUL7M zP13I(uoV`{R4NSbO^4H1HxJ<>lY8~bQ{={C4@-9??I5u~1koRmwR94og&5?CkhWY5 z(ziRVa)#Cu#KzNE8>^F5O|UwHd3GwGi|qandD?yr$ZVfKiDguF*LiUcTw8AM(;3My z@n~_{o=dxxa(utjN3s)N^g0L3bG;txZ@j!cDOTiVJQZHIV=Fs$N1NFZ{E!{7vF`nI zPc1e_YJ7~Ac}VXH#AAB~Oss6NcL|9l?;wR~`iu#-ic}-0Yw#FdKD7<3k)!x3Z0RJV z5#rjeOj|k&-ZQxssJ@syDF-`4rvs*x_P15rc&Hsu_<(HV-d$ZH8LE3$n^RTmjsDJG ztkdphowV+DFhA38d3HviFIME%%W6zdSkt6F7unwPzZHg#H4niSyraCT**iwqPsgX# zDV?o~kM)wZ^fj%#Ii0VT1JVI};3q0PsL?uJz7-+$b9TmpRDNAG{KDtUwYz2(Y7L67 zi}`l(c!nJoHzfwmaN4IfU9fLxnMmf2rv9JB$@>V{bHz_gli{a6EaW!}H|BdNSR2t4`6qBQM{AVmbw70V1lbu*|T`9s8#@7P4wrmfvu8T#98T*`hnD z7y&mx*46! z*oX5pd$_l{Jxx;ZQPo6qiJZ>je3h?2bGR+DPP%jI=GGsztyf?rt*hEW75VKa^OSPO zNmjQ{0w)ud=J)Mic^6LB6%l3uxML>)){oW6Bb}T@$Z$Nvoj?-hsxa0%tpsnckrzI-03{=AUq{?;BvxA4XCO$&p>F z-0uFZ|NpwWD{?Zn&$e{zt^+-MT-dbdkwF?x-VFF6=tcO`Igo4MDrpN-<*eDp`8iV z-d+LBa-_ZK-9=(YApf*?zmwI@P-v?Yb!f(3ycLIo)+7;Eblvq@r`kdP2z%1wg@^u* zPxqZMur#(6L+%a}<@Q~7Pn(Ls`_t(Zc83@1I#M6V|7@~5SIvwq+Lg;IATzJRJoOIP zyYGXGdrfv=sLC(_JAd#mY@{5SN2@`cL;VS>yL$!?DSNWs+R1FSd_V;8EW2s2Kb0sx z-5jBdRd(MRruDLYfQyD}sJx-I>vcXxZ#1WFlbdzHV5PH|+vpX+9o1y-oKOX^u5&q( zSJ|%warudfrp^tohWNaXcd107wHyiab+mK~^|DkkJ>EUeecxT(8OW)|$27&h2$xw{ z(RcN1vDq0_r&SZgRv};@B!zuesn)RPt+Ofn6rmN~CA&f%dX@!L<8pByID~cE2MRmw zQA)5-KfK4-{l1T$P35X`|F-yJ4jir9WV%2-M8v#ro=O_sn$lFpp>(~$KpCh z>)g1?vv{ZD!b0>bi+8^gZpQ!RRFQ0Fm>nQ8jNE9(AxFq0a=0#UJ2t*LSCNeOK;!OF zYu6JJH#cL8IC_!Ow9)EY3;Ug)`d3KqgV(leDW{5cjLECinJT_^4eW!JSui}6vRXhK zw`%}_?CkXG!il1WWwvddjo z%o2LdY{qI3hzCsaFn@!!c2zm984AaM6!tH)H`|)5oW#oX%i00%3gl9}nr30tWRhR6 zZ`H*&ARmkufB0>4dMD0w(5Mg@WeqqnOE@2?n~(9CG6InyLz9vy+dUd)jb<<$B;{>2~5a@62Fnm({Km1n2fFpp=ex9n?e z#i#O8k%@OJ6DQCDuah;fPrX#~%6q!M-Bk^n%AD;slWW`Yl)-xUdYL4xPR=@ZwG zLt7V?5%W8qKfyR1^X}@m-u5+cFFNKqQC7~zW8t)CI|UHCdd6!+xegCh?sN;Y=nfdj zZ3@zkpuG}w&ThIUcJ}cukJfda3*nIbOby;$A)3xTOddxsCKPe|)f=XnCwPpCRcQ}$g-`>R2%*SlQqgaqTIXdiZ{HdGdb)E zKJr4<1}5D8v8dyBvXYK-5zo~zVY#p!Qk)hi7R~${m#DwUFzo`tD}Dj_pr=g8%j?~A zgDtR!S3yR&=e!WV3``B+!9ti7*3p@)+>J})DBTk@VIA0x^{bG|C)J4V4Dx?zRJitb z>-l1uIA%FlnTtvj$JIOGC*3EYDkmM3gmXM(Qk}J{%pWn}PMgU~J7ncGutoG>=^~_2 z*nXILMI7=Y3{sVakF}FG*&){Yke}fkVh#G(FQ8-G9ygC;NuGh1)?XX7m0GT!%-%#C z`$JAOM;U7KUhz{OoaJGn*ZB^v^{-G%j<4T#0t$!4r9L=z205yQ)<80v%-9`|a(AcF z(8C9G^QTZ%w!JGO>-@RRS!AeC>IVl{G z@!1!r71`}|^Bhbd3yOAHWr}B$3(N@)!f!g)9fgz-v-PF>raB#HUd1=%_p%&6K}w(b zGpjypZ{L^k!431+J{p&`6x{5j9RAa>dPN+HeYwpUypOB8wsQ;}LHhPPo})q%RV1Et z6?wJ?TlL+>^h`T#v(~;Zg_X7&*-5bL;%htys)|2;S@e`CcqLW>m0+FzRC5hancNpV z!B0Cl%lPP8&M9{2F}V)BR4di1#2PEfnQ(v~wX4N$m|5#uJ*Hxy8CyHY?o?4UbRaE9l|CO(cuWx7 z8Ho&8?(R7MSpa)tBUK`{*fsOh&L!ZJ4-wYY`&#duL|_>+y?1WWs({p(i>a=!ouIS1 z|H6Rd$d{828J0#zMQdwkUmsYeGqV6bIH@9JtVs?hD^}h!G&8Uz=B*~0Fu#evH)l7S z&;<59@k+M9p^+U7UFEs7WmbWn6nlgHSDT;9RsVH{5^d!lE!<4Ug3m9jXr zkeyu#BG7R$$!9*#gLxCH)H9ni#$YpONIrK)cTbaE9|Uh7*lr}dwOebrtIAxY zGfK4r8_9@E7qzha3NRwp(aF*2?_GL*4~Oof=}tSV7m==pPd&Sj$XzS$PUI(;fqSf>x9+5O zmcUcGZvh%j@_egA@kS~L+v!%<)qDg;RBXInZl4#@!tEO0v z>Yg>9NiT*l1Pqs#K<~b{iqFuz{akTKx^`4`+w3OBO}YmHO7p^YaPV$Yu`kbNr`m%* zizJ-YRT~L?wbw(Hax1tD1&V22$5TCUo#sl6oqs?huXT*?u>V#G;)qp9*)^9v^AE@X zWknKc`)n=i_vPO3Ws-yJAyO4KCSifRhr{ZH$@leexv+TLSyp>zwQ(`EwRQKXMAYcQ z=T_BzV%PG}e(z^E0ip0xh}Qhx8m5&3{3{ml&Q`Fzr8$bOSQ*k5!OBJ3iLg%zx5XQ1 zniuNs*gtFjucpKoM4L{ntU+hhTA322P`&v)S&wL$tfG?8y{A|BYxx$N@Ot?Q9(b)+ zh&UCI?4a77?BevD%<*icKoW@4b@}6*zs6yfFp^%ITWX$iyF9(TDGw z<7kMc$<%7M@n+J_hsB;e(TKn!tdO)MZH2qliq3#!~=GU#P%2C7@`%YMm zV|lfj&&*)r+j2wWl|NN(pGA-S3{z-dX4W5@pn&Yso*2!0tu7GmU8!9~c4|(hfwBmg ztA>qa(Rk{;A z=bNP9L!zP65X=VOl7;BA{!@(cbA2ygA{VJ>r4<;&Xsw2Qi&NRreLpm>Q$sHJ*NK9D zhu&ECQuR(+c-`I$+u^S5Dw3mlgluXwIYf+?50^z2CAw14+RC5h{H3wNlZx%6;u${E zx|~?8(-J#6j+R@2!+acCd|O4C5c`Y8_CeGh&PWgNvl$XE;>jYRoUWNf4k?dsZi0!G zs6I;*WP(5STpBm^5<_|bBBy?Dt*(tvO}s}Jm8Zx!aJwB0dknD!5nubZYMQJXeu^gN zE+)4l=*}n1sFfy7st%8Z^+SBVdWoK71v2?Zo<4HQ|Ol zrCN8jGBU?lCEYsPB)Ua4-=&>acH}M!@o_8h@K+yvfK)t%hP&&gbri4YihBPN{no18 z|5mO*hqP7P5fRW&k3*(vM~i>+&NAXguFs_B5k+g~fH1U9X6weU_=?Cjk8utegS6Fo zdjhyOG%f$Guh2z(f;HNWs|8%I_YAla-NM^W7;9(#BCbWb*kL{Ast>w0+w!qyAimg0 z==sRr_W@Ah@F%jgivbbv6aLbSO%pWBw^Wn{Nd!&m6ReI;%2axq zR@{tQ9Zhl#4dOR^p#8`Cw=)*a9A5;ZW4cx$$n^Bft^USRC##|xh{p=er0sh(3%lDu zE^kyh18GEv8s6%w>E5y07^9(bO?5oWIGT-o?eX=`&LZ^f+U*sMRzZK|?PZSgt0z2V z;a+Egd5uXKfcLtZbyQpR=*BB;H|88E{%D7_su}BQKBFs~nSZ*fkFv0$MYD|9VsrKv zcYMQDVJ|5lWwUsrvQ`oU7!>~5^YZRWOXj$^%d_X;XJVvzy;WB6kHlCO{g9#$ zJ_AMg3AD9pYcAhsgZeuk@TgbQCx0PzE8XTs8Y4G`T6;FHm}S83a=!Ws%{d3{h-Vm} z{%e(D9nM^hle#lbJrXfJVUMh6^&}P}jS`t%2I2F~05l7s`dcfhzxT}L{f(M(Q<=Cq zxNN(KKs(Oa>}qENnJaZGBS=C6xP9|g*>RbpGxBh2_ZnJrM6ntcLqN8t|JLtT=9SLM z`^p&Tm!xudS!I92wmgDeeWv5a0}J8{a8|W#4XpwF#YZb)-ibwZ5+%RVPBSbmklCX> zTb?b>@gf@LA+<;SiNtJ7dgwvl?MSIbJQ}~en}1GX*Xx{b@^JpDXtla`k7eTKsdS z>YVJYJ$v@zwc}_2>vBeCf+@A3vrYVtbo@@Nlxy=8I^iYw4fGMmjpFLUS!Dy#_sRb} ziUpIHuT6a}0`*EHZKOCaUG_mAYJJl3n%dSY8-a~Fxy9L7$dg>n4lF=sUOkb3pLj)I zTSTJya{FqT%=InD_th-w)x84wi?hy0cO-9CsBMaGwQ+H-Qq*U<|LIvYbT%klbjisF zeRQ3C1)9*359blvSYKnYx~6{?U~Bn>m-tL(Jg1)GOz;V(Vb$W5Rgs=I*Uy?AyW09j zZ8Px|7I97%^qF^8YG3(^sPa+E;#s_e$H~QTwH|II?e94sZHsPagijc;?>(%%eq8M6 zy2(pUSF$Qv>+zH9Jvp*`kFM)U)p-ui(e>=+WUuhs#!jQYQA0oc2lJ#)R$-Su{B5#6 zH6s6KZ+4kjgZ->?BB#}Pwwu~DPZ(f5pH(VPz0Miff>oT=XRojZdUtLXu*#y^xE{{UPg!E@~!&+#D5?z&(tw0(;<})t8TA#qQzou z&)hw6;s`piF>TVJ<0m%hIVZRS8|cZp8bMag;t-+O;HvZi$%+)!Xwkd&>D5@Pk;^8k z99@9c46;GbL_-r)RwI=I`^>Xxw=9lVxE^U#^K`)19a{}q+awo}d*Zn~zECe zu$pB#S89h7+r|>`*U3&5YlqaueOHCX6Q8td`Nc{q@dO__Z)A6sczv;cEdN(t7U}n@ zSu)hljnv{4sk7jG@W*zb94eQ1~UC!R%5t-l+K zctX2z7%B}CL7H{oZ zt+{?iV)cJxt-WH?GSf2*w*Q@?=*p7hE=Q$3@{~DD{A4g^WM|VxV{HOo*cKvmm8?h` zJ)#)RFI=&|EgG?Jt4V8cJ-^|7q@Gx(-Fb4i)^Vmv+kC)2?B#(6^KTv_vS1c3u`d)u z!fuKOB1$G{hskkbL|j;(>pRNpCtUz|W0my~N65uJs_TMh?X<8Hzw&Us#enE>qJITk93Gb7hAqG-tICkH@I2@Xh+H$n$i%h_0B!J^Q{pAOWKPlhO`gjnnfzU zSjnLYUnPU}vShuK?A3Tz?kD;#^D+6T)#{Z{t1PyACA!0bZ#&0?2| z!rx}AdInEu{HbGjcXvd(GCwKewPzs~`FU%tiGR~J+~nDnd6HYn0aNJQIvuN~XX#eP zmD_b(PekzZN%cTZ4^sQw99_;sdj8OeV6CzccxdJ26QbFCvnWDWcneP;u|9YA6qVt^ zhGJonguG-`qq*z29h>?{<*ep-i8ER)FQhYPpzEHAf7CW>bh_rX7g=2m!Eyt%;B#-pdJrx2fE(Ux*i^RO_83DkOy*h zy*}&t@@%_Q#e$VidQPoi;7}QrtI6e1zY^=#ux`5^u&;=(TWpWEOl9TJmn;(moMaob zPR~(*D$s*7RO;qc zeKlR!_KSH#-&I2#PNo46$ipg}5o$CF%apB`?rJAm<5TRcV^m({`t`Z8#_nh-9zYh_ zvKsbkerg;$ik8^6-ql`ScUb6wS}`va5$#}3@>Ff+SQ0fRc$fe7z$?q^*{IP6Z_6dx zo0lage1vrJ8YJi}(@*T|`ef!?a28rmb~jX8JePgpkO+2Va<@z6{}PE~DAJm-_^ZQT z>pBK%HKxn5MK8>DT(i2PSeFjVOQ8e$}ufE=FK8er&pc8SK*$I`pAS&z~Xdq-En~D%uc>Udcw~AJsd%)0LyVS|pLQUyBAb>gaYCi(P)=C#@|T z@#PZj{=rGQ^Sj!@Swu5GXM=J67j+pRRGMIV?a8x>rJ}jJ7p%gW*s13rJ591-&(3zW zFOMinwL}2{#D$jWf3(&AwQMD@f_!AW-Sw`&xjisS`I;f zcnOQcAZunrJ0f_R>#|+r*mrDJ4DPC}i=FC$B(97!Ur1Jy$t^Zwp5l{fGt zI;nrTHoLM$HAptPt#4axujy-7Z^ez5TDU)plyXwi)H9r=URVw3Avf--QR`^5*Ov6= zh`wrqv2uR0rJg0)+sB_+(QAu#U~{vQ9YZbT-!DBOYw;z197>l)T*AF%%c)Gm^oQclfEm8u@*Ts*K+IYTR`oG2d?f2%L}+11IQ z+Oa}jS)SHaPP~PMe9xMRqsAy^GjOf$^c>p$o6cvFKK^LU!aX^@AvEddLKTY>%Q;(t+@AxU+jh?EyZ_URw1Ev7spx6SER^j zSM28}8j9m=G0Xv;4JFUj*S0~S>kmkVS zV67F^_}GnKtcj-9;nsZXar%sH{jlF@&y(%AE9c~H^RdJQa_hQ(^dUp;oFf5v!%SN-sNWEp3=!rRX!&NI(yMuVf za8cb(-fm=`7A-e zb)Jvy)x>3$qbF&e6D6%}YBpcNTio{qU}xPZ%dTcu&mqOx!wUtr3Crsa1VmJlo4LmgiYsg4rM3KJQl# zpeXxKwu_8CgOEVGx>0OokLcrL&oBJkGdT{$K&z69YhOE0k--`k%0j>O=o17_U+qbb zsmB})`*hCJnh4?XR#UODY>K%>OZn&wslTrIE}O6lGnV=$CeM^{p)8N~X&ZjkK-pV- z^c1k2sNSkJo{Q=#brSkLX;m~S{FMc(*!*6Ug|gLyJf3pkj2<)l{Fh$XSZIwDN$o13 zz!mF7q}8bi;jeT$lVu*Z{N}1p=Y7|~3Lb19z|S(*{=4tKq3_SAxR!^!#n*fXJ)1CH zE|Jj6UhRmhe(lwGX#F0PUVqT$r!rC0_?O*eERIz8VCZF=Of=MR?mJW}NmA)>QSFnpF-R+*EhodcMRLSd{9(JwRwU+Ocp<=rSm5hkvCKQ!+Bw$zQm;>| z=;s47@!cv>4LlSct%umlQSP{G@7NlE18a?=n%BBtykv*s|MeBAdE6(3r>bovi*h5H)B1J{xcIeJ{Val2wS|-3>JZr&U>*DTs9j~1h}Vh@I*m1t zPf072$Zl`K29%f>uS2gb#=m=LR>tnQFpwP1q?D__hggK2}h z=y&$Qlc-+gKsnoJpttHqQaGz`t%{w)VxF3+8t;i({#Bvt5e@Q%7gejOy!;85u{1hY zF=7isZLDH3)a-|7t?^rQ;)Bd$gdKgF$v)iSI6m;Q%%Q>k_E&Vol$hwd3pvy5Do&m$ zO4=tm^J9#sq6CEa=R*ypcLC-X;D%m{jqiN^t7 zE8+Rxsz7epnup8TDpj>mOA*BKp1R74>a~a{vh{VXO-@5vO)6fBm81F2gNLUV;$lrF zbpAaU65n)arMqWB_HQT8%hkQ&tV&Ys70>KbbK<*rhm3b%tK!fYTSlr=&MK%_DPk5S z@W!#YU_tAk>*^d1l7Rt|XFUtaBMXNySl%uc-Qk->?PRlx79Mt#p-`qt=Cnr|b9mE# z=3Y-_Axfgp=2sE&LXkkj)#$?@yf`dsipPE8jsp^{nLd$#64tyANA=tMA}4v+P2M;m zg&(RgGNan!+%9dAS$vZqpTtD3BFG*w20}{TA@)+?UFGXD=dct5Mj1h-b)^b@h`UH^ z-A^Xu@U?cSfPISP(}rRq`{fszRrGR1rQ)d~o&+=Kq&4g~VV~^f=OWlhd^(%gKA$Ch z(qOK6Dyf-XX{tK5n`w4l6KApk7VUgceN^d-Y5K3OTeQVjyPR@`Hu&2w_snf3A7Q~u zb@dV}Wgtma9sRB7F&h(No9**xnIZOMA=DkokI^zzMzJd|nityBzT$Bl^KRc~S8a?} zVXLcq{0Nnt z^j&ljT3>q7*`B}3K$`t{QH*EoocRcI6~6EKWTXn@7-Qbs$F}n}lOUgUVz@Pw&2g6vWc3*XOx1pv zmvt2plK<%r$+yNXnlk}qdisU<&lZCBT)w~+Phm5%C4yBs>p8`jA>JA-}!Cl}+6#Imz> zkBzOU&gDrSWH-z6PDtjZeKY32(K2Uz7b|Rs#F11x2HYDN_ui{-MM^O#TdEeSvv|aj zc}9_GZ6V9taF>_*vu*J&radvpEfL|W8UV3l`eR1M#(KKwb?hm6Eaf369JHkA+}*(E zC^yoR4eF0x?@;i!9AAu8n`h(VG6c28hupCW;HqEBK!x>o94u=sj8_&ef2v2UEkb&l zDYuHMJ{xJR789<#!d;FXH^)KxGAa-AQB~DFsjTEl+OAfb?8$Fr+ZQZry?kX2M$EOBJ3qxO*7W<=hCSVz2?0EDV5Y1smPn~(aS}s( zT`u{YT8xy}<(|(IRIO`|7oJ!p5*CH|W}n|3okxD+*lNH-zMWvVZzrl>#)MemHmpyM?Mut5)q#B2y200&7S|$7 zEjd&job)f9`IUITa`1@?6!FEMMU~&Rn{QtzzWh$7nk=J4N#CsW{pQxRMK#2<`XjR( z;a9I#?rG%*w!)BSjpr|#c`v?<+UHfGgYS5NWj*V)KdUCN!%>aCx>J*jt2-ixPWoVW z4mB_9!*x;2NB;T@N~Ex+7%3)X|2)m}qO=Oo&aUrr%8xPv>wH~KnBV>oCfFQh)jr=8 z)5T5r;B6PY+QrADLz=Iu0JEgn7cHz7)3mmpX9rJI3)Bzay!kG8k%DzcYX$vj#@#$! zoh!0^YuG-VPIZ9A;uG)1cKHl7FY}fv zE{&eP~qqXtavpkF4nw zQ`74Ew#6wAJBqHw3E%a-7b#v<0NGn5D5_PH>MvbeY05+vlZ|l<7fbN)PCS_dZTr5w zZUmXol1MjSk&+e1-rl{%mG3Y`B%#ebz%t5nEfUURDkb8m;4J|`)B`-emi(;LHc>A=LYW~rXL#UAsUQ}v zMI|0uZ{nq2Fc)d<=E$s)%*nU$@YldQ*q=^@G^MQjmQ?CFQx*wb(0o^56tAtrE{ zKaCY3m}Maj%9+Ks);w!B>B+;IyYUx*2Xc|+Gc2n%d-gOMQuex<-@76?WUi_aBFT|G z(8W1)kjI4DSNw@4cb7>Q9qlTtv(RoASOrv{$`JECLHB%AE4HBY{{^6zq-a4=KFWzWhCCz8pBUMBc(e^d%tghCKS^3^AsKIAT2-fGA}JRF|OZVp9av8 z4I)x2-B@Tf^*+DD<$y3fF<2**ZbF{a`stYtG+TPgV3b=H$^|0Sl& z7+BL-uJr!joR1GH5VvtmL{vEN@SlTleRYlobs;so0wt_q{o ze-%B}d)}+okj>IoG1&8|_SGFNU8`zaSuxUVbMlAmtb$Kso^9>SdMNlL?qRl;+l!Fa z+MbNXcIyk~TGQY)HtUR~4KHO^{>CJRR(-O!Cmu8OEFQN1sB-lgfccO%28XW1U%s^} z_Uel4H(->OL1mzR0F7{VnvX~Q6UXcxJ(;)e}I znQN9APp^^2JNneZF0^)DHO@Qa#o}a>j)CIV$mGO&cf|#ZPdT&J%rrH_Sch|;^j2{p zR?F~(hb+#|+p(UXU^K4GjcJj{{$>~Dn9h6J`@qQjdku26(?z?3 z-K|dPaWkDsJN#YGHBrIxz}ADaW*=1n{TCJ_xg(O5TE%25&hUPvkY~Q zJzflTQehUQ7&L<~NMNPw9s0D0VSL7baaDcs$v4d_JIys37hP)~PsR_YS?+rk3;fvF zp5=6iqoHF*vf<*N^wZE-4AX=0(7I2*neNItZDdG}8jVN@9iQ**rr=Z1TF1MU$!^ z4vX6ARJoH@+F~A?`r&dEq3*g07qqyVE#ZmpMVOI$WfzU}M|e+rAsZs2Xlo@)HkVw|Yl030tVmuTo&7Or_1yDk5Xb z-~6nm+2ODqI`8vue8WEPcLk@{q2PiWO13UG^)XnhsqBu>bKirog zdd;mu=K*K!5IM)D_{pE-RoCY^dxengJ4Z*r%JO0HTOWpPPcY0P8=Y6B{ z1b*3GJ!G>nY^5c3@?P1fugueeW|BijEYHi6L#9`& zOqJhga-5C#CsXriecEEGsO(vH_KWJG1PUWX9{(3#u*(-xp^s16X31$&bKEaFLQJpm z)@ZfI8TZhq#f)sjfLT|M>4d>Jy*$*Iz0=S5Vp=orw^Skyu16?S}h5TH9`t;sa z;-%rxkOeTACFUKiF7z+Qc%+`Js{-dQ`ti;q#)Y_e$TnJd;IxMhKJ6ff^_VU0%=6?_ zUgp>MkhNmbc$EyEa8}2cIb1dY+8$BdCh+A!cXBz>bnOZ*h?@s(s4v&<;y zcG!94W7vl&Tk#8{{Xi(q%$szg}rdnGvKE5$1YIP|w8*uFFX>$!ev^*Ku3*qs?nRfrA`2!~-p?%=6|J z!7RXPEfD0@y&HAaH=&K!e2y7xVYONYc}R@5|5*l=gJCe^w9oi3o^8cA?})caX%`0f zJd}U((dp-U*+J8r4=MYVMl7<5t!!~_;xO< zdpb3`kwu32?QV(~vyFhn`P2hz^{)|mL`&abnIQsT%wlqIM^c}7(3a)Kz{$>LVqg&( z>JZ|oqwH#?bN0qVaoVR(Y3Unc1> z-rU|@LqIoc8`)e8wqMm+CRZyOm3_vNi=}MVvJ4?nFKfm~EunO_mdu-%;m1kdWn&ia zd;q`Tk3F-y&t7bHMWa8sweUjq$GNz{f_~r4ur67}jdM2Bl+>cwcxdPys;->1uqItJ zlY(nHVWC}?SfPrn-bGrBimOJ&19>DvIJ@0D+^2EZ?)X#>tD2h)X7ue-^LVqU3kexG zp)t<7E)n>vTdI4x{?)2lniPZ>W+3gI5_0L+vq_W!Y|&I!|u7N&l>i zp`Os`T87HeyjGnx!<-~-4Jo#J_AeJs&Q+28H%5k#uViq?X@mHg#qnXp$qfd0;f!?g zB~p5dD=Lhl!7FyiBFAAqjf)GTtD|~&gM~dAY-}^cg?aFpkvx6*9`o~7ZIH>xB1+}& zzZ{Kc2r%53d_qQ9w7AIYkkHE>{iiq0*CQ&&cDVJ7FaMr%yx<0M*vxB0estGMPtw8~ zMz*xZk#Slp!Y0X;)vae}(pL{f4+iPp3P5_E${)wXOE2m5m|>K8Z|}`K)<|fp0+VQb z)omF{`eK6xvC5WTY((!s9f30Y9n0l$27WkmC!tO}jB&|qBqhVZh&{vh8MrCC=$ zJR*=3G99f0#jrYMJRf0~yzuME56&_ytTGutqM8jP+OImy@$KZvv3{dtC+mt9*S#R< zI!}o|xMFTxM$C$i#>TySXR<1*kPiI(^--p07G#a(Qd8)lZl;d4)$ zcb|5oIq49DVmzy3MrO;o_BO8Z)rR#6gjheWdLLtHZc#$5vH7#QLDCw>soH z#HYWD!}+)jXy&P{c{0K5Ss!XTr_sMmS#2ot@aqaTe@Pr-`1K5twSS*DG$!k@Q67}X z5bM`gW}Gp=&c&Gip)CinTMehzQ@ALe?WDSFUrMk-`#4>nxX>2>8NUwsHN;H0`d=Tvg;z`(0yi0e9I(OxRbT9L>`3YTc6O0 zY5&hMD`eMkRn;NGEMv?HMR`!|tAdl-%2=OSW_Tr|xXQz=B5X@`UXEoJ6_G_pl46D= zdd!+7<*l);0X$(`FXQHW^Qva;IjZH5w}y6w``9w~uE*I>0=U_#t$8S{n@M2oe8j)n=~qiQ%}t9904_2sO;- z{v?^Cx$0Hc&#T2q$cQ5YW`~?S*V6K}s445>h3rt#jNL4v!PRt|lf_pv$rx5aMK`vW zQKTjdru-?ZT0dZhsVtt)!mfS!H5><&>lDP*9IPbA!z{*4 zalv}KN>-3jO@bNPd_n7^h^?d;K_5^1#@C#22o;T0Ui0;|=QX=M5nVKduiZ$D?`dpI zZzaKM{v!nz7~;*l7$?)HKEI_G!s5tWo=+++_N5_SuY3F75o4Y!) zZ^+n2Hmh8RpNHTNSvG`cSr30Rv=`qjJ@J$iMb1^=kuVa zO6-vfZ4qL8e6hFKf(wpzb!=EJlUXH8X1-X28kbc?jC0<`P~4ai^87o-v_p_Kh&rH5 zms#^ads$~yKC^ogXJ7KRbJZIfZ0B8Vu^zrWDAL)2b$`jB2|g=nzBwiz_r+6|8*8RJ z@1)YTQQ{(BWr1knz47Kfd(%HJveB>SAR%vcvgk02m8|PE=BuvstF1hZwQ@5K;7PkN z@MlAQ(mQ)#r=5qKu|Zn#;J2#l89VTHokk4q6C-l5lSSnZNjNW8X`umbJS{?0uwsD> zYKe!kMGyU6NeyRALD7u7YcE0*^f-dMXi$at z$DO0kb;4bYImfwHaZDcx{-6j~*!OvRw#8^`Qnsk~bU{a-aUoewBrVStU3vQ$c*%Y< zLX?c6S#NCg%v|db-}9(BAx-)@+7*ArzA;`R2~PT1>2OD?5g22ev(Fy$Ty@Btm}_(IwRD;o@DS-7fAo0Xk-A~Wri(mQNdTWBq}$FI8>$76Q3t4-$S z?>)Qq8N0fQoh0#D3>48SrqShNSVLtLUy$TF-$FP#8YWY$KiE0zrxJmg`PKCiIN+hs>j+Kmi%kv!YW;+{g_;L{y3IUHJt$924>rP!Mm zxKA$^GeuG;(@>pa)hwak2y@|}Kh9nG#5uIIJB*SSWb-L*#4szI%QwAo7p}Zdx|%>= zUNfpV6$koZAhZ8Q660Fv^NWF_<2c+qLsksXQk#+4lm5$uLt5|j<+qdP_+b+)@zm(M zp7rpH1Ns=W3Pa)EVLgGtb?@a1toSM0H^QjKwbqa{`?_|H7l@0XFsjVyOh$S`i8bpZ zt*sC9Ectg_c6ISUg6Hg>lE}}Jt4u6b@>GoTQG4EbF#Tf&COt;QSa-!)z4M`&*=Xe{ zidcuMw1rE?lr{Nb*6YP=aoC)3ROV$(2x)b64v8Mt_!|SOUh$55*otHpof4pdC5d63 zezT3u?>LWfTC4$iS-Vl{lAfaRjNnCUQD;Oo$*!5aJfywr#%Eh+c9GX;ZQ^nfg&$R` zn992CBH(9V&nn?BTbtiLlH8=x4at7bL2vc4+`yx;EbdB8m?iN>=e}()GRusPv1T@# ztdps$@s_n|ft=Q#<(>vna)>p3@>E#+MKwEv&3y2 z4;cj?yZAYKYSmLb8tIVFMh`2?$tV)kecr|s9ir5=xHdN#8h8?92Z-wbE=ILB^m$4NERxO|l_nm6Y72yzlJUzAlVvF)YR6%1aXiXoqB zkr*PM9vC^6%2d6iIO}0ADG(n`$C zwTCe;>(6K8V-0StGJ>qDzAOS;En+5*YY#Okj-(jlNSF3n_&}@IA_A`Lqm`9fAPGay z_rtF>JDTVEqUtjK^jI2=*59XJRhBHx>-`rRTJXrGc1YyJp(`(T!f6+O`h_)E$tFGg zK-vzvmz%D`V7#O1)f3&gV^Q|A3!-{Xt6Rm*AN$_TBHa}nSrU&%_S9l6DOSW=F~dSW zp|#m0IFh^Tn1meuSmROGty!}x)OuDw$d{Eyv`3sS^74jk!E(0f=X*K3N?z59N8ji7 ztBAZX2ExOp)_y$D9uh335nt!717d&qB}*6YW>?+Kfs&MYo#d)fzCF5*F`czni?EKd zbdYES=JJ)fajBg}bmdd;MWM0eWE~4hv^KRaWE+n2uJt0D;waR~%F;0!&!p?kQ|u?_ z^hk5u)7)#;4k17E%1^M9%f8|XD_NnP9M5wOER;p=st4s^e37g_MvNhe4QDl(_PB^c zW8zYcmcz78W_&iU+S>KLZAnIFRv5E5Ijy~bIZix`XZQ1|(OS>Loz@ufK8bJ+b>47? zujz6hD|eMwW-rF%n;FUCu`rE28q?$oBl1LKI=g0xT%~=HGaq7r_wq(^vM|e_?e|*E z4!xX_FX1vG3zM~~hb!%~xtc0h%cXRmwnG|6t+)DV*gK7I(-w}CYqr`Q8_NrHs4B%r z@-P-^W7t4jI-nR@ZOK?g*Vn3HT-IwNQKYLJkh$lrEYa8Rl@>*2XJNWSyKC?Ga;)-% zr8#V*qqgC#1GLH)rjN|4MxXxZK`!#IbW0>c2#@tir~Z?l6*8)-Aw|o zTfs3@JhLd`pwelYh zi+Fuv#Vg+EES`++Wqf(jNIV#K6`_%}*NOwEd>%6ojS=tXUV!G9HG_usS8;rZIND@2 zjjfJx&5p%+jE0xibdm};MEmsw~b`)M2Z-ovfc8pt-1oPmVSUXCznA zV2bBI+#p)b>6n>EV{QK(nD`RCd}XDsVWf_~TeRJ&K7 zF`Z9A#lg{Wnbq$s7b8YvEB5DCV?_|&AR9WZ#eC6ywud=cP+XN4E|Sjir1Y8x>2x&4 znXbI3J*$)Lp4Ia!e#4bLa;6!v0PR_`jO-|~cHetZHQwnjPgzvH7!mqua~D_PSnZ<4 z*xmOY%McBB*7gm6cK2ehd}`dhtE#dG$Hm>&Eceig{l>%+9`j}I**-mR!*SI+`snL9 zJC^9Ger&!GKEIUB+BzFW4~#KdlzKk5zrn1&Y+sGdc6TACiIg&d^sb5r^GQo`5mc>% zB35PrR9;#)hP=F*FIKfCH9q1KFOy-OgXL%L!d4xisnKhJ=ClHa_G+ss;b19iyk;@3 zw3JKP9dny=`V7)?FW=L`{`iL=#CT)t+uM@`#+#v6q_;aa6W6USh7jx;GJ!8R0 z^44yZ&dS>1AS143L1V&gZvJ9*@_J7P%VE`~g}3uoOp-s}vfmi_#=k~%-6vaQ#28)G z&NBuu#{WC`I^NO_X?YnQ<4Du%@IGE#8zn0ItIox=-sX_SR=mpWEXtCyL0k3I*!cx!I>VAqs!q zO@1;&&8Z*9a;fMXXVviXjLzaguRHJkVm*(L3j@^o>@wxT7W`%;IZ2BPJs}~L_hVRF zJSN8|dzW}fmb3ef2q8KB&Q`CT)#Mtl)?UqyiS2-jNH$}+!GrtUQ1+z1&$ijCri+S>j9+E=O zO1)w99vg8}e%Gdt1Tm8IG)y0BW5@Uqx(|~q$^ZJ`${I-hd;N}Tl^CdBo9pSzs%%OA zB%1GArE=xCxnNg&&X$dbM0=k^l3#qYetK9e#>J!S7EkQsbbnpc*%8!CcoNIpIoIu9L)weI>J;vyo$Q9!?LlB zE^=B+*~k}V!(tZWMIN5WIxBgMB}orC&O=YSSYcywT(Qh?HCAgOqm|`cU$G%lcoBlK z9!9um^HdYIi`b*BcYfv{BzI;fXFNoCMB78PEO3me34BW>#xorrN zitfob#vMJ?T6nuQ=CnV%Rl_{Do{NBEMsq|fCe?azSB|MH=O4DM8S^9UA?x#RSyBy$ zB?)8MTu;-`@U`Tjby)P6Np{s%jQjT$G$0AZFkd@5bQpUYC0)SN&1Lvl4fJ5P3@ zi2+`Wr7=?^kGc9|-*rrdFCN8p*2IA4>2?Us+6dL<2Z~k1r>aBL*U^aJM^qsPqik)F`CAyr`Rkn&V zqgvnS(RS{XSffogWZl?oKRbQJ%Q5jzpQSl(#1xF~<%-;!W#S~S(8U%n*z*g?cBam3 zn-n985VAH4m)Y4nT{K-i>Nl6&ryrrOzBGd-M~qI2@p;$y`I&Xq_&k)gM&K*&R4@6^ zef6kH+Dc&Tw6K+TX-`Y_immh;o5rqu5|xk0#i)MLXv4w|*NYQZ{Ba^P&ib4^w6hQv zWA)~RI5D;(7V}6gU5~q}Vp$R{qhOz;?)g0bWLN*4&a#XCEXk`~*Vg{4NZlwhPbR8g z+MvarxGC0Sj68ZBET0FA+*6c(KE&g!rY|qkCRRyu?W))2kV_Uctvxi{pnr-g6?$RCu zr%oQBAI>pJzGG2+)+~$`C1Eutq{HoVmH7;JWf7FPq07uP(Gg2fs{6)y#k09E^qsgK z7Qo;ye%P3u7&#-O$j(~Y;>ZXrl3!IxUd-m}Y{E-+tk0~N>a(sfIi8BP>|Fkpk0gjE z2*)5cVAAJBvQGtIH7>ujGRMZzaU6|rW)`nKpJI!4hp|PZk+CKsW_!}~c~-_}(KNY9 z(e5Bgza!3zPuNLq=SO2+^t`~^+2WiJ=)dbhj@EKzd>TVDG-)qOYad#3$PHOh0YesJ zAe7;7PJdVUFDLxkV;(Hh=m~MMV=zo);NZ+s?Pgp(ipy9wGR$(I`Nq!oo0l%1LF%&x zV0M)a1N;4qwFKrOsa!E53Hh?Q=_?mk6<|p_&E)Kx*m?E;W)XkTw<9jeF>4HXr;}~2 zSUxVUj%|E0j4tEM@x7dp81{|<<9c;ne1*1%H{Q|N6&BpZ6f5Vke%&K0Pp^~S3ea;! z?3>~DC0Q6ttc*OIYTpau50+brSZ=CK-zcGQrYInNkFs`tg6-saZlKH2>`fwcOub$ZHZ zh*U2#RLkkh$67aj9NKC1&19Zt_c$v4#yFHGE|T134eY0mFcf!mI+Bvz?#+wyS))xX ziAsHVWl{A!592kScw%UJci%c?A6=#J&I;O$GW)LCcV=UjK-ivth_!o-Iq2BF&v)1f zXHg3m1|4i@bW+2iPfw`tY6JVP;@j-r%}UR7Vr7vH6KTcUIkQ$)iDoF%>0Lg!BO}i9 z{dR$qvR?D!$yFK9n8mfb9kE7ZpE$*!d32pM#dT2!QBh|E>)6-M{luL=#vG|(DgtYt zjrz3jb%?vz+MX_Jim5Vw(UKR6C~aXkThDfS=8uPX^s6r|m^Dwlk*ww9XtAV?yv4Ps zppzc{%6ivjbL}(@&uKj=r*FgwbZi@^AuY@DUolHs)+cr2CNYc1Gi&_1!vmdTlbp$v z$5!35FVu9Dop4z#dPJmPm1Q+SXYG)fj(FMtqYds{X_Uge$kv|TC#yhTzNmy zG*{%ai1p209dw^3%$_Xc^1lA0X)A7P;akx=&uBF=9pSGH1|Byfj>k;%V--hqs&Hl$ zUDZ45F<*~IwIn-9^fDus#K6_n(yYzQpCN?J{TWByV?mp9I#+v(Aleq$)#OH!=Lloh z-NR02*7|S%`UV5$xSeFVT5j+6&Xch z94rpt&@VsChUdJBiN*P5o)Hkwr)~L1zx-i=mOPv%$Y6o9UJTjM`rK`D%l&p*(6J>= z$;`5l_icUG&W>h?K)UmRY`~pLS77} z85QhXEdeUSn^#MpJj7)|8xkAoIgLzeu|;Q&{9CRH|&>M)b6~`MI4h^)Qah5IF}ix-Ffs7avZMd?fRnrxQ@%(VgeSPDSBcepA}`H?vu9DHgdDF zJ#Q?KJH!x_8M1VG(}MxOdl)*sUDH+-gB>za3s14SaYh?A33POA{VjXg93$rPv^hl; zoEW8JtTn&dO)~phX;?CC`(`bq<~mOM%SSC)#fGy#`(uMlT8c6ME>W_IOm_1%J=v-^ zE3>}wr{<(O^JhBEH9N^#%LGy1XHsNYX{I|=tYw=!RW01k)t#b`WoaD`@Ud97nGLa6 zc9jO>rwcYc4(-@*eV%JIL*?Sz@MT~771lv}@^@xL^%&3jeZHncEQCJoushJ-~Fb$Uvr-?|K^vy?b>(#y`vep;~qc#*cW}mkALjXJo>+V*e|{R z?bp5XkNnT~dG&j}`n~?wBYx%KuX)(7J>=IP+}~>-^cxR+-2-0#9b+m}-oN~wuX)&O9+ng`UiSbJ{`dX;{pS7r{nmZGNPN@1NhFihJMQ7{E$`y* zt#|M5_wM%gfA45U-cj=2diUpj;kVrOowxqblYi_9KmFLByZ$8~`tu+3iy!c^N8NrM zhOzRi55@18#mV>>x3T-ONB!LOKYPQ=9`#G_|MK^H#Uo$-e*fcr@%k$d_xEcL@%I}K zeC>l?`yk%QKNxlu$Nz6`$E^3a=eGNI6eI7H^G*id$-p}q_`@>r)LXy&bH4o8T71=a zz4mjS_UZre`iH;uBft6wf8w9~%t!q8GrsEDAAQzO-tz7@KKUho^?jc8*!TRj$A9a; zdfS(N=QFQ|H$vVuA3_Kusr_R-(*kN)mMzv*v1<$1sS-8Vn& z_MiFE&wa$Vy!>mw{)G?y@NfU>YyZKAe9<+3<+pD7k`H|8^?&ZYUU1F*ZoB83|K4{! z`R_mT5jTI=DeLwpH9{u1y_0k`G^0$51&)@4_Kk)1qzW9YteC)G7 z^Z8GF(w9B%*Pr((AOG(^>Epir3xDW7fAQNs`x|fjsayZ)yT0k)-1K$-`HMdH!Ed_v zb6$D#H-GvM-tkB8{;GR^?;Ahvmn}7L^Cq3x_f9I2K{KkLwk^k@`U;fMw zdHKWs_RF5|ao2qDtzY#OPqQ`qori2AcX@x#6F%tn-+SgY*F5LW*7x{??!WifAOF|h zcC^3xQ@elBG46NY_O@rf>)nnW?9qPvo$bfo@R{!4@B=S;uwCQvEOYJio^|at_kO{X z?m^ufkH!bzDcjpO{n*oQ_I~qi-}2E{??3pDrRSRGy!e6S?0D{-7tee6Q!aS^`uq4* z!g+k}^Z)sc=iMKC_4F^e?JI8kvRkiv>gQkgG1q83~D^w>|m>5o6@#v2}U!$;lt(U0-=(br#p>f#$QVTP%H7#-@O3T!(e{;#g$dVlr%iTvlMtw8la10|BVr`9vqND z96#d7;)9xsaTX&hzVg?DVom-Z_y0Wc7a6f1|N8&GI$~dmC9=R@$iH}T|E2lsMX_hu z;2m*XiMfiA`|D#dief(@L5&dL@!vQQBQEyW-{=+7{EgqgaVw7WzZNk>k|1A6u&$V! zI0pWrDVF*-BE)DSKzhl4<5%3u#P%Wnt;PMn+K6=*W5faN{~N!5eJhsvHzoxC`b3P| zUr+zFUmRs(^u+r7Z6D$*e`8O~LEN7HLsoqCul0Z9^1thUqeHBdSdzFkitCBJA#Our zZN$BbI0pWJJfUBt00zR&-6FODp+wVZ$P7jqZ${)_zI7A4k7 zeDoK+zf%66wEt`n`$g^sf%unJ>_vfSSu`zb5oL+) zigt@!L@FYRuv3^Nd?~yuJSV&$JR^K0d@9TnHVYSpQX)H1xahLzqo_ed20dm5cmfB2 zlfX;h3y=de0PVmZUfG-dVID%Yl0aL&bz<|h3iAqFoMSDcvA{o&VsMjlDf^dUSNk|s- z3o->Mf@^}afT6Mh#q3YA5EqNk!EktVPgC;>#k z7RW~kAL0Xj2PHurVUJ+FFa!8*cov)tw?ynfq#zm)41^-m1sROohdhY9f;@#hg4~L< zMq-gQh=&LbLtk8t$jPdy#u@B< zDd9b7Vrd)InBl;=EPz9ck)Nd>VXG9HRfSq|2I?k?mOR@&#}}?{o_U*C0mP6y5gpNQ z3XV7J&e9Uq3_w>5C^9#*H3Tc$`VOe1{p1PB!N6)1%(bwpi zbW{3XS|U|{HEo$qQ6j?^`xlbuBxkNnQpWs8Dh74_P=ZzZ7X*MEVbWZF^ouvXzwZag!D_GMX$+(M|E zgUsBT+&O+=lrVgI=-OcCfX9IPfbPKI0oFkAVEWL|u-@p;F`o&ksqyK`*`M=I2{#uL z$QzfK%Rg7`X{q$(H58M_tYQVRv)EnidiDi2oE^zJ&WvU#t^GrjqPnbXTZ$pOEn*1W zbN6RFr&!~SqYs8}3|{<`(Z}hz)NRtWuG6cds(o+!p7!tU)*ZM`tFF@S)4gf^*ujxu z{@B(j>>QWiKzX|w%TVJwibCK&BMFjT1oo1jNe+kwY}iz?KA$mfWY^LDfMr-(7><-qHJ$pJ$f|&nbJUH<=wgAIK>3 zy^IguQn^Xvh92GMf<>pT&Ib358@=FuPlH;+s-pbk&Tnv2QvNYzDyzmcY_{ftG9KVlQLnTv! ziQHNCq|?~!Q0E`BzMk&cPWKLMyH;CT>%P`Ut+2L+w!!vwo%LNQJzx8{e-ehUqfO&E zQ}1WLExcYlOL1SBqMlr9W}-My-UxrYutZb`JcY2%FR*C>6+bl^juQqM}~NV{HJO3Rt%7fp&yq(<$g^rrM?N=s#1 zLq}q_Z{Np(#E}CN{WJFnwX#hg<3saBxVVpwIKYkO~lhufI9UBIDG zhp4`|wfLGO`CTh}g7<45Ja@?A@S(%-!+M9l9Qe9Veh+Ntxx^z|A+hQa?4WJFSsrhl zZ`(UtE*m}4wN~#{xP-Bk6hX)MY^DkI2YJ^*(sbk4?x9QlGu^ozQ>|B;k2Oxz|5Mjm z8&bQm_HwOS9lAcUVXCpXxv$l{qonIv@4i1bhjK>w6Hzl+^D>L!lw&J9X;O^4tXfVD z?}~saQ~@9V*CF+g9LPq9!vhL%JPZ~m~2vtwqD_W|3(7mkJ>KXO9$ zB;w?j6DG%fj*cH1-5%fwJ%l<0^-mv^tkY z%h`O+LlJ%W)i>Dw65ZZ~#!1s<`(O%Ib;ZXs= zx8*vphZ&Ldd#jI@PLm7>y|Xb>l(9X-z`&he|1Mm+ZA)^aTs^DCs=A^wvw~NiS>98= zxgxN#vg%$9q3&zrWXrpbik?FQ=STTdeG44QK01m!05qXm(TfVw8aDdjru%GmZ3uS9 z_`V6|Mbb7`C-QbN_eUM^KJnr7-gD2->s*9f^1sw|G5^A9@}0AvPstz09X_!yZf9{q zPOMM(^MDs#XIxC}d(024<7?hgvcvXBq(h!?v*`Gx?1juJ>PXg~qHe!-)8;qz2{k#D zTgzXR>X$ed|1Nr4G*R@b_;U%ath0Qk(xqm+uCB4aMX%#^w^2WF@ZIRiNrzd0kU?@- z{zUCqt79GEmhdx#w!jXE8?+EQ1N{!wg<3&Sz(HXO|1=lFKF)YXd$bZm!7YBAx1PzK zuo%rB^z9dRlRBi@PBrT_YSky#YScJZf2z7rRa3RI`gx6Poo>UerfaPO9YsB`f%=iP z$PZR` z=nUjF(Is{&RfpU+N1lipHtUb=l5Uf3N~ybCy;MweVtHYT+kXeV_I^?3}*j)%_l6DpQQ>5kkM;36srye`tVL{ zH_JEF*AOeumM52zi<^t&i&_ik3U?KG6kjTlC|fC)uX<49SZ~tg+4`ab((|IUkLF_+vtxue9;4>t*nH6ziO>cs?j~mee2h`4ts?Md=ATtIUGN|eQM98 zgRhQiorIooIoFpwcz(kL)eFJrrIOXo=A6ntZhb`mz_;CLNmg4EqH&>@{BC>1IiYO- zXR4@wM;)qgQ&tVxE=*_Tt%??(&t4oa7>w_Y>8NXdT;ExJqT)`eL@})(G+#c?FLx}5 znB$y_&eP6+U$CPnxum=7Ol3gL_WF-axVHD5F}>)4rQ!1N_tS~<+KU+!&DCgnFcZy5 z=6x0%7SRAj=sYwAwil)ky9&JtSr0rBX7G=50d@rAJnh6v1Vv$SaQ@*;^rXp{#_;-q zi+%L&oX(%^wANcKr<${y;+mqHN}BF87q@I}OX`^EYUtG+SRB@zD45A4kSMokq3lHA zb2vvT8KNV^eJK#mL0XkVLCp`2AZC+aC8h)qN)G9PE7c`Kj~g z&mT@6Kbw7;f1>axxHGAA?ld;V16u@c*I z+o}__T@8m?6gtS=J^kfF^MQE$?Q-j+w6of_w#l{G zwq>=wZlCJ-(3R5@*1vJEc;wnd{Y*F^kaC(TV&?HbK$|7F=)DT#YKL@1MxQKA*4Mk} zc_sV53_TgGzBMw*cX#^!e-8H@yLR%;X{EF1b9>KOp4)d;@{G!cIBIZ1PitFIqf+fq1+4Ua z;rl#X&Qj+3-^2{&&#OQ8{%rYqKO^&(XQq61LT*$3tD@_rITg5?=k;ODD(!OJiv6ZT zo5m8Sj?C>Nx>HtG4$wa_KXSbIS;F7IacCoK5Pk(Qf#^geBP!u}utaDk&?kJ)_vYrZ zm}~23>sOp8zKcN%2WC^J*2XW7S`OAY+zflk3RdsOF;=xEyvbrgLjUQt0lu z{T+u2jv`L9os>SEdb;cMrqk}HGESU6)^qsUftEezca$YukL!r23Ub-B$IZiW!Yai0 zhYnFi55HF`9jd^4O^>03&p(~898&K++OFGVS6f)|xMaNGcJ9M0&ad{L@brrBf4-dn zx5aO*-{sP4f7bsp%xcc5%bzRSRMua4u{ONXsnx49q4(uL?TEzW`q|BdZDjYAIa(s~ z2In*%DT;%*!6@)`NNrR$ij5jYT|(s{vk@WiLTC?AB|ON7aksH5)~M9=D|;!WizvdA zIfEJYBxl@dtZ3xk@Y^A&p_ak9!K9%L!{BRpg-1gVnzBnfPTI zIhxg9-MOxXTBlX@tMp;vaPID`bH4`Cv%WLF=BCZ0-bqbOwMsMn`sQ2Wj~hRge)nbx zbA1a3N}g04tx0US+>+8U(_=I6bYyKJcJ?D-nmoVKPCv}*bK-)32oH>5YJ%OAXcJkzCHH=i@atCz7G&7M@SOHzWI(>VCMLg(WKGD z#c|znjq&s2787BUO;h$M%p^NRnl?Yk}A*`ZVxSy>@gQM-ZpTj`)8|p1Fy=VEW7Yw zZf$0GM&ysYug_A4KBs<~{Fw5w`Q!Odk3MUpqQCC?j`^wadvi7;?^n_HvdSuIolEoE zc0u=@Kk$*v3Cr0Yf+gkg>X)_WY zKd0d zL*2}{!if@a07tk7YE05XMh9Jrp<+jHQTRvro%ki39ZnNFgAS2>CjCzG1j-Uo3-t$T z1opfvwkvah{*iiZC1r_3K11?e+(E1%Tqisva0yjJ(&7Pf$kM|V4H|-B%g*E_i%!96 zQ4TT_*gAzg)p;!igM%hDmb&)motoX4-tYiI$hFA1*s-k#6L0QN*zL4;U>|4yqXRz= zSR8QOpS}0@Zp==8;*NN?xWdTyA=>`-Ub8MX>(^VZ8eY<-DZAqCNVY-n+^aM=xqY^E zOk<#;E58L&|Ge@{$>)6K?BxuVADL;tK5Kl0zCZNN?``fskN#o&)BSc`3hTY@r$1jR zzM7<0{L0Gi$TuqaP~la(&{))VtULIR;s|GgINM14y%a&CFrq4hWwO_C*rk$$GEhtM}SV54ZrM7Y(LmoUA?o+t?+0L z;aBdD*|hVYPkvy&8~P{s&BoV1UZuUly+*w`{ZHJxU+)ipx}GZiz53@&rgq-XBA;^g z8cM@#>tI(`fBSI5MAK|1v1ciVc9zBEMF3mi$`b#R{(?@zb;?yKTvqz2{8L3oHA&S< zwOWOyyr}d_QBom5ZVS#GgO<&b3X$kSY=cb$SB0j09%qS#VeVXG(i*ALs~)S|717G( zRaL4c?JnJg;mu0nxbaOz3D91|HOV8gcW{FW-l~(D5A>pqOw5JW!|PL=qupn`BmB<< zpA1Jt`@|`2-IWlNSdx^n-Czf1$Nla5lP0&7#_Men#_WvT6j~DS!^hP?tsCpVS4Nh&<{!!8{A~J$OilZklj8E$=1uvl zyqB9^db}KZIr?h>$A;Cu;k@J`x#yZAqVH{?hWc*}=FfCX~>;=v@UabHF z6hf~fzDmqXAHv||$cm$?E1JrBzJ~WrD=Znd7)M1HvRkT`jIU3CTJZbO{P4ucZ&9bC z`=hI(Eu!_K(jq>ES%ugK4*RmbvfKdYVf%wtPfgC~t83m=s>2RR_Cu?AnQNbxiWgQV zcMU7_Av@ffa%_FC{#|K+b2qc0A;eD%uUjqlsW zl$wuPsr}!mKfSY7^6HCwE1-1|&3PSmec3}n6H~J{7Hw8K*KTkHqSJ^kQeQAzwYeVaNt7Xdpi&N%Zrc1_Mh7SxddbhPZHSlU4$|n@k z@KlViY@gJA316f${5+HZ{3CiStQB|&U;;UC6kRBo5W;|?5Ji{>u7SEB3CPr=U*mqs zS13uT`DlL9Vd=XX{m(SpqS`vuZkt2@24xqf>u0xq_dyST&)c3(o*z7}yW`xHUHhFR z9hdBqtk0R-82_XHOY4*>Pu>F)CFu-KzT`9GRuQDi*)QW?1}A!g+m{>rYbMLJieKcp zWtnB{`@WVs@yYxH;T`sE<(sb8$**s`Hhtp&_DlmQF&{m@y!{%SzWsMq&f&t)vZK}c z4Tfz6-3bHgWBlnw0(l9whT+-+jz}GuHC(dNr22wR&N@X?OUpkt2J3~6C!No`D!Dni zOL|0s+lafI`|QReuJ4_nZm@93up6>owdgf{YZPs;rt?)ZKuuGbE04hIV6MtAB=b=J zASz&{&?=xr)Gdq<@&tg;URW-?Ai4;YLd;Z6*G zI`8yG3`PvIjU!F7&AQCLSQuDtv9z@;wiq@4WhQTGY&@~fML$GGsBuK~f?^21S5`w( z9nKIw;b^bjSzaN=&323@3@P=IJGjk`_32f9W#}Sko>kU+@GT(rYsHu3Pq`nQ-fv53 zeK+=QQ;O^R)DL$*4Sae3wdqIrFR$$6e5sPIiqTq3^Z5>8Z|=~Qi6e9ONxxS4Okcq} z*n*@w)>2Vky27T86cSWxxpN+n`ejogu1AGGD0U`dTehr&Q-aVe% z+_PQtoZdQ^+f`ago9{7xY%r;#uK7e&TB%6x8a7$>vy=$+46y@t5>hWp6nY7E@d>;) zystbG?-Jizuub?*qzCDN=EKX7Bncbo7qSrSO*}*XqSCmEhx#SWRP9%~JN0P>0fsw_ zjE!@Q2aHRM9gKGxtvCE;(4u!&N1&;wKBXL^kc^9zos+PDhl|X)?6of|_N3vt65foG|s9lDqO|;VXS20B-4>ja0FBi*eT@kM|g1FX|6rjj(d|U$s6Yl@r{KqMII0Z zm?XjwwO#VPG!h++t-{MIBq+UC$x+MJxTK|}^GLTyFGD}jAj6>4;F!UZk$RIgC-8tjks87h6)EbUbzO`unP0b2b4YS_cgyz7@d@;c4^RmT43-Ny z77`UQ5X=nv5C{uk`)2qcz4YDLE+02w*T>l0uy|?mbX}V6Z_RmCE2TGbwpfZxzoZE1 z0iT9^5>*H!`Ptn2oGP{xo57N0N3*HyT23!lga1U}Ey6)0Ve1eWzj57B(Bm7{%KM^ZOVccbpIj8CS{GW~K&^B)v{ESIQx-*C0{epg+;<4DWoxA{!+6m>oOp^ygmm;N8F zNU2EUsh*zkQ;UCW4>~ru^tvZ{Kl9xb@FZw=NKI&Am_@i-_(Yge7$qbj_(Y(Cf7+&Q zuV3z4T-!mMtZf`EbWG&et?39fG*sgh%kiEVw)B_;3*iCl15$)P`AFVt&JA`pOP966 zTwr>!I#{3B8Jt;e5`S6HBzgzQg_R@NC{?LlGI!9m*cSYVe5T?#Ww`2owU_GGHEcCg zH0w2=X=-b3(QsFvRn<{3Q0kJ`$J=A(q+=wm!S@5I{7#gZW4cHzW9NHf?9)2<6Ys9XI?C>99+M%0+bpt>74f>RO?sJ=TR&;c-GqA##^%>^q zJ=S`tmZmfedbvX8v}7>y1gr{(78>w9xc{(yST@Z4jMcT$we~d=Mja!SS;B&Hu5u0d ztAa_<3BQizZ;Z@fq?FioHsjDh{d`wV!GnH5v6LHBYsDsvaucO45n~ zxmP$cdP4fO1b{GrC=0sTyVtr`%*dw}N~h7|`-i6bE_GSAnKil9eX24kmngv&?$4Xe z&dMzMrJFIGF8cB0$JrlKKR%>S{XF{XZstOEMcz!|&QiYCq4*RUI6|OJ650|3!UE`&mt8tA5-FDXTf@_h-V;`m;JMe5sN|<@Xp-9!JgHhg5 zIgy1Ck>T$`j|F1_*ZaBqjCmw%eB$(d{Ue(s3ssXIgXcPjG`6W6Qh1MBlRYG5g5tpp zA;*Q1d@_d*zDLP3@N41pNm?$gm1alpq?fIAGfY`&>`1N-A0<=-44@(KqsT83Ia0kc z)##tteR#gyUWGKpw@L?;r<5&J)Kq$uZIpwQv=!gV_v3T0LFhZu4<$?yUm>l64$dov zBejL%NX(s8pZsUUVxXfZz2jL+LxW0fZsm=#m&NpgJ9&q4u4K*qe*G&WLo0*!(=%f* zL-=cN=H~3@x$XrH#jncjt4!YHR3WQm|rAAX*TThAWB&2c-$qWXBwyV zOpJe9kZoriAG`K?wD|b=#|J?|Ey9-~Y@?*3_e3W|Pe-vLvm@AHD9j9YY3ird zXRCFqj#N68K+{`0&(LGFuuHi=_%*^|Kn7-o*p5n;d?j6zo6bdKJos~f_y_? zh3|`Oh^mNQ7vmb!6fKG>iPVTt2`dej355EUdYgM}aox4S(tghBvKhuGT`y3JtJkd=sY|rCYg?Jo z>~QWG{%c_ez=RqjHlji$U8SXE8_?$1x40Di6FEcqC-NEccje{ex5;hAV{oT1cVt7P z>m?Y7Vd!PiGEbdtwT50DB0nRz%&ty+8#yu%+qh`3`aob(AG7 zbb+6j`hjgy>`>3w-DgBKcd>PMlyKeeanr}p|6Gt~==bn{B4N==F|T8)V)n#*i@p*y z69EZ-8zK?J_N(zR_S~~E-pO`-m-R{WC8O*5SnYJRol53%N|<%h5vWR-4*))pxI0)Y zYbCV)Roj*6r9p~161amEEf>sc~z7w>WgX?m0ZLceHsbXhDtw(BN!aVJQ5WR2H^Nu~R)ycfS$S+}k$F zQQh^KN1@LV|NfwYP|Ju7Q902wF?(XOV>icU#ypCKMQKEIhZ+Xk1Wa#=@Ver5z}eQJ z(Z?K|#?j~js zH5TU=NhD>;mnF*;RVsw8&G2R2;Z*Zvgqwg%(6{iP$cGYfQdH@9*%#Rt_hJ ztHzpRLoq7oG;q|bP{I@W0`?S$7mRZ}nDMmZ%aJ6j1;otAc+qgipQ4_H4*%Ac#>aKn zs%t77${;1EqC*Ap`5Jkra?Nt>bJKJ8kLUyez-wz&!$_ASp6%Iad`6Ep>xdlQ64C_Ai_^xqb5b!LqOcPo=K`JlK6|&i=elfhB-ut<{xX5B3)K0guAqER&J@!nm4nQL zP6s1Rlv-f$(77a&v}qD znsXudR^EJmYGG}$X&ItYt0t}faPzBnbkD#a`bfkSdA^NYP9?F_g^BPCDI!)=$wtFk zk7bl}=%4Xnd?rTut0a+_Si{*q1S5QL_;{!#)O|4&ZFE z^Kx`saC)$Q$vV>fgVCa%i`Gk3wBlo&oh(;^07pS$1#_HyW(8f1n!o&uGDSMQ7(l#6 zU@kN)%r0ysFbUH{Wzqw(-IBtJ7B!UqhQVWP=Z^30g%{Ue8TXd<+KT>)U+YyOSEzt)am!-U>yQ)B0By`QDPCgrbG5EVr z*tMfwsfE~psoPtPu7sC6m-ZFs7OfQCEj(ISRk*ikUvYcM{jyILs?}4qvW<6Ic6QwF zkr|j8;Z1Iyr;&&Ql$>c)XNT_i!njiJZuH_Emjemi19_Q$v8@TNiHJe z;Kv}rLNYg+b&vjOCjf(6jvWqv#qkf>{Q9wqU?gGeA~Q> zx!7DpZd@)u7n{GUz`AH-NlDqI$`3X24TH_>_8mRi1ID8#r}*=E21M{JKIL^2}pgKtXv!gE7k1giwP z_^JB5^&q;^H~g``Wo>Ex)yQ5yP0L)ZLNOeVL3c|wAci1n!dF~RmhIXu>hSU>$_El^ z@jc z7t|Eimfy9jKWVsN!gfxyNLX28=M-H<`SW$q!?%QZ<_(@OV}A*GMhv4~sDBfcbd5+fItNS5St6zS!z zl?Ez-zK(g0P2vU%`b5^ybodg|Qqoh}O%}kUV!1d=IcfPSc_jr$1(d>5`Bu4d{8rpg zOr~rkIR00UcnsAR?dQE=U7;tfsE`{LuFkBRU=6qb>F?opY-wF;EUEibZBW@;R#gHo zPAhy`FqMBV|8YJ&zq(+ka9^=^>8)~|D$Uw`4eBkb9mzc=U<{oB-y`eEKd42lNdXe> zCAA0pQ1PMqWnE{Z9&>x}skYv=)&sg}(tmgG*|2qyNzr<-$#H?3Gd9283~ZK&dlZuw zbv&Xmv^VIIKgkE{iP%`P;h6oB)qb;K!(hE8%_LQULJRJT>@Ud)gbQ>?_=8u>mScXS zzoJ&J_$=d=tSPU^TgaQqKgppK)ur&|cPs8x9*wysVp?$y^YR2JAPV{p-i%~P5T(Xs z?xPj4Cvi{k$#NR0Fj>6xL5UZL-B7kLgm;Lwjc&d&LAtb{ zGE+F7Fs$)M&@BSj2YqO;t2L-{E-x(EUX)zWoOdJlVa`%^UUqkOc#diA;XHmmP!v!i zDic<2uT^YRZ@t=S+-E*?Zk#<+MtryYZLOL+4`5KbvMzGUDniZw>Elg2EWPa39AjMf zc_{nr^@|K_3LXwU8vZE4Bl2jZUF5ZhE#d8ZXy zU`_iL_)M#iJC5;`wnX{Bu89P^_v|N(T$%y60&I%xL>eNt6VQZ@3pW=s7K{n=gk_=~ zDVv z(MQM1Y>*m3nIk-)N}>!Nimkc^U2P;EB*@Kvn}`|#2F82pIv6bujrFz9sveZDlw2q} zSnxg1Ay+TwU^XgSHv4e4NlsL5XI@SLqv%fQ{ffTo8}-+lr`jL%ycif6Jv;45@L1YM zf5%xCIU(=LRN)EA3!0t!$tGM&D|;KKzKt8ajC?x+c)_hl(23KI7N9_1+UPL&6LTIn1NeCx&<$|-&lgR zXS5ru15Jm3!nl00TqUjqvt71PY93Vy-wml3a5+>)E;Vea zlNd5rIvGCtXCS5bROgk}wno=F>1s&D_EJXCa)EVzcWz6Le$H_AYWCioO}Q8HbPLpr zPL#NndsKDQ-f1jvb?8F(yAJ=D*f-}x+PC_MInTF%-IeUbpcGBi^>q1$Ddw`a4vxC6 z1s+_VVgH@MN5GaA7_A-~8)v@x^5(6Z3*)k4)niQx7icDIRT0BBDC0Y~j6U`Qt zNxtM_%C=>{)lk~qwLzvM=QmGN_y`a{JrHkEKO`HaAIk<~sA(lK$d-mQNo4dqvd4fugIs%pO?qWZ}N3L2hohcYM8gA}S?oMjo*_>T(RI^;cFZC#96!hlV=GJGoWNBxOWim2PWrbzG z$g$0HFL+(FxAbBKyr!=n)AF+8a&O6?>$vPJV$o^k9)rZ&0d197k9nrhs8!Kg%2PF5`3v4nG@(q41lBH z?%=2JbNCNQTH=RENe);Q_Z?2lC?Q2wMtL-Z7 zR~q>>`D*?vnLzbomk9L{+0qjDQ_5MI9r}GH_pL0}pK*TR?&p)~UlzP0{9V)`aEa>c zt-|=81mA5c+wLcvj3;a%#wEvmk30}IA0+S_@jmB1=4|M&(I(bB+$dgeujWOSkMffk zGwEMQUnp9r#tmfl)1Iw-qwp3B3F-6Lx!jrBY5a8eRO6J{blr603~lzp{Ca}z;x2O8 zlJjaCEtWxLUFB*BQbZcin?#A!A(>@a1B?lF2-TbiOS?!;yT@@Z>Crg%#dJEYF zZwgKnbQK&ZyjDakE-alYKUfuB`?A5l#j@jCkL7^LXz~Ek4DiJmA29wc&^2sO1?&c10i}5GSN3k$dys)@sf$3Q#CW}IZs0BB9**nxn|XXew9(o zqH)%EbAnHz4UiYm23R(H4`LF5Ln4sH2tC9W_(m89vJ=P>rt_b2&Db>zW%>bdop2ec zn$S1bJv})gHRd~tS_ibzX0`X~Vbrw^TM?ZT_d3*qq+-Pb;JCNyp8uCUE7M z^I+V_$oQ-2*Yo7X-OGk_C>t*@gYHD7%8cT)mAut=>FiqPY6@6gwwrZabs2Qu;{DtA zL4alOw$Q-v%804R*HI%;y-`k4+anPXF=0L-e*)3|kWH^W5pG(}@(x2b7cDr(+YR1o z*Q-q`@^CV;ZW6m;O+qbhHRBL9ap}Th&-`I9TOnbrY53^i;XnC(uD!-R{@o2-x4Q0h zjdbnq-q7RJ`>=1R|J%Usp{*l3#%@hyPOZ(D%_kGeK*aQx?N^;?YHLKsRTjVr?C_~WQsc-JG(O1xiCz0AQvv(Sv^b7Wumxm1RfAo1VaKU z3&CkBSgAN`_~}?0C>S@J?Xv2zm2psansd40*5EPZ_1H(!SKDvZ@3{YK|5N^aKVv^R z-xQx2uRf2vZX_3VCzL~t?KZ1CvpJ(C{TJF+>Lp5sa!=3;l3|Ekz=WU2ilJ+-Aj#^4 zq}hSV2V;kZKMVlTsD6}}Vd}s-5UDp=a{-i^_tD-xl_kaE0 z2l|K9Mvsg)OpM&1Jz1%#%x>GiGxZHA@cR<@St-n~Po9-~Y zqIXbhlNw3!9bN^UBdLd|0=)TjRwn(*%3bnn!s=|&l)^ZBSbp$$Kc;u7OQ!Q|yIPx4 zt9MIN^WElq&ArVLEpn~cHs|&a9d=#JZfY;1-+XY-aP6q(#N8>*%;x!af+A@@<>PYE zYAY>m?KD%4{Q}H^QQ#X37=jX^gXptpL_`A1ThS&_9XMBfQBVoa^a;2E4xWQ#tFrJ+ zdxrPgReBXoiS~x7Pn}#XTrF6gT(zL4Q^UYqEd8}$Mmp1wJ;M3U%M?_KWTCs@^T^YZ zS~C6UPq+i}E=oAnQT2~n5xOh-hYkN2W6dlrRIMhg_t9WY+7n^c8oFNKU^?)bzsY%C;bzBH~T#MLi;ZFE%x2&5B}pkuxs$;5PIb1 zsKxl~MAp=knJaU<7fupmNePtTWvf*@ZH)e$;mWFIZ{$AWb%8Tc%fc?v3%~%94S_&i zp= zGSPXfyQHUKpuY}fSY;S$lxZ|)L@}x{I&4HRv@wiY=V~CO|6W&4Crayz#woQp6}(b` zyazrTqa?dSstm<|yFu@XTETpa+bk60KFwrxb}65nu~h{%G9sv$r<&z)AO?nA;dW_$4o@Iy==6aN!>)RTXSdT zvZOdWxoNys{*qu(*eCi1#6wt+YtU(^3v3^lH3_a<1lL&`z!sqQp!(1fh#jN~%-Q@c zQWL!f`>q!PbwMsak`Lk6@}BXIg4;3PJ6;D*mw$zi5yQP|?O=TaWmodJ$?|71&g+jdIMWy@7*HkvEu2ZW~i%~CEm(bXt;i_S(v7-J~ zT|xbdT8Zkg%9L`c(j`SRh2L^!`0Lmvv`9u<+C|b66^;mmML@zt;eu_vW1Ksz5(bIx zOnbMAT}fT?qTt9gizFh0uz_$B9F2Soj*_U&E6*FvN6)9vOE0`!Fel6svWT}AuanM@ zpHeW!?IzG zux?lo;37l|It6_TI}G25&_ME$6jYl;mE>os7t+UMB4jPlRCGP&C{`0! zigU%6;x*)U%l(q8ksFk2mP?g8D5ox$fw#cF!p&jVVK-s6pc7<$WQ?U*l0_0HQQF8_ z_#v1G@*Z#%wFxfpvAjmk3HEvxk1?`VNYA4cQ~Ot;s~#(<%kbqlO9o5Rlr+j!$^~%y zLFuIEFP&IgUP@Z#EI(TDSzTSNqF$kGrCYDz7!1Y;vy%0beV22R>%-IIlljGhqe6Yq zp50&$>~Y8n#21 z3ity?z>26xlqY&GdMYe zD)I_SUgEukp=6fiI;m7CN$C^P&C)6|(K1hE(q#r@nq>xM@?>7fB*`erv`QyR)1{6| zO-uSozLg-M%utEQmxyfmD2xV0K{X*@uCpjixJPi2|Atr2o#J3Pf$Y1iQKmWb83V<* zzJ^=-L64zh=>6c_uzVQlCh zXdUz^^d!^=st8?$ltUgvc7yE?2O)wv*x!JMz&T(SumjAdP5{w42|NHkgW1=MfHou! zau?DMX8a{Wzd~71KM-{$%p3k0z6SR|yhqF;Y>{V?rARu`92JMUf%g@{iGH$*Kw3ElXv! zyyx6?+#F6KXN8@^-ptlv&$EhIFIdT}gRDdr_{GJ#%KFNxV=-Aq>;vrYY%be}^P0m0 z--b%L%DhXwd0r?#pKl_CVdBYS39o4dj2IZq^Vci2QRf!`&AAFAsyFRM90-u*gsZ5e*3c z4@Xx47RC2=H(-NKQ91=l1w>E*X{5UwNkQ!H?*1tq(kUUOq>>6q2ugRycJI!9_xnHh z8CaGf=FA)C-uu318lkt)704fSscS((5QjtH{07~swVXCi8K(erk!Nr|axytDIjNji z;MF^D{KrY-d;ssIa&kD?;EX&@5je8~^t;z`YB&v`>%E2ZhttJb4&?l%3nuQpUH0bgV;ojyJa=W=Ct_18D`2QY*&iH>Y9=Ikz=`1`MUJajt z6X22vJ?1 z;U44~fnm%&#I*ol*?{*QK=-~k*Olu9&h+4hbN#r%Tp#dr$H8lRphjQ?lmQNbpVQ(h za}~M5TtO~yB?u4H3KpS%&=@obb%5g=&;e+Hz5@h$p-yNRyfX*QLnMF(4^TXi;T{IV z2mHn>Km{R z53EWO*uN578Lk3X1+U~mgx?L9fQ!H}a2_}tMuy>l62dI7wLzeP@EvF%R0E&PgnfWL z1;}58orfg=ghGM#fdkM!I0Vy&X~JY+@-RUd7KQ?tQ2=+F<1TUg0eWrR4sHX8eigu) z(zz)B$H&|U+{<8`1ildg@bLxMI0EDj0R;DP4{(*Zs@&aNX|5<&oQvj)aM_RumkwdU zXE?wL&1C^y2LzXo%MZRU0nStAs&MrIqKAR4+5t@nf9@sjIq-L002W!st>gaW{^8DW znOrJ&7i66-wQMq!~t$hfbbIV&ffsDW>^NS5Zr;Mz*bMd zJb=v_!xUh0K*fR$a2ewcf_qj4(0Bvv`V=<~Sc*HidOdLc65!fd5R$tJY+@8z05&iT zeT7<~TBr&tfyzOq&4Y5GOyC{aP!5y@6@$+eKsTZmsst9(3bjKc&`)4X)6h1A1FVG? zASlJ%%hlwX0gOGlK>+oO+&dsErGR@<2Yl);(9<9T%??qR5=;-=PX|~WK<5dF%ek-` zfXpO_JuEPG15^y)N8w&@Uw9JmxH1Jo|uf!8U(gh1w;;P!9} zK-Rnk{#$q8TWSCm7?%J%WEfm&HS`f^eB6dEK`~GS;_Q5NP*I!I^c1=&?K}BJWP-)2JFcQ zcyT26EcZS41Gk0S#a#hbEe=zInZW{JCqa(Ngw+F!Sp^;?1yHeuM}kQF7DS?EaJ6&r z6*vNcLMS2B5Jre&2wQ|3A`pylL=++zL?D0g*$v?f;*cdmAEAkmM(`rwh*_Yu(FiYx zr@}7-bZz0Lz)R8aB@mITVXtA=Kn^j5?F0HfIMBQN8F+=QF2-^98)$ z1istF8R7f|F?ol>0CQDIfaZS40w5d-Sl<(1aWw#^MTicGadklqjN)G4W&$r81Nex- zRAIK@E?xs3)d>861(O8Gc);V~Pr&S?1wIUT6ar+q{QwbffWSq>U66s&5qXFjz^>X5 zjesTmKr|sb5MMz5aS5Ub#PGL>YlsUV|N9_}LB5m#8FCp|Ss55NK-6{s9w-inK-B&Y z{Ou874-PP8pqRA`JiZXj9TP#`Far1>xXZw9%7EA023*w(%qRDPTtnlmafUdpK=mXA zWUDKjo19=!!|lR3&avbea|}4T939R+jygw;qs`Ic9N-)T!+~QB&I;z7;aufB2RZLE z=LbM_lY@k0K<09VqM!%BKO2D^Q6QE7<*j=l3iWVTxkA9V+(7Jn52DQs3O z?k)npvk178G++U)h#15b#7B^;S`fX6Nuc*aMIew^fqc}*0;58$*HfkEH^Z~6i}?lL?K*pV#ow7(z^B!he74Lb}FqJaoh z!hH)Oj|0d=DDFDAtHsb$C;@VT4gjxV0*mPcw($X|!X$89IW`^9BE6A8;A042<(@#R#s+DM)I(|_MUg^C66mu1gZK(8 z>LubbA_#b$3PK22(g^td&jHi20(S!o{|9RY87>~?1L8CB82zEGl zoxncJzRiBbe# zx0*Wz)R**NE{li2&w}HDHc&3g!ti1|MvK`xWG|P!Odt+!c_E?gJZAhSoTB z0HNa?Db51Bn0=0I%jRXzvkF+ZSWYZ;u#z*)Y+~jzA26>oqnHuQAZ8ddl6i%Bi6&)dS>3+$< zcm@zm0CCv`_>dt&129B+#2$ncn6pR&j;so7Mjym38-R;9Kqmr`1jY@-b%54AFm8cY zNr-raCpbe3L^%?C6kY-RI|T3p7Kl$DVg7(Au>mhC2Nr(|WR^s3Jcyo;K^|@c`A!_D zQ(XYua|uLEKllfbIkDib#(?;j1MWyEA_M$|VDO(z!LNhNnFVb0C6@@0&fu)Db=XO) z8YZ4$!ni~qrb*KtQ5PxEloj$*vJRO|Y9)OqeId<|M94nmcCs<0k8+N>kH(_?qxUkp znZvAYHXmfbjfTC14 zGgcL)7Tqf#Dt1kZ2|5bQHCQ_T8R(n5HLI|CVK3ku?jGnZ>Hj$B zYiL!(;V8$L(b$TDHm%&xvrcCz4g_HydG|C(OkdCq>U{g89-#9iAv zcW%qvhTlGLyW@7&ovFKL?q7a5{&@76$}6dN;U5jtt#h6hbeC>cvTN~QM_MyFF83Z8 zPymT_b82C}W98{4FW!$FOgCVE=ZYfLP^*~p{KbM_gxy3(#8$+ANyJFjNsdbvOL|K- zNzldl#n(iuL>z>tz)DCB9}*jm{>&@Ea|ywK-Q^lXOg5E;X8AGO8P^zgj5CaSFiV#N zUK7h9LV)`t=sfq)hxoJwy+j(tt)x&gBzc62x%zu8)c%)-nkGL@Pg@Gw-E$mwo$ws= zy%s1I8XHj(RUg}bGXIq0nbdQyFKAuzyR3cX<&_s#RIk`v=D!ql!T#Lu)2oTu@r-C( z#D|bI|4px2S2KrC*2`vS6Ga0p9bxqu#VgW#B;E_Ep(|kyObPP%Hf|NOaBhk-Has-h zr_=N6M@j4Yx2OiY+Kbi9&lBZBWiLt|7Z(-T7Ks%dD#|NzE4C`RR61Gqvck7AwmRbr zz3xe)b`!g0xqZB2v3va|y`MG68d)CuF@ASSZMJe=c*$+$Bv>)sx7D_-jZ46vCHN2_ z;w@4iX@^80Rgun;mWe^2!gvHv#xZx;+xV@8&AyFa>tEN#Ru@*3SE83EmLis9mspED zOEyboOTNoGD;BFS)`T|3Hh*n%ap#C46eYFl2gedBQ5Mb_ht_bb1!Kw7Y6m~{m5#EGaU(GD?fF+1S!in$)`8PyUw z8vZnNJ&5LC;UnYe>uThPw2QYaH?1*g+&%cMn#E5D@C=%6(!8l zbLBdpWx$^A^;%s0#jl5(39aMbyEVB0DWDh<06Z%(mVt6WMc5(jDQqs!(wTKO^ ztT=|g z>tf`>gZYs;levM}H?!Af(`RwB*XAtdEf=mVGM7qLO4f!qJhv&h9U_`~mceBA!&-PY zFh>N-L|t~VrAHNNRLk}i>J}PQ7^j)Ou?(^kcPenhdGYx-2U&)ljSPxL#@V0rN+h3h zK5czw{*2~Xv9rZzrcO5`shrxM@Govp4F8F@VG}_;epkJwTv-m|Hs_8FAEq0w>DFl2 zDF2jEmwX{Ki*|(9Gmntxwo_Lh&cBmJL>ZuDn~#TU%bgvT3~S zhIzQvGCFg_{+O=K+VMLsTONGA zI{~jlw!*PdBQbvQ4?ti2W|Huk%`>5A-<|b4+jpk-bWBouV))6QvBOd4B6>r91f24j zbB8&P+ugP7Kguwg*#BHpTJ@q_$1aAj8rC22f;CM(y3@ECF|RSHGwSubw>PmPs`dR> zwK{y2QbktDwZhMNcAs>!A7&oSa7b@WdzhA%CZFDuzLjB=HJ9D>X+F=ZaJIOq?Azzn zYU{d=#-Qe1?V}xqJ?H!E22p>0{yjN~m`zytwM<;2Z%*x8Cy0=JsW<7-OlfusXBb-M zmcbms%FPJiCOL2$cpF%)GU8f62RP#FG3Hx_Jsn3arg)L1N$Z3jd>3whM{4KhHf+0T zD{ZTJ3%&hf+hxZQcM}gIW|8tK-)Kjeee4GAcf@Yg8?2q6s;Gu!$evs|apkvrRkeEb z5)4I6>P@XITWkd!Wn6_lD}4+DLW2Xtu#quQ_hW408skS!<|XV-v`a)JMke^3#KrB3 zosF`Hv<@Q#S^L|1v)xWRrP$rER587CsNg`dmXq3+ywmQ_qC0#BJeN4%sS5b_>l%yG zQ=MajgVMj!I)mC`zSYzPR$Es5R{~rj?`F=CEYFO|w7OJy>XVdbDQzj?sWxfX(&-s( zSv@%tdH)so7dw}o{`|Yzw2s+W+WfKodS_B^QoqlT^QheT_SE}1^`$qf|2Bx*i}-Ak z5jBP0$!uZYfM{H2xD!GJ`2)F!$CbyHhli&OiAIJYlHiYFzTBhGCOe1a!d#)J(M+gx zax3XSu+x@xuD;Cl;OZ;LrZW3Zy;uY|3BfI z;#Z_it8e<;!H2&&I zy@VSHXA=Yy_Mb$>hs8!mlOxT-1wt|cx_wGK99@!+*IJ)4#~eOp7^17KF{czF(*;TZO$s;z@7^Ru7Ei$}iqAL<$SUfVp^5b#B&(x$Aa=w5#5C;e>g%Y{lGX`DR55rFs>QtG2$RHh4A}x9N6h_ZajU4eI~V_{TFf zFnf6sz8bfYwfznMkmN>fpewVKIpW+BpyFeN)CPK-kzk#Fb`l%_>@XY>956 zZ{A4GK$c+U@AT0$(=@&`(X_W|R_TEmRhd57)}P|@rVDNr2bW#?{H0p6uB-8O^T~F{ zPM=DjqgOR{UXH^1+U5SqwmX%NGkeI5#ji6U+w+jy#Z@1S7lQ1p3p zBw8MwixNYb^TzRb04(9~cJ4_?j8nr3W}+Fbv^Ufk$|>?qQYTS`_?3`Eh$B28tP-ve zZAd=k_msV~aZn8_0qQy|5C_5jcn-gT@VHnD&_I}wS5-NyzN8hj|F2=3$*`%Lj|qTx8q;M^~7XFNk(dgEeARJ z2YByw&v#n2TLF1n$v9d+M%#4nvO?mXez5}rr+I%u()3FN#>TxR^O-&WG>3!w*1Ddx zziaBR53V`(IjNLWIGd;W=}*>thI_hXnrUin%7c{Z6uDGNDm^Va1CfQ#mdL%HFI}`= zLMfN4dhi9RulknI>ha@Hx7shM-`m4OV=pGmW`^gDm*1`xZkFxD5U}JZYC1iQ8O>&M z+_-08zCh^r0$53@2P@$wV8>GgZVYqd8bP}`!>qSVea0;9Dpi9rOv)ez5q$AZxEnj| z+xpvowlcS}w}!W@w->etcII$agkfSexsJMv@rD%u`N6OA5YcD(&4uN}b)*7hauv8L z=QXypFCCy9yncAm%*ZO#F2GUSwcA76$IJgn&`ikDaH~jxs58;;V?tvmV_|WvvC6UX zF<+wAB3r{%Lv4eoei7am-R+!v>_x3%<_#wM4Fh%KH8hpyWc($EgfuZv;d4xDa{IQ$ zDr2s3qT$cvz>(hG9~CW4je4~+mCI%J#f*Hp+}GJRGwaiR)BIAiQUX(4Q)*H?Qa#gN zr)y*~vZOvGm}2O!Jsu!ODV-h|X zW<)=8C#HOH?}lcQ9@;R&Sktu0Lc%u2;g-t<4>O-Z|9!zWVJeYdq6A_E;{Tou zPrQ37HfbbjD=9T;_EblrQG!i8HD-U5T0~aJzko^~7mw%8#r7Ai6wPiK=j%V$Hs9N? zV7TYDST{e3#}qnC8^RlJbT3|>_W65asQj017o`o^6kHEl^gjoeN)~B@DETydATur_ zDZM4_V%n{=*|b;bA2OCRZ)Ycdx|hc)_^o zr%*<`5Hbg04e#TILtE@SEP3V-{WZ{tJwE5_DEjYlMh(gHDlKRk_G;~j!*WRDdb zUNyw&wrO}O56j3&CJ4Po55X7=OVWoe_)5mC{kX-5U4K=#!S_AQ1`WkE37_wm!iuKy z6h8gP`jMfVzLF}KdM(8x<#Gxsr9E{n%{7CW$<02H`z1fR$hY)N#Xyx^EurCiQ)OFc z$9#`y|NbGD(TH*1Y0G(m<(jo4Tkmk+i5-;p^nI+?ppK;ueg#S8If6Ql7Qhr^SQuF> z3fqox!sMeDQ4755JjKW>2yu8T*AZG{C$eOj74#dlBUD|AJ~@i?g=j)tBlLh6sY`4j z-Xq;6_fwA2co`7WfK$iyM7Z%rVOsf*3lqg=c1=qo6r5CY)n&Ec?pHdPYNBj*!LrSE z%3;_g-^0kK!2d^3L#S`Ww-e*h6|s)-PeF_nNHj~tB%Vn~IEjrnjOB@riaZx49Gu|q z?=9wj&MD3AiKV4!<00mOHLZFzTZPu$B4R%LuXs8+SeiS&aou3?-&E#U+F;L5qt1V= zLtkNa|5cqTFDSMtIGUTA9g%rEohR*YibP6Q@{{CW$(|{;sWEA^^vcY(Y?0iz`H@9# zrB5p+s?OGmHgcL4+c2H#y`lXthe}5~#@nZJ=dUeGtmkbpaeGOc)E)YB)+R?1#*b)4 z+Veg@y+eCpNEmZ$9M%hq#pYtD=)-6SlohWM&paX>ZVH=&Zg6DToj{BC7+r+6hq{Ln z18NQ2Nk|fvC`CF+!jQYkGZa}`4n3S1!F~rxfIhH7)Hke{;8T&K5`4S)WTh2DRWmiP zI_D289P~R}VaB#pu~T#8cdhd{>hsk9ZBSw;CEVhKW3))@%eb!i7bo{5s3a_&)Hx{= zpBdX6ef7jZcuz=7V7~7sPfOP#hkl!{$C8c^4+2>i&1IEaa9= z+T8rZ$)wRUzrXb!>Y%o88Xao4DwoRiinsEapU!7H0we{~P^soAJIOQ22U32g{76Nl zzsLy6x|GwK8(yGQtWy^Dxx3o4PVnnu^Hw{x^Wab4ft2Brv0oEyGldJMR(5ZE+$Q38 zlci~sjO*-v2o7II?P*;a|9c z5QUw=@@9%Nh_r1gopO}&lDwDvm()XABpH+Y$*OBYY18 zsUoQo;k#XBLlhsX{?w4sxqM*e;NioM%-Sq}+YUOsbFuU&@W%Nq2bPCug~vsPMJdNT zj;)P57rzp}6Q2@49oH6X6yp`eiUP;q z?oB+NIkj+fWobQOyB*IWZBTm|?(9}*2?i=jc=%DC=rD{D_6Js!&x~&$-zxShb_^qr z(L(E>czFkrj}V&hF>Vy#L7!PsOkD<-Mx&ysM=2>}CGr5NnKVdJAeWJ&DRI;cnk1ux zS%-~bVFQ^7AT_9A1Cf+EOC6lGlp~6117G?ql%Lm#7d$fpU#ZBIT2AkY19e zNnT`03Lo_#tqOEkTe72}AFwE-HtHDmjKH$+CGjIt$}*Y?o+{7PC$*05e{YC1F)_Vw z@zUn~@o;Am_d8y_z5@XtgH^&JBTk*rj4qD(9h)8}7B3S&7`H19in$j3?!8YA2D#;fT}8$ zGM986Fd+s}gk(n=BHbZhp;UlM&mKl4YlLGCSV1jsIfla@Aq*2A*i|jvE5D;`sQyB0 zTQAVC)>zEc%HpC;^l=wwlG}B!M&F@;6kwC*BkrAWitdS_#kR&BjdzSE$Jxax#pXtT zI}sDn8d?%$?tj}m)*a=1%KnDcSu<&q41)okZuNUgGBS@Owgr{Y7h!n}I?;KnVcB68 z_pg8WZ=X>2yLS5~=lW08Ruv8u1 zgJLAJ1fc^kUBompiZ>HggT8?g!=A-{#NNibV1HtcV$Px;q8{-E@u(ul;5T8?+y;&( zo5Cz*M9?j0x>O6wS@JKEFNudlA|gqlqZD^cHL{<5Qq3n9a!d3olB<+!|1}gh6}A-t79`Z~HU#AS8+VwbL}k%$gGzlAY!jY|$mT2s6j0ffinu?M}N$}E; zU5MN81F#wBHb;*=&rD-npnK2)saGi9$@|D%q$i}Cq|YQQxfEFBQ|c(qpP|5#<9Koh z;iq`Q(b0Tuf*PVj5*fR1%cdxPQKf5G=_DT@9z1mTqS;5w9NR|@RxW?s^}QqfYyvsK zQDMmuFHandeif4uYY~?bcQ;Nl?no>Y9UkQqNe@#A5eU5JTkDzTs^<9A_M^q)qeh3m z9w2C~tJNvE?D->hR3MFa3v#9x64W;fm%?XM{_Puf>#OVXZ8vKQt6!|HsQ6cMvd}s& zHAgSYG~;cWLuzQs_vHJ@naPNh)|CF#UFqL5(z1T!sOL2od?-#W8~&_Q(^MDt^>B;k zcl|EUpZ5m74zG`~Cnz)h3-?wOH=b^f;nzujs81MtY;WiU>=@!7(wa9KbpkDg$;PZ= zkk}ycQ}Gu@Lzx>PPhV828xsu_t3!V_4B8QLqzB;TJ+Pg3kD_ zc<=I9c7AYt#F}hAaroUq{{6=^kE$Z%OQm#03;9qy7dd@YPkiV4xkdG9p}&elfxqTD zpR~RE)>Ri-eZ1mni9w-u-uoQutP>f7X<4bADV8as;HXJ?lA4-^01B6x*}p%T=Fb&& zmHa9ft2+OMzoF&Z`_^YaGP)anv3|?_3HcW|(OXJ-~vFVHlV**jj8aHWM3w?Zy~ke9;$CCwa|yb|E|9*I>%reo&LSpT%PI(ZADv zQmGU>N-H^%Y)CdCpCylzUr<7+4`{>mSf)PvD0Cf0K@{;m#T4_e3B`y(k{x?0<#LsV z)d>5J=w8yVGuk@LXTIBtZ9Cv_!ezl-%6p$5KHyI9pU|1`uaSqMu19;vtj9>iF2}gX z1V{5mIYjD*e-4=n%=T0CHgT7CF0)5ktD6fP?lH8}yRz?^ijy2+*Ao#I_9AkI?MEHJ zC9Pu?*QN%?2!r;&dOK6va=+2)-d87AER6 zR+cWF*`HOP!_EyV*i(!vg?)CYE~vF_BsUGWb#x5&u=3R^Zr9o(KDEbSOlLrp9`Nl-yf_ewhS|eCZe{1Ri+{x5d828 zZUkUK1HdY;GUDiWXyt$hJ)~$;uoOXx7o`R4a=O#b(T5npEMtx__dcABtU$fTeik4L z$BOexwM&=E=PB3kUDcG*b2WH+DDTJ*^G2(WcJ7XIE><2Fy`%lK19O6xLs!G|A{C-6 zqs3!h#1zJa#{7sbjq*KlE+QzbC3prra|S4Ixa~Nex9hWK zQ`spSDH^G5smW=7(oHi3ve`MVd0z{z6^E2v|NNu+VBKKj%jU%PsLtEHS^d*P{9^_a z#xrsYo6GOlWw$TmD@nD~#|&L|2J{;?jCjYRfJy?h?nta8-z~ltzMp)_eD-|pSP85H z#tZF&+RMv879nEcSlACJfuql+F=rUR=^Hc|+GW7b3n=#~?NL8*rfUBjo;I~PdnmTUwq}OYpL2OcP}{z zRwfxa{aLD+jp;RMsI;QgT(Fw=vuyh=_@Y`xUCu9k-H zrCq&031Dy5`)|x-%&f&CW;K69b>|8phn!7|W5PL+-2dRWkXF3)C|-;Nb_x58ZGUpF8$G=03>Y_Pp9WeTX+e!F>hF;RLXCSW-+uh7LU%c(^xJh>D|#Qa!1Q z)c3S^^frbHYnWXQ^}zNZKk-IleE2U3b&Fa{ZtgAw`R0XciN=67XTR1#FOx{q1Pc$F zUB`boX}jI`eC%`9A03n!@;>ZL#NHDzQCFg6V@}6J$1tO{qd6zyBd>?6g`N*e@Q3+$ zdN{eTk6*JXK30F^sgc%!ms+`MA3?rhiCq_fq0VzR=x2!Z&5Gsd*}(A=BbEJ%JyYL* zHuE>W{E}3eQD#!CSa2qHcaC({jST&Co3zr@q}0o)xYRdkCFvU(kF#QOuIDc0CluM0 z9<4ZA)%V4{0p9epwdF^9_wuhjgHC@Q{QC&@9L_H3uk~#@;ocM5DOJF?kx(Mgk-5Pm zi^@QcVJ5Iee5U*<{Js2*{7?Az@IU7p#j-F+3>o#E_Z^Qdk`Awed2^+qF?J~{h53Q; zold1C(1_Hp)GTTbRftwh^QVV1o-<+W9L^JN7MzH@f;xm%7O)k5B!<}ac8|ZDnv%Sl z{5~Tcrvotu&zhVz^|sh+({JzRROL9|tpp&O~|f zitsccF2S{6EU1su#%^P+Gj#!;2N>)0Sx~+1!kA?I$9%{7#@2y)xjFC#B$M|#MxCEm zNJ7+6qEPC9OsD)C<$%4mng+UB`jSS7!`-IOEEH{W?TL=NT}3>GynKAK{EGq;gE=8O zVfx{1;kzSvBhtf1!oGy=3vmk)54h<2!pqjZ&Uy0qR~sLT)}u3rhV+wkX4Hk1g=FcH zMZ&SzEkrt7kvfdKux`7kIIa8FW9Z8-t1iCwJ%9nhYSt zpParw|9<)6y7l%7K7m|M+hz`P@?q-8hrBuHM_6tCEP;N(9--&L0wVDucSTN#92995 z))Gz$vxjQpnhPo*8170FiN=U5};Hv290I3ByPxY#kh^p`tyt&i9>+TPK$2dqop{@h#Y zSY(<10O)$Ffn6{yfaA-QV=1;N1u4#{4q%m6HIoX~%A@nJg};g?%lInK)WGY%ea&pi z_}-!;-%)b`&*v)DUvVk1+$cM17?KG;9W+~VGH?<1#b#v3ZE9) zC3;7+R3;Tq}4l;tEd!>M>@XFGNsUgd_&rwSUi5S&G706&dwT&AYm0`t*Z2 zCdW*_9n-dswR`1o+u7W0%tOQ5!dJ$>Ish3Y5&S3EH6%8~G9)+nchK!XoIlC8z#Hj_ zcI$Q0J|1Fo)ME9ht8uJ>rS6P|rOFk#yHbgwX8cT^Iw*`TM;zZQTF#t(H$FHbG4QF! z_lHBv?MCXC=E|uur(&f7+uUBD9y^nMHO)UYJH;SHB_$ZF@Q#4hwCfqBSynlZazzSy zi#kd-Dy*w}YHu~VGzWmJUE53VKRNt&OndUiZ2DsL>Zi>cI2lqC6~Q#;9D%`+nY<*l zJSc6i5mXWO7x5956-yUmi;0V)#5={@#lDNOL{vqTgoTCX1d4%GN?}{kH&Od}5j=ko zeeiMcOimwe4d|Xwgrq^u?kDH~m%-)0^bom7J6;X6KK4F8UNA@GtoW&2|LvKOwN(73 z;;&BAEY=OtM;H~F=$Ymp<63Fi**k~>wGmT~S6+8~-2IyUIRPtyFN5ZSR)U@dEd@>n zT=wtwE%$cxeBpN4dB4MT+X~AIX0nIF4_?`Cp*5vurFdOBQ{t7-U5qcnge^oR;?~xQ zi&8U@|9XZm_8;u=_;J5Q=IdrHr|L$@=x(c2z(J35oi~9ARsI7j(-{~%Bo=vFniFvsDC_- zU_~tn?hbS0`azdDRcsmdQ37@r~k_cMd zeAn4MTe6XgLaGhw_qA;GWDRDFJ{~qV>$Whmxo`i;G0i2yecSVxPq5#y6Z|s+ z^GRU6B5W%U*FyYEIZsEkVmYbYXK*j%1X%m=K%0OS@>uLQ>`!b9Sl1Q6Uc|J4nKqXf z&AW~KgD8RD1N8#NkQ`ViS7RM#K4Was&x6h>5{*mKrl-^O87L+n%Z1&_xxn>-UqJTr zI$$us61gJw5}%|F%8bY-E1%ixqv@_|qi%Qg97_)1S*^Mz`s z{J-5}VzmNqQPD6nraW1EM`6u+;ms8MZ~oBbzUSQ|-%qq0`s!QPQT^z1PMKKAav`$d zd0u$#qfZi_MsrY~l0NC>8t2{2mn@tHl|M%1wV&gwZEFJ>o_*VDIq@Ca^`-Z2zwHom zwEdso6m0J7;{1yGhTXOsUY0aMv88`x)&V_6Z`e<`GV&0Q9O&?~M?FL3qu!t#QA@nO zyy@VnoLitDZVlGWEr)J#qSzL!17KhFC_Ro=K^3HCftlf6FrSH}3{VoOrZgA&GX@r9 z>LS1#HISve7ck-cw}pO-9+Mp0{YExW(OK0_!&5tE|7F8l#%GUuACs`IwKH3_a--%;X?}8zPOx3&%@;HuiR z2q5vGr^^)43g^PCVF6$s7{ak;Yq5ktwaNsomD))e25XN;KsUWSv6qlZcthwWND|Az z{$T`|UsI^h=_i;;>*9C;50N>rauzIOsBm1xM*WJ`E4>bb(L<|8#?0%j zqU=zPAujpuIbLUdc>{cc;zKOMeuwXils_?cLOV(`>dy(;6FiaW;q9UM!Mg(O{Y1Po z-3Oifj^DLGT6i3dKjfoN)Q(ZlQ2HuUBKc7`3~Pu)bB3tB_%9oyOM&FxNltdwzJKS8+^ff4NVk zNDW_|SYudIW2^a(m9FPM!v|2q{i8|ag3}-8uuCDU=^N$SdH8S=ni@y1Vb-$WL&mTg zI1#}`j`CdLUEx(m>7g*FR$gn~Ql4$3Fj55}42Q!8pd!wBwiQc($)#`8*i->(0Huh$ zAMC`IfH6(7Bu|oyDYaBQErB7&f^qh9&w)yn@2IcX2>~gQx8jOYL(;|a_m%JMeXRMP zZk~RwQQF~CX8M->HiwVDbjo&p>Y?kM=iB4o5*QNP95NkR8m1W@7_Jds9@Z85A%qbm z71-x@#OJuDtlL|sN&6w|kH-!iy>O^dKUQa-#z$qgtf5q}Xd?eZ-nZOR#u$lzCwgsa zA!*w3-@cK^f%@LaPV@G-=6{WE>QZY+m01<(W#p2~;;bTE;eUnK3fl{h6bTkfmBg1) z$~r1qE7{e-wT$}uuUXAyZ6iN+b%*_|?-v>h{?qt(Yr<&8W;+zYglWytr5n(s!Op8H*^6|V z*g=pXWZ|vwa6B6)i1)`2;4c$gh*6|mvJ7>YR?HY=i9jD=)<{*g?M44fnoPwNToFI>&na`lfzIj*N`?PvlMu%;`;3F+wC!mLyF!qhwNz=_n?KZ2^_R?2(cv zVXT3`HQ{ZsOS_b%H|1)Ta@C&hyQPzO!26(z$;{D<$JVS4*?Bn}bB4Q}@%Z6Y>vO|z z+g~{l3QP}L4O$NR5VRVI4@d@lk>*|MDeA82f^d9pw_=4i|8>OUPz}&E`l<0k#Zdms zZWZy{f<0(u#A)_#stuuIGhs!4e)p9A-z&pg{dv7_I$PQgw5)zzuGg#mSzTN?SrJyQ zRpwjTQgXlKVadOebET$b;pN2@7M0v8PK|2ajRxpzY4fSJ@E^y!B6<`1-u|u`?jBwG z2c#rse$2mIGG6_;ZnSk}Cky|C7)GX25@`+eVPKJuS<>t$>~{79I9{{&gL$43>jtxi zu|!7zwG1_|KWIgc1vM!h1U&vEsEAC$$>JzG%pEn{c^ogk5T8rPA|lA~plS-qkYa@c zS-Y#CvceJ*#GfyO5_>ACvge;{vf@eABN__YTY9|)R}RS^$v5L#nAzCd?{oa^?C5sQ zPfO_P6RV zc69!4+r-W3<8vzuSC`4FHX9GOKJ47b`w}-vXDD^lCE60bo)O4gV(w$bviw;tEH<-{ zsRo$LGF_hTO1nUPK`9}BB~25V1PwwWz5=%o_kPEEhqgVpy|^v46Awf=ig0i7d4vsc zSA?juG(1Cz{Th;n&m+I1eqy--HX^m+`cl88ljL=j=hTY!h3d#1_-5#0+?L`(BOS4L%{hgT4fC1o)QveDHSg%Jyh*djj;31CD#z?zd_-mpy7~ ztZBHdcMYi7X)AllMeGg}cM&>@RpXK2?qTXteDGPD$kqQAtY@?)4vpO%<_uK*D(d;$ zY5N1#PHfR{uKsrV>;1;=hVTZx28)Jw4GN7bjhkP^n(j6Wv<|dYf3NG9?~?Dm_G_U( zd~jj-)F}1u;|cim!`bzD`=vK4wQK)2TDJ;!T=6>uKT;|A4`m!AuhVoMMk1q<@t4uh zsAZgDh%r9VvGfbHMk){00Mt#qA$1V(1YJTB{s&G6m$hTOv%FoiowNOAdj(YF4(vR^ zoxq>4sCc}| z7GbSvfikN9$(2S5gflW`VoS}ac2yZqw#WE_|>IF!8wk*91xw9^~T`JSC5c zrJbRDpnaj`((cg=X^Ye->MF$wWZ-p@0qFvJa33!fCH_u`|V)HN~^wWGho zl)awaej5p^oMWP9W=D<~3mvRDpsjmN^Yh*o=%1rwYX8s^oXOSc-?Pp0&lXQC?^*r17QQjFX|tWW(}CN< z&k)*)4@pX({sBwzrCg+Z07n!>7N~=qBx69OD2EtL93dEkDrN!vWgKNSmg&G8@<%kU0Dia+UWHMuUG|uu|l% zc+xKKJ+87x6%3RW)Oa-}HS=|R_OIy&AN+jiugUU}2Gd0Itz#CJ!B(Eu2%G0N<2D;M zLpJAamaUbo6|8U;PmXPv$(t%1!5hCd5;qJy@KpD?))@^WwMC`V@_1=KsYY=Dkr06j z44n4_(57@@&QKqdZ15V}(i`ThSCbd=e{tCPQ7~E{xdbjPfgTZCsbn&TpCfQ>-cKju1edSm;e^j8fu4u%>9A3AJIF}`Rr zXCiP|?l9A&z~qR@1LMv^T}Gb{1{p5vJ0AF`SFBT`^<C;1TJC=QQwge%mli@TA&}N_K_k9;<&M`u8pR(g%z3QYm1Ee*aT}_al&h&U_yBE$)w!W*QtbQ?HT$^&+O;9$Md%rA{YIZY?qBz6jsq| zOKacO-*0$sN^JFP#cT`hyxEb)y}|9^g77K$ExZiDfpCiOnD8GVAIwGyz~|S5`-BSw zpvne#Ob8fBgxiEX!Vm#VbOt&s7}9MLFFA{BM-im{qqft&(mNQdOlfu?rv;LQrNj3j z>v>M1#4&%c+5FLh7Q)h^6tNMB+Ff^d$4RTpQsv4O0+l$*Pk}VS8TGFk&^~c38EuTt z51q@pcwJw;PkN1dKlIY{{PgI$@w$CFY;9?60WI9V91Rck4mC^F`^tlgYx2Bua2dkx z@m&=Xx5XSpgoQ@<-(f@13cO@Q2do%+1=R2!(#xp7$b6&#LIdv5PRG{yO|1=)b=E3& z)o|t1@~iyT#kqye1KWQnZEo6C>G7E-d;0X-&oJv z2-+0f`nh#xTVtnh=M><`*?4Wj7lIx!gD6Uh1QlXvvOoDTxr4k$7NTfU%qeb^P%utY z;wcxvlgh4BZcttWe{ZC;QCOg2CzyJNI!9Fj$}M!DU4vx2W0*5>%qrGBb`Zw}GUYl0 z1)j@@Oi5Y7qk*i7r}|ziNBVZl-w=lwENng|D;P~@?~@6&da+g zuoX%ajg`ukb}RcTzf;avu26odd_q}V`HPaVQm!IP!B8PW{*>GqSw9&=Y4YwmDYsp8 ziCf}mpz%Z$iWThUKgjnVhJ}jc?LrzOa$$S9sT>3FboLVrUV0DMxr`xOl8zBA2!8kn zxNkeyooG;t?X$JI`Ev80Y~`)^YE>d-wS7c1K+8-K*U$_t?5k{AzY&{p$J(vf>!ea?c)5l_yT^qCTlkQ|GI> z>U#BC^{9G8{kM8sHSw2TCvQLR6z>x6PH&ah>3h*vP(u%A3Qlqheng&p!1W#z?kj{esME*0) zT<@={NuA<3R^PpTe_g-2TkiMC`KoKTYo%+p>jl>cSEg&ME5|jDY_->Q*VWwpv^&pz z%pJr1ZOiMf)TPwV=vWPzBE#~CN*Pul8v8=Ud{Hn4j$`{ou`ori$(V^%b)(O^6 ztedT;t=FwCtBBF80c*YWvh}33$hyS(oVAnHAH6sF9e(d$&weALl&B4sY<_$2S!A2Y zbLJP!vF4Q#>3sJ2vdL=t77kMttd~@An)|sQ(9ee74fjILZLkkIhC;!ggDW8b^bR_L z9<5Z{s}*R=w70ZZv`N}n?HO&THeAcpMrqmF80~rO1#Ox(OPj-8@(Z-Zkmy!vh1y1K zE8j2e(++5-wBNPsTBR1!bj==Y7VH%46C4%H3BCnYU}Nw^@Io*;kUH~o}nl&Q*Jp|pGo%VZ;5 zsbVzU0n=nV9EKf`tF|cLv%Q$R?uwMvEc2n2ELT2*qOcksOd&*qHLQK5tmB>AAyDjv zZgHA>^UIX0a0*;-F3cvu9radIGw!W##{KNgjr;2pOtJjsuPXPrqwfSPnIdH^^annd zSGq&u5lWdjEWQx$LmkS1G*kz@Vu!v2Ho}wWZPF{@ByEOHG9&z4I0J@M<8V0ShhR|_ zIvF|$(c~9+4f|kF91ficm4>Q9*Ft*80w1OWamt1R^D1ns^^C^zP?o~scxX8pdKPr0 z*>G}JaJT+WIBrMa2wgzATY4EJp$da>bQk8*9iCT1dMkrDazeidE$WTgw(13KXaxL# z>5xw5LlRhu(x0PlA>}KGDut|n&bD0QHD8%YH)s|cV;9#ltiahka>1PV7g33@CXYmr&cJEjxt#gGhS5Y!s%H6Lt&A! z5NgDS$_K2yi+-;uuRx`n0Np8D=>WIJ4q2uivfb}EZyS`TT!>mz#bEe94+#h4xEi=g zhtY6@zFhwhr%Z=qH59s6H$4p=)kCP5j7~NPUom<-l&=J~*kRE$MLEfNdK`}pLpw30E26ro5lz1|9?X(JxohML8Y$Tk?S=fm7s1U+Itn$LxzG9ACZ z2u*7&?6HyXw1#jtnY2HY=cC#35*)JGyz>qHBXYnx^xlP6&*-(dA%PyHF|x+O^qNmD z{aSoyC|HRb;}wU}6$;jq%4qyGN11_M^BDI_81;FK{$+SDmu-ucHY`qu_| zY^CAN577Ay_L>e^Y8*5ysn8(357FqUcfil>82w%J7R0D6%&e|NQ?lI#^Sihp{+AOo47R2!7c^P|Pfh;#xj? zKBu3BzH*3uZlj+CjFV+3@IK@3eaKZy>2V&~=Hsb+V*V*-Eyvgf#@j|*wUhDm6OX&8 zzc9M?(8|v^L%MoB?G&JGE-lU{56*^DmIF`eS#s`3V$vUNy1))8iz%Nn8a}6ul}2l8iB$p7Sx20!0<#=FIQa)sC&B|_hcO^~cULtV-49F6zWh+{JBHX&-EIh})<_LGsR zmO}fRL4F%Y$znuH&R=J|(}t1Oo_yF22X$bri$U;voKc@mPJ9V6)hx7<^Y1FWSd2dp z5T6V9ri%I3qepYke-mQaN;D&%w1q&}k+IQ{^Jq^^6`hE6YnX&B@mMo>PVq!s()Uy{ zcP%l$fohjf?;Pbc^GONMj^G68%yYahXZ1V0+lxyhXd?;YPFu!#4_JPKnQcbns%a2= zUgxT0u~>l?g?M*8ny!bLw~hKeqxUDY+QqgXU?^^br?(!$)LJs^3if-O8D%ou(-C5* z=nvbiJ?Cua>P9fS-MX9al`iALll1#nqQ8|fTY$gh^++BLSwwx0wT1XbYMhH_xJyu1x!|<?j#W+^s^_WyVxQfOGa5y$aB8*vrQAcR8X;0`E>SYBQECQK%)Q1*E(-EIU#=8IkEkgdQe7sZ^Cg)5;H;V0@1IJ^z{wuHCnIaNYxy*&e&38oT-cBc-d2fu_hxDMZawH(LwL- zr{A5Z>3FO=uIs_FFUx@}pCS`vQl1c_SR2ao!PJ2~ABc$GUrG~R&uU#hP=uaIXbKH&|Ug)8(nHR+k5oar3-Ws^k1qW zXEfQKm24Hkb+KYNOZq;{>(cv@@hSJKrT2Gfg?~jyz09#LQOfXd8U8+tn~$?R#&hZV z@C~#6Kk1^ zV)0lko^Vo9>F2|^q_dF|A2agZ0Q7hgFUf1ZOp%3tBT(`g9F=9{$_!LXr*vn(uBa`? zaeJ~sE25B0c5vVU8!?H%&l*RR*Qs6{F2_|?=EzYgcqMb#pzO?H{fF9E&zUxN@~o*Z zO`V)0#I&5WmKpN(C(_J>PSCgzHl<~xGCFHk?@=QL4B@$n+GSMcsIEN5Qva`k{{T&@ Bu%iF~ diff --git a/selfdrive/assets/sounds/engage.wav b/selfdrive/assets/sounds/engage.wav new file mode 100644 index 0000000000000000000000000000000000000000..ff094bfb01b4c1ac01de35b41c14c9a5c138f7cd GIT binary patch literal 92172 zcmYJZ1z6MH`#-$VH5xWnFa~3=jg7&8(cK|sccNmqeiRk4K|xdykPbmmy1Tn$qhZA8 zt^xZGf8XbNuKPN7oP3@8#CvDwxY}A-@pu9OhfEJzUc7c!K^y=806Fx$fTKJB0=NL; z06PySdpO4=)4?1L0F*ZUpN!n#{%7yA^Jng!=|2VpY_a#)T>m%#u+0Vl_SidY9>6Y} z#nE@!Y)}~j>cvKIcY$^zU1Px&C4mp^-tTk0G#-J$<3ktG%f%SCys|> z?FX*^$$g#oU(9|^evZ!1N#o_@+%L!Xk9atIzZB2^YT@S8{D1ZB$L`m;-|D{HuVY`| zuYH%j-^+bOfPblb|Le&PNA6>0b0nM7%RNpX_a%$dyA4j*`lqjR>`jig`H!|aoW)7m z{ui^$v9>sQ_v1D>a$nozq;37nv!8F@VsU7{+zzMC9genN_Wz@O@9ukaAHlx-|55&5 zkN&T>`(E4c`M!tvIDQe}NI{Mi{2z$`gaE>vSP_6ICr0F-6a#=b);@^l|9;gk|<3dyT!sUSZF3v<3DYC(LkYfjz;VWivQ@lEe4q2z!h@$_XPJ&fv%~_Aq;h zL&F?<uyY;rhn)g6j)c9+w1n5qC0AD(`*1X1*9cZayTh8qXo_JT50L z7BC#R0%&4y?_OYSZ_rmD3p31M#)+Y~^b_5R9e_6V*7nwc_9NXoeeNS4rs5WlZQbXJ z7Y>z{LCh#^;Q-_gZM?Q;vdt3Un)HBH_i8S#eVn0A< zh3f=HdF!}B*mrhLZrxu0vqD&!o!^)}H)A&K&D3M&GnHrb=Z-JzEM_bPEKMxxFA6Q@ zFCJU2T8-W~v3+fay6e94VC%)|m$?bXD&4U4MAc$`WZKfN3$f>-@KK{Ne!t|>t&6Ja ziFDqX#vPXEqJkkg(9GZE(Mjm#otv5W2oK)hJ9O*h)tBeLo=`s&;xgjEwu!O4WHw^d zqSr^6CN5wFQC<)yu|3|rozfMj8UL}c{=n}4+RipP*6Y@8R~J_g)?BG)HhH&Q>h$Qo z)#KhMWl<{UI!(oa^y!nd_&O;AY%J|D+XyPN&Bd(Y;_pWu{7kJ9{W_ve28-McRq2fK!+io}L zUPrGyx>R?LdGh_?dj}$|i27I5GZmgnTJStw|G=ysxYY5b{!B%C(RAMXoO{_F+1zdktdX1mr8?eSfnbkfK!^U&&Lwz80i6aeaun1KI;WQa%c@@)o9N%tDmG-P`x z0DtWGuf2ADY4u{(N9BFhm)nt*f9%R`cZN=#*>#m+SU%hwcnMbkpYh8D&FZexQ^IGY6O}BGhdJ!RW`8Pb#CvG^_ zHXfMN_NO+xsHn9fy|$|n)OM`<-2iJMVHpSz5e7lsbfn`L{lr+>{HdKPVFv69Zc3MJmSyw6R^RfXK_*c| z;h^Y47I_Na#VSXqQ)1G-N%*C`uJSqj>ge0xPbDEw<4aDoMYO7hMo`BQ+UMbW%(JWdz$aoPBmqy+RWRkZx@@Iy zR!7Yyv?5nPW2~dhjc%i=^vv!!Oo+s%-8b-8pM4x(6F+VS9gSR1IZ@=%{ABp#$|b%@ z2u$rT)zGT?fXNZl(-$vdymD@_?ngf{{WsS4yn7!f-QmBYaq`oF*QO6Osujw_s`qr~ zKMZQN{;D{c_baX9cUaP7QbIxP=eexkm;O|!RUz-sIYb8At5TZPw7q6bl{DysEG z|C8}c<0JZqHMdoEDN>u<{aqk^+zW79Ru zksX^1=Z&X=ZO}M1AKe2MwoZ))&z`(}0poS(~9!WbzT~cXFR!m@h!)(&K8&w^cZIl=oy7IZ;Ey>6GdB*c9pYQLc z1FnbB6KAr$szrKEPmOJD330>xR4-~rnSQkY;LbeWcpm8$aeMti>65Uh8c(er*W9i1 zdVALMAl=4EkAxeCb&9y`6)oOlbkp!{ne{)adn)l&FKhZ5m~ETAxZ&Ihi`ltF-L>K^ z9`*xXY0wv$2S}jGA@x+vquS#XC|L>ThEkRx@bhhIOc8oLYi;sWlkfa|^QHLxu~z}l z0ncS$9Pkz5jC5PXsoyv9^XkTFFQ!FUOG5c_6crCm52G74<1X~08t2llh~ApIH~ujF zk@&;OJLcC8oquu!;TU1;t3g7G$Xw@7+*V$|j_>sMcaOJAw;8mVc1ZR3^ly#EGn*Hr z*B)#g-Zca!@JV|4!PQUw=zydV-$ZFj2UYsvJG} z?VX?F>l-fs9E{^Hc3->uhkcKWHvdB?f;Il`yEikxoi6wkY@#GhQq@ngOmG%G5_v}I zviJ?tJ4f#!?p?p_dTr*y>*L-oR+fgkqiW%Za`9ZAmMz!C*Hhm|qX+-?f9)p@-Wk!G z5S%3}Z*A=Cr~>nNPy!9YlHzcgHfXEDUrasjInhufigcdvTm>(mBmGuDlvO{A96Z+o zEHlpVif8`d3fOxq=d+Ix@Vw*Yi?_JXks;Z!q_mo1Tob#mbNav*mfudgSRoFtpsQ}4 z?fBx5-sumQ6t1P*T)WkK)9sq?rMOdq2c_-N#@S>8j5IV>RF4PE3SDWKYh`9m+D<;4 zQk$_|xVb8{{eW%6VUzm0K}{~{wVbZWO~ zA$r8K<4{#&j$pED1S`n?<3r!9e+U83BYk4tJqlp`*ojk5cP)`@lI`PVCalxAqr{;I zS5*hfqzTi0%On3}_l4~%lh>YH|K;`C)ATI*sLz2a%cFYf>Za)PkXxc@yr=hmZAPp* zE(a}nEdRGUzj1x%0q_Z*fbf8*fMmJ!MX(|CHi92DtQ3Kr$GNM!5d+oRajTd``E}Vt zA|8NKD}CeAy~peMik$vFh^-EJ_POUR@Bh3Aeg5!O^80Ur5@EyfCFw^>yc#2EMH4YA zM*s^V59C&q&B+v_E4DsvO2?Pa#$6J*B73FwlJ&XvWu8pv)63Kn1;%FqJt7VM0w15%PG&4W(rjn%XG>hS)^hRlkcD#wMZe z$^8_&%7foDm{}hPX}w+1kv)+#9fAB->bLWH_upIuJhy!@;EVkz8}v9_Akilyszj*q zRqq@_Z|T8qp&*Z}rJ}R?Al2VO$cg14ejI#y?M%cO^;4}!E8R~zZddWGX8Q+-yVT^g{`X<58_iNhE>BQxX zMVvo zi1_>qo+(nIQGczga9Cxwe8ZdDMT{HfhFKs5>e0-?ZKIvqTom2nT%R2nageY%VkTOmT6T2$>O9YHFanx%)+chl$B zm)Ebq-%X<~ZXlY$RbLoF}qcgK?#rFS0jM@ZTs)K!E?2|68yzGmT;cxzK@ zeyc?D3np(3Ty=%DHi>R{3)NZ78RcI}bxJwPw^e#o>+nJ(7tPb!Kq^MR%3#^B+Q`xP zneheV0izm2UV}T-35v5u1a3fy1(%mTA=JrET}3mG4*0e)s$%lz{;=ZK!*+tO{y*Mc zdKLD<{P~6FdoRR&U%u1$wEZ#Rk2D*eOclV#q_f ze+&Vp4701|g=RvgpN#zUEp*vh(;7NN5yETSA2ok99PTOpxw??XlIFJdIQ4-+h>^a@ zaZ|9_3$yoTW@e$L|Cy8+xfsY$C$)-*;i^v+uRxzk)bU^1eY5N|In?LbN~$`UFZI_y zemdOzTmGlZ?+?C?^09hp|1!(x+3OGQ%RkM0T@L#Z+y47wR!#A%+VXa&Ho7QIeA86ioM_Qyfwbha{AST&9&5H_5@i&tKcGX=%q1LFky8+Y7>O0}CbCqP>?Z8{ z+*>27>kKO@m-w5GSvHr<184iW-s$5z= z(7=p_`G;FG+*2S5I9^^<#gX7nhG?hgBK5xMIqF@a;&t=2k5QDhEHtagg=C7RhE@rs zT1P?ekAbf7d(#)@yp|xVFso9lAS+QT9ZPPMFSZogMAV+QSrY%4te4 zg{ZBelc4Lv!N+BM-1NQqIm;HSR_lW{cWlgTO01WxIxR0*_?ju3Pz)2PCn=XmrD_gJ z2!yH3FOj?4Ra;pL*T?1h=304cUKd4Vp8Y)$Yx2`Kxa14#lcitW2k3|B54wI8pNL;> ze}5RJ5gnD-^yg0wwe&(Aq(gn+@np@?Br*)sQK{3|8 zrX8)lqy16mi0%{WqF%N^vC+7Rpt*o$iIs#6(Dt=$tnDq^T^oHHBkOHTcMB7R0aH`?>DR$M2G1hod|bOj3KZREw2s5?a5~vl)H!t(&e~n!>hH51`2kqsmyd*8~-k z3i-DtLu-uEq@AmisY|C~_5T>$Fgj^+%Iv5G-m1=;&vx1Nv0a?qGdq}_w{4`2k2TE7 z#X`dDoH5$KLbqNsR=pI9R&0f~Ns@)2z?2R4oFgNP?$Ksin@|#%!}S;PiynO{JSCVO zG#fDYY23fXKl#)7fbB0AzDI_pMTW$?rwnJ3i*VK1E#GPJW2tjDHZlPof@ldDh#XQI z{X_+b8z$(H)X4*y9+V7iN!|O@Sv_9^Gb4nFnAw(jmE|?-CYv$aI6IiVnLW;a(9Xl| zjqOt#u(hG(x*5@=$)H+SK`UGRBQ_BQhW1EE3eK{htxwOMALFLeT7_# zNrxv6M;w^;n)VpGM4JpNa|_Q;Gb$Mh?T|y__xbJj##aBEQ5)r^AzDAx zoGFRRx%9W{S8dGmpF1J;-yVE<7x41)!O!4;!a(b<>A`&A#?dDdkNrXAgp?%Ig4$#I zDC2MEFK^_rkMSFco|A5ndxiY2sDjZ`ox?e(-y~fin`^*s^Bmp3mA@8aI)6U@vG~m>$TRRxz{LR5K!KptZ?-?`eyYblN&1#{ zGjFPlR?pjMHQ+U&z3_3viS5Zp7x^xk4kp3X6yngim|LpjIF!0B$&_rZbwt}+w^UEc z@Q!hVDa69s%Eks^S7Z-&BsuXq`#WbjKX)E>s&SNeSg?g!e=xT;HrKnR)kFA#`Hj?) zJqfbm0kTq;o=lw?dfv@!O0DWFx|<#O=lrkMn3bQMKVE)k2c7v66<8fe`$GR(6&xDo z615V4IVCjnaUrepb<@#q`Jt4_-i3D?nR|M?IN?{~jxt~5P9lmGO3`;Pt5{RqbHX3u zhK8M1srDi2j()1q2~(iOJF9scC3~b}tCRMD11`L-j;=1e`!aWw26#2I;=S|7an(-Fx-t)sQQ}l(k^>@2pxnY7R(Fn;5*~8E{M3lmL z^osIb?7Z4z0)j**7g7pz>-6bHQ>K#^Rn|}JHXSsa1zomv zv)>KAvA%|X!v%l)F&QoyEtSyu+bY8%KcnnI9koq_mNBe2rMED*rm?dDwBSdG_=>-j zR)pMy{fBf#$tcxhUa7j^b%|uM1Ldx6vVOmjpc%>%ZZmK9%CXM5)a9g`zq^&ke;)E4 zaQEx3;s+)j7HxDavW>3jzSP)L-9h=wjfry!2(U%gRp*W}%KA=qxHkN#a4US1W%(!U zS4gaRWLDU6h-k3T_xW!%-=BpjgoQ?|#t8iCN;S%Y7dlqt*K4)M&{l?prdsByYdWkt zz$|aL(4=U$xheRxe4k>oay_;kx1^3HU!-K}av8W8hnY26(rrrYPdoiR@YmJG z-P42jpwvNc4+D1_*Kf|U4z1R0X1s=9w7(F!uv`k6U{$eOe7|-lR`Ii+$1r_+?J^C4 z6?Y1|vI_s`CmoBUMAe6rL%l;1gR6t9LsCO;{^W~3AO9#>CGB9&d{IqhZNqr`JZ*e9 zb`m@9uqwql+1=xj6m$ofNlZ&0horz5NEt;NWp8XbPLz0s+)6Q^#u!!3Rezq`R`rjUglR3krD5ZIt%WC8X$vFn@VojJRF7?LI!Jpp@Iyb zm~@(pTBA6#@sV?~%PqGmcR!C74^NMi?oqC!1KSQD+ea2E#@f^xax3nf(l7XL>DwYw zJgF?RmEP&#QEz&1J5NJR#eCu0?6kk0$*u9T(PI(G;U~kELa&8Yg)c_TM*oaoOQQWT z$l@vxEjv-u(d5zDN4FVyHR(I2v+`pzY4+3)@pX+4$jV=E|P9m?yK%H9zmQH6YL`BTwq^n4Kpt`r0Lw!c%eo{ ze~0Bu{S>~+O<;{ICr-Z~{X%bPcWO|nJW>S6(Mn?_KTgPwX^1TQ`6=8bd?x&KL~K+{ ztVd$V?~`d?vsDYZ%MrE5ntyk0(upIQlRR_pmzy?PcHRL&d?$roioTY-CTj%UM*Koq zDi2^U;g^Z`HMg{{>Gd0uO|Mz_T3@vTI66BUxfHq9xY@hwyT5ZIyJ{S`?zm$+V~I7b z(VwKeA*NuxQ6f-x$(uqixE^ocSbjA9b99jI)WO}zQ+29XJ@;+;{S@h6PverJvm?VJ zPDgAJzB?gyY$J%SIm4ZuiA*&dph2AMz}b-O1L?=t-9{G+&G}= zWNe>h{n@<8=n^$V)0*%R6D02dX%r_4`T#4pxR%|gGe?Pi109u(i&YOx?&hs#fc|tR z9Zg7$t&c8@dKo1WeJti=9B-mkvdABg4B=c<(fe|0Er0W3M=vdP=-l|i^nt~fYah0+ zv57qG0w+NY5@^|rP=92o;#bTAHA{7FawDBmEteO-ifh{>5h?)lT3*ERsP%SZ&0RU9;EnC1-1_&t9>tx`>uczs6xU@HWSJvPenVbIODX4d*oH4$)AxR8bHPlGy=u^98W=Hs=?^nU13>eaf9j zn`qUgr9uS*Sx#veQ;12K343vTaSgGyad+b_6Elv6_(;8=Y z+=1fs(>dgTk_*Nq^uSB!3CCo6y3H%g5L2)rPPc-*hVR3?QCO2Rl)5GIj@NhZ{)XqG z1Jh*Gw(n`@c+sLiWQ@nrtZagHh;TP)nZtBH!i|lv#m=gX< znL5+vHyy3L$ieetsZ(2Xwkw}E2X_^@PYS#O1xfmVUEy;I*OjwW`v`3skrWeZfdRk- zX%4iCvRSv=c8GAQaejTE_Q1UZKb@_dJRF*BtE`CTe8$K1+$jA-2{lQj5ri*TOyafB zFt_sViFMzF)-P!#N>!y4T+J7h+le1bIF>iz%=Jf zc8*-(?NX7d_PT=Rl8*M?)dB3-<*9->*ox2Q!mca#Z-HqLNJ;?G1;2}8D&sk`kwV_4 z1XKA8?M;rDYg<*=0PH6mPBW$5ZC3?j3Tg92#R<( zP_|agOOVOswiCBDF^`TojAvq-JZ4x}${P$Lh z=HIz=ne4E<|B8N=?N#~LTel!PvU#eGQdn`olcCx{uM76r!~ zQ1ejNCGSwaQn?H*IT)3!l5BeIVjPwoo1MtcKxbDcWk*kYX2L{Ya27m9Mfb& zGwO4#8$<=QB&9thPL3)i&si~d0c%^wR|;npCVmVNX@CxRQ)tb{a;{?G{KV|xjI=cQ zze;~{Q@c{{{qg?`O9y8@&eqR6R#;o|U&XDO=mwG2j81=A;9&Kb9P`aQ_v+KFxjicm z#sJa#QihOT_z_fvvWS|ox;xoiTU;;Q5O3;kL9x!aZMQ$`_|Qqh8RY!P>55~P{XN?R ztK;V1jJ@<1wJ~HUVO+&qaSl!apOiQ(jOU%*`?QHzPMNVBUl^?H9c;I4lB+#mK`8Mq zxRBeP)sk@}-7{_R@A}`XX-?_CGCZ^Va}fFbMV6(V6Anohn>=1$KX zRUM4&nytqzUYhH=dQkhv74E#<)F2IU95el z!$Zd}jwnZxL#Ewt8-kUI`H-=a0bI90QG>wL+=P2#OGxzPXQQA$Zz5W!aCBxmQDF>p0GYc6ed z-bUT-sr?a$B!`<0CH9}}dTbJ`z!nhGEJHp$LG3IJ6~YDVaWoD|ha8nk2QBbRa>?v) ztuHN1FlWYKgRgoC9fan$b=Fl^$~KCY@{i=Av(INrW$32U(*Wto=^Ys_vJ!KQ@=c23 zORrV>)$TPGv}JeC_BoC;PF$K5UQXJu+^yl#6z~T9k<152!@W>q7+gc9I^# zNZWLavtsmZVr+ldf$b&jzuG0+THD;>oK^pt78yO#pVkr7>L%XDbz;_0Yw&vTWyuK< zQ~syGudJxGKMVQH@iD!@>R!K&q-N>*?yC7RuVUK*pIqf^qs+$iuCxnjZ_~)>S29$x zF67AM>lZbamRE|_Wi&;!H}qf!QbygTxaP}N9&TaSg*+6YuVRhT!*Y$tcW4;)IsP{( zUh9}{rT(bVS5u~WuceK(v(17H)V9+`!$#FQ&vM?p%k-%6M}wPGkhTrkUR_r0hw_Ai zFnmuoTf$wWo(~FiVZB`Yy)ekcF=7WzX~<6FmiT&)>VxHficb~X%3aG^&A6WaUm7IM zE=@H3P=#Yhboh&|^Juulb)YX^QP1Bku zZQ~2DhDu-Li=de@kHyu5(|P3p_qOX-VGDPdOJi>bEomm5o-K9tH>yvU#}ykDIOH~D zwPu`3f0jl~^GQ3C-k4F6h0m2PxLa&oezAJ0KC7jsQ;Hriq&2=i-LM$H?!9Bhwao7W z8kdAaP>31S8_a|nA90L)TRVgL-2iTEV=8CvZQ*NaZ1vgdrInJEr=_#SfEmJc&FG%N zAL=`8F->>kF&tDSQBfFaDrYIJA+{qJ%cIH8-_lu4nb&2ujlCN@Njuj0s%5bLQT6%q z@M66J$K0{3-Hf>O$+VI*g>>nR;LI=CQh8#9cT21)ZqzI`l(e>YA^Kv69VcM3n@htR zMZ13727)!BD$=fU_DBJApb8B)PK?o%(IMzf88{jrG37V+uyC+kv{ba>whFM!v3O>_ zYAS3}W(e2U)Sb|>(zs1HrV3DgtH6YT!8l1gNJyZA>+`Pp=HhbX-1#ZZF~}f{X3+V* zg}b4+y1HDkWVS#xkCCmEwVC0PLCr|ch|k1kBXR@spA8U^Kl9r43;txJuG;X=P27{+j`Ax z(R$|4#NCnj{@I?x9dpe^^G*|hA@9FIKXf}kRo(pwd* z>XCYUOKV37=Qq!>v4yGd`GcH0$y~N0Z>inMI72r}n3<1vXa9MUV)G0=KQx`(G=o6*kl$SNsWF zg}aTLj1|Cw!nE7C|L{PcV-LMOxH-7KzxrXt-O|>gn1YGCnB3u3|RoGK{rkYKN(=ep` zr|YQ?G}1BQHG5+I&O*uZtfiS{u|EK1f^%+(G5YPWt1SWY7>EU@{L6;1DZzeRaunE@*0M%w?#Weym%jU7%UNzN9*|Vz@N0_-~7P{5sHUvTb}DvTeRjF>E%B$)7+EE?S~ ze4?+w@uI#aooI;n!oE~`p>P6@hb&5c7DEb0@Ck4o-;LcIT#;O`ntnE3HLTj7(sQHZ zc1uOWo!XaG+vPo_3MHLI2fmM0*VGtwDi_oM~o+z=O0WaT0(01qG*Y8Y!h&_1h+(0i|+VBlw{ zYIMiwk`bSgj^U>MalM1O3lv>VeG(5LNR))&rMv zXXhpfW1k0Q>AhWjZK}=f^_?|ZRU757viOpZ#hpdIMc;~qiWiFwOSj62k1)_Oyk~gUaK!*((5k0KRnp1R5+utI`*3%#3?+G#CW0WhCmk!UE0W4D%6(`r zY^!@!e9>|yXku;T$pD!K?>gAl+LXY-c(lr>;$0cO6kifre5v?nv1y50X<2eS>nAg2QqY~*{z9_3kV zHO@=Dg~TE+Xr*bZ>t3PW(ZlP1)DP2l*8idRk}9UFs}0f$)96jhb!bcgUw z%}2#TiKbwN_##&zQzcOV3KzV}ivf=91a6wGE-fU@+?=!>GZ}L4`_?1anb(@oG*o}3 z_F#2HrESH<^2M@>n0C3SwntRZ)#xeM{q5i*pBG&kh|w^l?mZDslGk5@da3JBEFl z2PpUsG%ukjOMvboexO)N3RoUoDnX2-Po`+iP~3H1=$@o@Q@5zOR4J;6Zld;r)(|;> zv`5gvQL$jWu_4)O{J11J_ zn=BgEYImwnRH;@Tuh=MGDnD9*uRK<@R=rv4(IC}~Z~NY9*K6H>bGV*i&zzk5v3!1m zw8H}A@}3rAirPs%0zZbC$k!-BF)&pI?uPmwQYrbnmW=jM9S7YBT?lno_p$C*9S`kl zEhf2|Y$pwyVwS4Lx-twc*u%RkTW<${&^DRZ~@jn(o@sdgmrYt93_pcK|(n zaANfAB-d>9V)UBt_C+?8XF=d4Xj}p*D-Rt)oI}NMUc?+z>%)r?r8IiTCR*nx7TUSm zo!URN#k3VEvzph*IiyPUD7=GOhl+;sZN-oBf$)cNMzRZ%eqtgbPX&5;aKNj(VOynZ z{Yz7G%S_+|X7uD>A>E@#sZ*ovb+bkzrv65)XpKnq*(!LIVO3dGVl}&_q;9z3YV)DC z$WEhPRKLS;DnpMsH$k5jezqN2ps=N=hEQ1pRzSrGxrPKLY7-Q3OzZ~?ztU;ccVrqY7VB zHVL*$ciie$p~D8fDgi|kz9(~N(CzVYIpIE zI4_@KH5xc?0Wewzv293;;Rft`zSOcmZ0? zTniK}2;j5ky0z!O9kL#^96O&kJvu=eiyX4-N6?7f4?6Z*>zkVz6&srCN^7CDEj3d$ z=WDI&!s^`{Z#T1A`#WTNg6Ss*Jw_i*geB&t=XcZ|F50ci0q`_E7 zUPYSHb(Jzz8ZLvNO}tOKt06cz!`~ypY zypl1J>=pG8uHskXxdMpX>DUCUsV;fWWiv4od84<6Jo>NFlDZW->)H}p>YB)nll60T zE_IMPow|~`ta{nTo+j?r&+T`*VteKKYlo7?k|%3t))xq?mp5Z~1_6@1x`Iw18wr$5 zE5s2VBp;=CO_`-)sdfM_tbUjHlXOpGN&`U#kRvp9NJtWhSWR%kr>ON}yD>>h_KHRF zyKn?l2uzm>5+{Jt1+jdexQ6#MS^sTRu0R%F%@2fUQeq_tz*>r*GDxVngA^}ZOo4TZa6)7z-5FmPGDNic`Ze((YECF+_>KGr3mGT zCUEYxfY9@Z4+^)@2+V)jNHrfkH|Ir^5s6MhYY;V7N!Lg@#2WP^!g2hVnwjc#l{?BN zXokWOWCW}Tk}2aSc|dGV_&)(Y-mAcdUDfT^>r=~z76xbTPZ7oeqZ@;w{id|2Zc68T z+jNU+b4KI)hLZY2^-lGv_1+D6jV{ecTg%$-bv^5??{gaB9~+t&nx2~%TG83K&Wd2S zaPBa9MApRWq^^JmphzSfHG;l?iNVIG9m4-5bf`xW#Yko(9a10BnHZoRN_dVZ<4RQF zSR0I$l7!+fc`3wU=mqdmX>EyV&^sX*e;79(;OV{3y^gGhs3Ltn#aqjfX5)waE{GomMlE;1N0;xUeAqUH!ohHIy` zp6-SKfAb~@`h%P#n9_$K-(cU7mrzS+V~jmkR?QDrj?X0=QcqLwQqNXDrQSw>5D0il zT$}0%Y$0Y=iK&>O;DRiI0p*agFe$cJmB=GOINxtBb#^*SdoyR%YH4`x)wJcLG-GdA zU{JHqrajbM4l^1H zDl4iRcov2&%e}!@By?VMM#4(w9^?kh5ZS08kESS#s)S<4Rp-@mab)~6d?5Z79*&R0 zvDH-7bX29Wr5I!7H|QADJ9!GC2r3P+ka3f=6q6RA3B2S*aQ)uXWfg2#tadJ5nv>xvzCe0KkcoZW<6`Pg?_~F(=p!3 zlL|KV35elSsaJ8s z=3vLLQ`lncHSDH}hl)QYQ2DZw1o|1ONWL5q0yC2b=NioD7nj4Z}g`IM41nvHs;FpT6w@WN=2kFxU8;SyY8M@1q9`}z2I z@IdoD7uLZ|x3vSyZVRVoZ!yCsM#gkTvIkG}ljughAG*<9><)5AWqVxvWc$aC=bdF; z?mZOR$-dSBzu{+N$rHfoYjd-Uw^vs=D|&p-j_Viix`3L9wU~t@M5Y`}f!>5)LShu+ zQIm?3=mI5oT=rgwp6y{uOv~Nf_{m=l`@dcg{(u@ z;MqtWg@>p+iq`0Hw58GmrB6yXmGDZHXl?XM#owqu3V!ld$N{)BELyG$JR`Fx)h|&X z<_B^U78NYvJH@jAyvH8fG2i~OF|>+YKDiJ%JHs@eOkk*uwha9k2<_{p9q&c=7<8v~ z-RpYWwc3^1o!-Mw%b+LquMfT(InFpc`C+gcO0gONJMVQbE5`O9~4=Ndg!BQ2ec$QLs3KVBdS=TQN9Ejh_He8Kpo@~z@suE z(h8DF;xJJ@kqN;fes5k)?mmF$-XzOoD{Ea~^~6&0JaF~`vwPw=gMYMjsAYh!|1q6R z)9HQPqt+wZbD*cKC$hJSM(Nw>7aO`UBE}e=7+|i?!WTVO0@mBMBzBzvAGmY*It9B# z(#6h6_DiF|>T(;?Zq7x<;~Jd`grd(koOX5Xg6khnFjrt+Si4t+@GaZD!eiF=I}7CT5B}F*#N^k~cIz zaHe0PkB@Fg>*|f~E$>yPwb5$m!u?SLPljSggc%7Fmznmn)(dvar`8^9hOi3u`hn{_ zZ2lFY3eZ(?hNO}V5e$_32Hl3?5DLf@)8dCF&~Y5&AY} z7Yk71hV$(RR0v-brHRW+k!1wHDG&(sIP3!48nJ`$M=m1OV~D@GALBl27*RNxoiZ=P^2U%-hy`JK_NuN$^&+sl6! zug&XlFz!tXP3SQKMioXlN5etHVEBN?fa}1g0kOfB!LA|rNc`w|#<>aKsm5vI+^+?l z<=$1_4cl$$-BI>mt~FTm^I zK5$uh0BjDb3U!pTfndPnGQQHHQqLtO#EeA)MFxfB1<&$-<;~=70JgFVcjH;lwhn9{ z*O<$Bi+=N0X5FWcO+B2*VqnJ_MxusuhJ=P92X79(8tfVL95Na982LMD#t@khm{Obe znr)spUTR#qwhrIwXT|J!0#$gr_^t|$32TTR5qFl9mX4R<2kS!&W0gj_6lriXMS>aYTvyV{7C(%3ZrEF z#iRvOYsPf$_Cn3AJE7_j;zAX*)GJku{#m7#njMn;tD5ts4c6 z`Hbl@RK{&55+>rihmM2FKPqAiiivE3C;=( z@;C4$^4{lBu*1MBFf-pXJns&JHSE^p8v}Y;_y@O{^FJaYjGN}E3i^9UtvH2+h`%rbjUxC><`&@;M;H4 zSC_6An`d^XSBTVO<0G*{*#po0-aVDQv)#_!rrq^j!M%b#qkW+Rp+lFW&SUA5<L6Ge5^5?72FB@3_?ZXCK7ZoIq3sw6`2TmBzZeIoIIcW9XU67 z9hnqa2I&!)0W1sBBe5ZNA$m>tA3->NB3>SD4X^>H6}t>88S^!U9N-Eq?^zAG{rLU? z_dfBK^`_!V@p9_?^%>piJfiBj=&0uqaOix1*w5Yf*|**Qvfr}Lcu;ZReyDt;b^Hd= zal&_2b8d1;etmc|eK-Gb_=JPT1<=H_!}bIk;c*j;5gHR0k<5UGz!{`6WJP2*WVGaj zql2x01;Hf2*g`Ky3wRbq z<@4_c<9p1zrW?;|_N>~r@s?NgZ(9mI#@p(9DuIA0%1A2J=XA8H)NAKn~B9zl<> z5myMjQ<<|L=T8@rS0Xo8w=?&>kHg40v_rr><}>y&Z~!lufPyH3xSwPTGzN|(WhVPf z)=Jh-R!R0B85dazDJ7{LYL0VA3W$FbB@+H1_=X>Z7l<1O48#e<{)FX=>5TCbpoR`X zqkMjPT6}DN_;Vk4XLBom!*Y#%b$Bs%K6bWsigBuVl8PWgBp*v3-yZcGRUb7RtsgNQ ze?ERXPDGfT2%QR?>7GYloL|1Zrn_CdYkVkqs(bE4pU2q3+QFH|{e!PZI7=i!;tF~N zRwCUYH6cqOD<_L5dr9_0`hj!`ObQkONs{moQxQE7Y~xSi_2YH`J5V#+gEfdbgRufQ zLcc_*8${0xNbV=-quhhqz22Svt-+1{wb7NyrQ^k?^OCc}Q{~fw6PA-wgcbrFF??Ks zdisw62vfuW!u*8zbpLey40*12S#l+QvwK@}pZl1N{D(FG*uXr)MgWKKVhDJNGKe=x z&OkHZ|47eCA!LeV3}lm}?xeF|daw@2j>Mc;iHMc(8GjdV9JdQKzAo%RtX0el3}Orc zfHC@4w9@BwBnYYg^yRVYVdI|SUgFN`_VZ23b^X=yCHAHK#TQg8xz7?#aZbOVu%C=0 zQV{PEUl56iSp@Xt--+=l-5KUN`Gw|X-WAWy=xxIN$HzCwuV{&Ya?Dojc3>giYXWkj zIO0{38_+yB8ijU?CQ@o>~`(0@*(~y>iGwH5=Jss9F8BZ z6#gQCF;Nb2Gf5Um7u*TH0|QXA`x<-<(f|dKq!8y4WfF!ExZ@k)$>WLxrEoN`ov^|& zYcUQ0+<@2UeJEcf`uP#*hFpI#dg^}^dQ5q^y4Sf+yW76yyY;@QyuP}Uy$ZSLAiKRlni*uSK^es!~V>w8c4xcpT3{003b1~1kz zb_P%oF9m;t;E`~HsEAmTWPk(*bVu@=WR>`osFN@d6}e_SG(0KXT%ZBa6qo{B0bT;z zfiR#SPB3;6)*|K|hCD_-fCONUZjVO&{O0NXgV^2Jwd-d+2n?!jes3ffI2&H z1|ZXWi{G|)j-+nao>?fv$embLyZ=hSOFPEI6=>C z#@6uoV~2b#u-vNTd#OgHUF}^HT}O5I2z;*#)@EI=RB@Cqo>iaHo)8?j_#@_rO)U6l zXhK$!OWOKxuD{O3GgVnlUGT_p=&B2X2`NliMx(&-EC3Uam4mAi>bMvOTQWPSqHeqg zzHxf*_5YNJ=Pyj3)88HXs(YR|o?Cu4D%P}6q!*Xu6JY=nSv;B?_{<9rR35%DkjAo&0MkN>M{eE&G= z5Aq3jF|uheSXHm8 zbdu|t_LA`R^V>7FZI{KKDd+LDv8?gU$-_;QVF|YnE(>%^F6lB4_Aolj+9qEA&3^|BKJ_m&Z>` z?>_rdd*V46T1grsv_2_^OT`E|aOl!J5Gn((Z!b>V55DXc?(px%?0FpQ9#$PL?twS^ z7D&c9dnsBIYqu*lON5I|3#Ril{(i`j|5K2;lt!0Qmbjn5n&6$FmZ+K9lqFP%UR~IN z(XTT-y7Bky3cZw+l|w*0TrJ*2+CI;N!LRS#?5Fqti_zs5qW`o$_Pu@WC+{ubYH!D9 zo?#HDQLC^d#>+3nl1C{;>t;i?d@6KQDZPnYiZz}?V{1JYWuQ7ZqJrjeuc)lejkb;{H75)7D5~LD+1@o#jm-Hti0d~>}J3Io4JYu1LOgifKyLmSuN67 z*~Y|~!vpFKe1-PfF2xoVsQttzEU*`Qy{NtltG=xHiEX~qt}Bhl z7f&UxFt0aW055#cm+k{DPL67}?=6muzv;eJ<5Xah+!EP=NbbdMD;yhrNZ`o?Xr>Cl(s2CybFP1E_Ab0>V?6X5>d`dc`}$o2%-Ss)2m5uR?iq$ zZpQ~}db3%BEUgPw0!1!aH7O1W53vB)yznalF5Xu5K?VYfMEvdNl8g4;wk4v;{(*_E z<(41y3DxOkZwo1NKV-s_>EpY;UxlxSv1lRb`azL{1JHIYRGN4K+I?YYlcmJOm#^|@_5Y#+vPK6G+6*k76dBc zrx>MCt$%B3X*F;6&Pml(%iYK0r$?##v@4f$r+t|q@6;L9V%5x7N4$tqQBwrVHi}~l_jBVh z@sd~I@*p`bp7(ZFM`t6(miwc+%v$K{+A3s=GIMYuRXlNy(E9fOviT)Lzh!{QK&;@oMg^xvu0oB6zdZ1 zTI0&)y5~&b)L_qMn`k9$L2Slr>Sqi$T-T4#{i>CuR-p7zW*OGPXUKv@X@!6AOnOCo zNWO77A3c#Xhy@RBy{ogXEGRn6k;)iO?2grrDhrbd#{ZvzarPB2_+3~~l>X24RNlYj zl}4>DLlp}}d-qrW0boQ>>L^wfek;)iSuIrz?Ky)PRF$M?Q*Gzy;On^Q*y70S$mc+0 zzir!LlVcrjWn#HwPGFX7Vr3|-yP__xL?e|Vgyblvg_1mB+TRDAdh7yL*=F-c&HC6o z4jS^S9Et^VMKh8T17h)_(!xxGVgFm%BVU(-Ov8MmRDSlPuH?E@V73Sj*v^V=eL7`+ z6vycUZPI>W{|>nl&64#~d8PSV@6zbQO9cyWD{319TNb+lyGJ{yy|KN8y}bRgoxYud zZJIUIa`$Dl(Sr_wTAdu1Xf1CaQ$INY{x}-@4GH4ww)V2!bn@^joU7Hdwz`Zuzx8)( z@{6B|(Z}DcLzV(fP_yR$^?eXQm~oWa&#~0`T(Sz5=8t`KQ@_^E4ri|o&_Ce6Ag^S| z;5-pX6nicERe3;NO$X0F*m%wqY<^<#*=p4K(&p5*#m>~e$iC8E&)(B+-zLY(-(1#Y zT#rJ7RuMyjOJJYvH_d+}E!a*^uP^5ggEkEo`6uxPS31iZBda2d`m#OJ@)8Oc!qEC}Qcgm5U#%+5UW|P1xo&w=11i1C)y&XN6pdw!!uU29Tpifgu&PmQC&JbrTCn|>*wgHwArr!EY8p8_N;*Ssxc6-_lPz`YP z+2)4mWOb)_#e0T!q#3T?f>pCog84TwVtA?A!dK1PM z7cqA5PWSJAVPF!HQ`9nya#%r(VAWEe6h>7`H9>mpM(d`U76H~Kc3Td_&SNgLZmVt> z?w)RUF0oD|_HI_urmyr~s0qn^hDGzHFt1U5B=W4 zi6kizjI3N!0ymkz0Sr9DNmxmOs~DeehwF$5oC&d>L)*W2c3$NYL1S{-U>%INZbXHF!|#??lD z4(AWu2DW%=88tCdVjWZ)^3;H{7uf>Ndo*liY^K_4n+%I3cLt3 z2__3;h;;n1{L3z*_HSm{e%;#+p+VAVrq!4Gc^6ktd_W%XC@mg)FaJ60hfImGwx+fI zr3s;Bx$UxJvg?vZp7+VCBHs=_`Zt+=5Z@9Xpr@b~zZO7V(N z2~+nW=zIuunD{!kI;zz>(CSnxQRbS*{`-4!(a*5&d=ZVI+QCFY*g>kntD!X!y)m~5 ztm&k=u_azLajmDlU&nP8)wYdKobOC9NC*QdVi{pvc7hDzpX7X0x3#tnUcHR860~=4 zW^;e#CI2eWm+sBko4q%?ext9Wy@}kd9D}V2jBmAyln5kk1=~4Z(BG1F?CjSsZc1W$Qny2j#rCmkKhi=4OR(a4U!Aa4wZ?(jM4T z=e8|WlxXu(GrN*<<7}hJ!WTp4gQ$c428D(ceZz_lj5|$Y`+c4VE#IztXn#E*Jtehb zyytW7@JNaMmDr!^mWhPBR`5*hpX{^ppazQ`g>jbIq*aBTgp-{sp$CW8cW-u|QEy+b zM|TgG4tq+gXcHsdk{2ya~En)8kr~E(nI*%8Ul9l zsmRyp6*#0IeXtGb5Tycjechi%US?ZXnD)(1IBs1Y%U%*bjXvr=qh1Og87^n`I#w$t zpN&&t&u6E{`)y2F)@l9v>4um_|(il`h|&=9*y-~j>9i!z1G7HW3Jqv0l0c#Y1&a%biN4@ zDJfpXGPPcv0Ha>BCTl&1cP`8x{NACjK)#i}M!xH>488xl?>O<;CYjk7WNQ>ChDmA& zBe{Pt6H;4|gyVcbieA+n;%rFFxs9}RJ2d%MT^3?w*QD|!gv4w|ScPGSoCGljr-W#I zV~Zk)o%`jGo|*HixWBr%`4k>LYCJEt$#9IgjzQbQ-33R`4zgD9N{cv4GAV?;NYqv} zEP2^w6>7iiT<~MXSl7TIndBZQ%>nx@~iL$Hw&{Q6+7`d zmcwJ^`S4!nO2Jgcz*&1nT~nD`-oMO-q?9<{X#4OFp>x6Sg3Uv|hRsK)#Z<%}rz~bU z76ezYG;nps4#K99E7N<)=RA*oSPn#M6z2?C9GCou&|s-ng`5{M+R+Bdrlyu%w#|+( zS0WE#uSoA_?=Rj+Pe1n!XA}Ev%PNyK-Bh(Zc}j_U!6GhxrVo_SM8;Ut59H^>dppaO zlfU}g+O%qoOAm6nGFTJIVxJ?4zG;OF1tkQf1uunaMl5`{if>EV$?7bCRzez6x~zuH zXWy--A7)*7Js$(Hz!fwXEMq(>!UhuOa!jgwnlJS|OgJq9Z9E+ooNL?;JRH5qy|=tZ zJX_t{T?QSH)=p-8hR#}&D%~;^qEHAY$05Bxc_%>^M$rA)Dfh0#vg)LF|4dtaZCmN< zzik;~iCwW3QPtn(L&SsIgZ>M44*eLO8r>LImlU1}&XX>Cs1w%ItAeMPkI(BFUvs}B-=No2J{2DNE=2Z7 z3pwK}ZKx`b>@h5q|DMf|?lb9oJQeiG8xe%>R>s1@m`3kY3q{TElKNc#jQd2ZxUy*U z2tHloJVR1@Iv9H^ z{}pUW#z`ex>%HN**{w~GQ-FK7x0x@kKQiF>?b_S^fRZ<1uU);2T;1&JEu4&^v=o(# zrTT>{xDA=wC{75L0e@~)5G$Ke^G>6&aOP$RO3ec2;HJ<13XbK7hKD=pCx~R#pTYETaW@lAtKk2;xVFt5-@Dl|Y<0sA{fp{?`xqqsQ z+Brsq7U*`a&O#n)KFPks{&@kKZyy56{XP8nUOjs3IRou{%%u#!YU(J}NHz$WbLBF` zk_qBPJpa4w+h1B?p33Y0)%IM2Sz3dtw0|b<$BIVBgk?6M=oZt^GC9r51msGtZI&f1<~HihTa|BTOO;{o7)AcU003)r5wW&EI8tlx6s} z?^{)S^~WOT$2X{sw69!|Ryh15eN@!U?A+^uO5*x*7^?bOFoSB-5=#cVb4O;^M0agZ zn3uZON6#U5N!KaIeA`hAYZDhe91WP#gOnxIiVvU7iq-+lhMWIPa_xJxz7aU@JeJlg z(WX^*P)=KTpBiYi&u?XbKMjgamM-XTkRPm_mEV0t=fiC#VWd)L)Z`%M z&lbUwgv!&a4r;RK-xy1qFIbh^=Gj*{v^z}LBWzi$Kby0dQ0pgXMyQa=iHKth#d1$G zFH#qQOmNrH9B%hc;&%O4Q)bD=&ilkV&zhKO*D82X#&lWk{U6+{oy;GZxW6^C^s~W# zBMNd$JSzul`xEvWtAC? zce=%fFHK*WPguHHbJ`%S5mp$MN@fGb75W6)YcJ#!C8XzI90D9%t4t=;iJ(l}5OkwE z#xvyJ-5TqBz&L2&pp&Y(x@MrJ&!&Uq>D0LML_f0O$^es=V z8mud<`>n_u7T?4A$R3xd;9zwQ42Ve zxr3j(lUhJ^=M@IUFY>nkC}sMm#ijg6{+eu>!juNjF#9w3m#mnh5>aQ+CfMsgikvN8 zd%Z7mzH#r1(ThJ%`iB<8%Exmm=q>hFCP_&~JzU4au*}rf!qGaVlPX;(l`Z8yIWL7TEj*(st2H;akha{ohOIfEOKQ+`^53G?*3(hxl_7Et zo0S+sdBxzzQNv#k4V9u+v{X~lDK`A}vei=F_SSyfvEOOb>BJG@kZWsYtAoiy#t@ITRiHH!X~SJ#L)b9DI+;7-iW_pgudub!>lO`vDuYJf(lM45s( zt07&mKhly)zUl(H?~G{7$gR|DEA3?*4;`BwYaG_?v~92~NneHGNE+ppgsgm#{mFQ-8x?|Q`AT{q z-)6qZw#s8J{!-ys+t&QKD|%pY+-e?ky?oE%^!X<2c^#XENPt{`j*xYgJ6@1U%uU8i z2}@m2XUJgCgvGqxGSWKQrrSouX3J{BLfq`anAxCP`$+At(w)q%*ax9Xo@7=iT`Jiy z!4~GqW6x#r(f6%yOL0?ULxynP)=zb&m5aq>`Sdv$sITn-=>+ND)6X;bv!rv-^8<>% zSMb;BH?MZ~_dkr;&8@9^?VclSuS=d*F!%8{z(drTOjewC{PxgLNlp1|m2iy>oeYCw zWAvBtX7=Vj=AC9vFP%+B42$&ew6E3PDgTmllAM7eA?sZKvFy>ZlJgURaHgK$-{PDF z@87O}UZ9#h9wdWjwN}=fRHv1t78&Kw=L+OlWSeHQ*#rMP-K$6~SoV_|o-RxN+orxIL z=(p=SZb8%s{%fizD%CIUEqpF`ET}GIDV8e*R=8LD)IBy4bVT+z4}F{1nR8gh+^Ii$ zccF35h7JN^5vufq7@{kB;EvO0aPBxuJlj3_9Ql17hR_nN8j{gbpzTyHip*1 zs^cm$%bZJBOK?h;N-fKSD^33m)$KM#wwJ&~2JyzpW?wAFZXWKdpEg_zKhaFNK>iOy^=)Tb=)8t2)d6)7X($eByBGwRE z?n+iJhEG&A;CX^M>~6H^d)dpmW4qm>wf`1Gr&vd9`W`zmTYof^*SxJdE@vzwC@n3) zCY7@VIwHEsx(2%MbV#&0H5=8IReqrQJIqLWiq;9W@r83Tu*A_#Qvg5| z_#{{eWb5s_bGD;_?boZE^MFaxVfSA8PKlQO`ip-Jm8|8`r9>s6#r4H`CAwuT6<5{E zb*{~yJJ5Pphp;Cd=8sm>cHEDRFLfWx0PeVNNZwI8GH|lj@?Hv!iHXP%D4M9=s$Xkq z>+b5c=uhZN>SO3B>Y!_>s8g%PDCWsJNzTKFg^2jpI3k%rbiNd|BqMmen2AWK+uk#= z!!%UVh0O|$^9=gI`P(g$+ii%xIPs&BAdFm>f8ryk$jt6hX zrRJ(vY`2Au_%D?2U!&&(*NDNC91QsErM$;NgJSG5w+h;-m>PWA^|~qg9R^Z{c!mN7 zJ$j=$+FBawgDP_hVKR&2TO$7;Cfwbu#0*d>7?_k`2+Q^P;MU~4=Duy)h^%~NeWy*K(?29gG4`YC!3Ity9~8X_-R zQ3gzf6tCDzVR`;FPGy$YbWRj(B#pRq7`Bg}uEG(Ky9sNJ^LUeaLvcNu?KMr9bw^d+ zNV&L!Osax`N{pJQrm}XuPOxr+uBUFSj)b{yr& zBE*f)R=_|?twpLvNQ9G#c6TRyp?Bo89kc?U6(4^bpoJH;H8h&kMpSv0qm{la_Aat0 zA}sz|l3(UqIr*=;o}gv4&#%`W6sKf2K=3Y|CxhsH^)YR^?b>RQ_0ISN^F&w(9r4 zggT-o%r>ts$v)TNy@`Kwbt`*Y%7<-d#td=<2SEY82F`PqUHViiB2qm<8yqck=7){TLPX%6??%ef z!%XS;zajd*`!4NvXiIJ5O#SaV);fhc+v-a;@^u2h4TBFO8Rda*Ow43>R zP6$+AmHSwGO#n%0X;7(E7u4gqYxODBi<%uChH}CpfInfq$H!%uXv=8Ex#{2 zBCRgzCME;z5Crf8xU1P9O!l;v6wIJ1d|GU6G}n9EOKpVwp7O@0rQMm_@!BC+A76Jt zds|CD(@?``{oDHL`mYVsjaki`t*IS--FAKML&IYc(@6_QtDm-&52epcZUUbQF&Jv!anuv^5Nup50EUN&?zWH%l+{b^}! zGwIZXH~0M-ni~5!{olgMYV!8aL--lx?OWsoCK#U&L`ykMXTTD}8Op~k^af@nu`InJ zXQHUAoUY=enyqTCnx^8YT%-719!(ZoszmHeWK$rRcZuVf`G~HRQW0E3fQ|z}mwk}A z5BFuGX^BNY-#s=UL}cw^O%Xuhq!c{H|53!>;?Zcjtei z*U7vNO3S)DAUm_Xsd#$CkixSi(Wd~@{bHWv7~%aOI0)?%e<}T5j!sctd0u5l)%}I< zi%V6c$`|D*MMimPnH>o}Q6k|y{wpqAwo`^&Y8Y8M(Gu_ufcA8DJ#*T4P_R|HGCwCb zc{fbo-_X6*{-@=k@u2=gU2H8^ty=AVEucQ9p{vQUHL`;PF4f;PTt7iH*Sp-eiQG3k z?YL%t^25l&{X^_dj!o;x6wL0%gC<}oqA9j1i6h$}f2x?S+^^!Nnxkr`TB!0_c}}rS zo>!Jfs!D7_q*6ef_Y+45voYNXg)t}^KOHOT+4_#*V)`g)$9FAoVSXxZv}52^PhO{g z+emYDBV)r;ok1OQonswSy-fpSlS>P&D;) zPy=N{RzrE?i)NQrf)1hX&0f5rs8nu$(`LJ!VBn~>9ZY{DLxaZpF)z(kJ+08 z%&xV8aN7AOc;8pAIQ*1M)CZyo}WM51Fq6eTo3%W+t$pM z#OBPW2FAjNqX)Knb5Ux7WT#}u-}a<->JIwOlCB~6hraSbx6zbImN~R#vJKtczeiZ- z_BZv959mxdd;|obZgLHp9EJgwIu2i+O@4BrD-kErH{w7^TB&-eU8x+YE6D{3eQ|41 z5~!2Vdx!$>Feeoo9}|EsA7w7-5E1gAKoXobk0;2^&PPc=sy zOB4eqO#=Bi$r1iO_7wWR$E=&|^MPaX{hz225iDWNaZiPf(GB1CLwo1CS33hb!rR%~ zjoKMH0y>?#4|?wVqlOd4v1WP~dQrQP@j>GW%hi{A`11uO5_gU$niNFkMVG;pf|7P` zcvS>+gdd=CVr&vIl3%3mq%fp&r4}VCBpAe{L{CM`guEaeyz!j*tbUA-G)ffaASD7^ zoMv?IN4^{E^T#8uy)T=0D>=*8espFt0Kw@l}D`+ZwPTXCCy`_B&Nu4VXk z-+x1CD02m8L3lNG3wZGJgyibK`|)RVENr}OqGVE5s!+NnrVh3YE@8g!0@=dmuqLq@ z2{9=(>3Qi3={)HJsZL2D2}!XHsIV}*KsPU#i-zrpF^cwiy zr_F{vc0|+#;#L~zj}Z&}PUr?^q%5ZeF-frTa?SB73D^m504M+F;^)z(_b#%3TZ5?T;ZxL^GX%p+H?CS6F9Ecxbp2V4BShn2A+dVttJlDCg zeAGjSV&mY$iM`04sov1HGas-IbARDK6uc8D5IsWW+KE(!^rQ5Gw6U~{6se?zxU^`a z$c$h*KbS|ILyqN{K92gD3__xVZ-H%rZuMw;<9+_^xM**CQ);zt!F$GWqGZHs(5G(+ z-qnTQ+1~!x){IhK&f4FiOeCA$!U5lr^a;kJLgy5k~1VKJdyepU#es^bT+* zZ`V>cL+^1v?{FVVK-!y=Kq(shC>22cWaT2@7W9;lE{8pcr$yXGN>AlV7sV9DrpndA zyA3H6LWAz2BoZC*ZE;$OOL0H(XfbKgD5#I{lYlTkBTpL#B`cH>i?)b@7VJS-1f0fr zL^9mVT-l%gIGo*qZS*Z?&HtO`nm~@Q4wdx(?%jvycb|9FbkTNm!UuaW`$q<`NAo5U zXPOp>SN%74b}dk52IMN~?)XU>;E$b!*F@90zhg7Ug?{xC?oTJVEJ2 zM@4DHZc!aHJYbkmL18q(H~eKhxtwlnmrN$~fz(0d4j^8_1)vw^!L!ao%Js|{;j#8! z_9n+FV&QtmW|C=4WVm)9t8c%j1I_^l!As!_J*jj;#xMle&AWf*Q1lb}!&>iS0vZAA5UEmcCO1lx>JKbDceOT0)JDO@8 zpB~W~A{$WZL+_RAA?=CpDeN`u4<8gCQ6F!e3Yha;idq}p;@tmn3^)(CKD^g|F2#7n zktKLfQcN~THAmOW^py?C3F9S&BnV~-L!mEVTQHy~97YYpf+nNPlfMv2zEtjRj&{~a zCJvNsGf#d2IwKsxjmMHi?|D?Zt-N44DLT;FVcn2g30a_-MW13FPag3f$`}ys*XWz* zUGM$e7u(N1C^YN6<_P*kYJYNR&<4Rr zAOQ3I^Ul5Yb;FtH@$g>M)~B`1rHi@PX`hM6QQ+|20B8R;%H%ljG3=G^E9*}kydN$d zYn;TG{jk8evbEl^-LT(zynKedV!2mCz5)Ef-o)b~en&b)iAN{KB+Pcr`G)s5#73x0 zSe7 z+7Zv*pG~t>)y3Dd7n3z(1H;;bLjCW0b$jyQAK|<3#U715*@4U<`_a!68z`^Fcv)}V zf4gcQd8~h)hH`(Xp4Bk?aI)}6iJwSmsMzW7nYvk3I3s!9@q+}_gejn}VAi6WqR*o3 zqI9B+uwD^XVIIK^eobB%E+O_NW()=bnnUt<5HXAW%bGQ0p-qr>jcZ= zbL%MoWosCF@JC-l4+O5${m`Y{O$xW|k?RW_5FC~o`#H%wd%y6w0@?huyL)JUx`>ih zR-POH7uccrAd* zz=D+NsP}&d>nqLyo?d=S!4P3_s6R|fG(j{*R9N&s*jFfzNSM$M0Y&~io^H+zHU;Kd z`U`4&igQp6p#|;|raoHh1LsY~IWwYjKXBV+{oC@!{C_hZleJ?CBl1Iq1K#~reO`TW zeUkkz2c`zwhw;WTC%#M<&JizFtbW`K*o`{uJfXUbzNLApN4GkLl z#kR|d!#m0^EXXI^BC-h0gaJfJMF&wrjsSE-m{@2RV#622t;sRULdi%@yF(EJ#wGH_ z?Z>1=d-pJXt$V(D{C(eT`}KOmve?4y4B6ECalTQ*;km(<0muN}fYpG=p#Ko%2+vs9 z1Z0|eP7?Jm{NsAew($PJQS)iWW#(<=<2)K3mNM>p!a`6xc?)#}Ju`D4+jmX_o?gCL zNQB_3(3)_H$dd>abV)=>AV^@DPlLyTlZ-8hDUa?O6@)CG_zq71TN~Z+G2*8B z9DoSk7v1JscUj(_Z<;xrv>4|ebs2sbL?8S<5H@f-a5eaHm}%5#e0(x}CU1UYNquc% z^VKfT;Vz=%JnK5@J_zX#u)-AA&uMa@BNhGcNE?vJR|wbT(}dEOGNrI8a^!M#@+9z4LyQHq1d)Poh5ibC5V{h?K<$y! ze7|{sTwwMQW@!cw8Yc=K@F1ZMZVM(o+P4Sfb@aJ1g7ZLl=hMdNO48!Dxr%Ah$@wwl zNWgHw(D~rppw^Jk@cR)#lz37wWi_k4;IUk~M!prd%W*h?NIG}D*1nfPiULHjMe$%n zTwnl2J+%UT22%%XIfonfIPW9>pn$f}8(|HRUXf*yP?0KOH=!&67ydDx1FR{X3pHxioDtN3w{zmb^x>WxG3m;D{hQU%P6%D|yO8FT<+CZ6W*z3L}@I?x15} z(qh%%py4j%MTg)C4hV^gXhM-tRTu^AC6qzLT!=-$kI$YP!46^JU|68GBX1)?ClJSZ z4XA#?zx#eEbV_gp-c#NBx2Cd;yFf9kIkh-GJ<2h1F{C_nImk3LG}JrHGkP}mJYg`s zKU;#bb@J9mHfeW19iStApP5{7-cdbKqKjf#;C>*C0R@rkQ{U2gFjcb-aa3@d@YO*2 z1iuQ;i;O_6VeeqHFlp$4Ff%IGUh>&+({Mzw{9{O?(WjUPDG>euPGC?zd*08YZbxt* zlc84jxAmvxx`m?I(J6}w#j#H#kl~j@BZJ+83_}w`=fm$t)yI7&_on0KUM&W%w5@Y* zx9q(+(mZ`}X?Yv*ID$rvWs93kSOY2}|3uAAU&4gLCe10!^T_v6AW6ss;8%QN@8J7+FI5Q^0GxZ#KB#4W!38;s17c(DRZ}cwAPCgxW?ow_2w?@9) zH(xe$KZ$C4Hi|W}J;aAvN%TYcLwUo1(W0@x6H8N?vq$qiOOvalo8dc<0~`bi%G$`f zr+m)9U;xGw9FuU8OH$L*FEClNm2%ec`15ZI>9EU)-{{y_%tZLq(2VXp=@QYZ;zsed;y(D8_)PHX!`<|g0-z98ZR-;U zlm4U(rqyEHWijRW%x%MW1OW<_3onYqLua7nPzorONRiN*KqbEbuRa$Sdp$EDN=jv; z0D@--i*UbUIip)VdEdoc^_&qP%nk~7s5h%u-Iw0YZ_Y$aWlqqIua1(B){f+jppCYV zc8q~1Y9<4x6J|H(-IsV)`8RyFPxmU0icgm=x$k~Gp#ki$t5K(8}~4dG1TL}6ZGTOm=D3RlFZ&y&a*#Ky$@g}$7+oxC5^OE`~vi^T`{ zgj~2+zNxriI{k9AxTm!}wf=F%Z}Hz8-wbFEYXY6K7abjt*dU|?R zWTAg4YqfIYX***7#j)s_-c{(`z!NS&3;Qiz0#PFPBg&y1r59y3XOrL@<-X%>;U^bB z7mOBc5KInBtMLj3sxd0RF`DNpbA1_JU{FefaY`C1Mh9(CGynz zxNF~V=YC^i6>Zsi;b|6gMr~?lVqu(Xd~ysiW;l*9K|bj$4-PpVDUPkxz7nO>iHKc}@|vsAI7y)Lk2wA+4Qh2T0TyT-l8L;?V(SQEH;gpME( zc@`Cz&W`adi#hudCkqdN?=62ML{cD5AX0!qKm&ruZ;pDWZEy&%DKZN%T+#fc)FfLZ zu_c_r)x<6b;5_R-e81_r0G_HH)$OTo<808bIxHQ`FU``;(mUm(9A#*kY6Qa)u~e{KWLbv8j3Wkx|d1XU_IJ2;mJg#R9A4uc0} zdX?PnUoxLrAGf2Nr`K&jLnqjq}~L4{LgsHIP1jf#Ns5ybm2_IT=fEM znPg3Jvuwxm0EXZ_7rvIi*GB3Cbg^aeD2X;f-^r<|-_WHp2D7lSzv1-aCgru{Q|I61 z7lg1w2KXuYvH3E1Ho2BL64>xrUNXL+bEDRzz#*+B)*%=L%421sZ#^;G>tBC4|355U z18|+~^L>5I*k+r$sqL>wZGN?F>#N(;wr$&1Z1X0$*6aVyZ~k-Vrqi@D+3a)noU{8T z`#d*B)|{^FSJtt3P{GsO1=*uBPp5ZF^GofJ^5O4Nc%}Val=5%tle9@0E3#ZUMfoAc zcgt2)Ev?;eerB(6hw=ZQv&f~grK-`oD6cQRZ3E|r%npx<+7)v#ZeG2V`dM&pxef9f zEN}2O;adHKdXwY2#uP-h51$h?z5}QJ#v`)E@GB5RHT2O{EYjln--?wObskP#=VU2Nx zb)EAB^G2w_JS7bkT{X=-BtDn?WxIV6%D&Ld;xiyS^sYQ z$=GJmdm^reo(h`fAM5kpV~n;;Iac2HF@|g~G|dak znUs~4u_}EPpgTO(nW9Xco!T;OWO_lyw=BQhC;1nOzJS^$8^VphEIS=z=$3pGDkWXg zROK1%0MA^XHUUe5mxQ&B`~(YhisC2NKaw!3K}`dq;j;!pLU#QD_5O{Ej5!}!66Odl z2)O1u%8SvhQP;}*N{-=qq7OIHebKJ7Y^d`$SS#{MCB^FsBJ$)p{j#29%uZjO_A0es zYUk92uu00CmY9*9S)84imr`)M_+eRPWs91tu+c2dv5y|i$DnrNk#wq()6DaDY3w)#?FlH6j>J5H)KcPS-%6`lRSL1 zmz2J;MdTZl5V|nQ&N^#fQ%23EsxIYyOSTu5=N-)1k##*IE*(qrNes(xz>%&mJH25Mdy*hvPa5#+HD>$y?^=L2pktu9u^rH z82u^6BTgBAGhU3h#_x(xiTfD4Fs3XjFfuHh41FHdH{iXm-n*kmk~UH0lAWfa@S~!@ zPK2x7gDltTS{uw2rKMs~hl0G^>)DqxwHeRSE~gTyFH&Bmv`Y<18<(!i^v_a zQc@mLGN+KsyOVPz3(Y)`z9y|G^}p1Esex(Ew8j~~GoNQ$bLSU?7fZ{+D<>IJ>t