From eafe00979c39522e4bdef424d3b7cd3a586366c5 Mon Sep 17 00:00:00 2001 From: neokii Date: Mon, 24 May 2021 11:42:06 +0900 Subject: [PATCH 01/27] merge changes from master-ci --- README.md | 1 + RELEASES.md | 5 +- SConstruct | 4 +- selfdrive/car/toyota/interface.py | 12 ++++- selfdrive/car/toyota/values.py | 26 ++++++++++- selfdrive/car/volkswagen/carstate.py | 53 +++++++++++++--------- selfdrive/manager/build.py | 20 ++++++-- selfdrive/test/setup_device_ci.sh | 3 -- selfdrive/ui/qt/home.cc | 2 +- selfdrive/ui/qt/sidebar.cc | 68 ++++++++++++++-------------- selfdrive/ui/qt/sidebar.h | 17 +++++-- 11 files changed, 137 insertions(+), 74 deletions(-) diff --git a/README.md b/README.md index 94bbb8acf55e4d..e92f07f3b6fe84 100644 --- a/README.md +++ b/README.md @@ -108,6 +108,7 @@ Supported Cars | Lexus | RX 2020-21 | All | openpilot | 0mph | 0mph | | Lexus | RX Hybrid 2016-19 | All | Stock3| 0mph | 0mph | | Lexus | RX Hybrid 2020 | All | openpilot | 0mph | 0mph | +| Lexus | UX Hybrid 2019 | All | openpilot | 0mph | 0mph | | Toyota | Avalon 2016-21 | TSS-P | Stock3| 20mph1 | 0mph | | Toyota | Camry 2018-20 | All | Stock | 0mph4 | 0mph | | Toyota | Camry 2021 | All | openpilot | 0mph | 0mph | diff --git a/RELEASES.md b/RELEASES.md index e947335d9dcd3c..c8f09f44e59775 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,7 +1,8 @@ Version 0.8.5 (2021-XX-XX) ======================== + * Smart model-based Forward Collision Warning * Hyundai Elantra 2021 support thanks to CruiseBrantley! - * Added smart model-based FCW + * Lexus UX Hybrid 2019 support thanks to brianhaugen2! Version 0.8.4 (2021-05-17) ======================== @@ -652,4 +653,4 @@ Version 0.1 (2016-11-29) * Adaptive cruise control is working * Lane keep assist is working * Support for Acura ILX 2016 with AcuraWatch Plus - * Support for Honda Civic 2016 Touring Edition \ No newline at end of file + * Support for Honda Civic 2016 Touring Edition diff --git a/SConstruct b/SConstruct index 0ffa8cd94057b3..4a2a1748176347 100644 --- a/SConstruct +++ b/SConstruct @@ -228,10 +228,8 @@ if os.environ.get('SCONS_CACHE'): if TICI: cache_dir = '/data/scons_cache' - if QCOM_REPLAY: - cache_dir = '/tmp/scons_cache_qcom_replay' - CacheDir(cache_dir) + Clean(["."], cache_dir) node_interval = 5 node_count = 0 diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py index 6a7201defe514c..19ae0accac68d0 100755 --- a/selfdrive/car/toyota/interface.py +++ b/selfdrive/car/toyota/interface.py @@ -25,7 +25,7 @@ def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=[]): # py ret.steerLimitTimer = 0.4 # Improved longitudinal tune - if candidate in [CAR.COROLLA_TSS2, CAR.COROLLAH_TSS2, CAR.RAV4_TSS2, CAR.RAV4H_TSS2, CAR.LEXUS_NX_TSS2]: + if candidate in [CAR.COROLLA_TSS2, CAR.COROLLAH_TSS2, CAR.RAV4_TSS2, CAR.RAV4H_TSS2, CAR.LEXUS_NX_TSS2, CAR.LEXUS_UXH_TSS2]: ret.longitudinalTuning.deadzoneBP = [0., 8.05] ret.longitudinalTuning.deadzoneV = [.0, .14] ret.longitudinalTuning.kpBP = [0., 5., 20.] @@ -308,6 +308,16 @@ def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=[]): # py ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.1]] ret.lateralTuning.pid.kf = 0.00006 + elif candidate == CAR.LEXUS_UXH_TSS2: + stop_and_go = True + ret.safetyParam = 73 + ret.wheelbase = 2.640 + ret.steerRatio = 16.0 + tire_stiffness_factor = 0.555 + ret.mass = 3500. * CV.LB_TO_KG + STD_CARGO_KG + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.5], [0.15]] + ret.lateralTuning.pid.kf = 0.00007 + ret.steerRateCost = 1. ret.centerToFront = ret.wheelbase * 0.44 diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 6611fb60c667d1..6f04a086638b4f 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -50,6 +50,7 @@ class CAR: LEXUS_NX = "LEXUS NX 2018" LEXUS_NX_TSS2 = "LEXUS NX 2020" MIRAI = "TOYOTA MIRAI 2021" # TSS 2.5 + LEXUS_UXH_TSS2 = "LEXUS UX HYBRID 2019" # addr: (ecu, cars, bus, 1/freq*100, vl) STATIC_MSGS = [ @@ -292,12 +293,15 @@ class CAR: }], CAR.MIRAI: [{ 15: 8, 36: 8, 37: 8, 164: 8, 166: 8, 170: 8, 180: 8, 203: 8, 295: 8, 401: 8, 426: 6, 466: 8, 467: 8, 494: 8, 495: 8, 550: 8, 552: 4, 560: 7, 562: 8, 581: 5, 608: 8, 610: 8, 643: 7, 664: 8, 665: 8, 666: 8, 728: 8, 740: 5, 742: 8, 743: 8, 761: 8, 764: 8, 765: 8, 789: 8, 791: 8, 800: 8, 810: 2, 812: 8, 818: 8, 822: 8, 824: 8, 829: 2, 830: 7, 835: 8, 836: 8, 845: 5, 863: 8, 865: 8, 870: 7, 871: 2, 877: 8, 881: 8, 889: 8, 891: 8, 892: 8, 893: 8, 894: 8, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 934: 8, 935: 8, 944: 8, 945: 8, 950: 8, 951: 8, 955: 8, 956: 8, 971: 7, 983: 8, 984: 8, 987: 8, 998: 5, 1002: 8, 1011: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1071: 8, 1076: 8, 1077: 8, 1081: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1172: 8, 1228: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1593: 8, 1595: 8, 1649: 8, 1653: 8, 1654: 8, 1655: 8, 1677: 8, 1745: 8, 1769: 8, 1770: 8, 1775: 8, 1777: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1792: 8, 1872: 8, 1880: 8, 1937: 8, 1945: 8, 1953: 8, 1961: 8, 1968: 8, 1976: 8, 1988: 8, 1996: 8, 2000: 8, 2001: 8, 2008: 8, 2009: 8, 2015: 8, 2016: 8, 2017: 8 + }], + CAR.LEXUS_UXH_TSS2: [{ + 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 401: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 643: 7, 658: 8, 713: 8, 728: 8, 740: 5, 742: 8, 743:8, 761: 8, 764: 8, 765: 8, 800: 8, 810: 2, 812: 8, 814: 8, 818: 8, 824: 8, 829: 2, 830: 7, 835: 8, 836: 8, 863: 8, 865: 8, 869: 7, 870: 7, 871: 2, 877: 8, 881: 8, 882: 8, 885: 8, 889: 8, 896: 8, 898: 8, 900:6, 902: 6, 905: 8, 918: 8, 921: 8, 933: 8, 934: 8, 935: 8, 942: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 5, 987: 8, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1014: 8,1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1063: 8, 1071: 8, 1076: 8, 1077: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1172: 8, 1228: 8,1235: 8, 1237: 8, 1264: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1592: 8, 1594: 8, 1595: 8, 1649: 8, 1775: 8, 1777: 8, 1779: 8, 1786: 8, 1787: 8,1788: 8, 1789: 8, 1792: 8, 1800: 8, 1872: 8, 1880: 8, 1904: 8, 1912: 8, 1937: 8, 1945: 8, 1953: 8, 1961: 8, 1968: 8, 1976: 8, 1990: 8, 1998: 8, 2015: 8, 2016: 8, 2024: 8 }] } # Don't use theses fingerprints for fingerprinting, they are still needed for ECU detection IGNORED_FINGERPRINTS = [CAR.RAV4H_TSS2, CAR.HIGHLANDERH_TSS2, CAR.LEXUS_RXH_TSS2, CAR.PRIUS_TSS2, - CAR.LEXUS_NX, CAR.LEXUS_NX_TSS2, CAR.CAMRY_TSS2, CAR.CAMRYH_TSS2, CAR.LEXUS_ESH, CAR.MIRAI] + CAR.LEXUS_NX, CAR.LEXUS_NX_TSS2, CAR.CAMRY_TSS2, CAR.CAMRYH_TSS2, CAR.LEXUS_ESH, CAR.MIRAI, CAR.LEXUS_UXH_TSS2] FW_VERSIONS = { CAR.AVALON: { @@ -1636,6 +1640,23 @@ class CAR: (Ecu.fwdRadar, 0x750, 0xf): [b'\x018821F6201200\x00\x00\x00\x00',], (Ecu.fwdCamera, 0x750, 0x6d): [b'\x028646F6201400\x00\x00\x00\x008646G5301200\x00\x00\x00\x00',], }, + CAR.LEXUS_UXH_TSS2: { + (Ecu.esp, 0x7b0, None): [ + b'F152676303\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B76012\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x700, None): [ + b'\x01896637621000\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 15): [ + b'\x018821F3301300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 109): [ + b'\x028646F76020C0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', + ], + }, } STEER_THRESHOLD = 100 @@ -1675,13 +1696,14 @@ class CAR: CAR.LEXUS_NX_TSS2: dbc_dict('toyota_nodsu_pt_generated', 'toyota_tss2_adas'), CAR.PRIUS_TSS2: dbc_dict('toyota_nodsu_hybrid_pt_generated', 'toyota_tss2_adas'), CAR.MIRAI: dbc_dict('toyota_nodsu_hybrid_pt_generated', 'toyota_tss2_adas'), + CAR.LEXUS_UXH_TSS2: dbc_dict('toyota_nodsu_hybrid_pt_generated', 'toyota_tss2_adas'), } # Toyota/Lexus Safety Sense 2.0 and 2.5 TSS2_CAR = set([CAR.RAV4_TSS2, CAR.COROLLA_TSS2, CAR.COROLLAH_TSS2, CAR.LEXUS_ES_TSS2, CAR.LEXUS_ESH_TSS2, CAR.RAV4H_TSS2, CAR.LEXUS_RX_TSS2, CAR.LEXUS_RXH_TSS2, CAR.HIGHLANDER_TSS2, CAR.HIGHLANDERH_TSS2, CAR.PRIUS_TSS2, CAR.CAMRY_TSS2, CAR.CAMRYH_TSS2, - CAR.MIRAI, CAR.LEXUS_NX_TSS2]) + CAR.MIRAI, CAR.LEXUS_NX_TSS2, CAR.LEXUS_UXH_TSS2]) NO_DSU_CAR = TSS2_CAR | set([CAR.CHR, CAR.CHRH, CAR.CAMRY, CAR.CAMRYH]) diff --git a/selfdrive/car/volkswagen/carstate.py b/selfdrive/car/volkswagen/carstate.py index 44ea7175c70b24..dad93575952389 100644 --- a/selfdrive/car/volkswagen/carstate.py +++ b/selfdrive/car/volkswagen/carstate.py @@ -186,11 +186,6 @@ def get_can_parser(CP): ("KBI_MFA_v_Einheit_02", "Einheiten_01", 0), # MPH vs KMH speed display ("KBI_Handbremse", "Kombi_01", 0), # Manual handbrake applied ("TSK_Status", "TSK_06", 0), # ACC engagement status from drivetrain coordinator - ("TSK_Fahrzeugmasse_02", "Motor_16", 0), # Estimated vehicle mass from drivetrain coordinator - ("ACC_Wunschgeschw", "ACC_02", 0), # ACC set speed - ("AWV2_Freigabe", "ACC_10", 0), # FCW brake jerk release - ("ANB_Teilbremsung_Freigabe", "ACC_10", 0), # AEB partial braking release - ("ANB_Zielbremsung_Freigabe", "ACC_10", 0), # AEB target braking release ("GRA_Hauptschalter", "GRA_ACC_01", 0), # ACC button, on/off ("GRA_Abbrechen", "GRA_ACC_01", 0), # ACC button, cancel ("GRA_Tip_Setzen", "GRA_ACC_01", 0), # ACC button, set @@ -211,31 +206,17 @@ def get_can_parser(CP): ("ESP_19", 100), # From J104 ABS/ESP controller ("ESP_05", 50), # From J104 ABS/ESP controller ("ESP_21", 50), # From J104 ABS/ESP controller - ("ACC_10", 50), # From J428 ACC radar control module ("Motor_20", 50), # From J623 Engine control module ("TSK_06", 50), # From J623 Engine control module - ("ESP_02", 50), - ("GRA_ACC_01", 33), # From J??? steering wheel control buttons - ("ACC_02", 17), # From J428 ACC radar control module + ("ESP_02", 50), # From J104 ABS/ESP controller + ("GRA_ACC_01", 33), # From J533 CAN gateway (via LIN from steering wheel controls) ("Gateway_72", 10), # From J533 CAN gateway (aggregated data) ("Motor_14", 10), # From J623 Engine control module ("Airbag_02", 5), # From J234 Airbag control module ("Kombi_01", 2), # From J285 Instrument cluster - ("Motor_16", 2), # From J623 Engine control module ("Einheiten_01", 1), # From J??? not known if gateway, cluster, or BCM ] - if CP.enableBsm: - signals += [ - ("SWA_Infostufe_SWA_li", "SWA_01", 0), # Blind spot object info, left - ("SWA_Warnung_SWA_li", "SWA_01", 0), # Blind spot object warning, left - ("SWA_Infostufe_SWA_re", "SWA_01", 0), # Blind spot object info, right - ("SWA_Warnung_SWA_re", "SWA_01", 0), # Blind spot object warning, right - ] - checks += [ - ("SWA_01", 20), - ] - if CP.transmissionType == TransmissionType.automatic: signals += [("GE_Fahrstufe", "Getriebe_11", 0)] # Auto trans gear selector position checks += [("Getriebe_11", 20)] # From J743 Auto transmission control module @@ -247,6 +228,14 @@ def get_can_parser(CP): ("BCM1_Rueckfahrlicht_Schalter", "Gateway_72", 0)] # Reverse light from BCM checks += [("Motor_14", 10)] # From J623 Engine control module + # TODO: Detect ACC radar bus location + signals += MqbExtraSignals.fwd_radar_signals + checks += MqbExtraSignals.fwd_radar_checks + # TODO: Detect BSM radar bus location + if CP.enableBsm: + signals += MqbExtraSignals.bsm_radar_signals + checks += MqbExtraSignals.bsm_radar_checks + return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, CANBUS.pt) @staticmethod @@ -267,3 +256,25 @@ def get_cam_can_parser(CP): ] return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, CANBUS.cam) + +class MqbExtraSignals: + # Additional signal and message lists for optional or bus-portable controllers + fwd_radar_signals = [ + ("ACC_Wunschgeschw", "ACC_02", 0), # ACC set speed + ("AWV2_Freigabe", "ACC_10", 0), # FCW brake jerk release + ("ANB_Teilbremsung_Freigabe", "ACC_10", 0), # AEB partial braking release + ("ANB_Zielbremsung_Freigabe", "ACC_10", 0), # AEB target braking release + ] + fwd_radar_checks = [ + ("ACC_10", 50), # From J428 ACC radar control module + ("ACC_02", 17), # From J428 ACC radar control module + ] + bsm_radar_signals = [ + ("SWA_Infostufe_SWA_li", "SWA_01", 0), # Blind spot object info, left + ("SWA_Warnung_SWA_li", "SWA_01", 0), # Blind spot object warning, left + ("SWA_Infostufe_SWA_re", "SWA_01", 0), # Blind spot object info, right + ("SWA_Warnung_SWA_re", "SWA_01", 0), # Blind spot object warning, right + ] + bsm_radar_checks = [ + ("SWA_01", 20), # From J1086 Lane Change Assist + ] diff --git a/selfdrive/manager/build.py b/selfdrive/manager/build.py index edacb9b22e02ea..c7fc83fdffffbc 100755 --- a/selfdrive/manager/build.py +++ b/selfdrive/manager/build.py @@ -1,19 +1,23 @@ #!/usr/bin/env python3 import os -import shutil import subprocess import sys import time import textwrap +from pathlib import Path # NOTE: Do NOT import anything here that needs be built (e.g. params) from common.basedir import BASEDIR from common.spinner import Spinner from common.text_window import TextWindow +from selfdrive.hardware import TICI from selfdrive.hardware.eon.apk import update_apks, pm_grant, appops_set from selfdrive.swaglog import cloudlog, add_file_handler from selfdrive.version import dirty +MAX_CACHE_SIZE = 2e9 +CACHE_DIR = Path("/data/scons_cache" if TICI else "/tmp/scons_cache") + TOTAL_SCONS_NODES = 2405 MAX_BUILD_PROGRESS = 100 PREBUILT = os.path.exists(os.path.join(BASEDIR, 'prebuilt')) @@ -27,7 +31,7 @@ def build(spinner, dirty=False): j_flag = "" if nproc is None else f"-j{nproc - 1}" for retry in [False]: - scons = subprocess.Popen(["scons", j_flag], cwd=BASEDIR, env=env, stderr=subprocess.PIPE) + scons = subprocess.Popen(["scons", j_flag, "--cache-populate"], cwd=BASEDIR, env=env, stderr=subprocess.PIPE) compile_output = [] @@ -61,8 +65,6 @@ def build(spinner, dirty=False): print("....%d" % i) time.sleep(1) subprocess.check_call(["scons", "-c"], cwd=BASEDIR, env=env) - shutil.rmtree("/tmp/scons_cache", ignore_errors=True) - shutil.rmtree("/data/scons_cache", ignore_errors=True) else: print("scons build failed after retry") sys.exit(1) @@ -83,6 +85,16 @@ def build(spinner, dirty=False): else: break + # enforce max cache size + cache_files = [f for f in CACHE_DIR.rglob('*') if f.is_file()] + cache_files.sort(key=lambda f: f.stat().st_mtime) + cache_size = sum(f.stat().st_size for f in cache_files) + for f in cache_files: + if cache_size < MAX_CACHE_SIZE: + break + cache_size -= f.stat().st_size + f.unlink() + if __name__ == "__main__" and not PREBUILT: spinner = Spinner() diff --git a/selfdrive/test/setup_device_ci.sh b/selfdrive/test/setup_device_ci.sh index cc04504ad96288..fc4d4496a75cfe 100755 --- a/selfdrive/test/setup_device_ci.sh +++ b/selfdrive/test/setup_device_ci.sh @@ -26,9 +26,6 @@ if [ ! -d "$SOURCE_DIR" ]; then git clone --depth 1 https://github.com/commaai/openpilot.git "$SOURCE_DIR" fi -# clear stale build cache -find /tmp/scons_cache*/* -mtime +1 -exec rm -rf '{}' \; || true - # this can get really big on the CI devices rm -rf /data/core diff --git a/selfdrive/ui/qt/home.cc b/selfdrive/ui/qt/home.cc index 4b9f050da36a14..128d46cfe063a9 100644 --- a/selfdrive/ui/qt/home.cc +++ b/selfdrive/ui/qt/home.cc @@ -21,7 +21,7 @@ HomeWindow::HomeWindow(QWidget* parent) : QWidget(parent) { sidebar = new Sidebar(this); layout->addWidget(sidebar); - QObject::connect(this, &HomeWindow::update, sidebar, &Sidebar::update); + QObject::connect(this, &HomeWindow::update, sidebar, &Sidebar::updateState); QObject::connect(sidebar, &Sidebar::openSettings, this, &HomeWindow::openSettings); slayout = new QStackedLayout(); diff --git a/selfdrive/ui/qt/sidebar.cc b/selfdrive/ui/qt/sidebar.cc index d7a915181bc7e1..1989967dedf869 100644 --- a/selfdrive/ui/qt/sidebar.cc +++ b/selfdrive/ui/qt/sidebar.cc @@ -37,6 +37,8 @@ Sidebar::Sidebar(QWidget *parent) : QFrame(parent) { home_img = QImage("../assets/images/button_home.png").scaled(180, 180, Qt::KeepAspectRatio, Qt::SmoothTransformation); settings_img = QImage("../assets/images/button_settings.png").scaled(settings_btn.width(), settings_btn.height(), Qt::IgnoreAspectRatio, Qt::SmoothTransformation);; + connect(this, &Sidebar::valueChanged, [=] { update(); }); + setFixedWidth(300); setMinimumHeight(vwp_h); setStyleSheet("background-color: rgb(57, 57, 57);"); @@ -48,46 +50,45 @@ void Sidebar::mousePressEvent(QMouseEvent *event) { } } -void Sidebar::update(const UIState &s) { - if (s.sm->frame % (6*UI_FREQ) == 0) { - connect_str = "OFFLINE"; - connect_status = warning_color; - auto last_ping = params.get("LastAthenaPingTime"); - if (last_ping) { - bool online = nanos_since_boot() - *last_ping < 80e9; - connect_str = online ? "ONLINE" : "ERROR"; - connect_status = online ? good_color : danger_color; - } - repaint(); - } +void Sidebar::updateState(const UIState &s) { + auto &sm = *(s.sm); - auto deviceState = (*s.sm)["deviceState"].getDeviceState(); - net_type = deviceState.getNetworkType(); - strength = deviceState.getNetworkStrength(); - wifi_addr = deviceState.getWifiIpAddress().cStr(); + auto deviceState = sm["deviceState"].getDeviceState(); + setProperty("netType", network_type[deviceState.getNetworkType()]); + setProperty("netStrength", signal_imgs[deviceState.getNetworkStrength()]); + setProperty("wifiAddr", deviceState.getWifiIpAddress().cStr()); + + auto last_ping = deviceState.getLastAthenaPingTime(); + if (last_ping == 0) { + setProperty("connectStr", "OFFLINE"); + setProperty("connectStatus", warning_color); + } else { + bool online = nanos_since_boot() - last_ping < 80e9; + setProperty("connectStr", online ? "ONLINE" : "ERROR"); + setProperty("connectStatus", online ? good_color : danger_color); + } - temp_status = danger_color; + QColor tempStatus = danger_color; auto ts = deviceState.getThermalStatus(); if (ts == cereal::DeviceState::ThermalStatus::GREEN) { - temp_status = good_color; + tempStatus = good_color; } else if (ts == cereal::DeviceState::ThermalStatus::YELLOW) { - temp_status = warning_color; + tempStatus = warning_color; } - temp_val = (int)deviceState.getAmbientTempC(); + setProperty("tempStatus", tempStatus); + setProperty("tempVal", (int)deviceState.getAmbientTempC()); - panda_str = "VEHICLE\nONLINE"; - panda_status = good_color; + QString pandaStr = "VEHICLE\nONLINE"; + QColor pandaStatus = good_color; if (s.scene.pandaType == cereal::PandaState::PandaType::UNKNOWN) { - panda_status = danger_color; - panda_str = "NO\nPANDA"; + pandaStatus = danger_color; + pandaStr = "NO\nPANDA"; } else if (Hardware::TICI() && s.scene.started) { - panda_str = QString("SATS %1\nACC %2").arg(s.scene.satelliteCount).arg(fmin(10, s.scene.gpsAccuracy), 0, 'f', 2); - panda_status = (*s.sm)["liveLocationKalman"].getLiveLocationKalman().getGpsOK() ? good_color : warning_color; - } - - if (s.sm->updated("deviceState") || s.sm->updated("pandaState")) { - repaint(); + pandaStr = QString("SATS %1\nACC %2").arg(s.scene.satelliteCount).arg(fmin(10, s.scene.gpsAccuracy), 0, 'f', 2); + pandaStatus = sm["liveLocationKalman"].getLiveLocationKalman().getGpsOK() ? good_color : warning_color; } + setProperty("pandaStr", pandaStr); + setProperty("pandaStatus", pandaStatus); } void Sidebar::paintEvent(QPaintEvent *event) { @@ -102,15 +103,16 @@ void Sidebar::paintEvent(QPaintEvent *event) { p.drawImage(60, 1080 - 180 - 40, home_img); // network - p.drawImage(58, 196, signal_imgs[strength]); + p.drawImage(58, 196, net_strength); configFont(p, "Open Sans", 30, "Regular"); p.setPen(QColor(0xff, 0xff, 0xff)); + const QRect r = QRect(0, 247, event->rect().width(), 50); - if(Hardware::EON() && net_type == cereal::DeviceState::NetworkType::WIFI) + if(Hardware::EON() && net_type == network_type[cereal::DeviceState::NetworkType::WIFI]) p.drawText(r, Qt::AlignCenter, wifi_addr); else - p.drawText(r, Qt::AlignCenter, network_type[net_type]); + p.drawText(r, Qt::AlignCenter, net_type); // metrics configFont(p, "Open Sans", 35, "Regular"); diff --git a/selfdrive/ui/qt/sidebar.h b/selfdrive/ui/qt/sidebar.h index eafbb76525102e..0e18e503a4a274 100644 --- a/selfdrive/ui/qt/sidebar.h +++ b/selfdrive/ui/qt/sidebar.h @@ -6,15 +6,25 @@ class Sidebar : public QFrame { Q_OBJECT + Q_PROPERTY(QString connectStr MEMBER connect_str NOTIFY valueChanged); + Q_PROPERTY(QColor connectStatus MEMBER connect_status NOTIFY valueChanged); + Q_PROPERTY(QString pandaStr MEMBER panda_str NOTIFY valueChanged); + Q_PROPERTY(QColor pandaStatus MEMBER panda_status NOTIFY valueChanged); + Q_PROPERTY(int tempVal MEMBER temp_val NOTIFY valueChanged); + Q_PROPERTY(QColor tempStatus MEMBER temp_status NOTIFY valueChanged); + Q_PROPERTY(QString netType MEMBER net_type NOTIFY valueChanged); + Q_PROPERTY(QImage netStrength MEMBER net_strength NOTIFY valueChanged); + Q_PROPERTY(QString wifiAddr MEMBER wifi_addr NOTIFY valueChanged); public: explicit Sidebar(QWidget* parent = 0); signals: void openSettings(); + void valueChanged(); public slots: - void update(const UIState &s); + void updateState(const UIState &s); protected: void paintEvent(QPaintEvent *event) override; @@ -45,14 +55,13 @@ public slots: const QColor warning_color = QColor(218, 202, 37); const QColor danger_color = QColor(201, 34, 49); - Params params; QString connect_str = "OFFLINE"; QColor connect_status = warning_color; QString panda_str = "NO\nPANDA"; QColor panda_status = warning_color; int temp_val = 0; QColor temp_status = warning_color; - cereal::DeviceState::NetworkType net_type; - cereal::DeviceState::NetworkStrength strength; + QString net_type; + QImage net_strength; QString wifi_addr = "--"; }; From 4fe1840ac85736a5e941d26b34edb72b9c316577 Mon Sep 17 00:00:00 2001 From: neokii Date: Mon, 24 May 2021 17:36:37 +0900 Subject: [PATCH 02/27] tune scc --- selfdrive/car/hyundai/scc_smoother.py | 2 +- selfdrive/controls/lib/long_mpc.py | 13 ++++++++----- 2 files changed, 9 insertions(+), 6 deletions(-) diff --git a/selfdrive/car/hyundai/scc_smoother.py b/selfdrive/car/hyundai/scc_smoother.py index 5a9972ba542344..d89db7e3e38532 100644 --- a/selfdrive/car/hyundai/scc_smoother.py +++ b/selfdrive/car/hyundai/scc_smoother.py @@ -169,7 +169,7 @@ def cal_max_speed(self, frame, CC, CS, sm, clu11_speed, controls): max_speed_clu = min(max_speed_clu, lead_speed) if not self.limited_lead: - self.max_speed_clu = clu11_speed + 5. + self.max_speed_clu = clu11_speed + 3. self.limited_lead = True else: self.limited_lead = False diff --git a/selfdrive/controls/lib/long_mpc.py b/selfdrive/controls/lib/long_mpc.py index 9d522a740c104a..fff03ca83ed3f1 100644 --- a/selfdrive/controls/lib/long_mpc.py +++ b/selfdrive/controls/lib/long_mpc.py @@ -15,6 +15,11 @@ CRUISE_GAP_BP = [1., 2., 3., 4.] CRUISE_GAP_V = [1.2, 1.5, 2.1, 2.73] +AUTO_TR_BP = [40.*CV.KPH_TO_MS, 60.*CV.KPH_TO_MS, 80.*CV.KPH_TO_MS, 100.*CV.KPH_TO_MS, 130.*CV.KPH_TO_MS] +AUTO_TR_V = [1.1, 1.25, 1.6, 2., 2.7] + +AUTO_TR_ENABLED = True +AUTO_TR_CRUISE_GAP = 1 class LongitudinalMpc(): def __init__(self, mpc_id): @@ -34,7 +39,7 @@ def __init__(self, mpc_id): self.duration = 0 self.cruise_gap = 0 - self.auto_tr = True + self.auto_tr = AUTO_TR_ENABLED def publish(self, pm): if LOG_MPC: @@ -110,10 +115,8 @@ def update(self, CS, lead): cruise_gap = int(clip(CS.cruiseGap, 1., 4.)) - if self.auto_tr and cruise_gap == 1: - TR = interp(v_ego, - [40.*CV.KPH_TO_MS, 60.*CV.KPH_TO_MS, 80.*CV.KPH_TO_MS, 100.*CV.KPH_TO_MS, 130.*CV.KPH_TO_MS], - [1.1, 1.25, 1.6, 2., 2.7]) + if self.auto_tr and cruise_gap == AUTO_TR_CRUISE_GAP: + TR = interp(v_ego, AUTO_TR_BP, AUTO_TR_V) else: TR = interp(float(cruise_gap), CRUISE_GAP_BP, CRUISE_GAP_V) From fd7734bb3a7f28b1dae93e1498688695397a2b4d Mon Sep 17 00:00:00 2001 From: neokii Date: Tue, 25 May 2021 20:30:32 +0900 Subject: [PATCH 03/27] change lead mark --- selfdrive/assets/images/lock_on_radar.png | Bin 0 -> 9977 bytes selfdrive/assets/images/lock_on_vision.png | Bin 0 -> 9921 bytes selfdrive/ui/paint.cc | 43 ++++++++++++++++++++- selfdrive/ui/ui.cc | 1 + selfdrive/ui/ui.h | 1 + 5 files changed, 43 insertions(+), 2 deletions(-) create mode 100644 selfdrive/assets/images/lock_on_radar.png create mode 100644 selfdrive/assets/images/lock_on_vision.png diff --git a/selfdrive/assets/images/lock_on_radar.png b/selfdrive/assets/images/lock_on_radar.png new file mode 100644 index 0000000000000000000000000000000000000000..3033c4aab29a9b4a79ec4706585a41dfc3c06011 GIT binary patch literal 9977 zcmX|GWmMEp7yj+i-5tWxxHQt;AzdpWB_N&Bu}h;!h_ti<(j^^BgCGb>*CO31A@%bA z@_v|eXYQSI?#w-R&V8P_ak|>71h}-g000oEt10ON0O)ZF0$@?>^yW*lOTSmuH`3cYR;Wo2}_q5N31gamjzg&q|DE$%GV zI&)z{L{aS9?>DPKMb6XhmzzKCzs<;ORh;G2k7FUR@zd0V^q#@-zbY`2pdtqQ23FU3 zL&JTKur^X93#f71F-P{e!bWzE&x3Uuo_}v z@dqL^0dkd76RDG@Rm5A|kCDo(lWJiVS4Nm&^LS#JnD8=kj;T{UB^R*gwK{l<8?ha3Q``h-s0L;31y z;gXne*ZV@YL-f}#@$%nXzO%0*lKTea@64N=dHfd}<$|P^xw(z?^;wNR1vBgKCL#9@ zJ(ft5JD2NFsoTrHsLnsE2tf;kD*6?wXY~B}7y9uJIFUAsn~AEoO?VHt48I_K>NYJf zZt^ufQqKgXtoSp*FOWEe4_y6hlMk={tUzzjWLBO5HBK_1pk$s>3tO}cO%7t15Ax3? z0GzhDcmL+ZMuWeOSRMC!IFh|n&1VDP_Ua!z0pO()E3e`Adf7p208q+DaM#Gwop)11 zk(l(|7>nI_w^kyN3aouS3d9Pyui*4vR$LX~3Y^hDY8be!_p?V=pQ#Dx zzcpksQe!xk_5zE?n5(oVOAY~o;kVK4ssbMob$Zgj@xLjyl#0?usube=eB~pMl}MSN z{nM*~Rytm!VC!f3Yohr?8O1?<yP@fAw??A6Ytr!$1#df3?Qh{GSKwD#6fz}rH z*LJ+t51kaDjKmQ^_fuf9W|UWhJ%?$}s+BU)vkH^UDHM~&2V#UB^ zT3|@>EYVbTxmbNs~>DMeRW2M_rxqyqMjR61@x!>?tmQgE;VJr`?9s(aG zfD$+x$N?=5A&)Qv-&_R-Gj}D(N-Wr2)Xg2p$LF`mQ^+TVSB7tNS2DjI+E1!vzTCEDkjP#S~kHW7DhWEkp9eXVo}k1Md_bXn$mK%gMf~B zHIK$KZkaM(C#iYSR^e9J0bctTqf@XPn7WH5y*Mv-m57^5=gRHDSKyD$?7M!%eHTwF z&wcviV6^`GLXzmGqr8U$(jL;)4~<`AHv5zNgu5UdzC z9Q?gdUf@gr!MV^D(Wux`)Fsv2ZdWoq_Cr$E@U!8$;Xgx>!^x#@)-zXb6Nhv`?H9uP zQwwJ8mv=J5oeM@FBdsa>DZ3l>oBB)Hs<^V9tF#+ei%M-*&x1jD}ePTh)apM4yDEUIb{I84f$n?}YzKaX1~1&q>V* z3FW$x3EEG(rl7dEn(@p>$59$ zpYls*u#5BluMyr z9Cu?QZF7Dchn4L*?Uv_q2l8`@OEFWjX7`J;M~h)jNWc8EiAB{*%&3U*`{cigM2Z-R znTaFO1kroBVlv|5e`LMxc5X`)$6t-J=ThAl-j7sKQSyaeP3_H$O=L_Iq@Sjzbh!q9 zx!XnV(Nr%C^b9a|4*LrUygWC)Iq3FV^kX}PRnyl3fIv0?fJXqp^~0mw0f0CB0I+KX01_DhK;{0yvR?%N=vmd3 z zSngjYea~8|)UQ#|od9#xj9I!p$@ww1oD-EJxwYJ~aVaw{CF$+Ax#&A~lzW<5HZY(P zNqqe|f)_zd3NS~a%V9Hvh!xa;$p4l~DmySY(6=|Ou>$p<$qt?Jg?{QDcWEJFG@$O1 zC?1PxA3+;f6oy>i*aT7qnT<5kCjN~_-g+%w0D_S;Gxz;^Ndzj$&I3){#B%X zgB~#1_daLz%Su#h4 zf6Ue7;U8dlkj7A)Y(rrAl(PYa&n!VrlMn8;3ucJXU14JlN;nL~nm$L|CkP_P*jX%XUICx>e&ls5YhVU~qQ^7E{KaX&L zh+ZcS zIq73j3l$u=n(TNp74j>x6*=r0d|4NMsrYjjfiCyzZTaHLC4$?^43#g^8ARnFeawIC zXCd(e6uW=yfO0~KS@EHwAS*lQx46v={=a`b#m0dT5&uQnW-Q5tp?*PDUeL_`B4Bxm zl{RUY0>rwU5FBIH(A0?VlbIQDz9JY^{%7mbQd=M0K?)@EgnAGJi$fc`ORCa!hj3>< ztm3HPAIln><-_Y9Yo4ZV*gfE+n!Az&4u*+ALRSYW!2|V8@)Yq=RVtc-U&<3?{K zP@4Io9xA9Xj+U;FPrBy3pdsF;)+usNZ4=mvrtYr^VLahpH*F?lbj<Is{ZL$LSJ5d2Nobczp*O zn$Ve+Dz@E@qhU#L?Dn>M{oYfIPsi%2{HDhVMi_f;A7WGGS-aga{-LqolPc%B<+3lq+?p^xoPA=|N|rldP28I`_D#l8^0si&vMHiv7` z=V@uOaNx*+uQ`s3APYKu#-M@HyI0{=NRldqw$J;&&f_;%qkmZktwCy%YQTpdFsT0X zB(fT80mx$kcv;<2b;Eu|M0MX8WS7=34q8m$VZfk!0J{`hzL&kJz&(G{(SDe*6f=YX zphv9^Bjk>^TNCt}+UpU^87E_k8B3}T79aL;<%m$)qZJKFC5RPJ`u6l@nuUcsiktkL z#oHT@uKA1VM&=_Q?qf0hiNR2R&RLCaHH!onY&ny+)oVn9w-Zs=Z;_rE4x$(3ps+r2;MvN6))u;TP4@ z3)uW6SaG45;i|IQLA%W;d`EhL+KcC569q0Gquc)$c0Q-Da4!yX6XW^&C8j57fykzo zx=DRjVEJIan}HPmsz$_vr}BNU?wZcC8<6HNDaSTZ`;k0!H$T_aYEt<3dd5d%xDHve z_HHd4+RSk{eR!9OBi3m4NzQ@=R7$^8OMNJx&|P>NyU(Anxh;7Fa<&%7df7MS3|q9*J`Pl+zhF^Dd}wa55uxx(snJ*m{yVgtb7B7hTEb{&Z#hKpw(EyPBIn#M68>(f|T&S37X&!oo})oOq(#GPbN%!d*j_8r__P zGS^+9Dt+-87ba0HBzX`Jc30OI0kemms!-`;ZJG_=FLPPYA=AS!i>a4_!%CNOnbG3$ z%31^-G{<;?NhU0AAZpa_f2JtIgHSqr?|Wea?HzPVWjMvu^t$(Fd)pjjed(U z`x2~6`>U4RBEo#_32sFMMk2PR>^v1(sGVpZOy__tMHpOdJFM9C)-f+z6VO--u~LNw z9g!fD?b4dQk$q%5xV?AE&>N0+;>+BygHDdGQ(wH{qO^Gq)`jrdoZJnj>kTkj32!PH z;_iVjTRe+~*!h5%0b%-P;w!YuH8u@^vbX4?=w25`jsDPzTkIFyC(3)jZ6I_~F&NBo zy^)vZA7~!=?)GVN28?kz{utF^3aOwkq?_b|TRv3Al1lce%*L#z4`3OL=}KA`(Dvmz2DurU#i6 z#*zDdn2~NxVx`m=fN{niKbhh|mS2L7e6j_YD8cT(ATyolTCAZWj+d@V8%GIt45pS~ zRLqJB>>>a;=S0?Gi@%x1XtX%YApI8{ny9Rmz$)fO+n(vhI?vXM^_$XbL{rI`^W4FT zfAg5~;*tX-izPE|OO%g0!e&CIcijbD+l+Oo@s3nPyysjp>`0Qe8FLQ9kOAlR)en14 zVxW8rYv=L^ZgKI>gmqk*W`cKiVTKU?wByaqyw;Y;z|mwk(HWMpDB!&B_OeK9Alu?n z0~`LN=GiUhHolALz>(}=8Z!IC=Zd$3&6Mht@cLS6gr3yhieU~FXwx9qd%lo*Et=MP z_Q`9`D=BQTXM5lpoC#LM73GMyN5pO$_Ax;Xp2!*_22uLSg6za(y0wsKSJDg6EF(3w ze9N!bV;2ymq+*XZdb-;14+S956;6$_F-E@V1nlmaP5r$B^z8}qj^tw-F2B^edphr= zao2Dma6WJfzB;_;L;h)!F8Rkp*-Lc@T3?X)jAzeG9sMF>LZ7*7@Kd%R8(;x{#=_}G zxDoY)?AnIgo_QA4vPgi_^zSzi-^b7sGb~!I0VW$kF^+0oi&p;=32_$pYpb7N2xfG91j`zxetWBVD2YEoks#_-b zOweBAwsN-~yW25C{Lp-S3P10O>o zfY;lyho+^22p`X-EnHAxolP0oRLQR+0-luJ;}U&}e8?}1A>&0~`mWsg?6U>n_Fm2| zPboLFhiFEX2|&Y1FFvF(9qj*<Nh z$h*Y?ji99?9&qEnGJnt3q@ME_{QXZMdPL@tnd-Q!*<2YGaXO8~=hxLLrW{N=Nh+Xb z%8}wf?{Jjp2GZ0*wx?LY*4)M9XZJv`F*8v z;($)W%F!=Ypi}6Zui+B806$H(^Xc&O9vWJV1$SFh^nCW8AzbMJLmPg2&?o*q^jN|8 z`=2$*-tNK8q|!_%yxgp@)BZNcRXXiy;L*M00*R4`b=T)VH|lWdo|p5xybm>HH=&6O zDB@Dk7Yn9Cf5W^e5gLM$pHC)DpL)s$bRLvh#^#R->mTIe-qmamF0>p-uCB~+AGK51 zk9J`9NSxnBq$P*b{$c_;(R}bBpOlTJTd%1=gMgWhTSa1Nj>-TwDvxml?^}Yb4fWvU z{y?x^lo{;%K~uF77T)Lw_7BU!F^ ztTE6bn|Wz@!|9XTN;y|~F`+f9^sq1Utrs|+k2t^Woi{!YPl1wM01jSJ2rOYNK=xK8 zm$055X7t&DetDVq+U9Fz5vCYeNcj5U2crPgoSZZfS}Bq)mg`w9mE6~o*s_d{eAbYR zaHUf0$B<)9H>g3S+Io3ZJ!O@HL*8Tmmea&5DuHJ!?z_L;BC}LDfYt`9g`Nu1Z+rUF z*(*B}rnNB%g0N4=Vy)Q*Rm?zUk{A84^uEu2^`*dE27Y*ZR9yy=!=*J{M_Hn4fo93k zv3W^!*!Jph8+xPp>KTrZ@&R>NV4Xmi3MoTPqAHDf&R3_1x;-sU*%e*1-ztP;=F2~dL#zwBj^DQ1} zl|tiMD@W>v-ql&V0NuO86i(1AwK8TE`V6qQCm5@NC-*Jpu<6KJiP0ELh#6Q29V+Yr z6TgykWuQyH%BF!W3R~`j&%bv|)9$xMDX^*lzJ=%5pABl!Njk-nf-}-`G>r=M8Gd|P@T`=*}HsjLZ#8G49Q=gG~5OO5R zDrRiNfdRMqVVP7w$KF+=vIu?(216`LD| zGy`N3XHH~WGDPe#BLA9N#RjdsFtWHJ1}x8jUng`dogAzCq;;c?!jhKKQ9PNHwpuRF zDnmgWFr#KUK{_BO^{z{YH z&sR(O%n))oN$(Xsp6 z4Th;enEw>h!X~CRvMO)@q#tZdeg%qlE`NUrS*pOl#q%e^!k>iHDWmGT%vswQK78Bv z<2{>0n;Y@~QXwdWQEyHWA&ctHP>7AC#;7nmzGgwWBQ79YubX7e%(D|&u(f9XGW^w9yoFf$CnKpZ>SZ@Wxs(hS z)kl)v5CO9305l6{w&G4zVBguV@Z>r9pO>RUB|ldlLQpYczPT4C2UJK(n9^$L9ECq- zcEwlY4hqIn&_Al3f0pDkpjX!6&fNS0#UXd-@63Z4?uBULf@`Jh{TsEdZaCyR(DQ{G zdyKLE<)PBL@C0TT_#XV}s|1gRm5ymi^^=!zXv3yz6#=vJcL#@%!EV0AmBWnH zXySJ^(xXY0Ne1xpr=I*T8oaWjukrdiT>M1RCe$EI^EPjw7kz1ngBg=uc%9ScKL!uA zQExC10mpmBN~{c{segIEFx$!ZlL>S@PJ}d}pfx7&gETxj*^k~UPo?%VM#sb)W+}jU6pl!`-W4{|~$AJN(W2u*Ywkjsc z-2Z+_yr1zyI;e{^6XLkvj-#aqaqa=5+NiI%x#QH|q84jA=q^pLqKj2+*tPaW8|hFa}he>Rtq+ zj&Vove3XnM0&G-Kgrmz{H49x-C$wc>^nqL?J$rM{rMvM>mXpjFAL`4koN+XQG3--3&x@y4u zpv!3A#Ub*70Dg0__Ez%8o8gyCttdPpxNGefxnx%ftHVFt%X>bepYC8_-GBafR;B~% z8f1&hao5?G29njL+-?`M$|?otVCu%N|FUXvx$S*? zu_;>_ap1CLiyo+5NH1c7@$!tvBaSSbNHOh1>{#?$jQJ_^Nl?M20$^`T7Ov=+BkSru zIzG>FWNkgz1hP-PTDTk`CSqm<-dW|6A@mRjLDnQjs)36$N>HBbfs7mbpxeegP-t}- z8!Ip&fOW;@;cRu2CF}sJJb|Jw)jYc!Zpf+el-b;Prfj6C1{B&cZyLQ(O@7FUWi#1c zf8jG=ZTwQzK+5+93pV7ztS?U)9?rNKjiHLsn3qs_MD*S&&ri~mCOm*zB6D=83%8iX9=SvfRee+QC z{y{ccoPxkGm6#O1Uq^TRiteEeO=w*_WqO$IvDCeSw;Za6NgX>SKky+cNf*)Zb^rdi zQ-A`G?_LOXAkz5@Pm^QX#7IdEs2k>hNgQ>OC*rnK9t$56@{mbAwupwXEv*Z>rr#(K z`h!3nM>XvbFFTkbyUkKS77i7NDt0}QM#i8nsQD0>7lu)&gnSTz{c!>}eH*IH9p z&t&C~!NuxFw5~LyVJ9-{bxp0gG2QpH>f{ln$0DL}_igz`KhcgZ{c~QzeAMJkA!-@F zU;C0g1fk7}*0>h)cA(1{=Bij3XIdQE5VR*uEDHnZT^116wChMxs@#;bhnEduJw+DcUlR^k5xP6=_6 literal 0 HcmV?d00001 diff --git a/selfdrive/assets/images/lock_on_vision.png b/selfdrive/assets/images/lock_on_vision.png new file mode 100644 index 0000000000000000000000000000000000000000..050372ddb3f48f9d067fa7d55e7896c97e518c82 GIT binary patch literal 9921 zcmYj$bzD^6^Zwl>m+p{SI$XNDOS)tckflXwP)cA|S`d_O!Jt_wNs*;{DQR#C0ciw% z)9~f<`|J0|ea*S|oY%c`=G>WiW}XC7V_kBRdn5n=kn8JdnF9dmZU_R13GalRf0^5z zfcWa!1ONaj?f)(ikekm003;?JnwqAjPkaJ>0-pHzLiIH@p}zh;ZXTYl01&)TVBv0Q zvCW`-`tz@bK|C_uz{i}P7;3JOh@^YRC&US%dJxZ9JWp@dNv*Ao&oWRHkC&W`Orke~ zk-a9FBl^YpAvx+}{Oh61)v%AxX1<+nj^2EoRoSXKDX1SK!Vr^X>PebOBgx7&*r`{d z`g{6Te~GA}NO*h!D&l$<&VXxf5O5Zuq;#JPL-ZX01y7L@0~n(`j2LU&E#;0zjvWXY z4Z;MzlQSSj(gA9r$r>eqnhpqAkj-ZS6yXDiVP~gxz*HDO@JDV=0my>0oG=hzo6boO zDtZS%Xrr4w^wXa zTs`_uEpQ>abu${jWUbt!6N%4U2^y(_y}XmRE^9d0C7udS8mM`y0t$O4TxRc#_n!ej z6+95Lb_xK;Z9bhp1c>pFPoh@Gf^H90uXT%f0i>ILsviJ6*5VPd9I99CCk6nmB9u^# zI?LZqCK!g0wUc0}lk^H96RpA1)1^VBLE?gB^+yO+z0wef9j###LWurQW0S&|J&8^8 zr4Z?|YNk;3rMz$?F6I%T+~I*>|tz zVHI9m!awJ++8}%ylr{z;gCC>;b!1o9gB!w)=k&^;tUOZG3lLcdUbI;kKUZ3rK?7ea z^?47IlZ1F2To1-QLz6-)N);Bb*(1wClb|WV-|`l$U;D{&l4eq8(%YPS8&;ktrFV}z zZE(TmSsjslIt+S$Am&%WukK%xzgT{89@~->IH~!4ISM0?a#^t@wRFlOjq2h?^Dky`WwcVybLB^)81xN3SAWQuy7z?f$*ISe-+`^v%Ngv( zS>x7|!`r&Qvwq|K4I(3trH|^5cNbvJV#OMM=fa3R0^Rt6|HO^2Zk8XdNp_i}iBIkIYJ|iUQMJ z3lcT^3imP}OVv*iHrEM+Hr$otf){VVuv%D`TIdqk zN9SL@5NgZ5W@}4St|%{-*OYu9XzM=Qm@jiQg^pq2EAWeP|~j5W^;+6Q15@hZ^y6eo`NMP*s_?nSS}?g zWiV1!_=gs$c=nm4xJ@gl!@Kk#yYTyCWTBx?>Cce%tqaz0(QC_VuZz-ux@2&|dNLlu zMKUatQm?e1j}n_`|KcArP5W*&&CiY*j#;bG?^-65K2Gbr(Vift? z$j8ZNV6 zo4GCO4j-c$o0D8`q#YLQ@hGs!o6>b>bZ-fWI*CtAFnBdAlBFV&$I`bv(EjT|;6Fe6 z)zHa*1$p&(UHfH=Uk+prJPzWP-j7JV7c8`q3>fbo&|ERwm{28spCR@PR~2ERX@YY9 zy2UN(Ec(v6dbXzNb5O;p;~}HUe=7d(*HzY)WPeKhv~d`b#WW2x4V!fP6gtG59uzUA5x-}~i5xc_6T2hG_+#Q?tYcM^edFQxCd9L(gC>?V18`awTA5lu z^W4QvQq8y3`xAlv_ZVdBq3dFUG7|>6EYL= zbDDNS?8e7>LPnvfd+)wUhw$`DeuizdMDv%w{bopRxSXd@$dLO2>LsD9&@LX8`tGft zMg^x)TBG}p`=;BA;VRddx|?3_#3oVp45Gnj^>3>PY=lV~HA;S4J`$J}BC2zDwRYSOaTeHuz?H)l>O8CBKkGl6885`>_uR ztCX5wHwt-8n^f*wXQ3n7`9h7Jp&oY*z3Ti5dbUeyMY0hSzPmKLZ*Kw@wZVOLyofDe zQK3(Gjiy^<%%YE+6Icq~V2Se?>d0A2Zz!+qX>l2In{?aW{3%>$OOaWTwV6fXO+LTS zK#qIZu>bEr?M2b7QGvy_s7B3}j~znwn=46^OTwUySfzp9N%vW4ugcrWyr1GVH$|-7adY5t-QotVb+dKu7X=5e zoxmNXo3tsD{^lZs5<(bsM&nN!U3By(& z*X}h{eqfSDXniDHrC8v!s&&Dg^4-q2K`&{HS~aJDjI+@8eff=6GZj@ZUsMA`~ctEc^XLn@iS4) zz;!j?zvY)gC?Zf)rH$D+_@W1${`zl&9-x+Q0#gE)E!7gfs-zy%(!2f@q|nsar@NG_ zgd_NwWAm9)*Njg=pBx%W@!Ig(9|&v_tla+!<^i~DEP;Ly2i|>WtjR8s{1Fu@bPnLtM!BS%h#Bh7>>zVh{+X zqX_Ix6Uqalfrzv(NuGcq^&~P5wr`s-Hymx`D{M_{CBqvWZ@`KEb<8rvEi!B=&Yr|c zU4$y7ZGKVof!lY=oWI=7y|71xBg?&qWhEzYUXkEUfEy(p2rr)f`?E7*-G`0k!Jrg|a zYluGQ*0vdC8U>*nFHk#Q0Z?-dqRDge0_=D&)>__c*)VMlVu2oPWJO4SjUM1 z_-{nU++#td;QA$8M&P^@A=LAM7dIk;UsVHm9C+s{RNL9W zrf`0qfXN8?PqtMh#7=JTnk_|JX+dJloxR76j@^`0O&AFa0#Onk2-fD`HkUjX3F`YD zbb~in9d(-A`;c9wu$MuNfdD~S1j^$ZQm}`J@?i?H^F%THm~4p~>;}pKuMJrI6%tA9 zD}RLF*z*Yd)*QrikX!q{O$9MyubUNQa=4+XVod5AWPE#tbG>M9^ zbK?71QTJQtIsYGDrfK7^1iwAP?xrl``cY}z3UP!8QiLn)OwVfNsu1&#H5uckVs5Z- z4P1aZoXp()@82qU8ns+OhsF?1*OOm$u>PmjJ_G&NG-tpGL;kiW*J-i%+`O>^MD6&D zx<+M_XOjQuCv3K7cRxw3C$4Z#YMrdfYix4sIQ*!#@+eGUao}@GeX%qzFz86`S#;R0 zw4+QaxAgB;>nemWV11eVWRvs~9=An}`aVaq?!^QAaeqE??wqD{INE9MZe-d1fX==q zO(2kwRr86D zk?OH=_xl!+U#@VMHE+Lmrd$HChhX+ToflE8pqC(}>We~>M*l^IgYWF@UE=J|7kL)= z9E{jJsE`MkMC011J;OB3@k z-=?n!iv)u}eFc+LB2bv~L4N1Zt@0+eeCWM!ayQ{X{LL^@K;(`?m{+x&0?q%6`I z32FVB^GQ+0_mrLlFLOu)vj8v2PDHKz?e;;b?qrhmFVE4fxnoqH%TICwZD850`AEXo z=X?tRahG}L7!Hr$;3^WE6=Bn)dIKKEv#o0h#eV1W9Ma8Dee`pn-bW7;n@oru3t3i}^d6|AC={RS<|4RDz?5r`FEMNFR@sz54UC+rW_9EHd{KubRQZsi& za9x$q%{##^eE5Ip9){J`&@;@&Ziri@-2>5*u zqGZ)~0$-e8(K_BDHzkGg!~!Oh5w1AwK#Jo1k^a7j$Gr>zUbZDC@P4oR6$Dh|?X`A? zokJY}@4)~Ut~FCl6^0tPk|^k}M{AF3f~iEL8&3K165iY!GYuc$Imst)*d)u|d#pP+ zWQl8gxq4%wJ-s%(E4Xp;D+LbBWioXLo=jP7Us?OFK{Y^p#+kbEsJgL4=v zyVb!sc;v}%0(20*(ItZ$sJLToY<=w;9^kVd;6-%4iO7K`x+;&PKphqYLa0mf{$R$q z8BqNCgWwNk1S?uF&(mbIsx*Y<9}eAfGykmN4Hc`4=&a{n#YO6ZNaqmz>7NqfXRiAcg~dtVQye@epmR-*{TmAYK2? z$AUXLAD)s6)_(J<)p{3`qw(`NN->ugy-988A9_UjghRH7>cDTElCkXjr_3o-CAS=w$5Z;* zuk>7YrSkGlW0&oyhyus-UD2Oqp{bA1pa}X-zYE2@A53ca`D>Qp^d=hx_)8_NsgJw? zW8!nBO1V5GZ7`L}t`n)$%VW}&htnB9{GZ{Q{PxDm@B*9@^m2+lEb{n?#v-ttpHO+3Auk<)B~<)|9iO`g5j;;F5e>I z2kSRZ8$vK7n2ZJ^`Hj4Ky%)y@W=xTRr%EtvkWAYv{GvdHxZwI+yZXq69j#5K{ey7$ zGa~G<)K6b}UyjYGxALGeo+at)41sBQ=3Ns>4W1-gdzFC6$!=QRwV^}u!7>8id+PoL z#nBv>IPRX~Q^DF8KS9&|=n59jD!=%!&?9RULs3^ii$Tp-{FHJEmt42gbhd=^<4ZK9 zFgCVH;P_G$(dpmnI8oo~Or6^AR!lI?LHga4T4P?f>^PB?JwRqPkHoz@JnIaJcNX zE_iJCd#^57% zoa`{4;wyopi^aRl_5fbShr6Q86nPMDeukY-^)W7y^O?;9hu@ZbB2}a9Rn&vMxv8_K z4zPU+TT>KuypM0oJZEYh5N=LTL}M$knm2`#b#3aR^#Qv_n;zWPeqqr@aD(G32aiWb zHsQ3@@b*g$qXjY#QO`V7DIJ7%>F1+Wse)y<{t@0O9>ik?RQzH2&_bO!s$wQ{Uuo)< zQMYs`ECA9g9Ga)QxP+HMCtC!60V?bE$$YO!?B4T`INxh|wf37gnu4yo9{qK3sEdaL z=|kBbQD;UiVef2CWQ@rqX{z(qv^Vlf#a{`&Dp|WAw&mp2%C7p=@=XOTl70bv>Gikc z(*dx3K0n@{n&zugtIVzj#g=DPlB#5<@qmunC!e~`m&79#5TS-U8onz&X6E>q(+}?{ zk=-tNY>#(W>`sibB?kff!Vhu_^L8z}J(~>$I!Z0YXg5n5d_UWYm%!tY?V z=(^#zJiO|Hxz$kn&)0f+2TxPu^7|-Wf!uCXhvp zDw|}F;cUrncF%K$_kOPa*@}Q7g;uUbc*py zd39xeOjj{)4F%BEB=jF&3=?mIlu+ac+S-(}KBN941n(Q05-M3f`-|1s+&O1*e_ig6 zD|fzCEsIACSEj z)8!a}z+nZZ8-Hg@q7?sh{J!tq<9M&Zpw?l}lM&&!@~(lx)OxN z*9n7t$yS(L*>QOSrgE`+?iF5~=<~EzTj0AK(e1EAj4HZQVm{F5{4k$%X>A@&`g(7D zXRTR`04g{6ctqe3I-56>WYT)RnByo!J|cMZo#WD9$0WN4)!dM2#azGLMyM`z3J>+>Mep}l^Pb|{!a z)Kn`1^@#)%bw=LL)3qVrr4Qm@{O%`XBLgZ!SHFKn02z%2s>&2H1inAF&DH;8^pwg} zOIsGwgs7-NH%HV=Vvr=D#Tq>1MT(;4O+QiO=exrPMIc^ket*0lhQh`9)?%gQ zaEKZ$3E3lxR=wX6{rrBccud8Y=8bNjqpj2Jfmedfi5?%$4!lQ3G1v1HbB1n0L&AVM zBi4&$=P8L%++TttbbkP@fQ!4BFCGogwC5ZW0@Se}8G$3k=WrLegB^%W@BG?^n3e3x zyhLb?2QXb)u@oKK!lk3ae)K=byMYGK`_TZ@ z@L{?p@RKO{X#C3ic*!%8RJD9K4U?GdfFXF=lAuRW)Y=#!F2-FGHXYlVtFcw)Lx4UB zzNt(tfYJukbk3qM^E4ppe@tpMb+>Q27=KBv2Ni459)-sqSWEhHF*u%*AqaA6;vWFV z6Xu&IU!ZyArID*zMNNiqEndK0nQdyz62a>msdKpeCp*B(VP#grmAVo5MsdYk{T9s}{gZBjxZE)kvfeqRiV>F`3{y{tQ05 z!_d~n3QpVhlO=G^LvddwW6cem3_LzLQxu99OETBUrhtJ|@N`}r<%pmc#U5rEfX8$E zkYPxRB{)X&PN8RJ`HJ3&TcubrM3T3A+-&Q|nHeVpF@v+2%iGtPnOz(!cd6zXSQ-_&=s*MIyFk8rn<s3fREbPGB5l{ zaa150ANt7;DSO1>TtiSzPPJWLX@9h*%u+f&ITk%mQU=VZcS>p>&y%0zoioVMBo5f; z@PVFm&7jAQ?7TTvZ01w+ugrzR&v+ZDt@xD`gNN`t2Ut`XLbLA610!qX$nKW9WkeaRrTqu)U z+~&8Rcuc6$^kBbH(I9GujTzZCKyk1{>lGZrL_ZfK$Z#b66?{aJNj4?B3!H)#2hds? z+3(#QI2>a7<-7OvV0G0#7axhcxR?Vwubll`ke}m1Ox^%5ql`#n-ys8GHEnwaJ^AYJ zw|NgYor=#GUDN>#7ok|Jo0#rtxI3808;W{KoIGL7H3W!qq&`{Poo zc74TV5(NDR9>-^8@;~Pvn$aR_AHUT9m^ep>__O!r*Hb%XlO885|6dqV5ZdP%_#TvSVW4 z0&R90_Px11@<%C0zlkS6vUvT&eA>}_Na2gYe_`j0oLkL$AAltwAEm7WNwcltDbt7^ z6~bUc{yT($exE_Ejqv+h*yZg16VxbC^?iiE!MWm}6u8LF1#l~1r>WTuT+)V*m4cId zN^W@owj;3`d#(Ofx-*~o@*_j*6?w!L%uR>(bFjVx@rhE6kyif&n~d)LXwgScI7$v^ zVC=E@MQPtsHt31-ghp8W7*^3HRP#mrN8ShrS_aAhG=9;^2%!vru6pMK7~P4S#$PN= z&Wd~y-_}1n&wIXx>HP09zaDWo{kc&|Jj$jl)(%E2VWFX23`BEZoCfh)1nSCO!b8T>(afBH;t@E3#%7^f9HQi!3(1TTne z(SZ@oyAl*+d${U+{)|mz_94y9hvJuHJ>cYsq^=ZFXKq;aEJo?WQ7S%ENe2JBP`BSD zII32Dd9Z=w5B{=cpHe&O8SR((H1TOPIVS(Z*ey@f$ zb3rjn^v~OQ*?q8SqS5{vSZ%%z0&m0w@gOI{fP7OHTG#81u|S1e=Rjs2Vdq7b(gqy57nmIg!)d(HUCsUI^}g_{B^m507#j#acBb(Qda$Z8^k zjzU^2!!Zq*8_hpiL%W)Ya8E%$xZf-Tw6v(obk*}@9CPD=&1B&LV#M*7?opu%;ilss zmD!x{$*8vR%DDc{BNxDpM8#*mcV1Ug#`{nD$Gij$vMVQUbbYJBomb{VM0$Ve-)D2L zRdDF;L`zW#O>VEP|5)<(v56=8{GGJE=r9eUZk{)wh}A!GqR#grrC~ycA+RsS1B50m zo3~1{?Mtb|+?Sth0F2IFWSaY}*BP5*B%vH@^GtU$#xMGPn_5pI|8h7k?zdZx1Sfzn zrYm*kK5JQu$IV@vv>sCk6(@<$Ep-gApHkC`c1V$6zGm}ViDj=%pP3w91DQFWnQ&1Z zp?eSRSOj9?PQ4J#1-ZHP+MDgd%{a!Rf{FBygiokBNksQ)w!cT-lf#Q z7wx;WzJzP5g`q_qqtfrF4z5i_SmzpEL(0%4a<{D`rPuXjbX9`8SVZkSC%L*Cn+5+P z0b@OR+`6Ih$pXMIIIt3b%h_swJO^FYTYkYgDF`6SJ9V6*qB=2&;dbw@l@ZFz5u6}B zeup-dThoP0m($KQ;M*(LC)=EoR5Zvyi7Dl6{;3F~7osD1z9jp!GIz$(gGkm~f!mze zqt!2*A@>>y9;WFNL(~*PNDVktgvY|7kXvGuUEHR89CvGZzaZ3EM7Saw3Wd)(hYyb> zDDNI}+=4|A+bW<-1iI&LQ|3eK@P-*Y#o$O;nBiP-PQqK@Q(9zOL?rpSW};UD0W?If zgo_8*{tPnEeQ~dGq?vcCJq77ppq4cKndYwJ?$5R<5Xh#=<7-Fxo5)V{l~X%pg1I6P za_rxF8OFaU7|bK{COARl&0TL$ku}DMh~kA4H2M+1>?|WgC2%*;(7Hl~f}7!48enK$ zH}4&iGx*N|W!B0=1H3a9T9%nd>qUi776xZG+S%`Wx8^>; z?ier5I(lCn=9F79Urp>Tq?PyXgKPmqz9ZBar_)=h6_({YOdemjynUr+r`zz$a`R=9 z-{{5CSY)|@D2VD$^Q^F%GsHCsBw{yoc{0fH%&aHUnH>qpH;gf*|dhv bJ3xTPfC`xvaq!nWju6n-Hr7IGAYT0+dB{-M literal 0 HcmV?d00001 diff --git a/selfdrive/ui/paint.cc b/selfdrive/ui/paint.cc index e95c3f426ba1fb..95d4faaa56d3b3 100644 --- a/selfdrive/ui/paint.cc +++ b/selfdrive/ui/paint.cc @@ -121,6 +121,41 @@ static void draw_lead(UIState *s, const cereal::RadarState::LeadData::Reader &le } } +static float lock_on_rotation[] = + {0.f, 0.2f*NVG_PI, 0.4f*NVG_PI, 0.6f*NVG_PI, 0.7f*NVG_PI, 0.5f*NVG_PI, 0.4f*NVG_PI, 0.3f*NVG_PI, 0.15f*NVG_PI}; + +static float lock_on_scale[] = {1.f, 1.1f, 1.2f, 1.1f, 1.f, 0.9f, 0.8f, 0.9f}; + +static void draw_lead_lock_on(UIState *s, const cereal::RadarState::LeadData::Reader &lead_data, const vertex_data &vd) { + auto [x, y] = vd; + + float d_rel = lead_data.getDRel(); + + float sz = std::clamp((25 * 30) / (d_rel / 3 + 30), 15.0f, 30.0f) * s->zoom; + x = std::clamp(x, 0.f, s->viz_rect.right() - sz / 2); + y = std::fmin(s->viz_rect.bottom() - sz * .4, y); + + float bg_alpha = 1.0f; + float img_alpha = 1.0f; + NVGcolor bg_color = nvgRGBA(0, 0, 0, (255 * bg_alpha)); + + const char* image = lead_data.getRadar() ? "lock_on_radar" : "lock_on_vision"; + + if(s->sm->frame % 2 == 0) { + s->lock_on_anim_index++; + } + + const int img_size = 110; + + nvgSave(s->vg); + nvgTranslate(s->vg, x, y); + nvgRotate(s->vg, lock_on_rotation[s->lock_on_anim_index % 9]); + float scale = lock_on_scale[s->lock_on_anim_index % 8]; + nvgScale(s->vg, scale, scale); + ui_draw_image(s, {-(img_size / 2), -(img_size / 2), img_size, img_size}, image, img_alpha); + nvgRestore(s->vg); +} + static void ui_draw_line(UIState *s, const line_vertices_data &vd, NVGcolor *color, NVGpaint *paint) { if (vd.cnt == 0) return; @@ -209,10 +244,10 @@ static void ui_draw_world(UIState *s) { auto lead_one = radar_state.getLeadOne(); auto lead_two = radar_state.getLeadTwo(); if (lead_one.getStatus()) { - draw_lead(s, lead_one, s->scene.lead_vertices[0]); + draw_lead_lock_on(s, lead_one, s->scene.lead_vertices[0]); } if (lead_two.getStatus() && (std::abs(lead_one.getDRel() - lead_two.getDRel()) > 3.0)) { - draw_lead(s, lead_two, s->scene.lead_vertices[1]); + draw_lead_lock_on(s, lead_two, s->scene.lead_vertices[1]); } //} @@ -1059,11 +1094,15 @@ void ui_nvg_init(UIState *s) { std::vector> images = { {"wheel", "../assets/img_chffr_wheel.png"}, {"driver_face", "../assets/img_driver_face.png"}, + {"brake", "../assets/img_brake_disc.png"}, {"autohold_warning", "../assets/img_autohold_warning.png"}, {"autohold_active", "../assets/img_autohold_active.png"}, {"img_nda", "../assets/img_nda.png"}, {"img_hda", "../assets/img_hda.png"}, + + {"lock_on_vision", "../assets/images/lock_on_vision.png"}, + {"lock_on_radar", "../assets/images/lock_on_radar.png"}, }; for (auto [name, file] : images) { s->images[name] = nvgCreateImage(s->vg, file, 1); diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index 690695169ecb9a..935f1f3a59000d 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -328,6 +328,7 @@ QUIState::QUIState(QObject *parent) : QObject(parent) { timer->start(0); touch_init(&(ui_state.touch)); + ui_state.lock_on_anim_index = 0; } void QUIState::update() { diff --git a/selfdrive/ui/ui.h b/selfdrive/ui/ui.h index fe16deda496552..2e8cf84e478456 100644 --- a/selfdrive/ui/ui.h +++ b/selfdrive/ui/ui.h @@ -167,6 +167,7 @@ typedef struct UIState { // bool show_debug_ui; TouchState touch; + int lock_on_anim_index; } UIState; From 1dfee044f3476e61959f9d020dfebe9bd9eb7f1e Mon Sep 17 00:00:00 2001 From: neokii Date: Wed, 26 May 2021 01:12:30 +0900 Subject: [PATCH 04/27] fix message --- selfdrive/ui/qt/sidebar.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/ui/qt/sidebar.cc b/selfdrive/ui/qt/sidebar.cc index 1989967dedf869..32769075b40c4a 100644 --- a/selfdrive/ui/qt/sidebar.cc +++ b/selfdrive/ui/qt/sidebar.cc @@ -63,7 +63,7 @@ void Sidebar::updateState(const UIState &s) { setProperty("connectStr", "OFFLINE"); setProperty("connectStatus", warning_color); } else { - bool online = nanos_since_boot() - last_ping < 80e9; + bool online = true;//nanos_since_boot() - last_ping < 80e9; setProperty("connectStr", online ? "ONLINE" : "ERROR"); setProperty("connectStatus", online ? good_color : danger_color); } From 919b9ed47a0a33e6e46aa9ec73faac7be67f349f Mon Sep 17 00:00:00 2001 From: neokii Date: Wed, 26 May 2021 10:18:01 +0900 Subject: [PATCH 05/27] tune long mpc --- selfdrive/controls/lib/long_mpc.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/controls/lib/long_mpc.py b/selfdrive/controls/lib/long_mpc.py index fff03ca83ed3f1..703f896069e699 100644 --- a/selfdrive/controls/lib/long_mpc.py +++ b/selfdrive/controls/lib/long_mpc.py @@ -83,7 +83,7 @@ def update(self, CS, lead): v_lead = max(0.0, lead.vLead) a_lead = lead.aLeadK - dist_cost = interp(lead.dRel, [4., 20.], [MPC_COST_LONG.DISTANCE/2.0, MPC_COST_LONG.DISTANCE]) + dist_cost = interp(lead.dRel, [5., 15.], [MPC_COST_LONG.DISTANCE/1.5, MPC_COST_LONG.DISTANCE]) self.libmpc.set_weights(MPC_COST_LONG.TTC, dist_cost, MPC_COST_LONG.ACCELERATION, MPC_COST_LONG.JERK) if (v_lead < 0.1 or -a_lead / 2.0 > v_lead): From 39dad0cb7715577691faa5795baba1cb24a81091 Mon Sep 17 00:00:00 2001 From: neokii Date: Wed, 26 May 2021 10:19:38 +0900 Subject: [PATCH 06/27] change image --- selfdrive/assets/images/lock_on_radar.png | Bin 9977 -> 9751 bytes selfdrive/assets/images/lock_on_vision.png | Bin 9921 -> 9751 bytes selfdrive/ui/paint.cc | 4 ++-- 3 files changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/assets/images/lock_on_radar.png b/selfdrive/assets/images/lock_on_radar.png index 3033c4aab29a9b4a79ec4706585a41dfc3c06011..7502ef3809dc5812d330392f8d3730b61a782ca1 100644 GIT binary patch delta 6989 zcmZ8mXH-)`x4j9Wgih#HKsuob0!kH8s#L)sE%Yi?ngTaLnp7!5Km&+^V1ZDimrxam zsDM%g6GRZ{O^UR~_sX9)Yt4^2b7rlxX7EhOx1lUTI!mrQu-{NQGe$6%t&Vrdoj*;SBxb++1tno`mFr!T=AA8W zQhp5~SFhEn)A9S+YUSbO@i6DTchNtp$B+4XLWg74Lh;+p!&{DnGBPr(dcSh`p7}{B z+)^mdam2*xdV%OriZz9oB8@I+F@Or!ngmil=_ZAp#OP3jD0@V`FzemQa`_K}k}ZwV zNlZtLa+o@dBqni529Ei_bq8zDfI3*Eb$Gj$4J7*q3t2Q0J6Bm&%H?y;h8En5LX>qs zh}PI01dzqVN0koE^QjCtn_AIaF8O5NsDEarcXJn)fUxQr0`WOY4D2}<8Cd?)!FZT1 zoyeKJH$hLkEJ+Si48>#mh;HyZUZIrVM0=tJQ4?JzR1DLFxtXB7&|pdX;R>Z_@&k-P zR~emr_&X5eL*yqe6Jbc|Nf|9CI0jWLh@qN!L8kS#>{FE+Xg;)UfjiASMBUoE#E)9) zMMD+&aE!d)!-QGt zVHwbjpuqQqmsXP&h(>GMI+Q3%F_8!TF!3Qw*kp{Fxr_P3J!sgN_%dGbW=a=W11n>3 zNqVRUeRMmV#tg`yz5QB)-j#c=8Hj|K*qv|;XdgZTlHX07QwOQl5v|?qU6l{&B!SjKp*(!2Z`i#GQblX)%>$YMaaQbgcAX!X7SwUG!<oxwKh?u23k~vTfkUi?n zb;65V3CnFih&5H2sZmv5`ru1nC(^M$*%ukn&z~kau5yNMfwXDe(Ny8@r#+lMZ2WQt z^CyXll2Adcj*B+XSE?FR@ZD^+QbZmy!K%|2cV{~JpqBeV6!8YG6Ff(n6<^ohTyGwj z6jGmpyVd*{nR(iDdb`IFN|0!ucKTZ(y0)rtH?WwD#wztrA;X~4?{AE?PIsmjUJv*i z?8TPg1brk*)2tOaBs!+Wq~0SJdYS?rw5Q%sW|N9I+|!UYi^f<_H@wEfgp0?h*ZQkc ze6Km|9TE$4y(r;G?IOBi5Hm_ZSM*@#*~ZCV9uh4PnCKez4I~#vbV=(3y|=)ZBKlpw zuQh<&anAD>yZ8;oxo20-d4{$gI?1Blm*2Z2%Dr^kn=akgT>W>{NE~PTc3)zH&cYe`NXv{$s2AB=iWUhk zB{PKTv2E6lwZCh1ZKSmf&Sl4~iUE_eqAQB>uX;Kx17w5Qznn9Dh&GLoZMDW6um!Li zK;DW0e|}#eF{;pWx#h)yNv&AP>>i!z-WZwEe^Zy(yk#MV3b&wOaz)iZ0Qo=-{cgct zwBS$P#)I>>3s!%@Jk;R2mnBcd*}h)n2=&1ij&w++R+=JE=`+1MVtl7@g3|@M_Hf;M z`)>L1-Ti@VuU1p`B6SmqZ|{;eFdhdm|wGlP(EtMIzVTB#$E8OUxG_ zbn&Fg1`v@nwoZyeU&!qylz_UZ_VzwHiI^IaQZ zE;Dbxqr;);;=sTh9VuIO<;P#`mE650(ujG0RlE948PM=Ilk?!@6nUcm#KZ9%r5SQHWAkTw_|xrNxAPvp zdO!iAfTxRpI65Jb?k4>f`k9AeiAO?fe0_TN3LWMWj-@M&HEgE`+Gz~9PVB7j48lJX+{Qhu5V!4?E6N+`z9CFI=z;TMo48PYgB&`z!;t?3A4+M0e z*zI~CIU89mFOb`FqrDURo;(6LKA=mU88ioCLoFJFECq^)%y}{D)S-OYfPb9UhWU3b z*pRe>eoYfh2gFVV$O=QGD68x2-`C|xUks96FDUeebes#9l7dvkne96szU^m>&GU&) z;o*U3E?ZVfoT@N_xP@Ct8A*(O3XAQ3In7Z)N%cnPBz+;*cCyHb#YPdeU?EcGg!P7XX7Oiy1`A9)stxk-K(TI8L46y)hWGPFq^vQHRfK? zoOUQQ2HV(g1Fn8H8`NbP(z@F4NpNUGLJ!BC> z#xE+8L`{;#-a@0TUKQiKAnIMu1yixJe1W1a(GbmFmQ|7jHz8`Y2}wpq>U>Rno}O5` z20TCz#eZ6HtC9=j1nUH8?9w|m%31ps?oh-tL*7%opvAtB#bwI{CUjeWfuZ7FWUfzU zbJy?dKts2}@M*hLU8bSxDUCKWs{C?ntYRf6hKhjfys}S|`ax7b+m2Cl&9X`@wnMR! z1EVeEaeeMwuH_qZrWN3oYAgh$|21s~Rk@Y`vO26oEa;b@hv5C(`=)b)sm18Y$5Sma z3uXZf4GD*V9zK(6FehjXUzgMmC5~d;XLl}IDoGwe|1%=t)5qP!R z=qL{7h@9P6JpMUiw#rQUx}z;H~!BBJlnLndcZ5l;k{h`vdwzS zLaK2p>zev+tz5GjOF$CUX?ONpq1ORqDQnCr4RRF2)06O64=8Mr(`D_T?)TBW^XMan zVTS({dK4nP|Cu+k7ry;zhe!1TJtZnLWTqAg2u`1HowsbW&$M_Co?U?`h7_>H-ZC;-YVRRO3u@^yxV8ni9XQ zttDIS$yUgXk3Y{q4jO+y;R|9V=w~WL-LwX|#fnq|$i=posm2$Ti~;>1UssXxrI$w$ zPay(t-%CSSyVPkz7mYMLaClueEh{)iDs6#CVLUF%!wuA)kw|Eh;)6hvGDdL6TO4qm zs|U;mDeJG2$}rprpoT4WUc!XyfO?Dj%u}Y4;YhQmGtlqud0_~v%?PLW<4rOc`Lw?X zrt6Q>Y!lS5Ds_lF|-vA?zNO_#m&^(xugYC$b7B9nU~P!-EBMxjI8#k4I{ z5id*de+kPIwTwFlR^Q;8PHt4}opRweqf8ovO0z7j>=aX80^>d`66joc8(hP`pp-{D zg)SeKMND+giI-tBSA5AOnC`NRrJtE_!GL_Yq>f62 z0&WuS|NRf@Y2RhuaYHBV1bk9(mAwg7y^ zb_9eo=gi}7{-oV7Vx}dl5!+zzyg0kqjmq)!aKBGpQJfgdUkcuHs1+v_qZ}8X;i9hb zGkX&(#R>`C2&91Pm;TKRVffjp7?c^`O7uDe7uFP-V|mD6fq_+*pSbAoUUwYK++_XjfxmO&d}?tS=UC<}--s~tvv zb9gKeS1=e`{H3EfF$$kC5#;)4Ys*n7wHZ$s-Ksx?g3%A=xdn2FF~18})`umwh@rac z@r}VOd#1M^F%{zyP~~rHh^`i%B`>~kL_Tq!l;lVqG78Tgbts7h23)JyF`A0kGwq?m z-^!sTZ}DN;*QLp4FnpkSV|Nu&BnjRsLI9Sm=iH;C+V~g@MZ|#8lsiN`?@3Ixt8`BS zO!p?(Rp&m=GcU3Ad;1KOSQLbDfU;glcVv=z3o5Mo(Qt);G`WAO1IYe8gLf&R4ui$b zS#dSd^1OX717S_rW}YPE9RfUW{`;mJ$Zoi&eD4%cXQ~U~fIq)ZB9B8&>Mbg$^mrAi zaD{VT^;0)W1hEa${-=E(RvMYP5?et}tXn7JKD`FjZM-mdRwctTIFZ+oEIbmrP znpX9AozK5hRHnRPNW9>tm^om22U5_?xR8Z1!>Qsvnd+CTsujSV3_1HVm?&kRi$uiW_un5b83olf2Dg|@?H z)?%`3AUORE+yfn|hEde*RB_@Y>UJZG$wUS{<=n*T@b*3A@|Sdq^kO+{PM^CpjKYw4 zM^|e+%QZ%*Z=}dM!BMbp0EDgFTjt2-{;2`ah0xy5g>UNJxzogpG$u!V+S~- z%ty8f?K@|6u5%(=LLydtt^9E_*l;1)R=6D(uu%usVRfVpNXb+@#kSX2@8>5E=c6UU z-;FcX4MoB(?fRz_!OZtBpM57+$D}OZo6>l)lPbz8*|G0cs_3UcPo}V9+W_!~U|pp* zL}gO{z$1V)HVr?S)`h5yep|&@7A{#Q+JiSfEW zwvYN~dy4~q9(x-C4z(GOTxL!FFsbv^F*52=A!7Q;>sE38y=7dOYRpT`LBZ5ME>=;WBfbeybiq8ar_3AlN9>NA*Bl%hm(dk_lvp%$ znm@xOoDbcQiLJ_NZwf4+n_O8>wpJ zoa$HItT_r=);#8VDqgf5=OBS<*V(F=eX4~l@iXR|OF20~+g5{SBP>QC==33MpU^xX zRIRi`q*Q$+34e4Lq{HQI1GNA~H_ck-7YAD zR!g^I6S;-{5*yQ01oI3tYXOkN)7Vakr;~&IoUK0b3$CkxWfb!yd;j?e!8{f?Mg76& zG_4>ipL-;)F8Wd$_wimvfCDWv{TD1ZCBj)2MqD5|!pt`v2afkA-x&hm?DUSs^$)%i z^wafV9&~vOUy>9ssX0e;BX@1Ua4JQm-Y6m+$xAm`?-Hku{i!jH<&o*fW;Tom(GK;` z{aiTJnnYxSZI<~x#2RG{vUdf_Dj4XR7u&JZRmGJs!E=Y;{z_*Psl(8u$fTo^{w+ie za>{IZB0$QuPG+iM@=W|esyi}nw8Ec$nM;zJir+syAf{q z7i6_#Sjdu_snd~g*8;h-N`%i{$?x*gsH%55KY{zyUiK~fgLeeyi(}+B_fA$ z?u%NOO8?rQ`-yLUb0G^aA}}LLg6eETH4Dqfw?^@B6)_Pu`&2^^t+*^%he|8+JI5HE zJxeAFM8Xz1YKtU|24Xy#E?0{tt#K8c|wk5+3O9+T%x$QXnThEk7>szJx`lf`D%-JiNVBM zKI@N=9rIOvnoZpyn&DrY+!FsSv;p9E<+w)oY;|rPxW8a+(d5K47l{T#JI4iPiNZEN zM}j7Gl1B+>&IjD5LDo6b#71Z#FO1!Y*V!&)5im+*Hm(!6v?oBxpj(<`)^KPOn?L>v z)P*zX)#YYl9cN_Le$g%cL)38>6qXrf|NT7qQsXa+Nf^ag5~lH@USUwPDB>@N&LM;t ziL^6CEwm2ki1@LKvD9pvQzu@(IX+8N@8-{Vk&ps%G&IAxx?gV@t06N{)O(#nW00yCN+MNmeH48J%{$7a-whcEE`u&Rao%2aaf^w%lu3l z-LgNXSu*pzCd1>W_3A5&d56`k?J@m-agd49w!5B1w0}5CXiw~tUb(7~`gX3BG%onL z`_I9`v+dW$QwVE)Rm0d9+Y48rlmY)0-}M$ybZka2vOh))cH*BT_`@v3{!Jp=xX$QX zu{Dz0Z{GsnU}{EK^M7V+jzhg z?4|Oy1UsoUgS+Fme9GXSHJ7+jS5yFoaT~^RmzPIZw;IU#0LMvq)5I!6Y7|S`Mb8{X zu2#J^I`1dXW2;srekw|~MWBt;Q~!V#(oJqEq;$TeIGHFeTv~#VPJ6Pe9n*H}dc0tG zJB?=gjA&aRtJL$N*_NIiEFeZ1) zx!0e;>3j^E_bV5!Y{#0OhT|IR<0cgIbc!8Dek>>th__=(>w)Sz8EQW3_I3LfAUJbc zoSL9hOqo)aeimcHt>LiDxI$Im>&n#sF_N+ukSZ<)JhMyWEls;iwY+~;RqcFee|fJv zEj`1;TjyPWTt;3>W=%;|gk{@4QsvC3vgzuB&aTh&zI z5du>h$k0O73HyakkU7J3M@R`%1{u?!QP*=LhE_e9!rHX z1xa>Swc}^zsx9&jfm%X*JMU2QIAk%Ypl9t>6$B0U^uLIxYkLa5J`2Y^%LZq+?iXP5 znL0G(5?v_G;OHQQADOlniXz3cT+|c;qV6xJhZj$o0ry;(mGK{(FkikB4FXJ5XhM(i zZ(Yuq^TLtxWK31BD#LYMkKTF?UY91OYL(sJWWaq99#M`AjQvEpm2XL=CZ zb>KNYN9q;SlKj~!-r4(TATO#>h6_56iZja!J^=yayBlz+vb0R#tQlQ1)34G)$Nd*& C0p%b7 delta 7290 zcmXw8c{J4T7yf+4jAiWmz74W8goLt93|S(wO_mIz>}!@RGb3wR6GjRlm8_Aq7_vr0 zg=87Yl4Xn~OSYfyAHVm%_uhNXd(S=hp67Y)n{##Fw7LzB6OuGSU$zRHSbY{swEE7U zFyrRT?JYK5?M$c7RU?@7iaq5)%D9PllKirqr^=beC)lJ1-55ks_jK1ZM~dVtbeC~? zdn(4mBw^}s1T1zG#00u=6AJ+G&O=k7bZgn*Yh{C%DTG^V%hdf?kf=3H~{fj zD2iSjWYaao0kQwx(FT7ozTmsN&5262C7cw`!t-Cuscoi&1Y@M123g*5G+5aM69+?e z4i1wHNO>e{Gq!JxT+RCzpMx0oM)A(CH(9~wc?IC`F?^hZ&)nc*6?j5>X62DFfWAkh zTb&c|WhJ|lr`YB-=?@z^76T=#Y0Md~j#XsgfW)q?Moz+Q!pkWKQq1Fg6M4mM;S(*G z-bf39F8GZUP;|iwY~Xo+?R*eE4}XIM!hVK=gTd&**Rphj{mbt||p#RU+yQ!u&{sRY)As_9}9C;C0-~O^P$GjIl{%DrT`;ot?_YI|8 zL*}j!l*C$XWuAe0Pq8{?DSz_=z5smLV&HT~(TbTVr0Oi8R?!R1fXDU9M?l(q7em`# z?gdUl$j8uUU!y2@1>CPYcz-9W>^9gy#5M;oySJPwg=f}M<==77sZnGnJCCfUr}m6@ zceTies^~&aMfOHrNII)(K$ZRX9k8+TSqd)TP@KAt8k3?UK9nD_esGCwQmE!{K*mWo zwM9KOcTfO(70xBW(AMdkZcYesnd;z;|u{$n}oMjG744c(V z<1iu+Y4v3fROmQELcb4&s3OBsLO-Od5!@1QhgVJ~nX@8s3NF+=g^-@Q2B_Fn`I0X+ z9+RGQ#@%(LE9kq(*}=D!p`%00{URNQCu0vAqX*krTV_BL%MSP%hq0yw!Q4o27L=uXE?SyD8~ zgs_&w`Pta0t8YS%XQ_WgpPm%c9>=VyG1oqIbZX3Kf`|NJulF zAp6qPV#LpDoinl_d5`f?06NU$3Eqy#d@`$sT9WP{R;-^cjP^el?x5nqCPJ zQ9gUKs;Tne%pNQ6achKIcHIy-nJO;~6Fh-*9fwy3M z#n=OXWWoKQ@~$(C(yuB@Y=Lgjp0@s|TkA+aY{zBe{Gy4=nI@0YzP}ALUBxs;0EaQ% zfW6m4($1DrgQGvFA_S^f3mvZYWNzA z#+9bmCfbEL@VBZ}{pBlCBF*QnT{r+uzG`~3sJZtSKz&1fW~(^xpK3);oiW!qGt8E2 z@W@7K$|&V1i$T5K{wc~)0(>PjRl`TQoZ4P=n7FE#y0E0N4thCXgv<4P_l+hmzn_ei ztbiaBOc6fZ#8^z4cF}(OP*x55e%o;5tto1Z+vT(xmD-w`>_pxI6jB9vsF-pgKKF%uR!idlfJW41WR5T6yX@+`!VyBqP!W21_Rn zL@zhbpOk+&X8pn@CJ=qa%df6MX)ZaCk9-qhuXlgSVeIfbaW{(b^9D>35V4LrBGun` z+;--DJZE}~QR?#~>PO@N->MjLVk<|9azOjUhffl4d#mPt_nl39J&cq_c=<^tRG%Dx zb=BITsR~zv&jzqykw>36CO6D)IHU{pw&VGOk;&67iJ>}zkiHq2o7@w%AdSB1; zxxamo2A#>o9ox7j_5uV*-`4g*$^N9HGFppj#y=nO;>QzYuN?*F`2D7GA9@#+8-Fob z-;~*(pUSA5ZY$vn@{zy&vm*=bh9c^@Ff4xZrEl60R0W*8qqTkr@%O#(pWP~wOVC5u z_)Unpz}Ffs$NLU*qVV$jurzuToe5r=Xg9S^%(XSCOch9#YoA`*1CN3{6To;b3VQ_^ zvCdA)aLaCZ$N5-f?eN%>Xwet%c`kR}4LLIOn{Vf?ERV}oh&ke%%f?YpjzzZ^R%HQg z1z&;eHsJz_d(WH$61r7{8rk+}D(0k&0iKV=kJVP%q^qy@&iE$2fQ#y{d~-nvY9_$M zlRn1oIy~Y(Q5=Stv*_IYm>4+Dr#_)2|5#TpFS)(rlfLj#sJJY%Y_5cI0mvpMjIH@Hu{{;l9F^Mzv!RXG)ltN$hL)`GJA#!t_H zONsg(Npk+KtaX>t-Hz}7V2I?L)&A!?oMxL2?ArC=Urax!lODIWn5wJyLj$e>+Jq4Sbk*XfMKIr-NR5xKe zCme*FFk^t(2`ByVG0(RQDBlpX)0*A=OOxjVG|*1nniW zeH*K|K;_xll?HX_w1-?-3*r4zwwxCGZOFNWMDOaLSUp0D%#_uKbRCyLFC0u8lHXa| z7cc@NhZNQPC}2K>Gj6F|^AQ`1{IiU~Ss@g&sS67Q%}ufQ1~Por#v}&gfbGu1-D36b zJjY#Qdc0`$g+rMoCU3j$b)BAUQr@GI@&`SQJVreD+8REBh33(W)iYjj!7@K+qKI!U zUch-=^p4D)CcXNF6-YJ1uq0uRr~jh={pA*VDswfX>YNCSHD}|e&hSW%^LaH~Tlx)f zT!fGBa?{s4gF6Uxda3_i3v)C4qvs&F$58EM11nS;#vEO6sXf+3KG+}~u|IBsD{B7s z%TXAyY3nNjw!1eWdz9mIq+bnMFaOE&eB`Bozkh0%FuIHL#or(fUl(udd77sz1vug_ zNXUe;%*Tmx?z_mji;t6=CYf;z4gbCY$sfPm)nEGid7qe- z!#2+ZyA-Yv7O;+zQb7(H*Q~SHu7shMZCgzg^~&cv{my`X(E1M; zd)`4)bp{BP>9}?)85dY4AIs|Qnp+X|QnW42Ket8$`-aPOI~0*+3}U9Y0+3Mc_VSmp z)XNg?hN`_mO^!6oO&^j0U%5Sp6sZQIXQ%aFeHvxK>JXc21fR{5B|0Wut1sQ&uQITc z7WVaJcO0fal@%jgvP}&& z`1DPR3+KI7)Dfl-e>V3Qiw|ED=d;-?-rj<`r6L@vhjbZ9zL+PQ-{?t$dw&n}z+{^v zF7_?1;|iO!?rU{3>t7{-*7NT|tfsh>6#4VKHv6u2@C(3x`nlRc3(tIslFbS4oe#A@ ziiULv(M2-hR!dAcAFSZ*HM4EG1AU$8v;Q_GRd}u#GYa061=ZQr+iMH2T7U3vpFoA~ z9!J}qvE@$+FP7E4t{y1}y(>O>DLRULc_M=&=lfYHpmnXxDY0-s<@#Da{HS`V=V#NJ z#_Y@wx%Kzl?gJm_J1%V>-p|g65%?+ww9*7KA)e}6<3^kJdBGmQ-o>{(?bS1bZhCTo zNI&DdR2>(-o{^FHD6}DpAx`wnQN*pdhmv$PrxJYYzSEFv>6T=||!ydo1U7 z|Hw3bT-ry=In`#eSx<^sHY^ZZ*Hp`aqwMKDbDlmkiZF=8}o>#EgkKEp@_!?3z zTk(-U>*MX-bsgDcx4o4hU**}#Q7GiX*Un6gclYNY|H|Ea zTzD-Lp8<*Z8lX{QU~obMidmZNYk}4~%x*E9*Iz>pI{;UM9KRtoyyWL=$|*$Y+pm%K zC1aEdx@!3Rwcx!<;DV=9(xN3<1ovd>k^TX3{W()rKi==odwE@DdJONrSLbIbZ5XPw zzDUT^qPHGhl!y35MmfgZdbHsC<9c({YiEXmAjLOUQibx?i?8XZGU7Q}XnhPvWBO{T zcV0@B7jJRDZDEoD z*<6&6Bm_O)z{-kpqA?@tT>_>VUA_Liq>_=IrJ1ViM+3*l}? z4$RQypSeZLC;o{Y?}2I~)ho&-FSfjm43Mt&Fr$1|Bhe3hDt}W}nP>_aFcq^CxyNyn zZ|YO$jVEXFNY6#ma15Js!{dM^EE(cUYjgcCcK{0*?O z2&s>+>5`9sb!?&k~C3?M^IySC5qc?cJ9 zPelEEwa>l8s8rB*Gg5>xC|b0~85h3mYmvp1LH}P%fFdm3ts+~W&&3&4cKnlEuWS#6 zWGY2~;)s<|I!m!Cy~es;lW^^{u??LjqN+PA_OBf_F=FP1wc{Qe;IsvN-4K*$m7ZPY zcst;sqT!?!C!fpXYU+LAau7WSzUw+`vy`2oqr@Ei~hv$rG<^P4=eN z2@lP}y*(`0i==>u&*;Kf`Jj^v%|se{zvAidbK${|GRh$cMp_l5%xknkrP&i)+uHd+(s)fftBV13)2f5Ehw-Y;)BWb6HT87GsZ zNFim`FqGzEw!hwRTgA;ZSbVuPbzL06g=hb`C&Xwz{7oX!9?zq%gH-zH(fm#qtq7$K zJSRcZ=I_$pD>k3dEzt!^TlQmNBK<;8ha&s4=uH@a94c6^X$j<`&)@(7OnXpxUh{K2 z8v+I~PjJ$Ed>J!+y5fRE$%vsX0Lz)|^@oQsBNBY|+~+nftJ<4clhEPLkP!wF(=L|p zm8#87W}Qw@r=i4xm5M~n+kzgP0Ydy&sQ_m9`}~t~27nZb8N57$q}jfFOhHVQGaWL9 zu`GquHj3`JnbQ%&iD{JmkA?X zmT50F#7PSiK02NY(X9S36qDI4J-&K$P0NYYg7=m2FEtcpypvj@#n8xW!m_118V_KN z6bq7Ht=fH;%Fy+d;p^Ce)_=4#C@<+IM6flUiwU#^70jbJWakX+%v^K`FPq+$z)6yJ zw4#5zMo3Mh@G?t;l-2O1;(E2>Cdn%?TC8E0a4~^z2sdTY@P>5fhDTE8ov|1ZC|0C? z;i5*&+cYpfbHK=4{K*n5_}tR*P{%^=!u(}`q#F?>V(~+dphIpa>Lw=g!OHEa`x0dD z0u4hw<;1)ipv1zT=h&5P%{@*-|kD~cH#Z5XCXdXIREKe1BQn($%vB3 zHle;cl^AONj1MFwf4!hp=V?4sjfqg z5qBtqVTBZ-VOqbAgyO@UJ(|YJ-j`oy zPNK*O>LK|%8*98I9t?W+)er74+Pw1DHXpb}UV;C3|NL{}8Ut@R$9TypDwReZK_5Cq z3Ll^6Pl~M3bPuaH!yZVZK0pgq>N{-ceiaI+vjh#ive4oY=TDt)zq9;rs4F}FTGE!- z+q%wo7pM-&2O7Eb?`zRGg(b`1eL8gNvJ{%W34vV-`nSq3Z5!km^7Qp3d1LG~yO&j> zH=q^on##{F}1@iZ|*4^WygzJ3n}bs%8%x zBE%+K?jmu(4F!&t~(d0zPtN;UM&a`ph5!yCG2a;yRE| zLTo@U!fKn(=I~>DN$P%`t#!e>TtA{WXX4}!xJQ6PEu05k9va+Z>1PNt$v8Rc{i<(QPrwdxKGRw&W*_GY>)NUbwQ1>PK2O+y6-YOW zw0BC12HPP))~=CQ-asxMRQuTPiAZwKo_&=lV`O1ShF~jg2<^20`Yz41>BmMX`KOp$ zKZlgYoC@T$p<7F5)qYWh>*@i{AMSGQ!6EcGo@NmSyiVDqKY1DPkuWT>yCv_R#2Le? zm%X7*ReP7d_VSND@T~#I}2@EUI?MeB2VGo|D+{RRFAfZ#$7jQ>? zb`1Q*?F)<c-=;$EUC{H0&E0eHDAaPZ7HI5L?jDH0D8?Anl@_ z{pYoccdfa5h;`4hB)HWubTA@tzo#PO(<+)vF&!a{8@RW8T-#$0 z!{iE>9m;+xphIBTR<9*3S&`5+CM<{ld*8Nn;8tch#ta{IM;KQ@Q~x+rUe%+qxs33i zofgYF#z}wawiT%660Z^QN{*fZ6~dpqe{fQqa-tJ|k(=2ni;V-nihCRx5;WVk987Jom6&#Z^Oy+<83svG~Ja>Gayr$avmC;0c)Yckp2)yl+ z##~x&!o2PydyA>7AUPw~gM_WeeU~WAKI^3ff;-Dw30s1b(-V@$oHI1Xf!y)FA>PEiw5KGwZU>3rl9 z4V|372R$X=*LxLIZU<^lewfg^?QLXZ2%zChw5y`yHhL?OsXiMtRBZdAU$D{Xb4^05 zUwVAsldS0Kd&j;Q%k{jLXF6${Sfw(2%2%VYM)Yt4^WgY#gzw7XaNIGrYCqW#tPu{ N80nj#D|N9k{{u0la%cbm diff --git a/selfdrive/assets/images/lock_on_vision.png b/selfdrive/assets/images/lock_on_vision.png index 050372ddb3f48f9d067fa7d55e7896c97e518c82..ba0370ecd8ecbfb49d142066f2376cdd6eda1a66 100644 GIT binary patch delta 7062 zcmb7}`8(9#8~%9=IXkTuFOL%fkKDMrZH>zyrY)|s)(GFf625g`dWY*CklrL@!QbBUP)h$VHG*EzJG1<9n3m`h)=NT*9PHN-yUne;;aBscvG zq^)uVT)s}b1J(Zh)kfLTwW&bI{rd2Qs;R&H-TosHoBnyb%_BPwgM&ju+& z&W8HVVgq=D@g*LDmcy<#qI^?YOu!;Fy@%)x@M*(Ea%+p}S*Yt(V2AIh z0tMJK8Uy-Q?n71CFeR}qW@k&g@1k{l=HX}4scE=pBq*9$6vU-x1jKN`0nwQM-;nz} z%VDN)12~c;0Gb65rRwrN;`1RskS*{o{!VB(9NFw z5g5m-6L9Ky7>1?hOK2M$s20@(Gc_A`T>jLS?sYfaf4{%oX{2pDmPUi9pyFHLN&tQx$lkMYINnS%wLjNLR<_~gtHDvWlRn5 z>0iIP5${gZT6eF9&?-6o~VA%IeH2t1Zn^p=QLPayLdXwQuBy{aSk#ItXjbE zohkijHbP-B+Yfdv&g4L!NVAjs_gU>ZO&Kb?yp7Ioq{MS7O{1^#(exd8<2Udo)i}AH zpX72YQIIs>d$Q&RjvM*6f!RH2xkWecVD^K_D3Ui}vwd0w@J5t$rBaa4r7)HnoRAm)59hq^xvA8m=9UYZLe zZChy$|7v6+OWjm23HsGJ;#$ez4Osts!32o9B~)wMG0ncFL0TF)ch5KD^egZFV&in+ z4-EANt>*+yyVoJ`i9E3AxCq-%qlgT{jEw-6!uMaTHqUnlN33NHTYzy@;6=AO3)G|h z*6N>a_b87liAf=qpJ!m}YSSr%Wu6~w*o<7F!^S!P9UN0~S2*N1WzNlUn7-neKSNQJ z0t?|$PC7tu;U(YZujU)Yq6(nt3#i^Gueq4Rn)A^il#iqioX_x*@jG=b|0XeMxBA z0mP_H5ZoWVrcap&eoHC}^;#3%c6 z?Gd=)0jV4OE`8UdC4fV$W9c6Uv3LHGzNKN`I6>`Wx$-O-co%}WB9Zdu&6;&oV_FfH zR|qfOWiGNKBqlJmo6T;7ve|5~9n!aV=tHOyf47gMS{A&7iiG8IXvNqj7<7u!^gE>1 zV#Jo+a>5?sf;+uA3zzRpDSkBpYPx%;o$PPNM-Q~o*w8{CBB1I$lM#NR%YUK_inRvcl8u*$(nkQrMO|I<}HVbE+*AzXpuf6@CB zE}h<@1)L(sylOj=sj2@wP`?+-pfPQ>K&IhC9yVkG68QvDuq{T1Vt%kSjLsj1xHBMC z)F2&UR}g|L>&)x3FxHcnXsAdt8>KR?OL}?z;Ri zrs&~7Xk@hQ-fD{1{H-AGe{8g06v_m>nG)3(TBTejFx7*l+0_jc4@XD-TdBfuhi7(w zAZoH|MENqkcO#_?=)my@R|PaAqpo=yt~?9DI8PaiuD^*cR#?0X=DK(UKWW**fz2X8 zNMA9oOXe;=Ra1-WSkU6gH!h@K_8tCTnM8p#tPWH~Z{qWL)?-;vg41G$Ny3i0b0k>r z-N)~kx>qxz>rGMj#m$U?Nf*G^Ibnx0t$W(15WCRrDH;A(q@icoeBv3PZ()M`@Ac&> zCrg6$!`vh@x-4RFKD*(8ty2lk7p%f&_$M(jdBxh1#bXi%WT6c zqw%X~R8&}ZVz__tSLHt=6)zGLPR^Q80Rv)kC|lRtR!X01P)Rc__`0XxUb$|CT!?`dpcx_TT7wa+xk)v93CnbeATq7Hj5PifidCT{;$}BRG3Ftn zPkM_F4p}Dx>_9La8svk^pN{l#N!8Kg%?J_A+Ks5bt_wp;2J~#r`mnpxYwf>T^-!3p zSBZXKsx#N%_!}3PZ|_R)Gb`TxcB`j{A324$cu5c^n8WexGXhD&@XTI`xs_Y4>FV2> zT<@NovfGp}P_-KMSq5(+Q?j`psX$p}5Sc~z_YweVj0LAD0vojFoi)i!y-W_+)-BU* zB0+L^@E}a`X~EnNeRRUDN3A?j1-W?1`Va2`Rf<++)Xr7+B6)oo+aJv=Z+>3gRFMMu zol4Sm23w83SxDepw^caSzc=rEOa^WT=5b|StsIXv8kD7S5dA91`bEv>@V^h{6FIt( zH8DnGvN(!V@gL(51fEBGwi3(ENgSvR@E^}B#Y$h<0xpMTY9dfP2e;31OjPy(e^VRLk7}MOGSwVr*HH(P z)gm9AY+cWZ(62dEryEn0?`-cz8&?2=32uit_AYgdK0-8o7*2%|{od1eV~vY}U%#bQ z_)iOxov*)jV!Ele%}NoI^?2QXBhcqKni|T9zjaeUgHkm2jo;?pF?6VMqHjYbILMA% zF^7|bSUbI%IPVg)F;0e5a9016=T4rgPSy)!m}C6ah2pXN7g``hzD`lzC7f5Q1SjHX z?bEss4b=}LUhWGb`<83HeKf5c?6}J3g95AYs~i&cjI`UHpq8-A5I$7L&$iEkLq!L1 zFX~F08{4a<)jK&J`al=JFS|I(-f z;`)UO=0!_Z4e-JFEYCfSz@tk!;A5ORHs?>z1%-FK;7>hXpeVY$qWQN6MV=u0m4$=z z%h@KK@#d5wa}utkpKNIjzWg}z=W{pE{jJ}nx{n1&#oKituX*L&P^ovt)SFl&Vz~aT z@CU}WWy_N5_7S!$pdU2LHOZ7B_JiUVkC`M2!L){rFV%fxX6oMgh!yRCCF0!>p#fNH8Hjf; z$6@*n0ow0Z(ZW-lrgZ6A3j{+!O8>pUYb__`R3FNW%>C~{(}7D1p|1G(;RDZSLr><( zOMv^W^$5F<_3>x<;0qxL&idp$9>At3{Q z&a-`*K^CVLk$49^AXEd! z&HW$u`YXl1th0(cdtt`Jp8*M7_ZitnK5ac9 zVLPd8!LU3&!|@kX8}Ay|G)EB}2!?-?IZGK;IX-I8RR_ZXOBn}z7T;+~|3jKF(9`#! z`)f5saxhj(0x&Kqu>-9v1#g!3JA}#xGu~A!xPrKLja6)02(f(jMUaILGQ9 z1pXSti14Vk?)%dwOqNGHJCdfZ$UZbX5vI)Z#*!oSqZeL@j7X0I87Z~n8x7PStZTKT~zc&{3)@scW&JZ63x zv+?t-Q}dr4{jsR$!ulhXQgYA&?L!wsXO{Q&B5DJUaSN~IYxf7fO1$C1KflV0{}-ms zH1O>p11IwA02KbbyK|pi@v`oQtr=ZE{eg!;*X(Y{Jq9fAA?vILqV>Glm@6i$)`K3{ zHLIdPDCA87js*_FQX}{Ms3kG=WrCPo6%Z+({QH>cv4#cM6a4A^^gbn@ZsJP1GFXjl z@sT2Xh1`u&5YK@*GJ-SwKb^`E{3Equ9;kZal(LQ@?#DGkR0uqHP55m4zP|+E`1G9$ zsoq91-npb^(W7pw)ahQS_?4FzTs!geib>6R)#E#LN8s@2)$@WGl!))Mg4B^qJCt2? zRZQa}i+$7Q8SMEa158OpH3fdtz2Nm{=;L_T87bZ*IisNTar=VDzz63_9=w*~KSVnm zSY)zT(4-0EOvZ6bHVOh$<(U z?pP@Lc9*~F)P+^|o$tFMAT9z1#`b}_^_=H$xJ1pD~#kvvzJ+TyAt2 zbi&yxJg4ARo-MHVvY3Z{pQ7xdNc>>x1uEgzVj1?9xEvlJ^M<};K6EP-C+(XiEP#E` z7p0tbVUG9>fj7WR7mKJuBTJN^6o~@$HPeh=>Zi7$_9$uw>}r;m&m8!sx$kANEZQUG zRUqR(oWrlLJP41EwHtqNYPb#(0%zG~-2nk8P5LIk;ZHjEC!QvGU9Ue}CK_ehr!4^# z@O$X|W<<^%5J{g-ibmle4O5uA@x_#@n7fU{8`G(N)Qi&_BdnoFfltqx>f<)hfn!?7)*WPvpE~W|Tb{Yv_y%FQR+udUpx44s%s2-o?^L4FDItPvb&#Dn zl8wC-R6ljDcIYwh)!&|}!cdEYYdIHouiuul>^Eg}=NW!eoXA7ySF2>1b!QLE&+^7C zu-BH|=TKcRJzVwXij2yeN$!M~g;!Lv*Bx(tv)puZW<%YRJ;RArry~Q3U;hoDZDCGD z$*1kDxsibLD_p;Tv-{gSiZA|F&EJa@b@zSU6mdfP&)Qj6niytsry@q^*SmN?5bSAU zY9qntT5lKf(b|SLuL#c%8fvo`c3Lv|k6nYmmW@p>0vVCRW$eyM3%w#e%Hw~n<`xS@ zkSa;^`}M3Kzy)nl$FdH~)`=g1~~vdb9gJEEC9A z&6w?2%4S|tA5cJN#<6PkFR)68kROggv0z-}2QGe4#}tNFX`H1avHHWdzwuly6Zv&8fZ|9` zQlDbbuyV2D&6(YF`_}#Db=%(zBv9qFR2gvqSxb}DuWm}Fo}6HkbC6bT zfB%aOPO;?{wQ>F&8PP<5x(AxK0LY%x$POL%d-hh}to12Mq|O}9ar}#ngQ79AMI_fL z=D)o3CK|k~$RJ_k2S2s(AP?tZ4A?VquzV(*Uk-MZgHp06^H7Uzhfc`BOuZ2>X{YyB zQvdL4wSI~o)Qvfd^>h4Xf=T-Ex3PdbLE?%^Js}k4VGneI-c@##-6;#B<+16oki{u1)Hu?!GRVOUTD5E3*ApUnL@Tnzy3b755gkjYP3FNwcF= zQzre?A*URcC-%dcRtYK9^6qg96Sc>(jkof|LDC%M1Qq;cy@^MXzHj?lFvL&_YP)u~ zipmcUU(aU%QOr)pw|6hRqXr?<%ek<^k(@3K;_YqvUAYl8vVg`j_VJl7_$9Ps%HKIF zp4KXqguYNdq!f#L&@KTeJu0@VIjms_njSaw7ipa6f{zRG6{c=g=i+O}et#QR09L)_ z=;lUyIA&YcwX|!SGZzJFUM3med`c`BqSn=Z+E{gDJF@xiPDl-My3Y%@G`w|LN0&3WL`d6-n$Fw#d%0 zdQL{2kMu1cMlF^AHrr9F*DLL)ayxu|2zM)vUBGjjad=CloI5r$J}=A@neoxuTWwEl zhP}LjY0ZH@Xvd;U8C>xckcbacoEjqAFK5N?ovC@ITcof66Wa5-(7wpiCG)u;R@+fF z>SJno9WK}ivFJDDBy8_=71a9goXqtI|44kt26v~OvT-g`GPD6^JL*aMq{w6U`kjJ5 z6OY+K{Rrk|RJY0}sXfAbaMlb8($T7b;9Ga^$`AR-lqzW(%^uu-9@i_h!_m@DZVk$jO{J|@&STFD7So+(hG4>(BM%u;v zUZ&ja6+REpl;Q0u3qt?=U?EJ*SdgPF%3;)?(*whnm}t8})^Z!=({I9x{q%og$1YeD zg0t~^4i3h~U9Av%yW2r|MR{Sn+0<4%+R~NB8h+6-qC(N*wV`6hU2c?=Q?rCc|H#!s zEO?FYAaYXkGVySCvnN>tp^y2#?Vab&(XUw zjcqTuo$~gS_E)w^9L__`XaLY z$D`$0k3$H}UfxQ+k}5K65ERM1zO|~4Rdq)dv_WG(!-wcv3{8U5mCTFV5^ExAIEAV_ zBchMOJO;1fg^9wQQ9L0;o@I#E<1BNDjp=g}_Kdu<`@W{Tq|8QaVl56ty^l_WZ7q)s+ZI6M+)E%vt< zp8jzV^V>=e`Qv`s0hDz;RJ~Vo;3L~LDBDOFsch?2=7?eVov5SIcltbA4{5F)JZo<& zK3oP#|7j=?pqo%DaHI~+4^uX)N{w5Zv`ep8gBnp5*R8-@=gSG)-t@dE2am+Z2f`*l zn)81i{kIN>q08PpW)18r{A_BS&6^_Wjay_$Vo1G+;Jbg60LvuxvUBv^e+}z9aM{4?G@JSFM9eXTXKtt7 z)WJ$-SMlLMe0A9Iv;Uok$RamlukO!6B9#26=O@$vWN&iCKh9a%{$C{Fcw`N~%Fl@T z3YKdw=1NR1Bj}L3eBsft+mXUaIrOx+c&Lbv&->4tR^u@A8LX6u&#)@CFdj^MCH7$} zJ8IR~Byd1iF78t6=p77OoB3v2fe^y5p#A9UbJ&T{ohg2sa=b0Zmnh?nIt9@ygd3q~ z&*zs3Qgfwj)BL-jAIZh#H)L7KKU&6fNfA%x=g(9n{k5Pb-^J@Y(YE2q22Y+WgC3+eSdxDzjMxWUFW&ZInVvv&vR#A=&-Ja*uWJ_6C=myZ!3i{IecH6 z?^8pWVMcu3$u!Q>Y|5d+=-KyXsW+xV({G$v{c$Z!J$caS#mtGus^>!Lc#{{*vpf^! zpF*jl$BodM2oGsO!0GU#onhD5>$mVN`;L)H?b|U+xxbfI9lknIcfVeKzZJ)?q@=_u zQQIHZf-trK61hPhKq3)g$SMKj{=d1x%gQhC6HC`4_+PwasqQ;?4TLR(rZX$c7riot zmR8?bV7|WnJI4>8wHx7Fz<%>ZTq4Xv2+|0JGo0>zB2LCh$l6W_Sbc z-d@hzb0fwPDuMN38rgWJ3`wQ1@ZeJ01_a4he~UZ2N(Ce=ofbK zNH@T`nT{D4!8aa!erq-yw*5M|ulImw2iOuQ_#Gg*U3_YiV&jf7+}uG|>(5JnmRtXU zo#RS*+6Mv!!L4Z*XxPy+Q$xiKWoRf^L%dAG4ysOIqo37 zqU2$-`ClvfDZ7@b7PCFpV^|0ns#=zd`QeiK^3yHHzZD#FIY{}e?CKI(LGG(IUC)}8 zfBE3NXM#f8gz}K8&Tz30W;YW=V7FnqulJs^HH3W^SOwpUiFKY5i~KJAP1fC7)SsKM z3Z>Z8B&?j5g3T2FQ_Xa3PsE3-TQv);YCgdG|r+iIy+w^N)B%^hv+M?xCk;vJH$ zA}r6^X0X6wy;ci429EURhbso2DW!EWuf;#KW=i2>hpy)s#2gjGSrIe|UIbLj+uRZz zjgW1AHjs%lpbUM(mFA=nY5#Qv6AhL~Y`xQyd^3KKL8SI)37{3Oxj+G#AMDD03%|dg zzYB@`FT!83iDdd6sW|PXl-}{)1^5QF{G?hJNpf|_QI;(P`>h>O_9^mr+?kY9;yXTi ztmD?v+m$?894YY;tYJvoOyIw6X8N5J<1|_Dsz+Id#p%NBw4sUg_&jgZNl}1~%$JP6 z+-PtJA7yf>ZN4@9UN&IBJj>w9kG{HK3+P@N^YBQ_wBEh;7X}Rtc>Q^U_1q7@jHSU4 z|LMj}6@*RkyN$VSuAy#tWqnY#C-Ksi#)%qLmr(Y~PwZR#tlzQ`7};09^R6{(mZ7!4 zY=gdmo?j;U98I8kqBPzy^dr zIvA~dUmxl=7f+ycojz>g zzEfx>n+qIv>=@~LfbHjaAL?*ly3Wa=-VgCtdj!G*T}roby@4kyk=z_@HLhzN1MPs! zYM&&vg=A=eCHB$P3VZ9wrlaTJ+{)_p+p_t|4^NEP#q~*V6>!wgAIn*}3Yzy1*bwv| z0g1iN^&`BRNcMr9h9x2-l6tSn*+_d+E24{3WCa*w+|SPo%j;>+a(0h#IPuwvhG0|$ z*uRSMAJixe{^SALMbdWvF4(UXZ>B@O9IK9nmZB=24tLGrf~L_^KPI7HtSExG%}xF@ zjcW${DRbNQsJU^^sy1gZ!Zu~2@^pnaoFs^MOzag|45)I3+nr@WrX8Hppt=u~ADKb! z{`uPT03S;B ze)#ipB+UdHu$@LWP)7;>rINc3DL3jLa*KGYOa!b{?qz&a20I3D*EdR8(3{62P@yj`?)-N z@|@i5`+LazV2D4W_ZH`5e&Rg(LfEZ!u503&Mck{Qvs{AZ?@LHy#40JRVd((%8^1F1 z#B?hvI&8duC&U+eWG<`xD8H3)g$#@5?+D$~$^Rl`h$xtGjN`YRD@06{wq#rh0&G}! zg{rjjbxq;i`pcf|XKrt@)11F%eF?jPuw4uq){p@tz)$>II^DwBh!hUF&;3eJ1x}+x zwYAjm2?l&3je;~F{zT32n!;tyr2oS7NTz4821G@_7vC)aI`6;R%Q28lrBuZNn;hJ- z;p+ty#0F*6TWind*IC@$w7Mt+Mr`Y1hodxF?;wgI1nx)I<+;{@^-Cu6LVs4{a5q?n zH_w1SLij_(=f@st!^)+n)DN=czv4*E6pA4(Ri%cW4CUrD{#?GyN07y4h2vI?!U~HM z#rLUF-J9DAHFrZ5?EWNH3QN2SO^Us>eu*eh)EVAvRs9x`Ucu>|=ewOLn!LNYPv%k@ zzSk(fxvzrn2y5~9RM+B#&gk_mMvjWJzX$Em#uW4N%@h%_aE+h&Y<^vFDfD>F08A+N z=vbuOc=rn_*8(J7QWcXJ*4|-k&Hi|BVp!w$X}~JdedzNx68b=l6NI~zxdHc>+KlC+ z*h1vjQ&-#&(H|%uGPwuD?(`JPH{@>y;Hhc#wxv%LVOrwC^!1NVvhk4>i*-BoD$kF4$)At#3>M`T3Xjt~ zFo%x}zVA_s{y}-LMuzYYqR{c_|2{oj?K)@oxd~;c{*q;{uh%ux9~bd7idF7lQvSi9 z*QmvQqPEMdhX%$5&P_5O$Kqo_O1=D}KZSpGO2jpkaH+2iP;~w3H?esLJj>7;Mbm*m zsr9>vsYCgh(Zc+e@78h;R-gkaN{oS9K>iH%_X4#9o1LGOdF5N#8w zh7NbRj-Am_@i>WaIX-E3DLl>|S;XTa|1*D#sOi(#$r}v!OSD@(X?oM46?sUNt$>dv zf{j#DL#97v7ZT-3;2QCUzX6xK;xa!a(SSQzbKx&D!}TcXi$LXu@bhML%18Z+8Ygwf z?pSxJ-@=BYdX#SEn}45T%Hq>3!rg?GcLkH4>9G2BJF^x9PXDZV7ewad>#8Ha{XWns z%|;03YKyPEh*op+vS+b@NNkO@LFe4812Yh`XnN_)9;*u|A!CyB>R0nSeX?@q9`L3o z%vIJ582%9a<=M7ffdN{7;%C&oitH+O{hTM#u=Tdj*L^6ZNrbcbTNjp$LukPl?Ge!S z^JiRyF7JHNtIIUkE$f`q{eauk=UU$=uFcEc^Yw*hy3NI8Uq>DU{*_LQdwr2byAd-! zbakTWpneh5#=Y7*-g3co<87U`dw@-7&0!g$J8sU{rE`vlu)55>1`qatGT;W&8k37>zjW6;pFiQ!cj5UZ zvtmSDNMB#5a60bedi@o`u?YbOX^U3Q|$Dh?*?io+_hknFd`B1}0m?b*sk+z+V z@!=-FjAcRD3~YQdsZLh1d$xhKeF;Uv7^RtY%y6+g|jrPTpLERoF>aA+rR{{j_p|rn+Ib)W^LzX{#1Vs&q zzCN_5VT4&M_D#;&&$K1)YjAFF*T}%Q;*{X)HKy|KwOEb@)$SUQJJcu<*1Od9_ejy)ycb`Zyb+oVEn{W zqcz=IrfU^@{IOT%@*+|GUFL4T=N*8n<9cY*QN#-D)e9@Mw#q&qz|oNGc^Mhb!}H1h zw*$b4xe6%0<=BRFKYY}*5mY(#3MrB|LltCk!Ctq%;AE__qh#2&(Xf ztLx_-h~`wWGl?gbut5ns9KF(=bK0GjFmb{6p&FMpVCCf3&+Z^m9}|IBiGL!FgNzz9e+5=hHi&_7 zQ@r(6U9yefn8Zgw(lPsDD{hrD?3m{>H)+al%qT*iY>L0Qi+wr!|L*gdy$C8yI{uM| zu&8w$=cXa&*_}>kBxYww%UX&uO|mqxS*6OGh(r$rvJ=rVnOiz?vJAdZ1d~C_g)x1( zpj2FNNwus32cisl*^XV|Y_V8W>y--?VG=6dw{P%$nRqGF4Y;Gwl;ZzZeOZ6BMsP1(HvDq7O0uT*e|`2OotdSoIjKYKy%co_Ld1oDws4QFl6Hz zjMTP2OhY&%_kwfgIp7CN+WIIxXmct6WH+c7d;+E9xI@V6&B+$XqLzmEQ>s$cv0v}C zW&E_MB#y<{|Xsa*B(9W6#R8&Hmdj>?|R(5)k~*CBn3RS zkAZk(ZgtXmVDppx{MH*xenlDh)1;{J0?tGRaMKeVTX4k7gn(vi(;GSAPVTe`H6L^X z@Q#x%QypxE?tRA_JvJNMcZ)>x#fw#+3?W^(k|+r`gEi(|?r=3vK4n)9bg)AGo}p4+odX;JsE@^BF(|(H+C#Ch*e%xNWT$mu>(O6!GOj zK00a0_lR+XnESxO9*t`1QsM}l@YngHku~EBPXn%Q?dT{bsixW+=Wt?S`b=gw*K?K0 z-&LKnt>B}%p@dk1!xRoW$MERJ#R8q6l!dZkReWlY-~EY}7vtlecveur>!SCg2P9Ib zIE|5aZot){Tf<2~$}^Mgy}I9TYuCL)6%dqk1SEMKC&tacA&VGDZV=GDi^9ilBZ@6x z>)Ll4Q6ZHVjFW~PF65BSCOB|*ZZ4oX1A-KKw?)@hPfpuQ81oU9zU`F}%k)I4+lyNg zWcDI|BZCD8u+`#tu7_6MdH&%HIjt`!`A~B-^0KzfKZ*(Y0{PHG> z2u$jK-f#O_t&>bxAzfMrcMB{bBKB@lJ8+wYu9z4$^63x1&80u`|@4 z7D?r}=`S_8gF^}NPev&StgF9;ud|Vk zjcG0e+i;yevWaodGe386_q)B?T`LyY+SkE*FIYPzk4JRSy~3IaFYm|LJ_K$jShL@I zOo+f%x2{-q7Z~9l zE@|#abWVV8!@JDzfG%kph4~8~MTiK6?aB>|n;dKA$cG2aDbdKUP{5>NpOZv`Y7l%l zvn^RDR5FlvBmRL8K{f@hDy}8G#lf0VrFwK-Vg@=iq!vsZ!44lg!LH5iJ{oKX5vFLK zxdmNpsn5wV;z8$G9D|!6FBxSgI>u-565acmO>=RaR&TR~M;p*PI5@ygJgK0J_LrFD znDDSPyPK3D2HnNUx4Ig;_2hMHucxmsvVMYTGW8D1nkKFgl=k}n#_kGAEHqg>2d01m zqNy3`iA%L~xpCr0MQAwYAGn5vE$*NWtP#DPDw^mmWz2qU);FZYI4gd^^FEiuDVZXxjKU&|$l2B;3-SbxXI}+N5_+ zRKxsaqRN$P;-#xRSh0JEq9^at=lEIk6^DdF1%8rkxhX|*>p^&TkXL{!oQx>i8e-Ov z%QNaYkLBCaGX8IvCzqyOB)jm}HQ+?Zg-p4}q_^who*ReyDeF00B_DE}H;5(2<-(K@0Z6Rdzc0b$Ar$F@Qsj6x`M-K0GLr)r~B*0H~1-@m_R9d{Y{puO5k>K52JR;+&R#OREI7v4yqL# zvEekHpZ&&3Pg<$wC4JM$R@rz&(fk9qOR@g*5L;7VhG!bG#h=fOx8j)B#MJf#K@P+? zhXSQ|X;|L~D^_yE!7vJY^XP}zzyY8I?35g9_m?GoG4j6O=5Nq=lw8-rH4~N*%10Qh z{(H#afAc6vLTn(ONsHC0mRpAE@w3-dL#vw-puBeWd#sd=+zE476JJi|f^INV+J;?x zp~J#u^ubdKWLe3Z`%}oTs-xv^MV+2BV6_m44PE#J9r9QE^NPPq(_W#=-Jy=bbt`T? zK7LQf<)e>Uh_i^T204M?FpY!ip~G_<*#qG6Iec7zLMSeDLI6`%^vdpMz}6^q=s!#n zmIm&gViG#RO?-;88-1ZC>UBcHpjAf0XEC2co;s9}M0(~mtEgd;jC? zLZzRK#`E~h-m?F0Og_-3lDkqIRn*Q&1upy(F8DK?vSlgP!5c!3HD>9Oeh7>IxuFHB zc%4L*#VW4FVBZw?G21rJAL&lCO=Yl3?U!5zAhQ+liQiG+j;II7tR>Pk-qi$!CO&I5 z>`sxJj-%dR^vzY10Pr?^WnNM{%~MI#$phP#O-{w))KimF?R{d~XkL}}Gi=b?962Y| zoSCmXwrd9fDfguiHKG01%6W$B0J5@nSQP13AMs3_)ta2GIsE-}{=VRP;it@)%#Xi&sE1l)t7qR9qKRi4N1yl3P?68=T|Lp3D{7;83V@{Co;(>9$DgX*${ z*|>+Mfq#(nHT%88#(`H1+&>}UIjpg^u&Nf$zKp&xdCX+>%P+|QaIfsLuS|xq z6I*=Oc8>cIFC;+R7VFflmrV?rnw_Gy)?mph9toKYaYS-n2iq~jRG&VuPgrhkPw(;B z`uI~#s#w`@H#hBd*Kjs&Lk%mkb+u*AxWoZ~1l&bf-{mf}U7f^CTTI`S_^bfnD>}?P z6B0V0lsMOC2YPtD>3C2AW+CU^s()nnZQpylV+MG4$LHE_iPPLXgb1}Uz29iO#Y2f!un3eg>6AeR6G7D|#1g}EF)UPjj7!CR`(Ruj@ zQ3L4^SFS}C*K>C~+fbj5S4N;V!&>%Z<>nQlr8OQ#Co4Z>^bmDK?pm{O-t@#IUIC7K zX=rfECxTZ1V-q^z7Q6|UZ4AfMcF8c8we9^kQ!;RixQoZEN;FjLnzA`8A~SqB z@9h#$QKzCvbg|6KnKafH5phZA{3<_&fgt8C+2# diff --git a/selfdrive/ui/paint.cc b/selfdrive/ui/paint.cc index 95d4faaa56d3b3..77280f86d410c4 100644 --- a/selfdrive/ui/paint.cc +++ b/selfdrive/ui/paint.cc @@ -133,7 +133,7 @@ static void draw_lead_lock_on(UIState *s, const cereal::RadarState::LeadData::Re float sz = std::clamp((25 * 30) / (d_rel / 3 + 30), 15.0f, 30.0f) * s->zoom; x = std::clamp(x, 0.f, s->viz_rect.right() - sz / 2); - y = std::fmin(s->viz_rect.bottom() - sz * .4, y); + y = std::fmin(s->viz_rect.bottom() - sz * .8, y); float bg_alpha = 1.0f; float img_alpha = 1.0f; @@ -149,7 +149,7 @@ static void draw_lead_lock_on(UIState *s, const cereal::RadarState::LeadData::Re nvgSave(s->vg); nvgTranslate(s->vg, x, y); - nvgRotate(s->vg, lock_on_rotation[s->lock_on_anim_index % 9]); + //nvgRotate(s->vg, lock_on_rotation[s->lock_on_anim_index % 9]); float scale = lock_on_scale[s->lock_on_anim_index % 8]; nvgScale(s->vg, scale, scale); ui_draw_image(s, {-(img_size / 2), -(img_size / 2), img_size, img_size}, image, img_alpha); From 14b8b10b36da2aac4a3aef1409de8b2532f92550 Mon Sep 17 00:00:00 2001 From: neokii Date: Wed, 26 May 2021 10:20:32 +0900 Subject: [PATCH 07/27] change image --- selfdrive/ui/paint.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/ui/paint.cc b/selfdrive/ui/paint.cc index 77280f86d410c4..c0304268f8c0a9 100644 --- a/selfdrive/ui/paint.cc +++ b/selfdrive/ui/paint.cc @@ -133,7 +133,7 @@ static void draw_lead_lock_on(UIState *s, const cereal::RadarState::LeadData::Re float sz = std::clamp((25 * 30) / (d_rel / 3 + 30), 15.0f, 30.0f) * s->zoom; x = std::clamp(x, 0.f, s->viz_rect.right() - sz / 2); - y = std::fmin(s->viz_rect.bottom() - sz * .8, y); + y = std::fmin(s->viz_rect.bottom() - sz, y); float bg_alpha = 1.0f; float img_alpha = 1.0f; From 3d4d96d849f5f15434f83b36afbe8c40642b493d Mon Sep 17 00:00:00 2001 From: neokii Date: Wed, 26 May 2021 11:50:52 +0900 Subject: [PATCH 08/27] fix --- selfdrive/ui/paint.cc | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/ui/paint.cc b/selfdrive/ui/paint.cc index c0304268f8c0a9..c0b254a334f426 100644 --- a/selfdrive/ui/paint.cc +++ b/selfdrive/ui/paint.cc @@ -129,11 +129,11 @@ static float lock_on_scale[] = {1.f, 1.1f, 1.2f, 1.1f, 1.f, 0.9f, 0.8f, 0.9f}; static void draw_lead_lock_on(UIState *s, const cereal::RadarState::LeadData::Reader &lead_data, const vertex_data &vd) { auto [x, y] = vd; - float d_rel = lead_data.getDRel(); + float d_rel = lead_data.getDRel() + 15.f; float sz = std::clamp((25 * 30) / (d_rel / 3 + 30), 15.0f, 30.0f) * s->zoom; x = std::clamp(x, 0.f, s->viz_rect.right() - sz / 2); - y = std::fmin(s->viz_rect.bottom() - sz, y); + y = std::fmin(s->viz_rect.bottom() - sz * .6, y); float bg_alpha = 1.0f; float img_alpha = 1.0f; From 3fb7b38618cea44f5c35a451f86ad8e96a3ba9cf Mon Sep 17 00:00:00 2001 From: neokii Date: Wed, 26 May 2021 12:34:19 +0900 Subject: [PATCH 09/27] merge changes from master-ci --- Jenkinsfile | 10 ++--- README.md | 2 +- RELEASES.md | 1 + cereal/log.capnp | 1 + installer/updater/update.json | 10 ++--- launch_env.sh | 2 +- selfdrive/assets/images/lock_on_radar.png | Bin 9751 -> 31545 bytes selfdrive/assets/images/lock_on_vision.png | Bin 9751 -> 31449 bytes selfdrive/athena/athenad.py | 1 + selfdrive/car/chrysler/values.py | 2 +- selfdrive/car/fingerprints.py | 4 -- selfdrive/car/honda/values.py | 20 --------- selfdrive/car/subaru/subarucan.py | 4 +- selfdrive/car/toyota/values.py | 42 ------------------ selfdrive/car/volkswagen/interface.py | 2 +- selfdrive/car/volkswagen/values.py | 49 +++++---------------- selfdrive/common/util.h | 3 ++ selfdrive/controls/controlsd.py | 8 ++-- selfdrive/debug/test_fw_query_on_routes.py | 11 ++--- selfdrive/loggerd/logger.cc | 8 ++-- selfdrive/loggerd/logger.h | 2 +- selfdrive/loggerd/loggerd.cc | 2 +- selfdrive/manager/manager.py | 2 +- selfdrive/test/setup_device_ci.sh | 7 ++- selfdrive/test/test_fingerprints.py | 4 -- 25 files changed, 56 insertions(+), 141 deletions(-) diff --git a/Jenkinsfile b/Jenkinsfile index ddf69e7995e8f5..dddccf4d360792 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -138,7 +138,7 @@ pipeline { stage('Replay Tests') { steps { phone_steps("eon2", [ - ["build QCOM_REPLAY", "SCONS_CACHE=1 QCOM_REPLAY=1 scons -j4"], + ["build QCOM_REPLAY", "cd selfdrive/manager && QCOM_REPLAY=1 ./build.py"], ["camerad/modeld replay", "cd selfdrive/test/process_replay && ./camera_replay.py"], ]) } @@ -147,7 +147,7 @@ pipeline { stage('HW + Unit Tests') { steps { phone_steps("eon", [ - ["build", "SCONS_CACHE=1 scons -j4"], + ["build", "cd selfdrive/manager && ./build.py"], ["test athena", "nosetests -s selfdrive/athena/tests/test_athenad_old.py"], ["test sounds", "nosetests -s selfdrive/test/test_sounds.py"], ["test boardd loopback", "nosetests -s selfdrive/boardd/tests/test_boardd_loopback.py"], @@ -186,7 +186,7 @@ pipeline { } steps { phone_steps("tici", [ - ["build", "SCONS_CACHE=1 scons -j8"], + ["build", "cd selfdrive/manager && ./build.py"], ["test loggerd", "python selfdrive/loggerd/tests/test_loggerd.py"], ["test encoder", "LD_LIBRARY_PATH=/usr/local/lib python selfdrive/loggerd/tests/test_encoder.py"], ["onroad tests", "cd selfdrive/test/ && ./test_onroad.py"], @@ -198,7 +198,7 @@ pipeline { stage('camerad') { steps { phone_steps("eon-party", [ - ["build", "SCONS_CACHE=1 scons -j8"], + ["build", "cd selfdrive/manager && ./build.py"], ["test camerad", "python selfdrive/camerad/test/test_camerad.py"], ["test exposure", "python selfdrive/camerad/test/test_exposure.py"], ]) @@ -208,7 +208,7 @@ pipeline { stage('Tici camerad') { steps { phone_steps("tici-party", [ - ["build", "SCONS_CACHE=1 scons -j8"], + ["build", "cd selfdrive/manager && ./build.py"], ["test camerad", "python selfdrive/camerad/test/test_camerad.py"], ["test exposure", "python selfdrive/camerad/test/test_exposure.py"], ]) diff --git a/README.md b/README.md index e92f07f3b6fe84..987151d63c0545 100644 --- a/README.md +++ b/README.md @@ -145,7 +145,7 @@ Community Maintained Cars and Features | Make | Model (US Market Reference) | Supported Package | ACC | No ACC accel below | No ALC below | | ----------| ------------------------------| ------------------| -----------------| -------------------| -------------| -| Audi | A3 2014-17 | Prestige | Stock | 0mph | 0mph | +| Audi | A3 2014-18 | Prestige | Stock | 0mph | 0mph | | Audi | A3 Sportback e-tron 2017-18 | Prestige | Stock | 0mph | 0mph | | Buick | Regal 20181 | Adaptive Cruise | openpilot | 0mph | 7mph | | Cadillac | ATS 20181 | Adaptive Cruise | openpilot | 0mph | 7mph | diff --git a/RELEASES.md b/RELEASES.md index c8f09f44e59775..4edc374c946cb7 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,5 +1,6 @@ Version 0.8.5 (2021-XX-XX) ======================== + * NEOS update: improved reliability and stability * Smart model-based Forward Collision Warning * Hyundai Elantra 2021 support thanks to CruiseBrantley! * Lexus UX Hybrid 2019 support thanks to brianhaugen2! diff --git a/cereal/log.capnp b/cereal/log.capnp index a1e881ac1245b9..01f9250572d257 100644 --- a/cereal/log.capnp +++ b/cereal/log.capnp @@ -1295,6 +1295,7 @@ struct Sentinel { startOfRoute @3; } type @0 :SentinelType; + signal @1 :Int32; } struct ManagerState { diff --git a/installer/updater/update.json b/installer/updater/update.json index 93d7f344a676f2..4653205442981e 100644 --- a/installer/updater/update.json +++ b/installer/updater/update.json @@ -1,7 +1,7 @@ { - "ota_url": "https://commadist.azureedge.net/neosupdate/ota-signed-969e22c42e5c6314e54bc3ccaa5c6a684f3130a53a7a70e0cea9f1453ceb0b06.zip", - "ota_hash": "969e22c42e5c6314e54bc3ccaa5c6a684f3130a53a7a70e0cea9f1453ceb0b06", - "recovery_url": "https://commadist.azureedge.net/neosupdate/recovery-9c784a24826c25df315d0ace864224478e9c0e86b904f5d1f8e18ea1037e842b.img", + "ota_url": "https://commadist.azureedge.net/neosupdate/ota-signed-c4f56c62c5603c86e2ae9d83008a8d42a91319979661d0c42fb97b85d9112266.zip", + "ota_hash": "c4f56c62c5603c86e2ae9d83008a8d42a91319979661d0c42fb97b85d9112266", + "recovery_url": "https://commadist.azureedge.net/neosupdate/recovery-c5db3790c3b09756e8e896187ddb3f1258315eb0a86030468baa187b84a3bbf5.img", "recovery_len": 15209772, - "recovery_hash": "9c784a24826c25df315d0ace864224478e9c0e86b904f5d1f8e18ea1037e842b" -} \ No newline at end of file + "recovery_hash": "c5db3790c3b09756e8e896187ddb3f1258315eb0a86030468baa187b84a3bbf5" +} diff --git a/launch_env.sh b/launch_env.sh index e7f700d1a73f00..e1ebfbb9631fca 100755 --- a/launch_env.sh +++ b/launch_env.sh @@ -7,7 +7,7 @@ export OPENBLAS_NUM_THREADS=1 export VECLIB_MAXIMUM_THREADS=1 if [ -z "$REQUIRED_NEOS_VERSION" ]; then - export REQUIRED_NEOS_VERSION="16.2" + export REQUIRED_NEOS_VERSION="17" fi if [ -z "$AGNOS_VERSION" ]; then diff --git a/selfdrive/assets/images/lock_on_radar.png b/selfdrive/assets/images/lock_on_radar.png index 7502ef3809dc5812d330392f8d3730b61a782ca1..47682382969d70c85359c0a17b67bffe1f8bc3a0 100644 GIT binary patch delta 29064 zcmW(+Wn2_p7azL28>BCPWmV?2O2 z2M#gEP2VBO{F4FK8bwFHU<>&|;(rUVJa-%jp{_r5CC{y;(dXEWfcX^q5VP)3~${;a~(CiiXA|;B;-W=AB0d{!>l+@ zwf@~7C?on{09IFl!8>Re)M7uijoixZ&-=v%#vGi<`G7bRkY7`Uf4k-k%ZiAP0B}S5 zWpst!jTFBU;ISUcb2eq$NN^1d`wHG^t+l?4hou)|Z zHGapzWFbV8q)-q9%%H@{0bD?w3fLwe`8D0?GXuT!Cpas~ z!$1iSRZ$NbFN!qBi7)#!u4xsc)KN_*DNUOA_JJe?eEewYFo@vS0gStC*A$_NzNS9a zMubG?JxTLj&QC?rn#K&=zxH`)r2WSu2#-&3)z>trBkGyYs?}V~j08xLHCthu!-!J= z45^NPw5Ufr_I4E2raU9}mGHkDrpysuAw(0O&)OFG=XER&DHhPVez_j#p~M%5%d6b} zWV2xcIx-WG`71wryVM1~|CGux3Dlj1W_?+g1wi}P$ZM+-~a^Ry2wT1Z){#9g&Vx8C)!ejmSd1;4k z_PSuk7-v&?&s)C>*(1Tn9&SMq)D&*641X|qw{M>+nI!L&>)-jkYZ@mdh$1Y=H`~@7 zDIvl-i7fvO^$sdB+^?XIMcuyj-@#!Rb7Mvk*5|*VsR`rzfRI$T|2lc0B8eRrL;-B5TanR28*K{=4E>HXt zK`~0-{__AwoaTmXP#{}%cqo&6-b}OMsBq61c5mNj2alSiO7CdI2v}1XKHPo_P&DjB zCi(X{lkD?Qb(kEY8sgLQNf_dF*7t73rbu|cK}h1&%YNWWSG&b)J@tS4O}cozkORP@ zRo%zQoCT~03p4WxW0|*+PkoPXL={;T7h&kA5RbFL>$WHL`s(mC5D|&l3~bx4U+q ziOKCtJ3ef{rf^uPz7cz@y77Yfu1JwVvHCqUxia-bCa-y{KsC3-6;MlusH`|Gc?W(# zE@_#Ra*|?9KOBI8-w2Q&QesVK5cl7r{c({8hIi{}aWUy@CP3%B$0%M9mk8L>J_trj zb>6P+rMlq9n}E-m!u09Y46m09>YA>tf?U;Q*cdX55Mf#QIcJe_YKvEpZOY$|7u(1L zD@=-i&{SpA%peq)fl*Oa4LU(kBCO5!Ayji zewYk3f&-(7nZAf9U9UP5ye5R_xAiW2!$%Ry$`!Wk-&L!EA_n|}`8*gD6_GLJ%nM;t zaZ0w&SYTOWIcQh141^ij%_bFy4?(VNX$e}T0 zoEPy!e@>R_I30|y>?NhNQh3+zs9;MjZ8V!mw{13!rA8Rof&_y+c=9Cw{pNX5kOt#) zuiOS@tPJb3li-6;9tW+#K9_Nj#d?sbOJ7g_SCmk)%8~sk9cr7p>aQc4rL+{nwMog? z%9omF=sS`1#=YwmN(P0(a z8o>|9=)J1;5(<=udFt?gCTmaSpI4mVtmQ+p} zMj*EsDv(xdU&t}G@@zn^rNq+U>$Qiz<3mjJs}G6JePh+5T;tn!t%FLLwBauQvz|Y! zkE@u{ZKXLje~SL?Ozx9rv3fTH29HN^xYQRD^A5ze@&JazON8jjDE>pUmvP40YadzV z$wSmaSG>?|@Q#RTpTEyTQqZ*;FgY8?8}RA6%Yp`o{QcIDzl{DGHO797PR%{yvxzuO zjB{}64O!&4gcNKabZBma3wqUTRj5N%thI6+RU7HO!peY z(gh4qv@ihYLPGa5_U`efMCt_B*d&GPHREFkHT?lMxLEvX`FY{&Ls3c0!@F%e_DBZ( zb3zKcLo=8X-1oO8cWU!^^vF;%JllNtr?+kryc+K3eD5+X z!I3sM)Z5euVfZ9spxDF+OK@6D>V?zJb}e$e9+7{|4^% z){shI4nuaa^tHHi`9EUeZy~II*vQBd>(;-YWnh5l>KFULEm%Tnusl8YAQaIfyV4qDoC5RRStjsNx{z z#7e}=qo@Me7(o8_e_e8|aK?#7>Q+~owkAUjTdQ*rM`%)RXr^33sjCmHV~X$Ni-ib? zX#5))ia5La|J|RYH3}<;y33eWvC87`1TqdgBU%WXqGRt4F{}vrL&@CqL4cHAg>k+V z&A;Ux^gib>6=1YFf{)SZYkOF& zxT6&}B-|t{9%wjq;`Zp&%VdNZTcu+MY3N>nfXLVPh~wq)fg&aBdlVC4`Bmxkq2>sV|0MqlR5E zOM-l3h5h355Xje>Eug2aGK~`Qnd*-(LB|N4EtHyulkwhb)~Y*ytJVGe^6wne`jSsR z(h~ck@Ov1<1?~G27#bL27i=L9Y-?5Tmpc4QlQa?WqfHW8$OC*F&M!+XVv&DC#)TG_So;}QN56L6WIo<|uyUwVqm!iY#0yqjpXk2S+OLHe`6PHXk|W>y z6acEoKqw_4R`rmRIL={*bcqsd#9m7DGEq9 zANUQjB&h3U6!aQ@>{jQgOknUoGpxkk?FoXfXIpSkoor~5%%c+srt8BrnjE^gNDweB z4gum|Qo}PdF`~<2u033>^+b_+SLM5C?IgjY(x>5nBVo{3`5;kB&B;N>c3J)E6j4vY4otr=X3OJVN4<(i+Kx;Aq<9yVeSr6r4XJ_)ioj1id zwEH#lkp$oS@DtaW?U=vVT=pl4B@{|cVyZf2_|8fEpWLWuy=#+X6YsdA$KL`v2r2v( zU>NxRA~W8W&)u53?LaieE)OR?Fs_>v?=2}ruFD4~cq;5O!d##)62?44cvLfXdS6j+Vvy+3i-$P=0XWj3AEQ za-`e9U(2X{!|?9qDKn&$GrSv0DZ^9Mj!ImpdZOc(cN`6>#1yBWZki0Y5CMt9R#uHl zC0W21-{-$Nag9N5?UjYYXktF8%^O83?J($K@E0)S?Dm@UX>po zm74opnG0)%a^bl_vrDDrwFjP*a%PJ0+r3vdg9fa$SmGx%s1I94`$C%bj@+qV_ zVdIJY7Q<@I(-mUfi-n;|p0$pnZ$iZ50+AIk_p3DXoPPG2C;qc!7uL-FfDr0Rj^6!5 zxvwfK-1yHPd61sW7$dzwPuuM5!ROO#=33H2lJ|MkQ}LBOXN<_Ju$0b|IbEh_3I}-3 za6y=DcS& z7;nL2c;vlz&7PM{Zm1q$UApzU?Z+_u*>W9dX)wjsJ_KRg&3`Jr5pmHds@iW0;H-^= zeFK{=ipJn$U!*p2)%+ADp=HvxjdNm_NOz4GX>1B;8qKW!!o7L&6+l3x0Wq2lq}GN+ zJy&nQqawEEG-4Y@%~Hy`L9B+a|CQ0RWGvvU`$=}ctAk0b3_+_hgx=;s#AJb&u7$pm zbxzOC5ec;xA&@LAP_6UcD_q7nZRI~dvSe$uG`!`z`qH1iXdWatIDp0Gd)-q9fi`LQ z9S>FZZ2xwW!%@zKM0=C|3rh7PNQo zjZHDieb~Gpp>Cdth-dojCS1OrhtzEmbyPvsx ziM-=?gHQuggk4P7p|_gOuxJftXY%g^dMfy+Q1bC<+Nbhi;s{=UROhP=8F6{}Uwfq# z={3^{@p{5OiTHDlTn#>%Ud%l#fjTeSLJ$-Y&BfY2^q->KS?rk8-xM8^DaXq`j8~8F z^9|U%Vl0iprHlsau%gmUmIN^p-KH#oJmoK?m6^ti4|lRPfMF zE(T~a_yym36!_wGyqJi0f5%pmDJI=LMCSU4q-Xnj%$_arK`L~zm2w`O4wr=ABVO=J zLtb~`*@0Z-XSrCC_g03_R$gLdsVc>{>A}aZhR;+dE3IRAhZtmpy^I7k(O&VmqJ*~C zejoDIO>>MT`cD90-)%YJF4bb~yt<&wu>UpzrR~jYH>NPcAPwf&T2HwvfOGXvrOas6 z@9$lR2Z#9P@K*fA*(zW@m+=N!qZ(8s44RKEq5K_(1}t+$O@b749eHNR9dD<}+-?A$ zy$Fv(ufQCM%Hxrgg@UJc(UR>giNGhfkw~%pm%Gv0pi-YDcx;MDOqmHa`YLaTy0Bl7 z(zZwgM8;^aq-=C??){M+;i|e1ZDuwMoSUH;19zbIVlgtm4T7=TP=1`yiA;zxLH{As z{n*qe+h6?DFN``q9O3#v);IsjksZjO?$Q9r4Gmca2UPz9$I<(2Its_-arrM989v zP{8mWEJU$AHF#jYEbj!l-}Ah`)(!1!PHi^&2d9+M}irx z@t@|6oOYb9CRf{TG#S=vz5xgXv^@P%blJaYJGv!hKY{0rFT%R=CQyn0#(U=7v4IkV zSz@GqCOkAI=gELC_r zDhoFlWxd`dc@)IXG;M#2hT(>!+h$kvyo19hAnLPk6IwPg3jjj%^*DelOqVEp8ZtD| zb!~ROy|oIvTRZ8#T{Ym>bL8mxVyGg`ZhS)SuKGwBGSanInRLMpALc2My{>3I>?qoM z`T_;aqX4b*mbGL6`l){Hz};m%7fC}!GI(}!eDn)~H*|!rl=SQd*>QktOC1ic;vII7 zB4(~nm>dg`E^N_i>fONRM_?uMj$wSE+SpCedG2wB)VnJ&OMO8rOx2outj_~ITT4n_ zqNF(+Kx&2znG4iX(dpj{3Ot)gGL5h0R4~j;O;2)KS|VPsUS20{k3=xb-Eu*+iWkf+ zbr@)($4u24V>L6ft8ZGE1IIZ(YP86mJH8Du-u9gd?;Ib0{ma5Iq0e!5R5$$l)xtZB zO|%JSZMtMH}*A zGjh|188TQH<2_<+@VMiu))WWXCD4U_Z)kM%$#S^0FO$WHq+Dr@uQoLJt?AUhhGGZ` zKlW&QuveSTsNfy9Pt2lEzhPf-&>gSB@rz-1@I_J1aNZ}?jG0q-0mra@C+b~BVrR{* z8ChbtI9>^Fu2LD{Xo5aQi{We!@H{>a_92ArLiWG$E&O9%;I zpYC(n3e!{MH2X-GACE9P=Ik>~AuMOAgkki@VE@5b^BE7yQY2!McVQt{%0f(Zmsf&E z{QktdL(3cydn^_Y@ykz~DDo^x!WVKy8jpLO-r!Wg9EBr?!?CGKS0M7J9zxJ8Ouck~ zCqE~p6ZjXdwfhSfjjd0g@54-I=6b5DJBKB#e^> zp9Rsv(Z7fvOB{17)EcXrkIchAB-~3&l>Ub)%00P_;3s}C>q1+l54OErf?$dsySwwW zrTOzQO7sohQ~ueTlM&SenR{@BvC1{7p@ann7;mK%)O_SccNdy0rDv5v6KYcc3&2Bn z83zi`o-MvTCu?)=hAC_Djd|Tx7WSQqo|uGMQ+OR-s8KrGwG7Z9V^&}5{>IhtB2>$B z(Z(HkFSRoNqBt~gmXyo)i5pGJoV76zD(lso%i&PR5g?*oiVF?WXyR7#?*R3PRH!4s zmnkQddL2#sKLl2n&01d50T6bd-V@K?4YyX1X<9w+xzRD5oixAx~ROrRL4Cr?Pga`?%p`2OsNmk}R%#X%_4GTNu%j^9Lzb6h4oH zRZd1$yD!P#+sB9(Ps9c}2Z?GiHhd&-7ONiLk>69kdHfEwg84Ts9IaGUqIY~q=`X0N zHSb?9e=R%Yq8n~PC=nfYSJ?73Pgd~fJ0BW-F&B9Q?GFp$9f}_HTP|F#U^c$Ne#Ey# zzY+O|CU8`mr{_NyGg_*ox0C9-7gdBZB%VgVy8J1L^d%tv^+61FH|W1m<76^$4HQsg ziB30?3*aZN?G7%VScpWog*B)3Qkh<8ZLPWeaTonr#hL{oeH~&WL6ph+q0Ut~rIEi1 zUtW{mA?|jXNwUAeJzdk)z0qzM)=4^tAtOTNO!;{wwwpv}%T(%JGkK z%SxNnp;4s-&aR7;+!z0e34mtqCpzaG!6;JwOI~|EZ1<}i7nOn!db6}7vZj?)h%l&!TX>y zw7lO1C;IN5h@%#)GWnxGwDjmnw$N5SkjOyxCTuax6bO_T!_mnrFb& zp-HN9h{`1s;%(LjGuV=b+l75s8z;aur~qskXW60!S=^k$`L#p(rJ(Ulc*w4*B<%4e z!{G#G*MBQ!mZQtqkt|h~Fq2o@%3V)&W720A^X7U_vYMghJgl~gD<;FmZW^tgkM()^ z>PDk+Q}_GJm#)dK6lkb@cnlB~s;6i)FGX6YeWF=To)*;~lm--p=uAHQEg%3-5Ws@m z2A%~+XBPe`7PYKcWk~lK8^YHpoq_J2^b@uq|J0K#n~R(@UxMGUNEEl@!0rtN;O-`( zPK`Am)D*w4An;b*`dorKf;5cll*Tz~Ii7IU#@$~eZ+2CSM{<-67aRNxon^2`Wi18-a|O}x5g~n(lA+E%Z<1hlzT zv_`l*2bM2eVvG}Xe;1fA;8&mejYv=FT0?DVQv21(;8~D7igD2i&z1sQ|9eS9{~Eq} z97emmLE(dp!JA4SIMU(rzRW6n_rC0nNDG8Ij-RUHwEJ|MaW_W$#vEikMpS_8 zq!}!k>s&QO2k6G9H}M+=j1n^ee!s2v*33wSzsYDeBl=c-em#FxAY<7{(_!J3h>{7y zCTICFT#!$ayNYhS4--=;u@8FhKn)y;>2vKi)l&2Jz^MgIoq7NH<<{evRhv`kmz*Yl zq72r|SW9|~hEvwK)3a*5cV_vR1rf)(R%VQu=ZIrlEI7Z$)tJZ9(phfs~Up_lD%uMWwz~UoCn-j%6x) z5(4mGYMD_ccATt{7lE#IvV?yRVe}mR8s7%6CNGkD-3%v5dp7*8BT+LgHSQldGs2`BtJ8k2LGeu#8%~jy>n9VC{omH_vG%W> zK67LvXKBuhJAa-*i9GJ{#hSF#kB79U>$%x_R!8#0zN7Dnd6k7;^HK5~H(xJTrz(Hh zc0Lhl7Mpbc;5zHlqLyMZwxS?KRWr@8e1Fj$4~fdL9aSatTd4n7!ZaC-AWVJzbhbuRhE|EoC^T5a8P{DsSLX69LMB&G_ry{ zzy#v?X31lH@5g-9K75xU_e#xqo2RZvWfl0cjy-oso4N7(NpI3$I{fjwh`JDG#CR=> z9Q)ZqYZ`<&WQmyX(@1xS6dZPGC1D#wkGE*SMN{U4Yc_kXE@hH+zK?RBPn9VPBuaW2 zLG4}?fP^CI*}HmOwizndb5*6JwG`mh-p?K+Et_NW{M2FlPw%?Gaw+0L)P%xxpjr8* zwzw>BjKRua`#=>sibZbq%&4uOXoNI>1EQ!tK@?S5UxL+|uf`5onoZJ`dQqhMzW~bC zvoARHJw+oiy7f(I$CuAZXZ_9H@=_Z!(gH3Ywm@)0=wU{^i}cpSNv928_L*ik(Sqg#l5WkYx&p1{e zZ_jdLgo;N^*?{b#^PaLU&WH>l`A@LD@TN2G^oMdkS;aJ4V-1Ayv)Jx#TDutq;h*UC zF(7Z0%^<8_dfRIc4|P#i<@f7Qp~JEQqt&OzNRdxWRCQ^@yR}VP)x~8f!_-2spUt(Q zx^f<+5b}4jUgtu>Tt@l=pgN)f>HY9r{`Aaw|Jx~7N=oj1Myl0sTXBp0P+?|nW zpCG+J)4!d#V#UWVr`c5%DblMhH{c1K#se!nf)0b}=Cz>2U;bGd3uQyp+HC*GzyJ#a zR=9OgbXyIcg?>oE7Bp)*by9=Y$6#Yb!Kv6x+9;umfH0r;5QsNfmDRo-V%)+j))tw? zkuL+eY>7wj-9~{^Mk!SGUp1rmY>@u1{0N3l#L_7W?{HE>q1?2d%egS={|1w#xvgXP z!hikWPna%m3p2X<%Vy{zKyqk?=(4^z53f4)G&8dh?5Fm3wU0Mt22gE09GY91pqW)l zcKX?EtUQ6;l`r8C*8VeD=3Cs=Mn=o zM7E`Nr=C9V)X{7mAWki+gX`qL^j!8m4-peJ+8S4)>qBX7 zH)gS`Y3gy3x`G<8;NDeyIPHX4sC)hpTGaS>Cg-R!(abD@ZkSx`%Ue6#N9P-Gqyf)cwxH0*I zo{A^UY}7v-VNjvNvsrBGZ7TOa)sgFl5~Os`9H-(FT=s&c+0VD-Mu#Mv=GxL2BNJSs z>@1#7AW{MPS*THxI;^LAR_d5@@DEC3l$ zRdGkd&uZzlFx_p4)C)i8F57)RNQaAWvF(k;ct4Xl5OMX&g4@F`e*HL8>h;?L13CWO1$q`iaQP{#mn(vrOM%EX*0e@uWy z_MxBaB68tnl*FV!i2TJ2OY-p(B{vNjLE+DaPz>nbA5=06aaj+f=qQS~iY#T!usu?V zcOc&Q0TqQA3__w|61(g)asZGMATA**Ku5osAlWggB<~esC6E;V)Bq#_roB>$op{+^7riutZ1qBwMGVE>cAhezI=_D> zBnp#T+Cp*>DbX*M%cms~gbT2K+qEKXZk=Vlok=*0n-4AC?mf{`%KjL_Ws4@ymBFZ5 zogUz;ME{n-L<9pMLL}yW_jqWibFUTmF)L++;D`(;GB%PY8_OjBVj?~SBJiU#p46q` zeM52`cNaWRsTA2UP3EzRMyGb{4n71>nb!HhlNUlfPAa919Pyb#v6PKms=s~WnUy8L z51YDtBpCE8{2IBsi#;|6*sxfeZyHVvKeJ-fAMhNKq&fXHlccKu&LRWWf`NlS z41_-pQwYm{W;ctXYjywe2Q(SMN280(o*|LIghhmXUcYKGb2ANGRyCm0I$k7YSnKFE z@-de6b7`}uQLPFzMr=S2NSQz+Aq$epcL*wVe&UD1URK;xqQ)pPBnG+~?(TL9|B8Hm zeh8Ftxo3f#Yluo(1@k|PR)wn$T`p3DC^iP6$qGq-7?#xqprpLniVc_3e}4sl zG#a?eH+{}A5)err0N|s=v>VSyWL?HvQ2qGKy@t4~4h>%_^<}KTwPywQPbJ4?QqOgMFX=qkES) zJ3ZoyhGu*A!~SxENr&s79gs`bgcy&4S1l1^|y>3H)=y}#Jt0*hLHbmXkh7uw&4)7LsEL!7wxK3 zVULEyw{JCn^_`3@DI3jnLk~>k>;L_B$x73?6Y)-7xU&d)Qf7I?E>5c?cFUv_axbKa zsROe54}Q2+8gA3`iahG2Bh#tnmg1{*>jZ;%+x%j!0PqOi1ptJwKu?|L)_O|Po5<0u z8(1r&F^7EuaoMF$K79B7;rY+QjF44i0Q|lH?D6fDuYl_CdJ;;G+!rca*i9c+N0P|I z50v^=YI*P1?}`SknW z0whUlY$Tz*lt^SX3WZW=-N#xO;W~%?`G6y%PszM{h5amyDa|66DHti73U6~d1O;Pl zn-tn=)2M(S)$vUNAdbbgQEQ&)%;G)pp3 z&3!tv*iPbmQ=2J8X6OSSGhMi|JtglVv2mz2MU%Nt4*2;|B4!5U`~*{^f3fteqIEuI zyG)&|nqXhpicfe%QtLcc!{`O$S|!5;1l9`9>hgFd!uo*Uye&8Y0O zinci(L0by%$32}(lKryCqKVaZCcEMlqT5@RwL6?Nq&*nnog!3)O>$v#Ts}Ydka!|< zidf?_uDG)SO)RtjserH9YFO>ON$rMAE4M;2H1~g&kZiHP?P4m$^eiU`TcF>-_`L>D zUW@H@=xA6PUSK%2brdbfen~Aex)-f58^%hJZqI&$8_CnO5;0)MdSTWPY9aTPvi zOA`8rpNq7<3zwLXP++oDA1W*D|NY!)t}2c{PhJW`qXbpSPcC|EJ#-eBO}Om3>Nh6x zW>+6`##ndTRGZ>;j#u@u4#rN!c0aaLM${RU@fqT_G$7*Sq`Z@Oiz zZeBI1Lu?DMlm+hhBMPhFDK|yUZmb<1KH>x!u84@rCcPVZB_M?YqCel?JYx zeE@Cnpy_hY3Lp%_O5ROEMl-?cf2JKQ3#4#*(RDz7WyFLdrmdGaFiO8!ZGM~{(Y zn61b1-v68L#;^ENFxUade{>sjS9S^Wrk2VsD7sQrl4}?B+=wfS!emtZ-s^=C^7D6K2)N$ z+*B7s3srknkn$o=8kZG*^Q&Bu!-SPf^WN&4X9NeWh}xAn02p5q=@7Y?X>86L< zcIsVZ*Zcj`;V`%?UZ!b$Y)C~Prta^8_$cGZb)O)uUhpYpM-us%^qFfDriz#r$VLv0 zA0NZ&Iu##LV^s*4yCHyq(JbwTB zdScR2yKy*sSM6O&6E4lWB0bdve#$zTkFulIvbQ1>JikLV8_z%qi&FJ{UFYxL zGeQ++u>{YZtXARQcjQ&zqhT(B{CYGFIcVAKy{!F_Az3{l2ixqE3BGJwaYYF00X}xs zwvw#evYL-lPRK9k!vV1!jbQaCv9(l%yJ2VBo&DTfW^*k$@Cxf^3sj>3w^GHm9kj^v zFj-1j|@xkLcdRO+-I-2y~E4*6G8(4ln#BCpIDsE;zQhlrIh)&7f3ujZP4E0G;p738# zlx}|t+|oR8bO8VoGpoOt8#CmcNjx15p1mq`cWV5sX`KuysXg(ahS0ykOLx;slsN9= z7pxn%?Wht(on0qhj39JVofmqT-hX$bRzlU?OC)kRaFwixiz*`8xgEt0QwL*lJ#C_o zBA~_t2^I5rN@t31%%krkS8HBQog|7XHA0diFfhtQYD~=cBuRb!%Nzp9Ai1ryi=lq| zVgK=qg8fLV06WsQQ6Ay5V*$+EfZ^`aeZKq0i&1W3vq~ z_#Kd^X3`^D*e{h}$jWRn7daZGt;B)_mbb;MwwM`IQv-s|tW;!8@2Td`coI`Oo;6{K z0~$D+wiN}om;xdER-8>glmg8BvO)5l@Pr3%0aH=7t2hTMfSUVx1;8&r_HB8i7D12{ zvV-UN?ZXxda+qhsl(H@hoMVgqU|SZjQV_5a0`M2ny9W&FG}`bb_m-XW9pv{Z-4|O0 zY+sryI^!t0h4-mNNft-Q-=ZoAYv#U|19{WX@#qml?0S=mrYihnK)ds&@`cUhPkZ}G zKG(t-k%}7FCaZrr6zxq6g!cRzgu|xk7s#GOW1YmoBEhCXB18d%4Is~Ut3*yJ+xZwF zMo)Ti5MP7)r+EZ;PawqmpW*YBI`!7pS4t89X* zn%YqgmbdLb%}=rAn1U_S#pjf9t%NK;(_uO!TyryF1SkA6VLb8Kn`>5_vTgf+TKSEC zqu~Dwb|H6HUOe|U-WHQ#@Wp$sT34d2(W1s()ghysJ72q6C)M%l`E6SMKn4!}Wl%#6 zJ0e29&+T55<(4cqMx(#k%mfL_c(Lefu)dP2p5KHxt=sL9hMgo^e%X*D)2aK2Zf}MU zOO5xb7hhS+JvZ!|uf~HY$@Bb(r&WyRx|cdgY)Oo=6L1%4Z@4;Xq-+0c|LI@c`ov*^ zNb&c-!`P`@&px0B$lOOE+Zlj{TVk=x~% zi*a~qB9+d*8f{m~Tz@Ya`m-sDtP@E^@kb^K-6TJAVGX03m9z ziR*+o8cjDb_p9y-L{L)M&{QZ-h@3=qVrlJK74Vt=GyvoGpN5`{tGrB%7G_Y87=mHa zlxdl;E=;#IS_x+P5sVd?+zqo2{381+enkMz&jwW%CQ?`TLAAZL_$Ba|+aQAHGcGr= zpEP+qJ>vRZ(+)&H`o+s~-+OZe7O|b&v}E8TRvcxIvJOii_8Oa_q<_NYB+D@#u&R(L zQh{#}w|o0S9Iai1bni30J?;Xd|2rd))D=AfD!bV1dir&0w3VZ3ZJ$xkNw07oWgc4e zyFw-NT2lS#6UJlZ^JTpVRMuSYDUUMexulh}77X%FYT71Mp()gE=POcUu;4{ww9T{E zy75J*$5`&f;ESq4>W|nIW{95hLlE)=Qb;Fw_Tdl2wBzJR+Yj~&50Qrm53!-A=Tijs% zJ6<6OjFRzoe=7+211?JGj>(PzGC$ZAS8Q-Xy-X%01!!Df!}65Ly>CU>EN=y?9m?M3 zty>}~UaC7+%^1x}-^ckUQrwf3711e;=K67LUz4SCJJjgbeo&BUK+I{Tsc2bp`{pKC z5TNF~Z2=>mby3Sk>iC#3W_HV4eg5@d{2P4ed_$kMa)HAH7pcaF{mJiZDH}|`hTsnE zU=V9@?-k0{z9U+VA1H$WtQJN~{gvrXzg z=uE_6?X~fD&2`B#yVt{_^e;CX$7TzK?_B23!MQ-xF1a8j?!M^_!+hNphz7T?5drh7#-C~eJ z6O&w4#bq|zf?a9<0>e_-kO8J3N#RI91*?9A{6>K|K*RV$GfSdt&$g^HjI_tAN|SEW zz8GY^qFWNEp3{V-tP{gFqFQ0qcQ39R#)by=ZWF{7A)0o&BA?6Hqq*VtsV|}IKKiEB z%{^M42!J^9z3{KGE&0;1t{JPi92e&3k4&J@mB4z=@5S1}m9Jn4#(iugTkGu0roVBc z5SzmkVZ1mSlQ8WCSa_vH3XE4D?6D1LgKuY@r)JGL5I@ThqR)m>&KHMetunau{7FO{ ze*VQ0*jhtXvc6edmTOK7rF!~)k~Y#@Z>ol`?sF#$a17y#8XXYnA$FIvi45&BV$6`$ zbT1n#;A(E^SfwIge_yG9TFl0WT&EABd#`ocZ$%i|lMntvT@!u#{`isxE+K&3YP7iQ zHR@~;>goSo`c;%_$|pvjKtu>xpL#`J&b1~6{J+7aZUqaYT5oAy{h5&5%uD;rE5ftr zy~QaRPpIpg2M|C8Wi4jfVPvnnBWX_QO4wLSp^FCKjfS+eSFJf-R{l#iomSAP+b(2w z$=(_1wO{vGzQOvbBgTZ)gE%%@xc#~;9kT2RJEsukBKFULNfm37t}DZB_zly2XG=>z zhgda+?7T6@*WmU-ld~hfk=2^hr@NJ5`spL>oz)8eyR+u?@qa-SINPU^;MgJs01yXL9}+CJ z>@Uq?f=D4lP(YOwslM<^zJBpqS%JUS!Y$gXnZJU;LkDox+{E8>ekqyL|{%rf_^ z_M>RinaR_y@0o1G?5F!t!vWZ8xI9Q8dit$rv-6SQUCfMFQY#tSHR*V0Im}{;N(EYN z&4E(E`=|3x0T8O|A5U|67*$Hv5B%iieHQ0#C{I%C&rok;RT)!h;i&s3>#6eNsA%CCOekvSeu0 zhQPimy`V4lJJ$Zq;))|0#?x- zyd7M+H~>HKSEl@k3=kGxDSh>5+i&?WedB0l4i8=BD$_|N?37Z!EcHkMDmFUZ~rkNU`@A>kFo!%g<5*FiH$&`Rd(M z`+HyI^#HPEfpLi=x|MKm^y6*e^PU5%+G5^~Tv)>O%zVPLhFX%p7>*HjyHa82XG<+| zKVRE>)kp@T`R3$s17)o>`imtRhf_XWTbm$&z|t=5n}Wzj3&MzCV9A`t$?3gq&e)9A z)h`%DsqE>W41M?GP*14)ahVwI=Pyn|p6Eg3^LMu0!MoSv@Hfhi%~Z}zGSVw=2TBQe zinNco1=KR{N?NfN??q!Df8NTlhzqS<@y(*-jASqOn&sxGA_4h?=pQv48PrP_Rog+( ztNWiK)f2;CqvIMKON%t?`&1dqXm-4{n7@4$5j++=>DewHWZFQnV&z2hC5YuRb*J3~shxWJv$G)|OhMb9W0=ti zQX-_rGfwSR3ksIw|?Q}7y$(?v7b7y z0+iyuHnKd;>b2OmcS6#^hI84st6hH5Y_lS`8MDuDx zBcF(luXZ2=i^x-i)D^vd6$8k!S{S~quh-^K+bCC^tkV_6_k0?CKK@+5=xAGl@9AXC zMdNLd`&&Z-^~wz4G{l{MQy#SaXw{sjQb1V^(JNGu7 zMx6gB>1L?M6YlZVZQ<0QnZ`{W!5TuvmBZnDciHm&RFSpNSj!(i_su9nECEQV>~>y? z$KjsONjObv^H|~sPuKO%3u^_TiXh}SYs!v7L4WM`mxk$fO{KG2JEC-cgzY@L=zJJ> z+tN6XcAh>U8TG-u04H4?uZEoFWM91&k`*b{aYzD8#|#yRHHf)sCE3Tiq!i&1pfF!3 zi@8yq_biT0idduZXMTCbQw=%pzU{8&wC`jj9F*_LNLJlki8pxDCZz1K~j)N*t|xBGzS7 zbkp;an4wkXQq@NEwj3q&4mmc#=$v_e8)Sw^PWMgT1O<9k#IE4vP=o!)my3Gv;GZNz z`?FhJr-ARE4V^Kr-~YP@?n>VzaSeOu18z)6u@fnOGWtl*3}=qVZ$L7HH;{lICxxzg zqj^0~6nxEGzFH)QMXAzdIi}kKh+1Uqc%k7pB;%6DF}{W6@xw)mk!L!q3A&beS_c{P zd6J%`{@OpGzlQmvJOz15Lx?I*7AlKC)azO>w7oDlq2r3rD`5Jm z-K?||p}1O=fHW?b<&ebOd)+H*5C!|5tRI6G9Y|(eh9%!l)%va?i$V7vI2W&}<^=0< zVmoJ#qJE*!jRb!Bc$l~5HznQ|hm))C7FWmEfdoUg9%`VbYTvdmF}a%cF3tDP)bJav z_MNw4r%lAkc$xvSsh|MtDxBqgBZC3!vq9E$lix+prc_vjWVSo`jY{@+StH*B?4!wM zs(TJPbROEELb=UNCU<-DgX9%nhhfLHJJ-R*Vn!ewSRoJZi`!xN``+U+3{cUFiqhfK z28vTIlzb08xkH*bhQ@Etw-R@MVXy{SY7x8)uF5V>GoJ5AJeK0AuIskZjdF4Ru}MM9 z59RI59+d7l6h#%;Jk>vxvQk!1mwc)Hg7}#oqhE?#u{N$2_kHv8v?Ml93Vh_Y+anrk zN2hs@`dL`ZEQ27-Y23i6q4nL-ngV(fO6REuRIJWA-7^gvwAx=T=0X)V_6O=L9Wbm`?4%? zO7)$kO`q9nTR)U}v%Jt$0t_T`NoZ&GtBd>%^;bCEp%Msj6`zzjug=jX3h|#iV)!?w z+qaXEN2gb!^>GnZTSP+TVYmgd&TC(tHIQ-=bOHL&ky#P)|OqgTp zkJrk5Jsh;W42(h{gUj(}jz(AnqKcR#ZHy18P0kao(k_aozS_O$oc)8Yk(O;0$(*3W zh0aJWuhe!S*)JYX0&EOA+#h#}TVrYdWQ@aCZ|=XlXi7c(Xx2g|G?2Ib>lFRgdp-43 zeqa0<2J}t1DoZ5T*C-=hB+-_TF`q!-ggeKz7m<7W6rV~x>{T{X!)z|*PC#<%{wBI5 z!nh{95+9qAt{OzNTa>(y*YIh}5gBxAPY3j1mIuSX92t<*n4r}-?v#E1H7!apxXc?e zFYMkFKA8G3F+JaU*739H$oI)h7EmPvr`odL-j`xr<7C(j3ldAQUmVDOXNl(};`WG; zI)ObTtJt*{@_!$&96O9f__`N_&Th2Z1`AD48!$X$k)G`=26c3=9UcklCMlDO3CZV~ zzE2Vec&zzFh6jmTzJ2Or(N+k&udP^`@7O6W+Jm?I+B5uX<=x_s5*zN%*2dSrb<~ra zTa1PN-VU^0AOZweiufjfh764xGn)&Z_fG_tpxtoPYE%ogx96V8>mfC(f6dqYjF1YU4K`C10t(5ZfHz7it^2ARCylb?D^Pv$Lc6m zJ;&840px(7BV6_kuZZAQY!&W@P@Ve*Ne zRy@R3L5AH@n+9(O&h;>`Q1m;tZy>;6o@Xk^*WiEzUYnihbXx7A$4DyJJRKwo9}E$S zHi8ne3bcgV%-2{>-Ji&j^mBO@eMN4|e2npC_in4$crSr_J!AmhnbS&{kaa51N-LsUKC?(mP{E|$2@ z{1H526MV z9{a3)iG@FF^l?%aP&%Ir>;lv7ma9srJ^#^F1S_S8XKQklNif2* z{HE(+-xt(hHz8Kj`P^CyfuF*iJ`G_)o(8#U@Z8mv>pbWbQZQb$BN}XGl6Oq_Zb^r^ z8utk9r!vk;s4Gq4szOZcGdk1GsoV!;FV22Onw6e9s+0nq*8@B_^TKl!J|*eU8}WVV z8tWHt2a5IyOB8)LBdU+-6gV5xc<5;-lq=Lv=qg!P5D2=w_Fu4#6h(eqhLWo`2wzy( zMC@5%6&gJ6BRc`*0Ge zt?p!k?p|ESi-Ww>cdtz2Y)d)hyI(g2T1}utWQa*4F*!Rgs+g(s6|#2E^`=vYE84J57x-EyzuJAw48qwb zIO|3!1J0TFj)c01wyt`QsW%9>7s=CiwU6x0M_7|7Ju8iug3OaE-PN0G`q)iL1X36|F7&q=J}9j6$#?aP3{btVM+~Cf>u! zfFT0@fo5kSNq@SugeBx=LJkXE9FL`!Uz$@yFOEy!1F%HS4cUR$;@R4xBHTpTi?P(d z%j~pkv$Zx<<0w);ruXM3)WlD|ge#9kvu<|ejaKmdhA;efw9?SBaWglMTkr-fH__IJ z)HS4F{%(!W^^OBsOYDx!M|zvsl>Or>de~@DL!tK4Ro2K-^~_IHC?u~s!qsw`0sjPH zQGX;v2Y4{2&k)!74PNGNzW6J2juRFWz42H>^n`C25$|iVlEg8Zkd#D%|CU{{9+ux5IIG5WE8-lF$Awaf)mu6V)C$|cVM6YO z8Gd$6x=H7Q$cwCo-~gP7)z6+ng?`CRAR1K#8bD9tI=a#fIMhXMl$U{``x8Hzu2#Nz zhY;6yE4oVSE!CTq`G+SGCN5X-u)kK!< zW!2}~2}_eW`&$0#|7U7VmJpr$10ojx3bbe--Q@jAipk4YD;9RIOsn6HT?l_X@bsWRl-`x^WVt5PPiX9Sc*RcY8#P2r3WjP?K>+iRsw* zXOTPx^F=)suD>>vh!nQ<0DI(H$z2d8{PwMpRTnq-5}Vb;hae2C;n4G~t)XbToo)?y z9?t(BmsBh>?cYpY!kUl>H}%0zQN`my9~aj)z!+eFr%UCrI4--~rO#L<|SP7gq%^4^ zNJR|(=e0wylcV1ZFcB@grDSqtrUFJZ>8^bVFU#k$(EO2+Dclc6Sfkm@$HtRH#%K+( z5sqv>;BaF6{qy4sNNqvpvHtfR^8K~Oeb zZhSC(CjvMH;Z7B-oU+08RXx+V8Ruf(PpAIu5(qeEPSX^4%KQigm`2+Kzwyxd*=ghfMj=&`jp!)IVr|D#BA}JJ_)8rIOd|f&`gF3wqtM<2Oyx zRx;j_O`8UkBsG)^#;zCgm~pB-#L0PAjOt&Kd3V(?3L=^%TKNx6@3>XkKk(Ypl2#Yu zi@q%<*jgBu2^<7VP1n3V>hy;rC8I_=GPLRT+HWRZ($-qn1NKIQ81;;ssP$Bs`6C?q zA1G6d6HPeVb)N;s%(6kkD@B#3;NgvABhcCnDvRGY>)XZe666OL0M(Bp zQ=QnykvP0=T!Bq(XG&n@eNtbyzqXg1>`9F1AAv1T z9JmSH3+HZ~RBBt_EQ8MFACRXE!dFBm*X2}hNeXW4#yYHJ_BHi_|Am(%%kKPO6>E4= zp7}ypp)M5c5*VnJDN_Y(79+`*=0m+I-fa)c0xcp@-9%~$b~FM<$)gEGGlu07sWV(2 z%z+a^1COtmc{Nd0*1vjGNEyL8OTSxybpXOhcYgxxjf3&guQ?*RKTo;!IBO|&P4p!m zikncFYjUE(QjMv)q#Z!HfxXV`Ch9**zRSJwRZREIh^Vvav2fn(OI1p>P<^1rNW=5` z58f$@bV^nwL-e=v;Rf`D&?4rAD<^!8B12^;tMzfE()Z)u!4d76qa0CL?KXTs<*-Ts zMmRJmzjGpRs=H*+9JYYQcT0ONh>!8lRA41O|c;4W2lqdp6&BJg<+KZuOnrZ+qi(XsUhk1X%0 zQL_Sh9iiauWI!Ey=3b;LU6&<7GI3+{j?_eSVMhK$8ym_$3B!8}nuYHa1wM{8{BGEW z8xs+Rcyrgc5Q?gcnE&w4DjuJoGoyX)@*uvEM{ASDLK~>S$$*9|pV4;f;Ob2#un< zdgK94WtX-v3<|B|!yp6UYf}vr6r8m>bN)wNrynCW9%%?S5d2eG=x2gyrXDfG^w61k z(YHGHPz(TkiGBE5vYq?8#qSt%s&U9jUZC-=-4<@0Fp|CdHoN&A05{Rc2u5TbjIF6L z-1}yA$ijkWiKD%>&qoC8UP|bYi0PV?iz9L3oVNl6T^|%A(&aqNM3)C53}W_G;7odv z06z!4jQVag2tx!Omoa90P%Dx+!Q zcQ2I`jkz=HLv@qsVaaSh7w=E5T70p#W3r0$xfoCo0I43_K7k1 z47K!%?fz}Ui>}f=kWvz2O9~=TO(_i=QZ;eP`6P>lPtMrv;x)DA@&Toya80|bVjxJO z=}!CbOJS?hD5a{F2-Ray-+0fzVqL3MwHSu~YOJ^dD|K4|QxzeWxzRPxlUlDL`(YP# zllL(sC{pvqHm3YLlPY`tD;Qn?W=jcr0@(*w2ho(I6OyfG#+)pYH>Z=f-|WKJ(VuH7CWU(BPWyz&E19b(-! zaedw};xF4@KZ^l*e+6X4bIMvocIVxdMf5SBgs zfb&>YAVMhOJ%K1sGd@Hz*s{1dygqYgA2Sjx)!fVYUS!YV$K$(H$wy9Y;q5z`mMiZS zVl>-5UX6u6K+~?1k=>bm!Uf|87GE<%JRf{xm_vTxO_*L~(v6DYB!OPyHQnvMc!kyp z9en62LL}IaOrlHj!^WCsr9V!Z;*h9#^lycJUsfCcDSXJ=!1to*DlB>L)z;3w1R}kb zEOGIygq4#C4MMMZMgOUZCyJTrMB>kkyk592QxKv6iVj>kF+gUd>3kNri<4T zmU8pHACSQVs;w5cc79S=Q334LOVT2Lf^%8g3eXVZn z{tW5ct39_JHQYM9`ZGKpw<4mz;cSK9gMsQZ!C@*npX3`hY8AMHLqi`EQ1uQ&{x26l z#U`bU@^x8pxBP&|Qq9EQ{Y*uF^*U}X2sWKDY=*m~FxR3eA{?FQZ|NK^a~F4Bxu5;)0;_l%{e6aht=m8j8?vUvD}(Slo#gZQbAoTQ;M!6WIH)~U z%Wi=_cb8+r3o<#1 z-;WCgh43j4;lY`y33GMAg3li1)%>lk0NpfAZEBo;3trN~w}#gqgsA-bhYLAIyhJ?$ zaSzEP>V|y6^M52~I=zn>Ac3lk%BH5!WEB)^xi9G?I9~wurpV}^Ik)v`c)si6{rWMj za;5@U6Fb1B=NunB$r8l8oxyw8h~=|uadk~)adEc(yY17_T|jMVgv_~va87EnL{@ej z{gUR2ObB?!?qr1ODAtH1yjPkmwMv6}3!e`ct9=BGIMd6qbvw!C+YfH-+xP(-PhTRF zy<>3Sk?U$;sJ%3bVX)qi&hsM&nn{XwIjkSV%FIZS_hLPYAYI??K_tUV{!9QN&eJc7 zMH^rcz0JjhjsV1YEd9;hCsqWw)Z-Kp&dUSQ_|ijA6TQacu*EyvyxFk9I%cUlW^2g0 z3z4_*r_n93?0A0Ad-wbq2R5TBXhx_bDUdvN?x@30yNXFKyE%&ZBmmGYFb1*ShmMx7 z1U(cC6oKy2JYJD&U6{O8?Zu5nx&DN5gs58Yk9~2{MMq_AWh|15$tyU6iFD5e@9Sg! zQCKCc0${=EME**_&#wQ7$$&?$(9BFnw*2__a~mPV8xa@s#xzvU_K;AibXzzDDFg^T z%fpPQ#Q+O}e2y1ZyWjwSI*=LBD|~Tyz@#xUfButbSIBMOcDiaI0lB_+Q{KXgNrO+9 zmllr?S?9&`eCr~+yj6%e8v^o^@#Kh4OkP=0q+QM2pqXST**F47jzgICH23=Fr z)z#812BPL z3l!Y6Wxj$nt9L?%e8?PbS2Pc5dO)kGnT+ecIjXH>Txov8-gcoAr>D@=sx1!9#p6Se zD*$n)f~&nQZ>=sv2E%VwFEEgVGNb=>Y4)5KH+HJBV9mb@E|K4q;V-VKTFPd0M}G8O z=d(=6rCyOy_Dh1$^eafp5AnU0PVV?Xm&i329+Ho{+d>gT`EO5xP{^29lzDrFt4CIP z0Q-rcq>6T1J`EZ%9uE`5 z3sF_ybMydJPSmhy9a33_<<)-Xt>g&Zf#A}ey)te^Ocb(g6iq_XYgXN7!#S|7J#s#4 zinMMu#luX`kj3C_S^LU`4T0%Vty8h&Mo0FIQMYri7?o6j93d5t9co3W>)f?bbq<@pkgO3r7g5LnL zJEWMD=YXDKU(f1dWts5O{ru=dc8poDs>)+dG~90;H0KrAq&T}bz7z>z3YA65()pGP zs#&_oqyj-jmc2cjLUR1eUs_XH`ddIP*S}W(2e_i%_}(0st9{{^aC=FhFS3lOpWlA? z6e-DCi%a>bCv1u~F0&X|E`V|+boXaJ|J6&Sb;)!6Ux2jZF~#*l2VJ}Hvq$vd`kln$ z^p~B#GM>UE5rM_ax~fb8_d+Y|7(d6lL0=zHAsbZV5_Gansrj$*VcPm?DCtg)hj@*6E_eEA2}@x8L%2SXe9C#89=Eu`2< z$L}S4yI@uuQ^#}w%vDGlo5(M%chFb>Mm3imlbf1YDf!|%&b4ac-gSCrYQuPJurF6U zRdXScL{sQM83{fF%$w;#%XOB!-memN)p<4^o9MKFgnEO(6ukjG@2iuVw!a>0x?csrSki7tmaIrPoH7pnL%PUjUjmso7Xtk)ZZS0v z+BF*v{9RD|uf96Xv2o4bdN1sFo7NwL^u)w?rPIQ>l{-KU=9W&@O|`z9`wM@bhp&ad zWtVUy+}w(ylh5?nvN6~WIk-Bvwd=aY{qu0gFt=@vEi&ISq!);y)WbI2Os7mlf;zGy zMm-WVzK!r4rRdhNcve65{p5UoMkgRmz;vkfH-~qhqh;z{cU$2Pbk>@OgWPFxnoPr&DCgC5)DJ{ir9 zKrinDM%3n7eWehUb+rd2mWe*xTua@~fK#Vs_WWS;$HdBO(<8}!#2p8NGl=2Qs}i9! zwBv#E3b$TB6Bl{ju3$=CH93J~D5#<)+&rO(Qy{Akv^! zNhv0TjjF|gVBXgOgShA)ALZmEogv5PL?{y6W!FcKC$0@>okgj)W;*Y&J=Dx*rb=lI z#B-YtH_>m;>5#|bLB=4DfC0Wcy&-!;lSd4i1P-`*^NBS176c!|9We1z-m`AiO22^9Y#ISlInP^T-C`>b*nFx z0#GqOKQowpwFS8N72oEg2ABDys$OG-C2umMsFJ_Rm-7B;E@MIkSt|wj>%}7z^o7Tc z03!1W!isEqy*F9`B8Rj~8q)c&wtSW)POiSsN_*~q-}(hhogP)z%0gE$iXcnwmBX`B z$4tl8+XWi-&H%K&pM6b$b>shv~T@MBH#5(G)(OQ$U!pV~gZ3(7Ue^^jbUt z0XeQ(ARYv|lq({~ZBCy}F51CsQ5{!A+Jakbj}GYIuKcVf=x}A24i5=WT|CJ~%^K{q z?s$Gkybmbs?mL}0Qi*m{SN|kc$NJqg#M;S`Xl+-b##TjiEDdT0+o5B5`0N zAq9i+NbKZ216~NSRwt^oEDDt7FAfmrbXm4KtL=aOip*x$sAkfBfSs(nU$mR&^xW;l z7ynb{Sw?;3OUQcaNv+^UA?$x$(VKMDT8o(XJ)9QUB`FtJ>;` zaGtJ|_SkW!lVP-Alag{BnzKb7rW` zpl{oE{{|ns6Ha`Rkz%a+qX;u)Pn%Eq7hX1X26xwP;@NG>%vm?LnYR!?D7>mH{y@RA zMPd$U3`N2{Hwzhce&eXxi$s+LMEg<0UvRe>3W!49;|Au+ml2dfzfobR^Z^>**=xhs zv)?Ql$IaDUPU*zd#FjP^P7pBdb-)&r%d)NN#>_0?>ZIWNZWbAs58Ul|r+$BvP1T~0 z=Av6K5%03uFV|vbC$}_6r!_;J(wX`}$eOnE)X9Mt%MYQQ$T-d|@HY_mpi)>LEL`@= z`|{%1;^F_z7HNdbX=VNr&^wGEwQaeGmi^W5*O;%j^h=wwb|Je*TTUr@f_j69VSy&j z5EZ9gWFBFiC_X9^gMb;z=$(~U_#+ckOcokZsEx(G7I(1*RP7eOpt=VIn?cqeh#QV{9{qZz= zlBcB#So0&m+m_noH2O;b8Ui_^&Uju$`>R+H83O^I^!mZJI3t}BP+Rll=UI6;J*oYC zTo^(jtludAs)pxNBNAkPqTrTMWCvWtZTR)F7$|^0a)tl;+4g+n%eYGW{d)gzy<9ag zY-IppHs2?hzD$U{M$Gz&C;5;a@rFW+j~ASXYsIK{hmx?dGo~Fr<|pCeNbous9z;CC z3`|eU*xv`aduK;Cwr@$6o4Q5Sh0FAo6HukVz}@rfTcZou>+T^6ovy1EU=`aMHM5lQEaRm;9i!GcAC(i@OB zD&B2I#Eo$@N8cCFNN>GJb}|9=g=%HhXJrvS zu_rR;&(Oo!WD=qTV^6=x-rqpa#PL|m2_%e&d}Zw~P<6)n!CU5I2F~ar^8Re=Z8#%k2-p`33-YN-@D@=((}hiq*WC!+L+j= z5XUoB(|j?a)F$J7jV?S-B6&QZIA_IPqZkqiCPLMrM|Xx+FB6*u4}JbBZd<#Old*dK zhoII=;Ln*7!Ihk7L|ZVh6bDACtc=BU78B93ARS%mfnSblVuTL|c;uOgBttS$a5)uL zFfv&6oUTL?FzHWIn~op9jo@pyCGeg7&Puw_;12AhnHCsb|rFv=&*q9qZW@Byr^rex#Fvz&K0@pwwJ#fJZloBH2WDV677 zALmq{8kaQYA!bb}KN2n;0zcs*#eRPJPj|fzC2cBMKl6=_KF8}{S(I^c!%9zU}VmyaK)qJY6vHv$z zZRnQwHRP({7=EeAdYQx^zdJg|IJN(^IZ+}4D0HP zN1bnet5MfyYKAw!q`F0!=PVJAZz=gg3Nf>c)W%tQHIPZ4nu4AUq_H-EkFy>DHnTv2 zm+fnN&BR@-PJU)e{6&IRAx*S_nm8)plUlT^Tht-qs(Yq;gp6K@Qrqtoy3jxr4NN2N zZVIMio`Qa#Q-7J;2u|4hVS5ksc2jSq=^DRc?^W{3kIAo%VF>z#X=0!4^}R%=okQCo zo)h3+6K!QaY$^8--VYpTjvf*>Kt~Wg2E;cB3&}WBNfQTY;RgL; zfQqc)HD7LbiJGQ&S2|Icx_XTd3hkvwm5OmB@$}sI{PU#$>B>F1Izz%#cdO-18RLVa zqKoPAF-XCLxR-HF@%{UO8RvHHN`VWtKhV+1m{7aRml_PymmMCG|ISf>8+yQaEpQ_n z$!PeOf`-(uk&wy7P!)gLW186dy-$!rYY(JsDrx=i9vL=c5{UMth8DRb)g+~;2_Oy1 zavfJ5tbO?Zb)ww>1z%bqBPMT=>ET>j+qUP%UQO$9-v4h2H$yzNj{`H?J8{apJGE;f z>B##up6Z$)O7Z7x<}!&mkA409WFlOz4JHue9?2ZoFd8x>lyo@dkW-CHZ<<;dXWXuEq55bFHw*UYD delta 7099 zcmb7pXH=6<@a~%sAfXd_FVYE35KyX!Ql$z8X`xrC(iC_Tq)C+`1T=ss2o?xMdI?p5 zhzcl0knlqg=}n5XKlk46_uTtwcV=hLnX~)s?94pPdysrnkw+G028?vPbN~P_8X4+a z0RZHD3IX6W=YvB?g=dXO5go{Bpi*7?%q;!^C zcVNGva%PM`E^8gnkUL+RI9beo?<-ou-YVC-Ce1rr+@$Wwi^R>#OE8}6# z`|qQFR*#?X_Jj_{tcMbInuoU?2W4brSoD77@ILpGQn;;9p5us()%5}~p%iNh4@DYN z&|&};t~CjyeAZ10JB`ty2vYV*dSTXkmF4mu1teP84C2Ho7nB_J$%hCnB2?+f5qMeJ?*k2IczbMfbAo>A?|vGQht-{ zNg5s{7`s#EoqTtw7#Q5iJ}yfxG|3s zAHjr8#z1POE~bz7p5(4v@ttrQGa!TZ&KnInSFZhLAQEC? zcgjAXee@Veem^0kPOXk??Plw$d_>6PPjQs~Nj1$(wi(xd$bc&?V_2fnq)iJ8jJ@IYf4?!8(?_ukrLaP;p*nH&#JyNd(vGTXhM|j^{aVfEdr6^X|K^(16ffg4R8ZD zjIbi2iO&1Ad=}6<@RKw@A+U#A&d8?g!jMNcqcNdjk6?Q-Mb zrs-*|{M)!#-f|??b#(`1G`$yC*d(`?2aMw8NMB(4qXwkw6YppI|1($Wkld`WCxGuq zi8JagG^n&alCvUJk@_J&cV@wW8O-x>^ye1piMi?b_$})P zBw;eb$Pl0_efYzAov$Y%W;u@xngi9qtVg}MPIz%Eai#4isirD3HLB`sA7c62L^|$2 zwj~D4i)TrWYaF55AZ=QAG*$SAX%FX*o4=g%CrOHuPyw8di#E_#sv1=A!)&cmL>@B1 zqSF_5cRKm7mg`{@=_bAt6e7=wZ)k6AG!IM)s!t)@YJQH)JZn0;)8hz2i4yJ8PJb&z z*Vh#81s2a@a7w*Xs4(dChnr)q)19e>Hv;|!d$A@sK_83KG;2i;iH>P8s`to+o~0bN zr`}X%m5Mmp*N`@g##&D|ydl7Zi^r(f`>RrXuRH7?kqUIZDB&pWBKR@V`Bi2l&;YYmv~5c2%RCVo?K{`u8&BVwlYNfqn& zW@uAS`&JU*>@&=nU_??P&EX9&x5k2GyX*%nlN&VYNM8dwXGOcOd~ivWd*!x2U3#Fo z_V2inG|u|{fy5@O&|T>5xhVD@~E;^qJmWG2XK{f$0KWdxY-&12_E~5E0%2O8jYoSZGY`tz^$YVO%+ z+TYJJ0d@{>t{g4Dey~Xi`Ca7A3%(0aO@Qp4p8?oF&f20Cth38_jGdb_C)R!S#;ND! zAodInAg4|#^XK$aGoepwzC0%}Y+*F6{K}3A9Pn=9%m4hS~*I{!m zRLraDI~62}hZERKGvsQ<7S50GKR2OnXKiDlb%N2*-}7I*n$6%vSR8rgs%RxjHty!BEyn-P@sBNU{#R)joId~3t#(+ z$?t*s-tPN{7eC6a#KZNdJteozlI2#4#elhHnlp#(9!2J>BGG90vt&>auM7{YEcAmc zr8<5(*p%nw*H2b#OTYeP@3{onXQY)+52;86#q!J0Kyvk^*z2%qMA|0m$D>V&m1cHq zD9%xH$SK1E&mk%^{6WW%yg}rTM`EEq5C@9go(GDfk;U@jYgJ56mphWElE?IVQwaM{M9a2oUX<}*PzHN2R4b}tCR`Lw5@}!h)Aw>fc zF(Q3&A!5W=Fp2?q$BkC(YC)>rgGVD*n` z!7a4a(`kC$Yvg$usbUw^DZSim>Y_K;`$hBGq0k_dr_7%hZSg_`(0J+X8RM1TOA@2ui>B`4Mi)=6WR-l<-KL=e?^^?)Yzqo{ti9fRh&WtCcNhhil=R$I{H#=KCjr-f zaa+83mfoMSKd?U!yhM%DfqL2oX0)gFW?a7wD4aDztKq%&OQQ4hPSL|YbaemPU9Z=E z^sY~SRIT$6ry=n}SVD@NE_3EZg}L7m1hqSuD0b(FoV{E7-}gC=$|qdb7)eh_ITJ26 zjA4HzqK4i0z7%lp(B|p^uOUbGbNR})>MaYY#;L4p>c6*g&S@+INmOUu+3y731k6fV zgV-|~)F_s_C*g@6P}m};%hEyJ@1uG5@h2?(4Br{_I7Is33r}P(V(0TNx9UeaN>paZ zOf3o!m_Aj32SVypioU-f*n2wtj(^Y24^8WfYqlM~V3(P%HFz)Wje>~?;HWv+RuNn; z*m;jF@C;V(VX{hDwnXC3s(RZJo9Spl7iP=~icYuSLr4uY(q`UUPM&H#HMrSXDu#e= z9KG-lcX?vYhh-U=V;3|HwP2pm!W2*o3gB%9vG&Ak9WO^XTVs|gKK!L((;QqST!(nC z)Z8XyRGrBj@&(z_O*PAfJ2vGD@?g}Iwe1&bUDZ(Qt<%-ST}KWG%r~X~Gc!1JT4z1> zQv$!>Y0lp20u2)6q-%Rz<4kk>`6TeV5}&QDC2Q^JcF4_7|DB^8H2!hQ8^l7?&s2)K zWz8j4q#7_=Y!l^;(+UXJzzFS*?65)hUG#6HLS4<5+o0=o`r|d*1T?Hl9U{+DR(Ic44qd_6-`e-5 z%U=0^m3+7_yaS0#kM#FdF!hF$Q`>N{e~$&HGwQ!d$GUvaVYGZQWtkPnyCQHfB%Pa^z({6RnKyTY@w^N*y8zO{Y_|bdqdxYdnC2 zg*EuS;YaB53@F22(>f4dcm<&s=qT!OuM~|nsE`fSZ*U9CLu^L$zW0SMw-&u+$1?rO z6iAld4Z)3xf;{(g8puDj0&_~N0N>vhfUnptzi{R}XdZX#KiW+rCfZpwQXA~O7e^PH zQ8{4&;rH1qiUVu;OTl{{z3QZ5l;h$vT+}swu5W^+SfQYsfs~EQ|7M1;d~Dy#=`fbV zFidRs)Q%A4xh8^$AQ4?=slaZ9ESISYQteX56H>#1527X4T_TzXZaRGRtQr_T-D2^a z0EySp>-*1neln3^8MFcB-bX)&vVdr_+F{IhhbR1T1%t80UptBuqX-!jL9UOtw;h#I zn+e3x?fN5V^uq-%{v1-w@50rMVTo;0sP0C5V=(i+>7B=n#rOnt`MVmDtA%ID%dhN_ zPu(Xa*;9v%!m~#mN+N*)*D5xwrs9oE&>kxMy&P)tju57OLwfcch7UDw?yW(JB*EK7 zNWhXs$UQo$jhEg~L<}fRxl1DOoW@kUO7|qdbZ>RlxsP)%NNoS!ImaXp4Ph9dY!t$e zO)_sog;hTpt`bou56*M|*}v!LE+y7sark*F&L&#!cOPURED1YIlf=9u5a53Mzn{vX z?52Clk4}Dd#<~!8#ETo`*>R{zy+s9;9*-gwzHr{Fe(Gk40IosW|E%xhY9kY8Vyh?4 zt&`z^PJ`+WK^)@ElmdG-p@s ztl++b4kZV1Iqz=Zc^JAHq(Jo5Z zCNk(KLKADlJNHp5U(+elOXVy%eeTjQ3Vr5XU9Isf*BHURks{{=M}fWp*y{Zi_H3^I zG!VHE+6TFOLbs{T1MZt?62e$0{gsRz;E=Kq*(P}4oYlF(fochfSoO8?$Isxx1!Y?i zcAUUw9YP0Waik4M$y7YUwbxi5- zxGRH>lMDnMzu?_Sdfz&=u7EzyL z-U(4m!2+qL%-bKiH*!I9aBN&gSL|_O(a>4`45x5DbW9MW6 zgp(X7BAFo?P%4!@{YRA#uj|nbT4B)Ad_`gp3p?FJ%Hl4v)UmLa-a4k6=zB5EMmjO>u9BxVq zzE_dI&am4x^8T>xB#FgsthgQlkeoMD)y6s0uen*X7qqN<%=c8hY&*$80oAT^RWS!t zi&^65nQt!T^b})T4VsNG8-;+F^dVfI-~umHt+Yg>RDCsxaC{V`!|84VwE#x9%wxXM zs@u5P=$i^qJdcM9I9u|0k=X8LPW*!1o(x7U-Huh{Hs)(=Oj8leGt8_7K#|U3J0YG< z4)*i5`lPS;t^(#!?9=Rn7b8UTSl|r(hmg~>imZI$k-WC#OKCg+30_8k11%HXR~#25 z!dVtZS|mBb%(ol|P7WsD8v@_$^iIU}4}TE#)Ae8;@I3mjNebB1oa6bCdp6-zib}mv zBskeiH(Bp8hmQT3F^%Q1>8EB^tOv;s{m)$}oN8SnvcWdX{62D>vJTn53S|)pbj^$H z*zKy~Oqk%lO9b6t>ujNP=$jN7byU*7hp0i$m@H5E$+_0aj5Um&i9gA8$Ht9TgbNTU zrZ?D8+~;d!!PG%1{VnLEe4)@z%s;KNYEEvI9W|xKw z9c_l)&tht20QDz~qm!4gbGka|C)3t^t<^f}`U1reNzl!wLkv&~POz^%tmO%x7`+`T z+&I>S9OY*%&Df}UhOHafn;(@2I09rh!wvs}EOzvZS#mRVIuh<$Tv;W;LRa&rl<& z%E|3fkbqDT6JfPaH3Tt=E0T5Sv@$;-hUo0M*;)Qb*b;kfk)+W;3~1X3_-#YO&v;cQ z{`-rcy=r@b?u1EWf5JlIsob>hGIcGV?cE4+tIF!H;&>0(9eIc$Q-oVpzDx6j9P^6T zTac+laevA79PyvhPELECHLda17V(gRNw-0tjmM~tg{nTyrtT2U@NZ3SiT@Vc0Pu%$ zT%&uoIu|#>U!b;Va^ks*M1!H7<06wpVVj>LQIk5!qr{vSctC@ybEb)n&_Z1tyBV*u zQ^?G3l*nXU$A5XBpOOJzo@CN+XcJpF`3BU5)9cmcX5t)YWY&Mdm;WK_xC#o(jKJ)_ zUnXB^{AD%?qZmuVG+x##3~Cld{AJfUf{-FncBbgX)&U(6KQ=MunjLfM#2dH9=Sb?^ zd>JnjQrH`s5uDv`wvE+Lq0_ZsG^bFIQ?}PLgaenQqYkxTsBCI^vRE+p=EZO=F6v@e zB{2!l_dVOWT3#%3agW{(4Fp^Yss|Sx2YhIzGk6y3Gb)D9ph-ZWd-MEup7u&eg#2cV z{@?fg&$0yjO?|H)KTBT7)@0Q9og9b2dr=QdfOH4E4t)BhI_ znJ8_$=UGJihrNXM)Gq0@s~Wj)_j*a=qMy6}JS;rhetkTJxZYPajC;AWcnwM!@L%=a zXb~No5s2)M5rdujCkgyC3$cHj$U3ew`c7<}?DpHYz&Dth)BYbX~D|is5N&4DRY{ZUw`Xu`+dwFRkd4&^rx`}K6f2*vKQUr z=+~F<*)77G)@pldQ3wlg7AzWci8Hp1dlh%Nye+{_YTe-8_-&suglElV&eT;EfPUPD zq1@%w@wM%S*?fTgG`wkIjXpJsx$Tl?jv{BPUK`x|>5JH^HHrTeCBe1`jFEckAJ9U& z$xVfv&bu5Z6UB*7OAyp)Pj_VBuJJ9r_gbJNX z7dZ&L8;T-NSmV_wPS;O6uB^W;p(T#V-FEKvr+2y#!|MIog)`f+rl;Yg#`>fQ%`}~2 zhm{`-$^+u<7}I({sIHTt=JRe}x9ivoCy)DrM4jQX$b@ZFk)eMPVC?K{?> z0qbw#NbE}@gNa$KLJ&&&CU=2_r<<9*05;^JV5Ow|J$eiNJh$+(OqV<_Nf(?r-y1*Z zPK*7rPAPcO4iipq`%fF}{f|~~Bd^+HxlpDc$?lqV{LFl{MZO_WON?*l8EPJfEF~56 ztiP^;U=W`EmymUB&)%GS> zE9v3IQ)a+@7ba!GMSOMMrS~c-Qi;Y7gh)Se4d4YGd+Js6vi$ijp1B7YATO#>h7-Dgjx);& cJ_P~edz%O;=CZWRb2<(%x^AXlrH6_8A4l5s0{{R3 diff --git a/selfdrive/assets/images/lock_on_vision.png b/selfdrive/assets/images/lock_on_vision.png index ba0370ecd8ecbfb49d142066f2376cdd6eda1a66..a634909bf8256faf11125e36c46cbb0d92b6ad37 100644 GIT binary patch delta 28967 zcmX6^Wk6K#)4fY~DAEnmEZyB8E#2KAO6Of#x}-t6K{}*ELb^MZZhj&t`L6%>10U`# zd+*$N=9xKj<~->tE59K$Q5tFr*chZ3003YsDayVD00_~)KQt8hCy{f&d_B!)4A2cp zNmfeRXZ6&?+lPGNcNdSyTJvnBx6ygmHcp16aG2?ftfSXqIKk5h!5T8}3NrBgs6R~y z5y#fQ?;9c}`x)O+vw3opo4G~hr{{m`pga4$L(7Yz9_0B3w=a z{U&JOkuoY#U^66AvHOP&^%f?1KGSLPir$^K@W|o+e}jq;^$m&$5U<=4m}?_2Ndahe zwNf{?2&mk5vwd=A=ooCYkXLja8NM?NrVIcNz_wL--lGYu4kV{A_i&p@$6<4k zw1fa;9o45(wkS{p3pR1!vTjVZn~1m>P@26F{j{KV7>al zML!C_$N{FdAN?~w&HNq`d6gWuf^1ur`gMrn>QzY7g&&&!#uT(Kp4b&6$CzY@{l|ru zk_7f0vc6B-Y|B_4A5`ouVP_Mzf9p3hhdZgZfI!%e^EuNd;NcxlB)8!%pG>%4lpJJ<9G1P zZ3YhX?oECoT7K6WIfANpx)h=|e0ksj@`BvlFUAIqJpVBNf0qR2NZ9#DHF?bTKxX&9 z*9zgz)PE$W(Enc)!$UqDekb?_`*+!WT>`%Y%DeHG$0~~hRDpv5M?uglYyy*sk^G5b zATYZN9UPNI&#aA^Zf1^msWpHHSnKdS-0na$h5&Y@;?);H7_?7D^$Cy&j`EjZYYBh~ z+*%gv?k~wpwV`qF2OZl;?%BJ=e~uY$tRCCfKp;6`tk?Nc+| z^7Q+9;pM~a!dh1ZjKKamO6n+MdF} z+Rm^CijX)A0K3ROnIPdIQAx&!>C(8&XPAY(KY|k-S`z9ayUjT~3h6G^oak!v z{JN(}<^`dI6FpaAG}B1UFnRbp&3LEcK%;P2I&o+|jE9AwuhMSsG$meCFsF=ykQhuu z)Qqpxyj+?g-D3oAy=+2sWtel0N8kowazDO*{FPdi_6G z1U7-9+d50vbpCfmab@xs30nAM)B&WHurQW-oG3g_)zhk1(pnT+|I!i?0#uND5qqbx zyo=Pinl684B^C#Yj>uAo0xB1re(Mj%5yYd6t36w{v3j1A)Q?FAV!|H;QYlnmH;uVg zC9Tx<#3V*a;nUi~+V;7`=Hb)x^3>Jg4bX?p8i*hz0&nLKy-XEebt4IdG0N-mkK}ci zG`Pqwt57})>N5rJgoQrj=E7o~tPP_E> zhw_AI*rsEd!dx!buMgs~TKrs6J8eyxH4Jys5Fp4>iQKieaaG~QP#kA_;=M>WsSG8Zl@(_rl`3Nn}Js?Gmp zc`gL+Rk4QLM;loi=t2x5Hw3se9IUqll6#8MV-U$mg=bDvaJYrrurNydotR6}U_Yp- zLyClRWQ%$);^?BuBdij}1t{Mu#$Rod7`(OU-pIG9+*sZP1sd^+lZ;J=aPIm;USwiY zkYytP4p47SoirUzVk9?ul5m4L?zqNM8`9ctpX$M%sS9QTODK9ZH5ftnftgpso;u9f zaY3mN)b0cnubJBj$#0FMqqYeD{PN-=3&VybW3PY)7yCU^hF~UPaJm)&^3US;6%i>3 zth^Nd*4?1PVw1{uM=p<1K?JEm1ezU!19Xy=K7@~5`K*ceunP%v;BBbXU`1u+zH*%* zR(}qO!H^J7Lu{)t&y3;Q{kLhgU(nbdzI^Mncc>_;9LgT`%Jg)UBM+qVd;VorC_K^;<@5@qYoZWei4fgr*d`Cb=&=p$*vnpv z#72Nx@l=+=x3N3>ML1)8tJQDSaU~Ei2{#7~ouZI9QP9wrZqA>2PgR`Arcc-B=)tQA z$g@Ay1=pARW`?+M$!0)fptmFqhK)>$l`V`wGA;9(!uU>0ufUUKL|da+PDAR7FSRb& z1BKxapUnetnZ=V3-NZo-|F~%3h{fSxx)Zn$LpEzg2wXCg9nRPeJia336J2o|<9k`N zWX84G?qT!wx#szt`}yMeW^LoMISwS#@g|Vng6B8AwWCFCByKtZkoa3e2{pajmbLSX zC2bZ0@+&O=+3%@J(EFLl1CrWy``A72VZy9aerCeRT<+B1?VqzJjYV*LGZFZp@u(< zZ3P26xLhL}fyRPxMTrnG%~=Y#H((^nbnWyD@jO3uwxa3^z?~tev((v5T}K z+SKnkT6fO&S@TSBPB-IR{qH8SBVdYS*>Sn6mL#}48Bpa$Bo>*m$y%|C1yg(UVN+1FUk)!{-6OV1yV2*T&dcgwQzQ;Sk6jeqWoDa}OjT}HAG1b@Z85@FKG&n5pV%~= z=k@~fOO_sPNBl;8Dv^rIApHH_D*ll%c!SfyZKpo<>Ac%F`s~xs$c(!kmvUJxx0jVv zVTt8yMAdTUJxde)@eH9%ygU)8fymrow^#D-b)JaqJkX`;AbhEXWaBfn>a*3J`wPrW zHoO=8uj2=imMI}(Dzkkhj23vcHOn-j_o4YAuw+c&tFI9MT&{o`*kT&AL#(Wav1wVK z^PNFLgefEFw`7}xb~P@tUt>Ae@;cV(@r12R7k!k>{oQ8*_#PZS&vodz%t_i;`22U_ zI#2yZKT2Mn1nb6EGx2>&pw!%=Uq*4La(X}YsBZb!q*Tmc`#&jTUqq!~yH!w9r?2<> z%!~a29R;;pp=&R-LFG~7(Yv_jFH?k+%g8k=$$tH&oEsQiizYtVs*VuNMtAkOC)B*v zM6SR$@{99P4sX@cR0;0zLKx$eQ#bwh6o-B7a0IsQ5B(el_Jv1H$?+UX2ce!X!vfqc z|2wfr#(~ZpvuZarHD;6%y>>leJdg zcqlh{%6G{orW)mGr*;=OQtSd+AHYo)xyla0Fux7AFFVo-#m)_v!a;_;Gz=C*IoM|$^xThAJl*FH9>VnX%4xK$cX-@`35U;3}2tlWRHs{T5C zM@Z$y6ALbbw=)`15R29Gz=?{ETNm%{|MtD=Ik%us=gZP_D`fB|d#{*`c z0?z19y1>tl?(~E4HGdu&+D{{+dqt?uZUV0+K!`*m<)zff2S5aNl=t@{n_4?CnykC_ z&_Cmh{`S@s$N24^shZ97wS$v@>8w+4*c# zx*9LcHsv#rEAi$esHWb1I|NIfmTf%0U_i346-QCHu4zuMZZxeSRn(dV;Iy{4NInZ! z0CClX|F-pKl%zWycaDM*8z=rhA9K5#d*;pcrOuG?w6kbB)lquh#wcb*pcJ-V%eA1% z(9N4^#GvE3IUuiS>xIO#A#rE@D@pNOMXq-fS&_w@zvA zXCjBo)_+e6FR{LJr6LXP%250$OA?#M31);XSkP1GuM%S-#JrR)bb%tKNq4Hj1LV&X zNS@5w#L3K{KKU>9mNr**0uKgEx@SMM_V+?$a{Z=T@bYn-=k?MAl==yHT@XKd+RIkC z&%nr@W5vI!;=TFxQ?EO_ll}4H1M1w<{mN$3b5P3?xSZpBH2T+y%`Q)Pe0>dMeun4H z%l}?R(obY2F>iR>k`~l|pNi>Vz`l{bZ(BXKc!6(TjD$?Mj>e#7CT0GeVf76SfQ1Yj z?{Lks?7Caw)$cZh!Gny#~qJ zi})_2`Lf6$G=BrboIWyDO;{4d&537Y<<@=B&+Ps&Ji0x{@$SkL-18ZuQlqjxcQM&d zc2_W9fajVoZ4M-^1EI!Ig)i!Fx{bPVaCLo@h{jKdktU=^T6#|_u8O8xlkvwJ(`H@y=EqvElf~T z?7q2K_z{_RK_PX6i%b-X(ninLtB8)nrrkDSefLJ(f>q8+zLdV}_m3SVIEcJ)VgPC z-h6UPzuhSVf1kn~$b(m5-TQU}VpO1lEE7#_AIld$61u8WJ#hFlK@u4-ua$e9he;`E z%^hSf;W_(lQ^JPZ3#GHkl63Bz4@hiwbkVtS_(g=OF5ysqRNJc7teTy($?9*CEbDW4 zesohv11d#0JvWddK;$ruX?+jq3I6B2Bl0>dn_liy+%nw8&WCRWICjw$OFwR@f-14r ze{T!l{^PnbMdb=c(?Gh{;r1ud))*4jWqTTV3g3`P9FH~J#eM{LoPGTW8rrw zRLDfU2QOYyz~dhv7w>~UxNPcjG?qD#KnRPkuumQLJzfPN$!Am< z39w4i1!FkUia`iX+s+6<^Y@Z6W@M$ah-?IXYEDfb>?3Xl<}Nq)T{m^}ypO|U_MD&; zPJizy=3I^(_9-RAY}KcDq5sTkgg&Y*cQ?LAn$ZtKi;a)&tW5md&Z*DpTLSkM-LU>F zEo5xKTfKF|caFg5T_;MqNcraNvfu5$9nKVej0k&+z@~!-j-v6|he>9+d**xFQT#H8 zS?GG};nCWaw?Fz_eUBG!L9$11ex@zz^N);;Xdo3HX1XW=-%XjeH;7)&Z`rM>i?-(v zv)RI-{q@5A@asJBXOZQ$W>+K#VRH)R?Mc4#t3(v8x{sv2$(055Sg5dq=eBpHXDufT zzcK2nxAe)t&ixi0c8Qu=9B$iwM9jt7?T9j(M27Nf?!f&syvti;ze}D9O8U?iJC19> zTKlGWcnSJK11oVF-6?3@_;6lDrukw;8)y z9L88Zt`%gH!7+r{Kc(as`)te+F)3{N(yxE@z9ql}&3(^uDK^)hZc?fWW~gAgV~CXc z_9ZTuVd?w#R#+^C)yTM|L_p`pmA1umgtueLSHuMo4pHur5hU|+z1m33+*PQYCg#)A zZp8J!?a>Y2ElOf%dZcd?t^fSku+mb4TlUW*f=vR92}r!54Y*3=*1ghm8MZk3_IY@q zZFq#Z&(gIigs_#d+!Q=WVAtF1Y$z$1*+K(EmYZJ!UWmQoDExa!)*5zFZ?B(WxX7mmj+IY+~~sPnf~9I8KjF~5BRfKz0c$!X(X zY#=(lnhBRYaKC@3HvQ8d|GRdKUuWPCy9@FZQ7`T2S3pF4RifBDcjji~PtW>z1tcJ; z-W5)0(002aKq&&^Uq4zL?TfsFSDpL)&rWO|w|rxaPZpYUn6)myxeL-lMoj@GTdYz9 z>C6IKH7kb`%JWc0;=tKC#1&)By^1xn^%n~lWKQ#_A%mVDRuHGv!9l@wE)*=zy9}kbK_Og*!tL|9d z-oI?|yn4q5Dw}Q+JCpXEO zz4Gsr$A>fO{2ASaUvvwMQ!j8|a@gdJiQfRr=s*v0=$ps0+gi`(qZ=J|@t*afB@tWe z=$(P3gV%O8`sB`2*cSerk!MOs#H^^C2v$3Aj>HX;UYfH8+pA6iW7wv|d51T(rWS9X zTZg@8zs6+UylVA9FQ+zInc{!{dRW((9w}J~ZC-B$0RtLf_kjY?emvQrxYwNN@>qQEV<(V<(LgO5<^nyt4DL-$Xi~TIT$YQAy6SGX5 zE3;O-=nk+>o?s~fxlwq+>JP|U1ak4Xi+*62d$^HEB0$rki;`MW4%v`TL)o*$#OCf+ zdE6-&QkLoLeQy@nKV#M!EUvG=u>S$GktnOtXpxr5=Wm%EZdKirM)SLL1o8{vbcFcx z@x|>I_zK{gKLjDW_JA&r*%ue-WcR0d#q@t~zB-hWqe?4_~cN}mP^ zI3B*xUv~WJc3Exg`Kn-$V--Kb({(pr;MGEeZ~TEITg}Qsgftkp@{(z@QBK>g;BzY) z+lu6|K{Q6nDHU7B($C~4e=3uUyZaO}Q7plmdPej52>msLokvNR%>1B9ta5U9DFH!V zndBRy*79L6?^oQxam+AQ*Y+vCk_={w?00GmsJDhmcYFUcyt3<5|Ed2#Wo1`_q{!@E zV4=Cy^Zj^?AWi27CNguQ)MY_tDK#(xhr7(e=cl#V;=aG^hj*_WHpE$pa>V)@YTM+# z9_)Dj-SysnRUaz0$?Aiws$@fSC2m?@0Q0HRjRvV&mmA;;a}WE;1X-k1CXg z8K10Ml_KEaw5=tU2cEuW>CZgu--~SIK)qr0j99Ekfhks9X8Lqa7m)VKAp!T9a=V>A(b!$&XK(rr6!Azk|-3M9oH^@o= zn4#t#Nzf?r7C-p=>HUT+XFPq;0){=%*o-iOb9W!?TU@#phYI_;S+aM!a zXRT>21jlYa2X4m?HAny6+%L7G)t%C8hsX>IkAA{xQwk`ChBXioh>%ftUOG#JakKcG zElp?8mK30_`X4kC1zhO+fO=z_S|t7n_bUfoWtBr@g1`F*RpABe#0z&ZBZ)ae@3ZLq z$ift0Jgx_YOI*YX1jfc-{0E)J`IEKC7${ja77gTqbA?t)Hv8$ zvo#6pFj!1W2L9NlkxA#>+**_&j)|%x8}$j;tvCsH)9Zu`8n)vxfHN0#D;j7vug>wy zCd}5G{``FTRvzcXw4>L75r=E*{mF#wYk5y008vbR6T7`KFWE^sX3FqWtphgr{-~tf@jcDIlDjfwIPYmSX(n^ zw2_wi*53*(+^!!%t41pdE4QXfZw}ye!)(1U$Mbt~DV&3A-P#IlrLY!x*e0i&L#l7X zLH1Bl&!!O-V?W%U_1?kLxof1J|CI4OtUP2G1g_S(k~xCcgW_ANx7B_1l=pOiG93}d z$TTVjhy{t@$Q|a467HJ$s$|HH^+6O+W~8xH02* z16?Duy6I|-E|fa+0SjYacl+!8={q7vBS{Wnx~N6RZ?Eb+5Y692p=fn_*!XVWiGa>W z=NA;9#1ONX*M*9RKj*&tDRMU1d$erGkLorkl$Qwm7h^Xwesh{}sFb4bRlQ7dyAhL~ z@p1B0$MJny={_vMh2C)ZEd@mX$A20Qz|Vvt&Ro2e=xj={rT3V{`nVJi@Pf`;x1n`KyFZg$8qlYmK=yl`xx`{ z^*+Z5XtBA~6JHt~0e#M3pe*Ee?Fj2Rhv2Hg^K6-+cg!nW$S0wn8tZUp2`txE zZnxhpQW>^9El$@E{Jt!}83^@OYsKHd8=#vvb)N3NRh;fCIjEMa`kBekVENT=H3fIP zp`;|M!*g!y&OH4#Q?JE`B+)+gS^#taVyY3x@==MiLs@L&~b z3bZR4=a!i`bqMQ~Zj@#hwNm;vO%qHKs~*~?@h;=XZ!)J)Z?WsfDv_QkdjfE$-rsI@ zf*~}wo@kuBM7pZYi4J&4bZXNZ5`*HjqcvrZkeYqU>E%!UahSDAZ=<2%Yj+=`%*Zc7 z1#o*AcXdN$u12_x9;J7Lyf>dily`8at8O;tAQ1cRbI=z#`Ib>^c&P`~i&SN^dx05R`!KZY&uXBO~F^$nB2R%5Br zZ;q8r-77eaq`&f1x*c*lNXoG~CTRoh?8w3H=aEH&lH9HfFJv9ZntpS6k34_!)Udku zYb*$R=q)Y{gs4Nu(_G2;re8hq+a@apXDXX43o2|jp?moNJP9?~Jb&m`o}zNeoS@bL0Z9Y7R0TLn_`NYond{Y$ z_p6|>;WY|06TjC+vN1gv3);Duj6kpKaaiqKAyQ!{r@3>}Q{(wntdH7%bXw_Sr&tMe z`&b#%+!}$?1C7i!kyExZ;2(tsXFdxlTWoowFVo2wR;cGi6v9nJ5HldTLZlkog)=g; z2FffJ?BL|umu&0Q;zP41#^=_p+uzB_KvV+Po^ja;eAlrIN!~L|5wgQH2^PR58HtV# z9@L{^D-2b4J3D1r@11ZH9z-H3)bvAxm~g~&4`3w2S0ln>mJ3<4@n3@SyC^!D$xv`& z>NI64t35yD=u9zVN6vtgdq`UWpx%5l2MQPpv_3f$zLF++o8u`fQo6Q0CV7%U$;nX~ zYA~feqKXP@%Kq}%oR72!Ji^?3n&@y*2*oO({mP z{~r}#qIVIK1noE2*70O#yg5O$8d^;fU}yVc zmFVB83CbJmiZC|;zG}Ox<@ml*l1 zp7#KqHAhqL7YyJy&#Z1iOBX-T5xlETi5Zs*SE5Can;s#n;Y77I^pk{PGVZ=LLPiaH zJMD1fV7v3s7@<(p{3)#?6@2o~CX(J;eYk`M4JCf2nAL0A!M_+#J`mPHl+^L8(F?pX zTN9mminor`Y}@VBBt&4-_TGs(_Hc{BdofceBu+mncrlK@51;7G*Zxfv09*Z!j{{l4 zFx#-55fAqs?~ae8VKbGRa@pgKK)KQ7&AZKW0{AduQqetmg9#s|6fuqGkBJ_KqB5b} zBQk?uCd9I9sTgJ@KZk|V$NQXfSoOZjv2!$}75tTio5^wUPH!&xV;NmYb4jllP`;S| zmk*zWD%-MR?|F6{QN^LD!l5ES0av}gapZ4~uW-8F zr2P<=Zo*b;sVvwKPSWRS#i-zlJyxY45_RWKO5jNsfls#3fD~Hns5+lXU--r?4H5O% zmi|&$ez__lGA%?gP#_=YX0Opeh^)#dWKKp!){gHJ?c=(HB7?7ofTRC zZb}0Y4a9e0B`-;t^L=OnHn}$Kgu%$k?LJM)(4!|U-N+sM=new&|2FR~pk__m+@6;0 zye=QwujlR@=Z(qn#6_{G&+|M1&ZFiGFj5<*MTolTFbIRB1%biT9I{9f2R5 zYW2m!V%pH4koX2%!WPdSNZ+9B=TZXWxA8)>QyFQF@htR?uIS}?0bi#S#7E?D^ifRu$SqjW zkkDArn3z6Uy{9!*+GX7+p68MM!AlfghsWV7Ja<()fhR7N7$5AJf(Wb73O|eLORS%3 z7%cwbiU`aLv?6g!nE3Qk)u^7l{{{Z1dMnwA#nTDaWZ|pFbmer(sN)w;eGGj>qB&8R9<0@aR z4UlVVC&Xck9vT`Bmaup|#QW86P#y~&QygpRO#`e7{~Z@D2Pa8Hz(@S=2Qcqyb!^B0 z+hobpVl<4`p`W;{$->>FVMr#pVZxj?G$xpnh{v~G80bwp<-~xO9R-RPf$O7&A^32W zPK38S4s%GR8$unx|WR&6#a%qzmH9)b&5NkhaAbC*f=Ug%K%ULYCNFgkeBf=Ti z6r`9HAcR^{L$~*5(!vk}*kfq8qs#xUDqX<&3-ewfYUqxdt78d`0s_kJ#Pb{#E&XX-!);(U z(!uw6+@L5`C!$ouL`h|{Ka;PW7sQf}?=ug;y9E#nvZ%rNGA94N%bCaD-mhoPzT`Q_ zFz{yiYLs#btTCkNwNtD=HenHLl=Ng^c3X7A6@jGungn4o9r!N-o7;$g6I3?0S-6q7 zVv^TsSk>@fkfG3jJsm}abr$v)7aKkC&iL)D(6Mche4kCVX?)Wkr9hOSCfeTHbd#R7 z%~R{l)pHA8xdxc1O{?WaPmAwSECEHjW~F#%;SuuM{tgfCO`2T}J~Q~9mVXKDBo9@tOU1!3X0VP z=&PTXjYS4@qsF8p?iI{cZUWBhhD16hZ{R>_T$D*B__CY*X$SienfsB1&|$+z0`TFU zW$RY@sa53X@*7)x53Z}r0F$=kT7L@D|LCVNB#&%nU11}KE5-+qAQ4^v?H0uUqua^K zFC0$G2?q2osM6ugU^N^WX@Gr~BapK)%%P&E!Vd*W=~hr3K%?8wMQ6T!Ea%98HY{4k zK}5Od;{AJI-Gg!_8#gl*IrAv3e730LhW{^1rRY5kuSz$he;5oO!HW!(HTLF_5D`fY zlL^N%jy8phhl{JA(UYvj61uJ}st?y^R>^jhpOW76zD@{!ZNstXgOk7;;8njL9-_Rm ze}=s`^K>d>XO}6fneSEe6x=^u5`^^XI51eClLR0oBYk|O-r43*HOwj!AihGw>L}YK zNr1Fs$<@a1`~_r%z%1=^3-u9KdGda8!54#>4ez+?jU6giUid2+s&4=GM>sue_+xLv zrqt+Lf~myl`_q-JayTv`lwz`p@l+B=yN%X_{iYctL0n)dcS4v=dV=GJG&m8#QNaQi z^_2`vO*2KgRt-)YZynYW$Q77sY74V_Nb0w|LEN?lwX&AcfHa#bmKLayj^@~p3+?}q z8YM@D65^+wVV5-93t?Yr-v5jvxoLTRzEXeWx zQdg^?^xNfjple;|J(l!58sixU;GL7uHfGO*z|PsO{EdZ1x~IwsO-$e98sW!hHhg5F zfAU7AHsUzT#gMWCh7$VhAI&&O0Pv;FEp`vC6nerH-^f-FS2)EkVkdt;Y}%&gfJAiX ziyXx(*^x7`n=|{y>{P4J1?^&zIW|qMJ=w(@x%<8V(HhxKUow4` zHpZZ*9X3o%ZIbj!NKDF^`*P|p?i7YwA-?q-QdxN#dNwPQFqNyovWVY)>2AM);?iBD z8)J(m5KoBSrh#ZL5jA#IcyyqsF3blac$REc{nEvS&SX!v}Z4%($mi1 zwchY96Ds1HCmlKY4!Yhv{O!&=hL~dl&ZsaGppL44@UDf;Tq1yfLk#tyyUcWGj_^!}<3bitStrdN8)qMyZ`^XFKyifA-Z0PBsQN9z-F1VRAzug~nf zzHnLGxX)_Lf9zxyUq5@POKLHhvM7XC@U!4U(v4Uux;6r(N2hXeV6C*`HBnn&ttFbp=inU+NT-eMvH#9CQRb2Q zF*DGDsm220xYPR@8{m$>_0;DO^bbQuS$X3{9G?9wIP+nHqKbzmAb{BsA9^^@capQ? zt3DMxJrP*@K_WB+r~NUTuQ#8yw?83fhLnuX-40Xue&sD=Z@<7O2^iI8A1k?qHQl_4 zQjp@N95$((L8tl@iqjo}@*QUWaW0bH_d`>6(;Ayltb1EQ47gb{8dFC@>!OKjk*biG(_|hbY2vsp2 zI1jR@7_!2s6kG}wAZD-h86MlZT<(w8XnF2)sYA>KF}-su6Gw+r6py(GJ4b!MjB|Om z*b_+&@yrRIE>L6xd4oDw!XOg6D3Qapjuq-*Q*7|fU5%Yvtks+~H%3MIg{A8rabNcG z@^_*9G}IZ#wS)QgOm!g9F&XgzR~8|U#y zPvqq>@malMsquqQey;%WWN>SWJGIw~&vHmaEXFeoLY+xRc%$0IDf-I=SF-r1e^mDZ z`Tx{s|DMjO=)EoGo8%=NN4_9>XS%u1;oPcJDioUkr37rWX(kT)CliE2+2Y>*DXn8q zw;6lFg$DeIk8U`JZVf&ns2Pikm42=EFibJjH+I_y`5W{HVQ%WWy#AAlO8hp~Hu^b* zOy9cd4u5}tdK_fWxU06j*g)8kQwd<@HHbL?tTur>))SM_N);a(X$-GqV~c6SG?+Pw`m z%nK%vdY8m2E9+RG?>1e0U3gMUp2r856LQf_u#sX}>O)jJ*`@G$Pf`{TU$Y-k1+*{y znp$c-^Yjn#Lc2K0w#R|OR^L}^sHGr!695)zAyI&hN8!KcvEi37{1 z+b@pDtsC4m&;VrAsc}-TjlG`@2je5jvpM@xmmiTYeQZ3pg7>ezB{q3>7g}2`uI^v4 zb}R{g@5S9A(LuDgj&JG>AIjuMOU<@Ja60Sx@RV_-F3!oiki^?In-6a=5>qYk?Ld_Y zw;Zn@iSLO_8^;@Z+T>nayzIg=x1?e6;+2{a_6;zUu7f8WxL`FS#pYFvvPpoFXbomC zF${B|tLec#V%_6+7&`8TnAn1CD$0V8q7n)X;~2|iW|EEQUR(bad|t2)pZ@m+iTj~& zhK4yDdu0pGzD(gCrLjEt9ALat4*pY&xzs^0d-f+M`MYmNlLp{Q?Y#OHUX-SX-V1#( zK8N>&$i%Me@I|-KU6$>;_cG{V(v0 z4~I&Hp7;|p`Gqzx&|9K0C@h1%Y^b@GLM$)#D*0%ok>Gji1#+X3O8Hc;D-Q<#c@*By zDL`=F9tHUIt$wmtRs{9sQ0W^yXt^?Z8)j~}9EG@C4IvnsVK1;?j)#=3Gb?@2U2Zac zETYu*IvW21^LpTs$c3MIXEJ!u`LJ?AHgfw#g)+B>@i7Mds;Uc|m9Tl`iW@c+aa3nf zMWolE>tmoRr8^&XhxHItLI>jWMckTJsnY8kp5HL83Nh7sjNzRpeDhZH#(;{JH%+`i z0B!}8l|i!g&*su+r>`V*{}>quGko0sNg6sqQ88zP0t_Cc>m(?sl~3gt%+yNzv&PvA zgZ}>sZ5Q-!@+{p-d|JAHd?Ot^b}OO%hkDoR0M(T=lyEwRR9)#I?iX!1a+GnEux*HYD_{r*j_U*MG0=z8<=H>xGj=!wYuFfR60@((hO({%W3FjqbsD zl%Qw$z#~*#^sNp|~6r4Eg>kE2@3jtlbZp*UR*G_OHNAMHxNPY!%;ltxA_>gn+ zTaY;)@M&q`{^oPQQ)`E*zg?tvU4)|ljlkHy3EdrhzU2&oy+Dim=t5f_r$ug6?~`Eu zW~|EybV`JW^eD?ZMiq`+o_Xb;`-j=Z`7#Dja!Rg2coBM8FGj%+oy}h5H+|KQX*++1Vzxb+t;a9XWA3z> z6uB>`fTPZ@7@FT&Ua?Z^x@>%K?`7cN>ylfG1zc8c_YN*8jE5hax}fNSWc*9WaFcE* z?9(#$f9&*zC)^g`_Le|KK4yOnE#D+cUn%8onvy!P`Y!wc`R zu~E|OhimfbNM}qB?mWZjy80v4lC;1-TkF7d-FqjK-$ON?`o^I;{++kqB~1;<%9A*o z9qrHJzu0={yH6Wp8Bc?>2$(=y3tT-5*B@iB#!$^WopJCBFhNG+-qop;!|LgqvH58;Y?l#gSq^2z->nGc@ z%&af+53N1u4U3E+m)sn$1j~FN@Fk<(?Y0TOv=v9h zdMM-&zrIW&i-8&oPQ<&qQq36o1zI(J4`8`%XS(F8VrlC!eQTL3AmFV*CQrfSkOXdO zybQani22loWCcEuY=0(Nxfpznn0~rF8H~T0?J@jI$e#8fm`Y7yqEHx#h#dwwSBn07 z&fq2US4wT>CIC(IDNsRxd9_DRa9)0QDEovVwy&(Y!peHO=7R-(U>5wC?ZAN(tth9W^3df)CI!J$|)v(~g^JriG^{fuTt4;XGH-XFg`n{)vgK7P=@rbh>HBjWX z{e$KJ1{%JT7e*CZxi#d8ZSS}h!H8>8nfc=`87yX5lQfS!zxaZ<3s2lO^_Y#;BhVEe zoI&?^pjQx=ovSwA>refnVyG>M@{-z&IUni!Mbz(Ix$e!6OQFZwuSiV;PXy-7k<;@Q z^-y)cRA5Q|X_D)f=G6`Hqlam>b?wmI=Lyuk5CH-7no{kc3rzeB+@6c00j^n(Ze}x!6PQm@R%b1}^5?A(`!j2+$9)1GFHe zxv(%Q%J~klLsLCrzQ%3vLz`tw(us>v3#a9r^(&5FqrmAc>k1zY6emPS30Jn17v*JsMl zU&~c&B7K6yJjdG+O5S)UuH8cHw_+ADU5n)3d$t$){$S2Agi00~o^F z1&X#by;jr$nGskX`*;%LBKi1v-u$_0ud^$AbRK}F+JOoy)Y|`g^3GJdj|;*2;36C{ z@=QATT(x^R=sjG_N6|#+qT_C%sjsdaJD{bSSa1N#Q1;v-rv^xbsJSFZ)aFLd{OQ8f z^R{oro?3ywAOh*CqMqEA;(t=}%EvqVdTpptjJBRCN@bIHn0N!A=uFmF%uabSs?dUr{Qok11Jn8~OhbeyU8GDL5kT>Q(X99Xqf6|s@`2|N3Q z99Oiy?+={*I=jMR^T*{KYu)Nu#I6Zs6KylkRUSV!vTR?G!5Wra7Q!J{30~ZBbeI;l z0Hh+a`Y??@s>G~c8ebaZnS<&x795^2|KP;is)sQ!RI>mU64?4c51n*bLJKK(h+VTacuQWWT`>F#yWYRxZs z1B>UUzMBu5Qa1to9d5H>DV*MP=z--o5j*urJI$KJZ^+Pk%cBsWikL@#B3fp!;VQ>i zp@;3$E6Uo_>%Y6!2AXt!x1_RtcHAU}Ugr*MMh%4ltWuzxA@RWg8Aa&P$9iiH4F4aR z!l$+{$JhDJS_BJTdlRgK7ve%(HmBvE+ISM4PKr*9W77Vwrn3yIs%hKs+O)JtHwXqT zB_dst(%sUHwA7*{1wlekO1h=H1VI65q+5~hu5b2pyx$M`p#p2Knwk4PuXB?45n@je z$+jF!kqQ&p2oASYF+tQs3Bbtz`=tIhMqP7!o#4@3KW~uOjfr2Z)X9-aW>q-{Av_ox zgQWFrp!dYDtu(OR;Gg0K6Aa0+vnaCoZtPZBx$Rp$gXmZCkH>YZVsEo4rpeNWwftZ> z%Zt;RGv&gq%4b3>L=*?o0poX`YqPI5u)9g&zWgN>^W<}= z#G89Pd4FGAR>9i027k1P6Y)2B#4%Syh!6&2SWEBkKqZOew1;^P$EpsQ8u@ac_@4V8a^Tk5s#Dz>cuH1i${_Uw+QJNIDW1?8&j3>)B}{oejOxO%L%^aLygB^& z0GjOkN?KiS{kNLbzA600H)6yz0hMClQ26AhXFS~O!|=@z9bBfxFt%b9axxHan;oc- z!zG6T$!T^po4UG@24z2LXQ---*$VDdOhBFXEc!kdj_;8|jO9ct{krbm*JPKI)dft* z$6wFb&<7MId9SNmz1wx;FRm&tk})S59qSK!FrZ01$cLOOdqRRos+#dBZ4GI_9*dhG zZLI@7>{B%QiQmjtMuR&P06xXPwGbhLcTw<6RPW&#oW+~zom=a))Uw#t@oCBa4T+oH zp)YU@+7o|CXazg}UoTR8RMQIMD>|${uJdlF??2}Qxv4LCWBmFyRIUhn55T1@m>GK(E80;CEC>@!Gj?AA4dqS-QJ4(B z`^%FCE$me8WDt!OUXC;PLip#MLEBe;a$FYQAEEui6_v^yVY!bAQ}xV( z<&%JKFu{<2iAA!=Y!hy{|I^4TS#X+tPOS6GD-UbWD#@!E5K}Hob>CXUi*2j;VYslk zIXX~lY3RNl>ww& zgc7ykY(lr)6e)0ErV@;E_tBf!6#fhy$ol5wva+DZ5+v@+o(K=H5e|eB#7sjEUP^wE zg@O~){;lhYllOCYzy)=P_9T#RJ6Z7h9qZ2X?!0;Fdy~Jt?!K8t`{w57$M2Afit?7K zZ$4ubI8+4JbICEg{?$#~OwR5Ow?O1!O zqJUupkFWah`Z$I-I~f#x?J|oHwP4riO%#|2dgT~N4}J1qjw_JN-i03#6tFzX+~%ZK zPj2->kj+XpJ4o;2+=n^VsCo-@~Y9#%IpAC)!xA%R`}kW3ro%Dol?JSRXAYa81B!pO*_bl z6YIb2M8=znC}Y*s*VOx1=deGrhCKKcLrAHl`a%rvvb|vandlbVJYSM*NoWubKdWHA z(yzF@mx{4JIV3d^q#PXkRhP2cqL1s*vNG&~E~pGNi0BSZ?kGWvy7l#4)a>=tey~n@ zA^jjn(uW3>Nu^;z4?n_%ntMQ)fp2gY7ePm+s?6^NrXJH4x-}%pjcg#BK`DbxI6t9m zb>USXR~r$4>%SnCUdfStPo?jtID&2KaM5RtP0CKrwA~Q^9g<29)ZI3^z?A$CxC<CiezL)O;kr7`x}CG*TxBsw;M`Kg8o}*_)owz;f3- zoWSGdjoj?keNvP;$Dn|~kj!BMnRG%C+Tc`@eTRG4Q(YoERo{jtqyxI7q3(evBzhy| z_$c2|2#ts%OVD?DrXzFo`Z1Qa)Fb$mBDs4CF3!&)&e69MI?3A#1i` z=QYp(S`yvvVo>$N0y%cmo3+iE=E!Wuc9p}&tTX?Jsv9G^uk#*gMSmbsQ;-r3c|Nh? z*B+JXvd>|CM*LTj^Qz%WLzXjZo%Z0=A1fp2k!w4*jwQ!v`ZL?d%O>s1XaQp@fB#VR zL`Rne8)_l|`_PsVk`B8isr2VFc2U*unelvUM~7xJt`N6V z)Wj7HrN<9yXY^{x3|}ed+F^C|n>p_LZh5q<^bIF@23P*d%+k$v;LV zkKVn!o`)l^eIYNu_MSVzc+ilF{+fE5o&mM{KpzFT2gpcjYfy7uZ-w&nMiREMBWUK0 zYc9B@fl=mfN*KX(>}FR#eqKy*W{q(nW2fewtff^x!t_^pHDr$2sAyR=k6zM7w-W`{ zsN8)Tvn}02LiVn9(m_q*a$r|Gz(Sl#?0KScH$3ZajA}ZsWR;~V4Dlkh3@glQ?;?ws zg_)LVLkQD8@+7gjj|vNQ4kPDeEUTIX4-={IC8gIvsb&6)t>7& zy~SfGeOv5l&}Kpv%Tb%S7pZ*gZ?Uk^b0d7^q9fu z+n=!xs+fmIELD9HVq%Is&#bRUkp23T-k7F7 zm&-w@axj1Hob0sGrK{TV7u0mU&S8+02Hn{^q6Yp$q?%J-C@*-)J7iXDW)tCzp{QcJ zC250)rUM^A9Kv~yWTg~3`9Fw@%z^__Ii2tE zVe_07m`Z(b8G(IV4v5J=iBIc%()3Yu2{&5*NZ#*%6~1p!Lxs9Hto<9-#j%|7%70c} z*`IQI`Tp;cB#kOn!R={POX~$jM&}8KN9^YyKoU z{`od|BE4;Gq>*Bdv|d?WFi2i*-6frf;BuzEIO5yWjq3eM>W`rkTw7Ice#!P6jM}p<15)~9$_CP*Yh?Dv5(P`dRANsQh_!Y^<0PgKs2rbqaGZid z%y>cKYH3Ql&WnWk!pG~HWQDzC2mPU-B~gG}(21ivu$O6DEyV>wID>kXlOhT&+tYFr zfb$!>wD|!?y4)huytSu=TCyF?5NZX&Gn0lkHR&BO_RdgC0E=e0>w%_VFV|1L)g zrlN))b&Bq!+3=*{5<#nX1H=Q9U)qczWRO4iGeTh=8EX0L?s8O%4JM`ks;K7RB5ZcT zqJeCWOy7n!d=Awx8EdiV6@|?^kxxYq`el^4$c68H;$t86@++=S`-Q*_dvPTYU(a_m z0kWTxyxaX&Z@G9r0G$Zvr<_f;@NCbW8%DKq9`j5DUF*9W$nq}ctKbVbuZOho#tjv? zoNq+7=i?BZH6HrxG}=_gys?2-c>*GG+WxKE_(`LX+M${JKn)nXbbQ`RT55~~iP2}a zqsHDYTM}s4<92sGn^xd8(M3Y>pmfJOsX!Cb=&`v2Uy;@I(L`VT%@Z8xtRfiv8kKD_ z0g;axpHVamw*M21LQE?wDL!nECxFfm|Nf;cZxXuThM@q^!QZri&D<*vKRMOn@hs66 zB#xmTWIAt!I$7H1Y*`%EdILbX&eP6degE)4>9-O8ug-KqbVDdb+-4xNoMW9W4Bst@ zjZ|+9A?6R57va-AYM<))dZ0Uu@jrID)!8-mX^#BIK4uhHnS_{e5Q)p^^sVFl%oe_t zO9U0s`gwe5s)xtMOI34`_6-pW3Cge+=v(W-DCPG$(T(mb`~H33+KA5Pr7AjG%Wy!f z1JVCMdP|h3lc!5tTda)dmZyNwMpuCuCxTK(miTFjg;=n{!)YAsCIG{z8g3phfV{J( zr++L!x7fVA%f2}#DB>E#byy=5^{;XMp*UqDqTu(aNgDV%*a-St5O(J=^f|A043$Ja zz{)qSRhWADDq3P*3G5c^fq}pDFo10D6{o;rlr1L-q_Y1Pv&lCqS=v|!6XH6|#9e<6 z4(>^66!2a=z>`Qo{U@svT-L@!ZI*??fubOSn#6!qKBfDtF6Qi9iGX_3ySCdc7~q}t z6!r9WOKVmH|8P}j1EMf|0IzL3`BtUuk?m;4?&Xhhn%88|;sxt>{k2>FoR5J&31bK& z_ytC8?$elHh?;eLs3J9c3NmSPe6Yf4f8cgX2Cm+xoZtt!3b+Q?Q{R6C#Z{9-m87L=xAi9MuMr%E zLq;l-?5F_;J;sx(=Qe)s6-^g?O`LQ~y+13+5t-qTA_pedi4-b1!=XEjC>O_PYbM}0 z$+kiC5kkFj`HuUZ05Q<8I5uY!NJE`pD_}Fg#~;jZ>>dzH%PnyK2d3pz)1{B-m2dg(z^UiO-cm1+Nk%12 z5IsE=;7G6ST1zB|edJSULicigkjgd)Su>lPTkyPU_8kS*#M-Y)nq38)<0dMrxwKrb z`%K91cj)2Yk+@+J@Eb;18l@-=X&9z>f#i>8bJw3ENa2SFQevklDARhRUgKL^hG@Sj zKSkrQKj^d`fQV&>bHRsgign4;|Jjt6uX(?hu^!Ba9)kVP1kJvn4b~55&2|OBp^koekGpE`}9!FJ129>co8| zMzmK1!9q=EOPep4t*rE#+{1#z(aW05YKlubw?X?TyT*i%!wG|gjM32`2uB~=Itny~ zR3f1JeYPu_byq`bT1z|pBMY80;WlYATkZi7~2af^=88)7>dup!oynrCw@Z3+bKHb|UD$U}pJg*L@P@qniTc`vo zkaZcFb239JAb`>BIp9#N*EsqtW^)SgPljWHqjiK(7*D|CEi{vyK>v0|YBqCLH$fAA zAD6ZGD3AB~@q|yJJ31i8#G#6pi&YXI(R9KXD}bORkKmSX@X29jwBu%CpOz-t4(#XF zlD0MOGW1fIz*-^nR}!%kXG*_V-qPKXH}{6o>>-out4-8zbZi5TGO}v)=|q5QjDFkR0)%I z(Z#=F?@!+)PCUS>dl}9&|E^*NW;%q8KCcN}>zeQBbp~d9$(_x!V)1*E9>P*NkTR3mQuqYvVA0~mu0=Y3GtCWVk zcMI?GCM|)9()nC+tgPUAN{}OJ)IxcI_H1?Ko534P0*KhPBvg;3%Uyu@_hM%rFJn8} zq~&W#ucR+{CK@FD;Qy)V9JJlTn{#*s{HLA3Y0_!RPo+11vs)&CHCQqfg@VVOQX9i) z-YPKpE?y6F%CQVLo-1Q73KI|}5Cj3j+Tj3F>METp<}-`%{{jCeko5~bxORYfapHPLMJHfX}`3N?d0}|cnw|?Djj1>`z49>aFdzxhUcOinrjGQ1 zof*cOV%#eSMkVm;Bf=EY>c(T6&!+z@_c&31wy$w3=kKs4UK-EGSCUuY!-*BHdlGeN z_yEOT28Evyk-|@tm%&e9!7lT%t9wfpc!3%=vY(jU`flg&`o|^r(I^_88Oq%l65KR9 z0gjnx_?0hVQQzMCV8)|+72%&+B`!l?6@B@YfZWn|xdmKuS9`}_;;j@1{tZ7nw|yOP z`@LzRnu}h1LhTnKO3N&pXz(phnZiWFa-(c1f`qMh4%9u#{I!>x_RHuDZ3$wJzQCVN z;pH1$4^`q3$b=V)4%xFOI$;|2CQnt0&x9-Gd}Yl8_X5|SK`Lj9hNBPL4p!l;k9zk| zw)y1*ERbP4lku|DZWtl*4w0U0 z*Xu29B46D&esuDW;n5R*mn$7WQ0f-RP8a}xHP|&3`Q~F5(+w5w;`tbdXgKB z==X;vn*jUMd@9uZYkYLU58ljppeK6uTj&L-!=gc7Ci#LK#uy0YwGUkjRiW+jA}u3N zG3Ospz}CH34)WKh1L|smmki(D3gU7KdGDzt$aQr}Jbd1)MQd;&uD@jGS?#OCH6ZjU z@TV;FNZ>jrD^Hq^CPTU2{Ff;_ez;s+b-ZPY;{JaoGSm5sUx4pH$a_&BPo(iP+5 z9C2DvfM-U}TRKdzRA`DCV&#GhnRuOjG>!sGkmXW1)q48}r^w+dqpNuO9M`RKUz+EZ zBQ+w+`z}tz_JGu__$VDJnemrNDm#{vKj;dW`Bp|?KGR=zQ}M>tH3ozy$k=pMjijLu z<DUZ*@|4(kh=5i7Ti)S|f5ujm%!O8ia|iNuE)&cOsVB77 z9y}Ai0m6%1+q2N!zXW&~CKSAj5|uB6j`N>9CE#8L6BQfTctfHxVCl?#*aid3oXvXv z!#sn_4|C%;Pf~45X`F*JlR&RapJ)8_Za*-~zJ^0TW)t8EoXwa`{UWM;KouIlM z)lgNHkW}*M#YE69&G7?&yOD*@_^yi*mviVg0e9< zp~}y$f#8DQvGfpXH^Si1ugY8fG%2`|cv?fgM1<@sh01)vO8zX`_#%yk zv*!Wqe{`Yx1BP9KFL#w4A!$_yG@XB;nWIuV(PW)X<>TZ*xWeHYo?j7S@jTtDij^;Z zE2XD7++*M^9g!fH?6(xL35X=s&!Pn5mfO_}1ho2+I@$K@H;-$ArBWa7$&vf`_~i$n z>M1)1Z5<fbHi)S({mn>1pd<)esV9c4qY`+hkNM-MsgeFLf_gbmB2-LRQxME`;LIY4fqpo}VTWCP&MF z2HH-|=zIZFr`8CAZZ(ltm3>bv+0ga6hUFb6fm&~ zI0t)P{F*JO9keVH_{agx2o&sM5f)Cf*d(G!i#*l9vUt5t|#Nu@C@>lJ3~Ivwg1 zmkT*bCFNPsJ`tpyH0D|h2ws0RuQug@(lNc+6wcByoAu3Dc2-qE@Le4Y_IhXNzSvr* zfy03N)47(sio$1^9(BX-jma{e|K#?3`EGybt-lQEN{Gtty964vSzo+Qq>|zfWWOu>p;>_99ELl9e15SY&ocp^&3PAAtTuv>Fuggx=h; zHT_^Z@uGV7$c22~n2YlqtZ`1~4toW^O)O9j{ozOqfEC$8!eZ3HfqfqgRnSO|NE(pZ z*xD&fx-SKhX5nNq+Wvd|L3cP$gA#?=E=2spR~?S$aP>K;1(>t;*HL-f!KJ#|GyOlyE;4RYyHuQ(i(JUN?dYYLh>ODoiFjUMw0f#UE0 zSdGG|>3;4}YXDfn!i%}#l~{Pa=v9glmF10#9q3QQ!7yYZ-&!m-nx*YXa73+SSbQ%m zyIbvS0=wUqLBC^YyH&`8ou6n(d0@jJzxT<5AZWPD)QRMbbxs+%N1j9wfm@Arm1!g z>VkgZtE{TFSi*y$EfR~zy&C-nSgZ7zL8gQjY=vK5kB`fyZ)k}nU#(cT+v7IqQVyMoidh*9P!_5P4l(iChWupL-OiIRb}4)kTC-z_@p8S zXmK`c@)zodUw+f)q}{0p1AkIa`pmy`7uDAy&#A{lI>uhJ<$Vmm%`3BEFbcRAFhh=q z(Ef@_AFlZ|4JviO#~9+U&k2Afnx@z(8?gtq9#!O!0=p?Pi`3w9V{PY@lf3TI5WInm zx_g6AaWk$IzViik28j#8s^R^k_IR$v5kz}|UMdcN0H8gxEtlwAHf~^(AvGFK?mDi16pP&f>d49; zwJvm6SF>n^crPX0Nicy~$V84pEsn|P8C?D607ph&N7cBzO!zYGPqE{97BYr_Kw;6l zsnh9MevlCyZ`~fR0{oZJ({k2K36krW5X@CTJnwdz`YA?#BN+LX5f&bpEv7n4xqqP8 zL;c=LueJzg+(Y{NMD@Me0X{qx-7@wX8kH6M-W{s=VVHjM3`>VHGZ|;5@e#QhD^#AP z6Q14cOctREot}5{PYnD)iMV_19k=K2{QRn8c!Bh?yum?J;dNmjYAIegGn$U| zy;t``l8MlWNOXws!B~_+i=d>$MJJ;*X@(a4U?9s41-gMmVC*Nn+*%jrBwPD^_w6cq ztN>F_{TqG1y%?|xoxfd3j~;RHq`bU#$2D-iZ&nZ@7Hq1HgDIe6%i*H;!WhEcKE2B) zLGwIB`^kNU4%SedU^RqT%G0O6kuJ=E{B*9aEm`jGtHMD4c`>Bk)=1}T8~k>il^K?* z?iR_i#o`RfDW$%H19T4@Xy((nX|mzO5iMs}RC`yIg|#O0>&8C_=K1D4kd9vr$=%)U zh!wTmhdUX}bFWv-H?2TPYvJ0uZvT?*Cwme08~giDiAaORzTHyXisC9XZ(UPdJmMu1 zFv*gc#P5`ef94S{aTA?g`WR&V;Pf{KDx*k;?cm3Bi|B5@o*Izw_Z=0s(<5bP$K&F9 z%xsVTJZ)39Kpry%{T_`D5v74ZKvqAxzzGrkS00q;zLi8ABq;eQm$eTS`R<-ipx~z| zjpmK|&jOm9{`6<1znQ}x@^#R9mN$vS0=cU_j`)fA)s;g`;H#fc34RiO3+u#M45Exm ztRNgy;OdfN?nkqO6+P0JsDaaVA4K#OAJVFu{FJTgq9!&*;tfdI&jyvRBN56{y=Fhg zxb%?rwA7IlMp6hS8D7AhfZB>ENRlEN(0;838U_`}zH?Sn{tRcENwqYwnX3^P=PA^A zawuT%rO7eQGd61xzTQ0$9Z{EeC z$J_ZUP-|ZhMNJj< z=rzvKvC_8jJ_YS0Odt!j(LYw#v{d?B7rjpY0PB2a*@sZpnpj~Vl+0y- zkQ*^*SyBu^2U4oNRHEP4KRtgw)7zgP{pMM%h^ySuC5hK@>2~_%&3;r<89cwnY^p+m zAeqh%JZ62AqJG~+6O)w2pc;}{Y?o$8!ytI*_(+hr~-kTd@uihb(3T(7YL4#t9z$Wx!*9Ccc|A06&q;VPexFjIdkeB1kJ>H1ig4iK7j zKK==7$fgOP^%w$z8s+(hORW)K-r@wi`AK6Ym!aZ@409tigH*@|Jp zzUbHqTl<4zWRD*yKM?{&J-T7_xI&G)DmLNmS}3a>Up83<>)lutHwyT~6c)P+QSqW> z)_fZZ1gw@knQzY5qInm52hi-QZ>oiLBeNq3T~_PvI^QAkxLYhOd0%j97$5o(m>FME z#Bwxl0%aI$iJmPOEv#@l9@x*rTAV!eS!CEtIu(tMzqUZVdZq1bR`u^D2c6YNF8-SG9bxYoJq8V1rvR1vUkJ^dmj>D$ptzi( zp@$UoZN{p%r{n&&>YNTISJkb8y*hFvA-0;&kj+KlZ5ZK_@Ll2yOYbR;1qA)TFbgt;n3f~L{B7O)2! zEdv^Lzy1143w(;Fq>|s5*lF@8Bs8mQRwHzQ7l-2Z++6uP zC{UTDAqRmU4PW{n(rH_7u)DH+Frsh1s9$ip-(|ve4I_(~yME0xmq28G##$tV-7v_v z+ImPzN~|F?G*5151up%Oa1;Wfca8TVm88H8lZ#okiJ+pJ8y!h1V^cP6ten+NaUvUh z=ALqXnvcgbkeXz(go!!hgx4xA~yK9-BBmQToEzengTm{K^BXaZV4($DEs4ERKd=UT65bw;O}= zNNzG_6L1FwJ4haFdkX8vVaC8|KcS-%W>ZUT>VNnr;JCG_X6(t755LizOY9-Df zA2jN#=d71?7@FucC7m=^_DhICFbM*2RLi2k3bJYgl~-77#0GKf)#EcI*SQ!R&6c|8 zW)}QdZ(0}Ivd|-%mAM9vRKhyRTHzXn$D82e^_gH$paCFDHLe4Nhb-jNUSR~E_n_X7 z(@D;dj9f*XyI}@nLeqozUuQ8>aY$U>cZ7#@^YH}mR-LlP`AB^Hj48-ZxAwMcxFiMn z_%Px24sFGE(iF(L`u=m~qIKRgp_DBM&LZ3P?96ZJ^!F%HAK}H@Uc(oJQC{+x+GC)+ zJ6l-qB^KllrE@4of8_lS>^<=+7}t!4*gOc$+Lw@JAs=;eeUa;`N>&F!tK!YIpP5}Y ztnE%Ml$P0_^AW;1K1+P&5J`7IO27NnaPmtq7$h%j33#!ozQ0rUz1u15^d|Ftuk>eN z1;etXjky-a?rM#D$zUP@12`C+BDwb~O{f{OP)hIW@uq1k_})mFG}CAqCPC>qRLbe- zUIM|Gi~Y1+xHs?)jYnRt z&yYW3;H4{DVCW#_{!PoP5crEV6ww)6{@<=moOZm?<9q3B@cS!WFAqkE1wM|EJz3`H z!Y{vnwpo7ujNI?&1}&|OZNz*^yPfE}(bz_x`E`QAC+3Yh`X#84lOpQ>w|L^DF*wTQ z^jint;T84iNIw(#7bMDyIl)QbgN%r0{q|4ipxp%jjD|scqvpM2#d0@58WZdlbd+cU zXJ(6Cvdr(?7*I@WPi=rZ0c<%%Xm0&cn4i?c6TNrv{WIrbgbZ@KEAomVU4==%**R&v zv@=Udn*TP{3JSzIj@?HIsCzCsIoX!AR=K`^z;im<|F(5whTwX%XC|)^V(M>l^DPHk^9m?&VLjuOP_0-aT9Y8q?*xXe zh?;+BD0HYHmXNgyam~p9fybN1i(q6ilZ=y-HF)TZ$p0+0tOu)M&NJ> z&}2IJ^Mrg)Bu6G|5B%OxgX*itQ?}QSRZ}#GuuJW8{nbhBKXM7#okI^$aBGS=%3GQJY+${^qUL@8!1+de)sFI0zC~8 z1_Du(9n!#XhP?I@*=8~*ggafF_nd8lhI(~S5oCIFD-SY(5}l;6asI!%CZz?7P^9l; zUcu|6Dyhx~dI4+q$u?Mh1#*I;zY^1n?6*<0#l!ES^9+X-#i>iQOHjuhvS-aUWR0@S5FcbqiV&)0?nJh7iC?N@BUt{b- z6tZO*LVYwCWQ(|c|AG6u@1M?jopYV*oa;KT>vbN_^PJuVWt)j5-moxYXAxil0D#@Z z*x)7rfX=!gfSK{EaqxTVUM2RD1t+L)VxV{H@eD05WH!tCq;J9Uh1E=9r=*pP)0=aN znf-`G4VO1Lv|k0uq)(WO->^uhi__J_UX|(e*9J*$1{p{@m2$X3txh|t?Z>P2(xa=B zf%o?7!sja|{|a>Z4@YeH=j}8NZ#xbQ3=VSZFK7Jw>LEr6{eff=#PA24hsP-pM(`el z62i)w2n^q^_yLcCtWO^8M-ajY3y`F7^XZZ&&7#4%%k$go8ruu?;9P=U8)l7P5< zEy!CQyV8L2O=&g-i&pm>qSwKv^%ux3&1Pqzo>zfAzP%C@VB25<7+k&&Rb#^x$2Oav zP3^po*7cc#pADzt(w>o^Xl5}Gm%cF&!vzP#V*Y!8~z;Rp~Ma-R!xZ?^S)0J)GvPhJxRhY7@U4UnTots4(cDBnP|@jae0Cybo>LhbeT|=HaE~{B9dC-OlJEXSF0&Q`$?$(5YpvtBk$>x% zjU=$5O0Y(O`>z$#fbNgF6rL&JJ-xNmbe0b6&?p^@H4RLJ7Le3HCoIX3KbddY>)^V@ z*B>>`4(Vi1;@bp@;dp1-4vyU{z~_0R!d@15jIc=g4Ba2=qx4MG&3P_aDz}}dlkD^A za9_!DYR!zuG~saroR_-;C35y!#6cQ-MD*)a$hF6Ey8^yWnSX|H8cm z*nS#CbO>f*46wZZ@XdPTd{=P9YSxe?4qORdaI3XMJ<4yX`qg@u@~DEC6jJeJ8n&iB zl|oqJ`N@XO$R#?ipYz|wF(r3~L-r`MZuf@h%lGo9DN52{VLZx77wCC?(YNWF#d?vL zB4~;a)f4448*^BFK01W*iPVns8CsOu)ZN-_`8ds?*$Z>2njdw{YdpQv660`NuN}?`KWuF!B)8kKuNQgtvw8_TgpBg?Rf5MLgNM}z6NhW5ypgTbLXA{B`zH| z;vw?l746YHghDCc(Ak4}1&IR;$HR_0Ha@BI8rCO1*`IBTzzy|FUl(xcy%sGA9AfX4 z{Bab2?=R(B684=F)Ha%{z>@on@Zw!&Biln_0#m!#?1w2E zO@><`y}O4#gi49``$(!)!Aq!UST2Wlj9r3Zhd9lkU3xV}e90{*4EHd&!<+N<(tT;A zZ>B(XSI?A_!>#y;!daUo_tz*Ayo0o16I24;k(j-h3chn47#&$5@!#h~b|4vuz7R{v zcwA%RQGmg2U7+~qf51=gR)9~qtQ<4u+ID;>0-qWTRK^q*nT%>xzD>ghHsJUGixX3c zcMoM&N3W_EMOY!MaXFG?#+JnY^wdrmw3<~3m*M!|^uC0Pr#EQOT)O z?uIgGPMOb>Y50(b^_hTVK7kZ$htZ{29BdAu^M@er3`kXVNPF02gwXOD^V$rI^`to( zD%!+Gsfg=TnNSd`@%zxg(ukrgjC6M9daN|ui<^VT1UBHjQ>I~R>3}3rLfN!}95#7W zWqmTDGJ)D}bbBP`puhK?|8%j}7!&`V!#mki7G%tE)Cg)b><_JAii~yKcS~`@0O?gP z4qlw2gis{-=S12PVkKYjSHHYVS%>3YKM%1_kr9#6%JEOXx@KRhLiTvL1nur9CH0OF zj>s~`4Y;RX^Nbvzc@{fM9F2UXF7sJ-eDX{y7F~+FrZ9vleApiv8Ev<_lHxUYGsycN zTb&oLWrN;MiWvy6P%aUe>cBGW8iq=TBg6kKS7NxsGrK+#wOBQye3?GDky83~;rN3q zf|^oMSG|pvpM_wYCr!lG-bNQGF5CfgT{wcDG~+hG=8+(zuQ=C53zuJNsYSIcXbI$7 z7t(KscK>foV!$d^7pkg1{^dODu^cGDX`$UTVOzsF60HCJ(+^DTt7);d#;E%e<|e>| z3*hUVu+5p)HRbafJKyCg75-PWzI(}H{25?iX^Q;s&812wD}v3#+$3|l9AaQDyZ(Wl z6Ry|?irc+}y z>_&=!TqfF@-5v|F>php%BhZPSb7cIAXePjG>`&DnsjkG9HpV8TA8r&aU$aKe$3P3v zj1YG1fe6;zr0U&-CAwq~nbuWG8hZ-Gs?rj1GaF(Uix9CVJw*qHtm6UpARG)0^1gw}mgotJBL{weVgQ2AYx;JNh*xl(h4&SZ2Da_O>M8B_9nX7R8bw1`>J2Lys zN_W2B?CusoPU0`zNRDw#5uo?FIvufg8w_ zY_3PDP*zz)W+DEAB!C*lv1p0H1{`>2Ofyq2kps5$O7$8^kQ^R72$OtTF#FR0opAF} z3r|!*E?%nc;|D;EqFoWSeZ{>{!9dpTXA{fYUspC%rGY-D;&k1C7US=hlK7S_RgSeE zP1~Q6fm?xjT$xuY#$t^J#&{GbN0Bc2V-kYE^XSY} zLHR1SF2Z}WDP1Bfp@7zk6|jc2vC`vDl&a+we=uw4`-}4Y!05yEI^ehDfqK8d@tkt3 z%;insQdp)I0>yK1>+Ft+Dn8)v>ca+6O_POYT0`u*8ep<|@5}+B+wv8|quE6mdC^ zH+|OweU784p`7@eHv}~)g|puUZ0{aJ2P?*V*Hwdq?8)V`IC+ST)2s3GEtE>MK=jmzze>?Ff~#*E0a=UKFZbzB0VXpn=fZxuwvB&ADqwf+|>*` zx|jpT9cy57{&e#xzUKvh?)Cyj(G`>|zCS4R1UW3vADmyxHtmSFpcGn=aK(LOD;w~o z$CCatDAb7RU5R}4 z`;qgU4e=+_DmK1E@2$C+d&eVIv?G>?cSD2*U~Oa}-aQDL8md#|EJCOOUMGBuV6 zhJuv7yMb4mPs*r1lxf-fKZ2$L7w1D=@pD55p3erK%#j;6{n|T6gP$>Ry_FR}p^&(v z5fiI0L6@u-IyY!>Fv=lDhOXZm$xlb^x3BbgV(daf`v06~`#g@+l?HRZsa>yxFhNXr z`7(^o1?nw5Sl|2mpoqt}T%-_+hL&7KIKR6)fa}YlD2L|$k9+-<<6qWV$DO?}qY}@6 zgwFenY{Q>79}seotT4O`K1t;O*Q?DlWks|Bi(WSOr!KRdR5W8)9-ra(3#zSmwQJfv zQ5*<{f15c&8Bskxs@Ky1!vQN9lX-eNinhDU|`?2d=6+~(vR$3A;DK54LEiVRd zl=V4=$^|ptQ7X8MxO$aUd`lRycJ)8CzU`hL1aFFt?0pYM+SPg_Bm&o#ysO`8`>ns* zC))9AKo5uKyPK}WH{#ZeNG4qdk?u=j4;^T!A;~L*2~z3KKuo=lj|OM6s~Mo%8}*Tm z$;QUsXL}#w-J!4Tme`CDib}K+9C7Q~3~sIuw((<(w%Ks-B= zp)SikG(Qoc%<<G!>zz~6pKXKDsOKUE!xhr< z&;p%97b9nu4-TU0{rBSL-ze1V_kWXo%Y}b_g%|%XOoyre`vERP^w|L@{CQW$KD*K- zy>&ZtxSl&a{8BIjXdGk?MOjeBtJ+N~|Rgv(THwicvJP1pT-1nmv z$JCVyVRBVLquV#nlTQwVNeQcS|HL zzvOf6z|ScqHRV-}ZPy-w!=qQu3uRCue#{6_hc9kZcF>hE4Ua7M&7Nnl=aURE#pP8L z_zm}hH(#KS<6Wnvd6VRggVM(w3LXO=ohx|o+DiWrarR)*i6SA>^1MJ@J=p~*z`0QS z+TJ?ot|-p-Cr+ZNx`A;G$on*UWq3Bzk{;rdJEAHDrc0@s3 z1PqMrBX#pR^RX$>_AHx6jA>+~Y1kfw*FK6sO5q zM>sCN_kFS;u8u=_`mHD5+QFK_HGaIX!aG9?lR~DoH{L?@`IR7~=ifbQd(8{-@Rwyh zPo?^44G2VBODMsmo$Y`{3vwqz3Ur?_nHjTsZb(9YWC(P^*&;Hl=vJ03xcjn*hkl=; z;-Wm z0||q(?6Piy0F)MeL%`@4o%=ISqk^8-A1+hPQk~Q001Eg6bZ#Re=QfCBKqp1xP>}jb z%$@im$`#C=2IBRpR6pv4sr6yjP^94JXH?mr#atOZuCh?7DbWkF1ZUV40x!$C-i`Y$2v%K-nAxcHJkX8otPte)@-EE~8 ze=FziMvA%nzG;j&q5Ws$tS3VZGre6NBmDb)JRk)2G&Qr8 zgLC9Eqb6wrrzFs;b_~bT@ZcLyM!x`j%U0g(z7IQ-DiC|ENh9VRAJGAX z>uvB2U~J1W;;W#hxyx+>GX*N*csK{qlq~?qcQ$d5R_ylv#RjL?af{hHe~FA}BtYE* zEt&yj_i1FiuKQgF>+d!O6lGFJ4(AyDMaDtlDA_WS>lE`}UV0-9URr3Fu>Mnk+Hio& z^DqG%m^fIz5Y8_J-;;+@vM6&<%Pq$a$iZ}-F)(4T|5wW3@LQEZiaykhIg9m6{3U{E z`tkSCfZIV5O3K|K6y_lhbb|gBc9i`o3!~Ms*{3FM{0e0n^T+i<5YvX(<9eGk%TTTj z>W1FF9+*qm$0;ka?RRelB6fr zncR3vEEuHL)_h)HxyL9FkAcm`J08tu6lyF)QWQx|zl5+XQrBq9iw%ejJlubn?8)%ECFnGBi3)0 z+fZfp__`48796{v=N9A8rf3;=Y-D_1m?tvhla06fuJ|;2Sv}LLqd?HMWv2?b{3#$A zAEq=pNOoAtir+m`^Gr8MVF9MJ=e41|k*A9mvq7wOBW%>i)G}OcurXr6Z_-J`!RZR9 z<=4?{mS| zp@9k%nqjf~gLIs$PQV_&#ow-*=NboK9jUVGNh-u2j_N%lZ73xXQv^@eq4&0B{|xlw zHQMnQ{uTGvK&VnGJx=1mEA3b>@8nqeyT(!WL7@iPh5R0--0Wq3574C1tw~El-`v1! zn7D}$M{AVhh+&5ZhAlDCZk?>{Ho|Yvh!y|k|HPhMs1O%o>-QWSjE%ceF8*$(o$`wE z!fvCnwP>WdGmka=f>lJhlE)h(rHnh=C~2oANz139U=S!<~)pWKDzt z=Es(I&SURcuKNY9>v0M@UH;(#E0&$ zSDpsUhZ_UhIVq0oj`w1kTRBvVc}}bP~@;>nQhSHYl_9{7u~WBUi50 zi@ez;w#XW zRHdb)I;FY9Kh^>haJ(q8yE9oQB?PkJxV%}mGR)Ep8JzXol^Uw229BO56tlRCO*3eD zY5`hbiAm=uUL=N};_MzUH0div^X&g|*|3{O?)^pg^@)zZr%jlH9ax1<27Jc0uBxlf zg3^X&MNVL6lbIqn>oNLZuIDQxu>oTZvPHt-kzh-azva->&x4pfYkB0)`=tj^*0oTL z98Ks18>r7=Y9||#}uB~?K(3@YuO#8hyC$YVaLz@w;v*l z+skzXJz|;m4f4u)dH%&BIe3juDVz#Gr0_-L++v{QD?(R0-d?Ii!CF!F>I|C z8?6Px2&00wqi@e)C&ITU1#HXkb{JoxtT*ZuL@yU power_failure = false; + inline static std::atomic signal = 0; inline operator bool() { return do_exit; } inline ExitHandler& operator=(bool v) { + signal = 0; do_exit = v; return *this; } @@ -160,6 +162,7 @@ class ExitHandler { #ifndef __APPLE__ power_failure = (sig == SIGPWR); #endif + signal = sig; do_exit = true; } inline static std::atomic do_exit = false; diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 0d561a5c895cba..005d8b1c8c0211 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -96,11 +96,11 @@ def __init__(self, sm=None, pm=None, can_sock=None): sounds_available = HARDWARE.get_sound_card_online() car_recognized = self.CP.carName != 'mock' - fuzzy_fingerprint = self.CP.fuzzyFingerprint # If stock camera is disconnected, we loaded car controls and it's not dashcam mode controller_available = self.CP.enableCamera and self.CI.CC is not None and not passive and not self.CP.dashcamOnly - community_feature = self.CP.communityFeature or fuzzy_fingerprint + community_feature = self.CP.communityFeature or self.CP.fuzzyFingerprint or \ + self.CP.fingerprintSource == car.CarParams.FingerprintSource.can community_feature_disallowed = community_feature and (not community_feature_toggle) self.read_only = not car_recognized or not controller_available or \ self.CP.dashcamOnly or community_feature_disallowed @@ -161,11 +161,11 @@ def __init__(self, sm=None, pm=None, can_sock=None): # TODO: no longer necessary, aside from process replay self.sm['liveParameters'].valid = True - self.startup_event = get_startup_event(car_recognized, controller_available, fuzzy_fingerprint) + self.startup_event = get_startup_event(car_recognized, controller_available, self.CP.fuzzyFingerprint) if not sounds_available: self.events.add(EventName.soundsUnavailable, static=True) - if community_feature_disallowed: + if community_feature_disallowed and car_recognized: self.events.add(EventName.communityFeatureDisallowed, static=True) if not car_recognized: self.events.add(EventName.carUnrecognized, static=True) diff --git a/selfdrive/debug/test_fw_query_on_routes.py b/selfdrive/debug/test_fw_query_on_routes.py index 5a3ccc957c00c6..8eeacd277d2b5f 100755 --- a/selfdrive/debug/test_fw_query_on_routes.py +++ b/selfdrive/debug/test_fw_query_on_routes.py @@ -8,19 +8,20 @@ from tqdm import tqdm from tools.lib.logreader import LogReader from tools.lib.route import Route +from selfdrive.car.car_helpers import interface_names from selfdrive.car.fw_versions import match_fw_to_car_exact, match_fw_to_car_fuzzy, build_fw_dict from selfdrive.car.toyota.values import FW_VERSIONS as TOYOTA_FW_VERSIONS from selfdrive.car.honda.values import FW_VERSIONS as HONDA_FW_VERSIONS from selfdrive.car.hyundai.values import FW_VERSIONS as HYUNDAI_FW_VERSIONS from selfdrive.car.volkswagen.values import FW_VERSIONS as VW_FW_VERSIONS -from selfdrive.car.toyota.values import FINGERPRINTS as TOYOTA_FINGERPRINTS -from selfdrive.car.honda.values import FINGERPRINTS as HONDA_FINGERPRINTS -from selfdrive.car.hyundai.values import FINGERPRINTS as HYUNDAI_FINGERPRINTS -from selfdrive.car.volkswagen.values import FINGERPRINTS as VW_FINGERPRINTS NO_API = "NO_API" in os.environ -SUPPORTED_CARS = list(TOYOTA_FINGERPRINTS.keys()) + list(HONDA_FINGERPRINTS.keys()) + list(HYUNDAI_FINGERPRINTS.keys())+ list(VW_FINGERPRINTS.keys()) +SUPPORTED_CARS = set(interface_names['toyota']) +SUPPORTED_CARS |= set(interface_names['honda']) +SUPPORTED_CARS |= set(interface_names['hyundai']) +SUPPORTED_CARS |= set(interface_names['volkswagen']) + try: from xx.pipeline.c.CarState import migration diff --git a/selfdrive/loggerd/logger.cc b/selfdrive/loggerd/logger.cc index e2308ef73a0cd3..442d792838320d 100644 --- a/selfdrive/loggerd/logger.cc +++ b/selfdrive/loggerd/logger.cc @@ -130,10 +130,11 @@ void log_init_data(LoggerState *s) { } -static void log_sentinel(LoggerState *s, cereal::Sentinel::SentinelType type) { +static void log_sentinel(LoggerState *s, cereal::Sentinel::SentinelType type, int signal=0) { MessageBuilder msg; auto sen = msg.initEvent().initSentinel(); sen.setType(type); + sen.setSignal(signal); auto bytes = msg.toBytes(); logger_log(s, bytes.begin(), bytes.size(), true); @@ -244,8 +245,9 @@ void logger_log(LoggerState *s, uint8_t* data, size_t data_size, bool in_qlog) { pthread_mutex_unlock(&s->lock); } -void logger_close(LoggerState *s) { - log_sentinel(s, cereal::Sentinel::SentinelType::END_OF_ROUTE); +void logger_close(LoggerState *s, ExitHandler *exit_handler) { + int signal = exit_handler == nullptr ? 0 : exit_handler->signal.load(); + log_sentinel(s, cereal::Sentinel::SentinelType::END_OF_ROUTE, signal); pthread_mutex_lock(&s->lock); if (s->cur_handle) { diff --git a/selfdrive/loggerd/logger.h b/selfdrive/loggerd/logger.h index f530a2b0496b7a..feea52572d2b01 100644 --- a/selfdrive/loggerd/logger.h +++ b/selfdrive/loggerd/logger.h @@ -83,7 +83,7 @@ int logger_next(LoggerState *s, const char* root_path, char* out_segment_path, size_t out_segment_path_len, int* out_part); LoggerHandle* logger_get_handle(LoggerState *s); -void logger_close(LoggerState *s); +void logger_close(LoggerState *s, ExitHandler *exit_handler=nullptr); 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); diff --git a/selfdrive/loggerd/loggerd.cc b/selfdrive/loggerd/loggerd.cc index c55115402eede8..9a642059071acb 100644 --- a/selfdrive/loggerd/loggerd.cc +++ b/selfdrive/loggerd/loggerd.cc @@ -468,7 +468,7 @@ int main(int argc, char** argv) { for (auto &t : encoder_threads) t.join(); LOGW("closing logger"); - logger_close(&s.logger); + logger_close(&s.logger, &do_exit); if (do_exit.power_failure){ LOGE("power failure"); diff --git a/selfdrive/manager/manager.py b/selfdrive/manager/manager.py index 9eaf02b3c1348e..eb06893c44a128 100755 --- a/selfdrive/manager/manager.py +++ b/selfdrive/manager/manager.py @@ -138,7 +138,7 @@ def manager_thread(): params = Params() ignore = [] - if params.get("DongleId") == UNREGISTERED_DONGLE_ID: + if params.get("DongleId", encoding='utf8') == UNREGISTERED_DONGLE_ID: ignore += ["manage_athenad", "uploader"] if os.getenv("NOBOARD") is not None: ignore.append("pandad") diff --git a/selfdrive/test/setup_device_ci.sh b/selfdrive/test/setup_device_ci.sh index fc4d4496a75cfe..d186f8c05f64f4 100755 --- a/selfdrive/test/setup_device_ci.sh +++ b/selfdrive/test/setup_device_ci.sh @@ -26,8 +26,11 @@ if [ ! -d "$SOURCE_DIR" ]; then git clone --depth 1 https://github.com/commaai/openpilot.git "$SOURCE_DIR" fi -# this can get really big on the CI devices -rm -rf /data/core +if [ -f "/EON" ]; then + rm -rf /data/core + rm -rf /data/neoupdate + rm -rf /data/safe_staging +fi # set up environment cd $SOURCE_DIR diff --git a/selfdrive/test/test_fingerprints.py b/selfdrive/test/test_fingerprints.py index 8877255c6b6cb4..178e113768721a 100755 --- a/selfdrive/test/test_fingerprints.py +++ b/selfdrive/test/test_fingerprints.py @@ -2,7 +2,6 @@ import os import sys from common.basedir import BASEDIR -from selfdrive.car.fingerprints import IGNORED_FINGERPRINTS # messages reserved for CAN based ignition (see can_ignition_hook function in panda/board/drivers/can) # (addr, len) @@ -66,9 +65,6 @@ def check_can_ignition_conflicts(fingerprints, brands): brand_names = [] for brand in fingerprints: for car in fingerprints[brand]: - if car in IGNORED_FINGERPRINTS: - continue - fingerprints_flat += fingerprints[brand][car] for i in range(len(fingerprints[brand][car])): car_names.append(car) From f3f674d023cc6cef53312f8adca95d08b28f6913 Mon Sep 17 00:00:00 2001 From: neokii Date: Wed, 26 May 2021 17:13:47 +0900 Subject: [PATCH 10/27] bmx055 magnetometer fix reference frame --- selfdrive/sensord/sensors/bmx055_magn.cc | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/selfdrive/sensord/sensors/bmx055_magn.cc b/selfdrive/sensord/sensors/bmx055_magn.cc index 438e5b49484980..b00feba4fd63c4 100644 --- a/selfdrive/sensord/sensors/bmx055_magn.cc +++ b/selfdrive/sensord/sensors/bmx055_magn.cc @@ -216,18 +216,22 @@ bool BMX055_Magn::parse_xyz(uint8_t buffer[8], int16_t *x, int16_t *y, int16_t * void BMX055_Magn::get_event(cereal::SensorEventData::Builder &event){ uint64_t start_time = nanos_since_boot(); uint8_t buffer[8]; - int16_t x, y, z; + int16_t _x, _y, x, y, z; int len = read_register(BMX055_MAGN_I2C_REG_DATAX_LSB, buffer, sizeof(buffer)); assert(len == sizeof(buffer)); - if (parse_xyz(buffer, &x, &y, &z)){ + if (parse_xyz(buffer, &_x, &_y, &z)){ event.setSource(cereal::SensorEventData::SensorSource::BMX055); - event.setVersion(1); + event.setVersion(2); event.setSensor(SENSOR_MAGNETOMETER_UNCALIBRATED); event.setType(SENSOR_TYPE_MAGNETIC_FIELD_UNCALIBRATED); event.setTimestamp(start_time); + // Move magnetometer into same reference frame as accel/gryo + x = -_y; + y = _x; + // Axis convention x = -x; y = -y; From 8e9458ce65e5f63667ee063333532f2fd378530e Mon Sep 17 00:00:00 2001 From: neokii Date: Wed, 26 May 2021 21:13:28 +0900 Subject: [PATCH 11/27] add custom lead mark --- ...ock_on_radar.png => custom_lead_radar.png} | Bin ...k_on_vision.png => custom_lead_vision.png} | Bin selfdrive/common/params.cc | 1 + selfdrive/manager/manager.py | 3 +- selfdrive/ui/paint.cc | 31 ++++++++++++++---- selfdrive/ui/qt/offroad/settings.cc | 7 ++++ selfdrive/ui/ui.cc | 6 ++-- selfdrive/ui/ui.h | 2 +- 8 files changed, 38 insertions(+), 12 deletions(-) rename selfdrive/assets/images/{lock_on_radar.png => custom_lead_radar.png} (100%) rename selfdrive/assets/images/{lock_on_vision.png => custom_lead_vision.png} (100%) diff --git a/selfdrive/assets/images/lock_on_radar.png b/selfdrive/assets/images/custom_lead_radar.png similarity index 100% rename from selfdrive/assets/images/lock_on_radar.png rename to selfdrive/assets/images/custom_lead_radar.png diff --git a/selfdrive/assets/images/lock_on_vision.png b/selfdrive/assets/images/custom_lead_vision.png similarity index 100% rename from selfdrive/assets/images/lock_on_vision.png rename to selfdrive/assets/images/custom_lead_vision.png diff --git a/selfdrive/common/params.cc b/selfdrive/common/params.cc index 8dd231786f8058..bcdba18d47c59b 100644 --- a/selfdrive/common/params.cc +++ b/selfdrive/common/params.cc @@ -228,6 +228,7 @@ std::unordered_map keys = { {"SccSmootherSyncGasPressed", PERSISTENT}, {"FuseWithStockScc", PERSISTENT}, {"ShowDebugUI", PERSISTENT}, + {"CustomLeadMark", PERSISTENT}, }; } // namespace diff --git a/selfdrive/manager/manager.py b/selfdrive/manager/manager.py index eb06893c44a128..962465f1d0973a 100755 --- a/selfdrive/manager/manager.py +++ b/selfdrive/manager/manager.py @@ -49,7 +49,8 @@ def manager_init(): ("SccSmootherSlowOnCurves", "0"), ("SccSmootherSyncGasPressed", "0"), ("FuseWithStockScc", "0"), - ("ShowDebugUI", "0") + ("ShowDebugUI", "0"), + ("CustomLeadMark", "0") ] if TICI: diff --git a/selfdrive/ui/paint.cc b/selfdrive/ui/paint.cc index c0b254a334f426..d59e772946d2ed 100644 --- a/selfdrive/ui/paint.cc +++ b/selfdrive/ui/paint.cc @@ -126,20 +126,29 @@ static float lock_on_rotation[] = static float lock_on_scale[] = {1.f, 1.1f, 1.2f, 1.1f, 1.f, 0.9f, 0.8f, 0.9f}; -static void draw_lead_lock_on(UIState *s, const cereal::RadarState::LeadData::Reader &lead_data, const vertex_data &vd) { +static void draw_lead_custom(UIState *s, const cereal::RadarState::LeadData::Reader &lead_data, const vertex_data &vd) { auto [x, y] = vd; - float d_rel = lead_data.getDRel() + 15.f; + float d_rel = lead_data.getDRel(); float sz = std::clamp((25 * 30) / (d_rel / 3 + 30), 15.0f, 30.0f) * s->zoom; x = std::clamp(x, 0.f, s->viz_rect.right() - sz / 2); + + if(d_rel < 10) + { + const float c = 0.7f; + float r = d_rel * ((1.f - c) / 10.f) + c; + if(r > 0.f) + y = y * r; + } + y = std::fmin(s->viz_rect.bottom() - sz * .6, y); float bg_alpha = 1.0f; float img_alpha = 1.0f; NVGcolor bg_color = nvgRGBA(0, 0, 0, (255 * bg_alpha)); - const char* image = lead_data.getRadar() ? "lock_on_radar" : "lock_on_vision"; + const char* image = lead_data.getRadar() ? "custom_lead_radar" : "custom_lead_vision"; if(s->sm->frame % 2 == 0) { s->lock_on_anim_index++; @@ -244,10 +253,18 @@ static void ui_draw_world(UIState *s) { auto lead_one = radar_state.getLeadOne(); auto lead_two = radar_state.getLeadTwo(); if (lead_one.getStatus()) { - draw_lead_lock_on(s, lead_one, s->scene.lead_vertices[0]); + + if (s->custom_lead_mark) + draw_lead_custom(s, lead_one, s->scene.lead_vertices[0]); + else + draw_lead(s, lead_one, s->scene.lead_vertices[0]); } if (lead_two.getStatus() && (std::abs(lead_one.getDRel() - lead_two.getDRel()) > 3.0)) { - draw_lead_lock_on(s, lead_two, s->scene.lead_vertices[1]); + + if (s->custom_lead_mark) + draw_lead_custom(s, lead_two, s->scene.lead_vertices[1]); + else + draw_lead(s, lead_two, s->scene.lead_vertices[1]); } //} @@ -1101,8 +1118,8 @@ void ui_nvg_init(UIState *s) { {"img_nda", "../assets/img_nda.png"}, {"img_hda", "../assets/img_hda.png"}, - {"lock_on_vision", "../assets/images/lock_on_vision.png"}, - {"lock_on_radar", "../assets/images/lock_on_radar.png"}, + {"custom_lead_vision", "../assets/images/custom_lead_vision.png"}, + {"custom_lead_radar", "../assets/images/custom_lead_radar.png"}, }; for (auto [name, file] : images) { s->images[name] = nvgCreateImage(s->vg, file, 1); diff --git a/selfdrive/ui/qt/offroad/settings.cc b/selfdrive/ui/qt/offroad/settings.cc index fa7c81023af139..ecdc54f81c49a3 100644 --- a/selfdrive/ui/qt/offroad/settings.cc +++ b/selfdrive/ui/qt/offroad/settings.cc @@ -343,6 +343,13 @@ QWidget * community_panel() { "../assets/offroad/icon_shell.png" )); + toggles_list->addWidget(horizontal_line()); + toggles_list->addWidget(new ParamControl("CustomLeadMark", + "Use custom lead mark", + "", + "../assets/offroad/icon_road.png" + )); + QWidget *widget = new QWidget; widget->setLayout(toggles_list); return widget; diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index 935f1f3a59000d..9ad92b9e277946 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -207,11 +207,11 @@ static void update_state(UIState *s) { static void update_params(UIState *s) { const uint64_t frame = s->sm->frame; UIScene &scene = s->scene; - Params params; if (frame % (5*UI_FREQ) == 0) { + Params params; scene.is_metric = params.getBool("IsMetric"); - } else if (frame % (7*UI_FREQ) == 0) { - s->show_debug_ui = params.getBool("ShowDebugUI"); + s->show_debug_ui = params.getBool("ShowDebugUI"); + s->custom_lead_mark = params.getBool("CustomLeadMark"); } } diff --git a/selfdrive/ui/ui.h b/selfdrive/ui/ui.h index 2e8cf84e478456..8a2cfd186ddd5a 100644 --- a/selfdrive/ui/ui.h +++ b/selfdrive/ui/ui.h @@ -165,7 +165,7 @@ typedef struct UIState { float zoom; // - bool show_debug_ui; + bool show_debug_ui, custom_lead_mark; TouchState touch; int lock_on_anim_index; From 9426aad8ae67604ac1ad3f164e94dcafb9c44c00 Mon Sep 17 00:00:00 2001 From: neokii Date: Wed, 26 May 2021 21:22:08 +0900 Subject: [PATCH 12/27] fix hda --- selfdrive/car/hyundai/carcontroller.py | 4 +++- selfdrive/car/hyundai/hyundaican.py | 9 +++++++++ 2 files changed, 12 insertions(+), 1 deletion(-) diff --git a/selfdrive/car/hyundai/carcontroller.py b/selfdrive/car/hyundai/carcontroller.py index bd7cba4bdc9a8a..f0e2722b56b49a 100644 --- a/selfdrive/car/hyundai/carcontroller.py +++ b/selfdrive/car/hyundai/carcontroller.py @@ -5,7 +5,7 @@ from selfdrive.car import apply_std_steer_torque_limits from selfdrive.car.hyundai.hyundaican import create_lkas11, create_clu11, \ create_scc11, create_scc12, create_scc13, create_scc14, \ - create_mdps12, create_lfahda_mfc + create_mdps12, create_lfahda_mfc, create_hda_mfc from selfdrive.car.hyundai.scc_smoother import SccSmoother from selfdrive.car.hyundai.values import Buttons, CAR, FEATURES, CarControllerParams from opendbc.can.packer import CANPacker @@ -253,5 +253,7 @@ def update(self, enabled, CS, frame, CC, actuators, pcm_cancel_cmd, visual_alert activated_hda = road_speed_limiter_get_active() if self.car_fingerprint in FEATURES["send_lfa_mfa"]: can_sends.append(create_lfahda_mfc(self.packer, enabled, activated_hda)) + elif CS.mdps_bus == 0: + can_sends.append(create_hda_mfc(self.packer, activated_hda)) return can_sends diff --git a/selfdrive/car/hyundai/hyundaican.py b/selfdrive/car/hyundai/hyundaican.py index c1c2f3fef0597c..fbcf63d3e83741 100644 --- a/selfdrive/car/hyundai/hyundaican.py +++ b/selfdrive/car/hyundai/hyundaican.py @@ -93,6 +93,15 @@ def create_lfahda_mfc(packer, enabled, active): return packer.make_can_msg("LFAHDA_MFC", 0, values) +def create_hda_mfc(packer, active): + values = { + "HDA_USM": 2, + "HDA_Active": 1 if active > 0 else 0, + "HDA_Icon_State": 1 if active > 0 else 0, + } + + return packer.make_can_msg("LFAHDA_MFC", 0, values) + def create_mdps12(packer, frame, mdps12): values = copy.copy(mdps12) values["CF_Mdps_ToiActive"] = 0 From 7beeecdd03e6f654a9d267762c161ddeca9d018a Mon Sep 17 00:00:00 2001 From: neokii Date: Wed, 26 May 2021 22:54:48 +0900 Subject: [PATCH 13/27] fix position --- selfdrive/ui/paint.cc | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/ui/paint.cc b/selfdrive/ui/paint.cc index d59e772946d2ed..5a6e1384601292 100644 --- a/selfdrive/ui/paint.cc +++ b/selfdrive/ui/paint.cc @@ -134,10 +134,10 @@ static void draw_lead_custom(UIState *s, const cereal::RadarState::LeadData::Rea float sz = std::clamp((25 * 30) / (d_rel / 3 + 30), 15.0f, 30.0f) * s->zoom; x = std::clamp(x, 0.f, s->viz_rect.right() - sz / 2); - if(d_rel < 10) + if(d_rel < 5) { const float c = 0.7f; - float r = d_rel * ((1.f - c) / 10.f) + c; + float r = d_rel * ((1.f - c) / 5.f) + c; if(r > 0.f) y = y * r; } From 3129587d7e8940138fe10a92217b8380358e5ab1 Mon Sep 17 00:00:00 2001 From: neokii Date: Wed, 26 May 2021 23:13:52 +0900 Subject: [PATCH 14/27] merge changes from master-ci --- selfdrive/manager/manager.py | 1 - selfdrive/sensord/sensors/lsm6ds3_gyro.cc | 4 ++-- 2 files changed, 2 insertions(+), 3 deletions(-) diff --git a/selfdrive/manager/manager.py b/selfdrive/manager/manager.py index 962465f1d0973a..90d12feab5d983 100755 --- a/selfdrive/manager/manager.py +++ b/selfdrive/manager/manager.py @@ -55,7 +55,6 @@ def manager_init(): if TICI: default_params.append(("EnableLteOnroad", "1")) - default_params.append(("IsUploadRawEnabled", "1")) if params.get_bool("RecordFrontLock"): params.put_bool("RecordFront", True) diff --git a/selfdrive/sensord/sensors/lsm6ds3_gyro.cc b/selfdrive/sensord/sensors/lsm6ds3_gyro.cc index d38335eb61a9c1..ae651f2cbd5fd9 100644 --- a/selfdrive/sensord/sensors/lsm6ds3_gyro.cc +++ b/selfdrive/sensord/sensors/lsm6ds3_gyro.cc @@ -45,13 +45,13 @@ void LSM6DS3_Gyro::get_event(cereal::SensorEventData::Builder &event){ int len = read_register(LSM6DS3_GYRO_I2C_REG_OUTX_L_G, buffer, sizeof(buffer)); assert(len == sizeof(buffer)); - float scale = 250.0f / (1 << 15); + float scale = 8.75 / 1000.0; float x = DEG2RAD(read_16_bit(buffer[0], buffer[1]) * scale); float y = DEG2RAD(read_16_bit(buffer[2], buffer[3]) * scale); float z = DEG2RAD(read_16_bit(buffer[4], buffer[5]) * scale); event.setSource(cereal::SensorEventData::SensorSource::LSM6DS3); - event.setVersion(1); + event.setVersion(2); event.setSensor(SENSOR_GYRO_UNCALIBRATED); event.setType(SENSOR_TYPE_GYROSCOPE_UNCALIBRATED); event.setTimestamp(start_time); From b57f7c5c99d08755bdff03dec17ee4503d7b91ef Mon Sep 17 00:00:00 2001 From: neokii Date: Thu, 27 May 2021 01:03:28 +0900 Subject: [PATCH 15/27] tune scc --- selfdrive/car/hyundai/scc_smoother.py | 4 ++-- selfdrive/controls/lib/long_mpc.py | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/selfdrive/car/hyundai/scc_smoother.py b/selfdrive/car/hyundai/scc_smoother.py index d89db7e3e38532..a8898ea51be583 100644 --- a/selfdrive/car/hyundai/scc_smoother.py +++ b/selfdrive/car/hyundai/scc_smoother.py @@ -266,10 +266,10 @@ def get_long_lead_speed(self, CS, clu11_speed, sm): if lead is not None: d = lead.dRel - 5. #cruise_gap = clip(CS.cruise_gap, 1., 4.) - if 0. < d < -lead.vRel * (10. + 3.) * 2. and lead.vRel < -1.: + if 0. < d < -lead.vRel * (9. + 1.) * 2. and lead.vRel < -1.: t = d / lead.vRel accel = -(lead.vRel / t) * self.speed_conv_to_clu - accel *= 1.4 + accel *= 1.3 if accel < 0.: target_speed = clu11_speed + accel diff --git a/selfdrive/controls/lib/long_mpc.py b/selfdrive/controls/lib/long_mpc.py index 703f896069e699..a942085e2b6323 100644 --- a/selfdrive/controls/lib/long_mpc.py +++ b/selfdrive/controls/lib/long_mpc.py @@ -83,7 +83,7 @@ def update(self, CS, lead): v_lead = max(0.0, lead.vLead) a_lead = lead.aLeadK - dist_cost = interp(lead.dRel, [5., 15.], [MPC_COST_LONG.DISTANCE/1.5, MPC_COST_LONG.DISTANCE]) + dist_cost = interp(lead.dRel, [5., 10.], [MPC_COST_LONG.DISTANCE/1.5, MPC_COST_LONG.DISTANCE]) self.libmpc.set_weights(MPC_COST_LONG.TTC, dist_cost, MPC_COST_LONG.ACCELERATION, MPC_COST_LONG.JERK) if (v_lead < 0.1 or -a_lead / 2.0 > v_lead): From a2b76897cf944c4a1c9afa6a102459b19378ea30 Mon Sep 17 00:00:00 2001 From: neokii Date: Thu, 27 May 2021 09:52:05 +0900 Subject: [PATCH 16/27] fix position --- selfdrive/ui/paint.cc | 12 +++++++----- 1 file changed, 7 insertions(+), 5 deletions(-) diff --git a/selfdrive/ui/paint.cc b/selfdrive/ui/paint.cc index 5a6e1384601292..55d9863aa72dbb 100644 --- a/selfdrive/ui/paint.cc +++ b/selfdrive/ui/paint.cc @@ -134,10 +134,9 @@ static void draw_lead_custom(UIState *s, const cereal::RadarState::LeadData::Rea float sz = std::clamp((25 * 30) / (d_rel / 3 + 30), 15.0f, 30.0f) * s->zoom; x = std::clamp(x, 0.f, s->viz_rect.right() - sz / 2); - if(d_rel < 5) - { - const float c = 0.7f; - float r = d_rel * ((1.f - c) / 5.f) + c; + if(d_rel < 30) { + const float c = 0.77f; + float r = d_rel * ((1.f - c) / 30.f) + c; if(r > 0.f) y = y * r; } @@ -154,7 +153,10 @@ static void draw_lead_custom(UIState *s, const cereal::RadarState::LeadData::Rea s->lock_on_anim_index++; } - const int img_size = 110; + int img_size = 80; + if(d_rel < 100) { + img_size = (int)(-2/5 * d_rel + 120); + } nvgSave(s->vg); nvgTranslate(s->vg, x, y); From b1e2fdcc5c2360a2c8ef06e9c7932abc946655b2 Mon Sep 17 00:00:00 2001 From: neokii Date: Thu, 27 May 2021 11:09:59 +0900 Subject: [PATCH 17/27] merge changes from master-ci --- README.md | 3 +- RELEASES.md | 1 + common/transformations/camera.py | 11 +---- selfdrive/athena/athenad.py | 12 +++++- selfdrive/camerad/snapshot/snapshot.py | 50 ++++++++++++++-------- selfdrive/car/car_helpers.py | 2 +- selfdrive/car/fingerprints.py | 5 +++ selfdrive/car/nissan/values.py | 2 +- selfdrive/car/tests/test_car_interfaces.py | 5 ++- selfdrive/car/volkswagen/interface.py | 5 +++ selfdrive/car/volkswagen/values.py | 24 +++++++++++ selfdrive/debug/show_matching_cars.py | 4 +- selfdrive/ui/ui.cc | 29 +++++++------ selfdrive/version.py | 7 ++- 14 files changed, 109 insertions(+), 51 deletions(-) diff --git a/README.md b/README.md index 987151d63c0545..cec3c32dab4cbe 100644 --- a/README.md +++ b/README.md @@ -179,12 +179,13 @@ Community Maintained Cars and Features | Kia | Sorento 2018-19 | SCC + LKAS | Stock | 0mph | 0mph | | Kia | Stinger 2018 | SCC + LKAS | Stock | 0mph | 0mph | | Kia | Ceed 2019 | SCC + LKAS | Stock | 0mph | 0mph | -| Nissan | Altima 2020 | ProPILOT | Stock | 0mph | 0mph | +| Nissan | Altima 2019-20 | ProPILOT | Stock | 0mph | 0mph | | Nissan | Leaf 2018-20 | ProPILOT | Stock | 0mph | 0mph | | Nissan | Rogue 2018-20 | ProPILOT | Stock | 0mph | 0mph | | Nissan | X-Trail 2017 | ProPILOT | Stock | 0mph | 0mph | | SEAT | Ateca 2018 | Driver Assistance | Stock | 0mph | 0mph | | Škoda | Kodiaq 2018 | Driver Assistance | Stock | 0mph | 0mph | +| Škoda | Octavia 2015, 2019 | Driver Assistance | Stock | 0mph | 0mph | | Škoda | Scala 2020 | Driver Assistance | Stock | 0mph | 0mph | | Škoda | Superb 2015-18 | Driver Assistance | Stock | 0mph | 0mph | | Subaru | Ascent 2019 | EyeSight | Stock | 0mph | 0mph | diff --git a/RELEASES.md b/RELEASES.md index 4edc374c946cb7..5dbf50b1819500 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -4,6 +4,7 @@ Version 0.8.5 (2021-XX-XX) * Smart model-based Forward Collision Warning * Hyundai Elantra 2021 support thanks to CruiseBrantley! * Lexus UX Hybrid 2019 support thanks to brianhaugen2! + * Škoda Octavia 2015 & 2019 support thanks to jyoung8607! Version 0.8.4 (2021-05-17) ======================== diff --git a/common/transformations/camera.py b/common/transformations/camera.py index 9c365dc7e3adb8..29ce3277d77ead 100644 --- a/common/transformations/camera.py +++ b/common/transformations/camera.py @@ -5,14 +5,12 @@ ## -- hardcoded hardware params -- eon_f_focal_length = 910.0 -eon_d_focal_length = 860.0 -leon_d_focal_length = 650.0 +eon_d_focal_length = 650.0 tici_f_focal_length = 2648.0 tici_e_focal_length = tici_d_focal_length = 567.0 # probably wrong? magnification is not consistent across frame eon_f_frame_size = (1164, 874) -eon_d_frame_size = (1152, 864) -leon_d_frame_size = (816, 612) +eon_d_frame_size = (816, 612) tici_f_frame_size = tici_e_frame_size = tici_d_frame_size = (1928, 1208) # aka 'K' aka camera_frame_from_view_frame @@ -22,11 +20,6 @@ [0.0, 0.0, 1.0]]) eon_intrinsics = eon_fcam_intrinsics # xx -leon_dcam_intrinsics = np.array([ - [leon_d_focal_length, 0.0, float(leon_d_frame_size[0])/2], - [0.0, leon_d_focal_length, float(leon_d_frame_size[1])/2], - [0.0, 0.0, 1.0]]) - eon_dcam_intrinsics = np.array([ [eon_d_focal_length, 0.0, float(eon_d_frame_size[0])/2], [0.0, eon_d_focal_length, float(eon_d_frame_size[1])/2], diff --git a/selfdrive/athena/athenad.py b/selfdrive/athena/athenad.py index 5d308f7a77aecd..c6d6b8f69b6f67 100755 --- a/selfdrive/athena/athenad.py +++ b/selfdrive/athena/athenad.py @@ -30,7 +30,7 @@ from selfdrive.loggerd.xattr_cache import getxattr, setxattr from selfdrive.swaglog import cloudlog, SWAGLOG_DIR import selfdrive.crash as crash -from selfdrive.version import dirty, origin, branch, commit +from selfdrive.version import dirty, origin, branch, commit, get_version, get_git_remote, get_git_branch, get_git_commit ATHENA_HOST = os.getenv('ATHENA_HOST', 'wss://athena.comma.ai') HANDLER_THREADS = int(os.getenv('HANDLER_THREADS', "4")) @@ -132,6 +132,16 @@ def getMessage(service=None, timeout=1000): return ret.to_dict() +@dispatcher.add_method +def getVersion(): + return { + "version": get_version(), + "remote": get_git_remote(), + "branch": get_git_branch(), + "commit": get_git_commit(), + } + + @dispatcher.add_method def setNavDestination(latitude=0, longitude=0): destination = { diff --git a/selfdrive/camerad/snapshot/snapshot.py b/selfdrive/camerad/snapshot/snapshot.py index eb7bb93af32f8e..b7dd300da160af 100755 --- a/selfdrive/camerad/snapshot/snapshot.py +++ b/selfdrive/camerad/snapshot/snapshot.py @@ -1,18 +1,21 @@ #!/usr/bin/env python3 import os -import signal import subprocess import time import numpy as np from PIL import Image +from typing import List import cereal.messaging as messaging -from common.basedir import BASEDIR from common.params import Params -from common.transformations.camera import eon_f_frame_size, eon_d_frame_size, leon_d_frame_size, tici_f_frame_size +from common.realtime import DT_MDL +from common.transformations.camera import eon_f_frame_size, eon_d_frame_size, tici_f_frame_size from selfdrive.hardware import TICI from selfdrive.controls.lib.alertmanager import set_offroad_alert +from selfdrive.manager.process_config import managed_processes + +LM_THRESH = 120 # defined in selfdrive/camerad/imgproc/utils.h def jpeg_write(fn, dat): @@ -29,8 +32,14 @@ def extract_image(dat, frame_sizes): return np.dstack([r, g, b]) -def get_snapshots(frame="roadCameraState", front_frame="driverCameraState"): - frame_sizes = [eon_f_frame_size, eon_d_frame_size, leon_d_frame_size, tici_f_frame_size] +def rois_in_focus(lapres: List[float]) -> float: + sz = len(lapres) + return sum([1. / sz for sharpness in + lapres if sharpness >= LM_THRESH]) + + +def get_snapshots(frame="roadCameraState", front_frame="driverCameraState", focus_perc_threshold=0.): + frame_sizes = [eon_f_frame_size, eon_d_frame_size, tici_f_frame_size] frame_sizes = {w * h: (w, h) for (w, h) in frame_sizes} sockets = [] @@ -39,10 +48,17 @@ def get_snapshots(frame="roadCameraState", front_frame="driverCameraState"): if front_frame is not None: sockets.append(front_frame) + # wait 4 sec from camerad startup for focus and exposure sm = messaging.SubMaster(sockets) - while min(sm.logMonoTime.values()) == 0: + while sm[sockets[0]].frameId < int(4. / DT_MDL): sm.update() + start_t = time.monotonic() + while time.monotonic() - start_t < 10: + sm.update() + if min(sm.rcv_frame.values()) > 1 and rois_in_focus(sm[frame].sharpnessScore) >= focus_perc_threshold: + break + rear = extract_image(sm[frame].image, frame_sizes) if frame is not None else None front = extract_image(sm[front_frame].image, frame_sizes) if front_frame is not None else None return rear, front @@ -63,7 +79,6 @@ def snapshot(): # Check if camerad is already started try: subprocess.check_call(["pgrep", "camerad"]) - print("Camerad already running") params.put_bool("IsTakingSnapshot", False) params.delete("Offroad_IsTakingSnapshot") @@ -71,23 +86,19 @@ def snapshot(): except subprocess.CalledProcessError: pass - env = os.environ.copy() - env["SEND_ROAD"] = "1" - env["SEND_WIDE_ROAD"] = "1" + os.environ["SEND_ROAD"] = "1" + os.environ["SEND_WIDE_ROAD"] = "1" if front_camera_allowed: - env["SEND_DRIVER"] = "1" - - proc = subprocess.Popen(os.path.join(BASEDIR, "selfdrive/camerad/camerad"), - cwd=os.path.join(BASEDIR, "selfdrive/camerad"), env=env) - time.sleep(3.0) + os.environ["SEND_DRIVER"] = "1" + managed_processes['camerad'].start() frame = "wideRoadCameraState" if TICI else "roadCameraState" front_frame = "driverCameraState" if front_camera_allowed else None - rear, front = get_snapshots(frame, front_frame) + focus_perc_threshold = 0. if TICI else 10 / 12. - proc.send_signal(signal.SIGINT) - proc.communicate() + rear, front = get_snapshots(frame, front_frame, focus_perc_threshold) + managed_processes['camerad'].stop() params.put_bool("IsTakingSnapshot", False) set_offroad_alert("Offroad_IsTakingSnapshot", False) @@ -103,6 +114,7 @@ def snapshot(): if pic is not None: print(pic.shape) jpeg_write("/tmp/back.jpg", pic) - jpeg_write("/tmp/front.jpg", fpic) + if fpic is not None: + jpeg_write("/tmp/front.jpg", fpic) else: print("Error taking snapshot") diff --git a/selfdrive/car/car_helpers.py b/selfdrive/car/car_helpers.py index d548f7e4a6a662..6d9d2b8752629e 100644 --- a/selfdrive/car/car_helpers.py +++ b/selfdrive/car/car_helpers.py @@ -113,7 +113,7 @@ def fingerprint(logcan, sendcan, has_relay): Params().put("CarVin", vin) finger = gen_empty_fingerprint() - candidate_cars = {i: all_known_cars() for i in [0]} # attempt fingerprint on bus 0 only + candidate_cars = {i: all_legacy_fingerprint_cars() for i in [0, 1]} # attempt fingerprint on both bus 0 and 1 frame = 0 frame_fingerprint = 10 # 0.1s car_fingerprint = None diff --git a/selfdrive/car/fingerprints.py b/selfdrive/car/fingerprints.py index 9daa940792d81b..b09e14a429ffb9 100644 --- a/selfdrive/car/fingerprints.py +++ b/selfdrive/car/fingerprints.py @@ -72,4 +72,9 @@ def eliminate_incompatible_cars(msg, candidate_cars): def all_known_cars(): """Returns a list of all known car strings.""" + return list({*FW_VERSIONS.keys(), *_FINGERPRINTS.keys()}) + + +def all_legacy_fingerprint_cars(): + """Returns a list of all known car strings, FPv1 only.""" return list(_FINGERPRINTS.keys()) diff --git a/selfdrive/car/nissan/values.py b/selfdrive/car/nissan/values.py index 1bd8d8d80f4a96..3c91d3d22403de 100644 --- a/selfdrive/car/nissan/values.py +++ b/selfdrive/car/nissan/values.py @@ -50,7 +50,7 @@ class CAR: ], CAR.ALTIMA: [ { - 2: 5, 42: 6, 346: 6, 347: 5, 348: 8, 349: 7, 386: 8, 397: 8, 398: 8, 520: 2, 523: 6, 548: 8, 634: 7, 645: 8, 658: 8, 665: 8, 666: 8, 674: 2, 682: 8, 683: 8, 689: 8, 723: 8, 758: 3, 772: 8, 773: 6, 774: 7, 775: 8, 776: 6, 777: 7, 778: 6, 783: 3, 851: 8, 855: 5, 1001: 6, 1041: 8, 1042: 8, 1055: 3, 1100: 7, 1104: 4, 1105: 6, 1107: 4, 1108: 8, 1110: 7, 1111: 7, 1227: 8, 1228: 8, 1229: 8, 1232: 8, 1247: 4, 1266: 8, 1273: 7, 1306: 1, 1342: 1, 1376: 8, 1401: 8, 1497: 3, 1514: 6, 1526: 8, 1527: 5, 1792: 8, 1821: 8, 1823: 8, 1837: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 1988: 8, 2000: 8, 2001: 8, 2004: 8, 2005: 8, 2015: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8 + 2: 5, 42: 6, 346: 6, 347: 5, 348: 8, 349: 7, 361: 8, 386: 8, 389: 8, 397: 8, 398: 8, 403: 8, 438: 8, 451: 8, 517: 8, 520: 2, 522: 8, 523: 6, 539: 8, 541: 7, 542: 8, 543: 8, 544: 8, 545: 8, 546: 8, 547: 8, 548: 8, 570: 8, 576: 8, 577: 8, 582: 8, 583: 8, 584: 8, 586: 8, 587: 8, 588: 8, 589: 8, 590: 8, 591: 8, 592: 8, 600: 8, 601: 8, 610: 8, 611: 8, 612: 8, 614: 8, 615: 8, 616: 8, 617: 8, 622: 8, 623: 8, 634: 7, 638: 8, 645: 8, 648: 5, 654: 6, 658: 8, 659: 8, 660: 8, 661: 8, 665: 8, 666: 8, 674: 2, 675: 8, 676: 8, 682: 8, 683: 8, 684: 8, 685: 8, 686: 8, 687: 8, 689: 8, 690: 8, 703: 8, 708: 7, 709: 7, 711: 7, 712: 7, 713: 7, 714: 8, 715: 8, 716: 8, 717: 7, 718: 7, 719: 7, 720: 7, 723: 8, 726: 7, 727: 7, 728: 7, 735: 8, 746: 8, 748: 6, 749: 6, 750: 8, 758: 3, 772: 8, 773: 6, 774: 7, 775: 8, 776: 6, 777: 7, 778: 6, 779: 7, 781: 7, 782: 7, 783: 3, 851: 8, 855: 5, 1001: 6, 1041: 8, 1042: 8, 1055: 3, 1100: 7, 1104: 4, 1105: 6, 1107: 4, 1108: 8, 1110: 7, 1111: 7, 1144: 7, 1145: 7, 1227: 8, 1228: 8, 1229: 8, 1232: 8, 1247: 4, 1258: 8, 1259: 8, 1266: 8, 1273: 7, 1306: 1, 1314: 8, 1323: 8, 1324: 8, 1342: 1, 1376: 8, 1401: 8, 1454: 8, 1497: 3, 1514: 6, 1526: 8, 1527: 5, 1792: 8, 1821: 8, 1823: 8, 1837: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 1988: 8, 2000: 8, 2001: 8, 2004: 8, 2005: 8, 2015: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8 }, ] } diff --git a/selfdrive/car/tests/test_car_interfaces.py b/selfdrive/car/tests/test_car_interfaces.py index 7f603cb42d5057..93dc05c8386561 100755 --- a/selfdrive/car/tests/test_car_interfaces.py +++ b/selfdrive/car/tests/test_car_interfaces.py @@ -13,7 +13,10 @@ class TestCarInterfaces(unittest.TestCase): @parameterized.expand([(car,) for car in all_known_cars()]) def test_car_interfaces(self, car_name): print(car_name) - fingerprint = FINGERPRINTS[car_name][0] + if car_name in FINGERPRINTS: + fingerprint = FINGERPRINTS[car_name][0] + else: + fingerprint = {} CarInterface, CarController, CarState = interfaces[car_name] fingerprints = { diff --git a/selfdrive/car/volkswagen/interface.py b/selfdrive/car/volkswagen/interface.py index 9211264aacddc2..e6a1971a1433c0 100644 --- a/selfdrive/car/volkswagen/interface.py +++ b/selfdrive/car/volkswagen/interface.py @@ -97,6 +97,11 @@ def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=None): ret.mass = 1569 + STD_CARGO_KG ret.wheelbase = 2.79 + elif candidate == CAR.SKODA_OCTAVIA_MK3: + # Averages of all 5E/NE Octavia variants + ret.mass = 1388 + STD_CARGO_KG + ret.wheelbase = 2.68 + elif candidate == CAR.SKODA_SCALA_MK1: # Averages of all NW Scala variants ret.mass = 1192 + STD_CARGO_KG diff --git a/selfdrive/car/volkswagen/values.py b/selfdrive/car/volkswagen/values.py index 4768bbd16cdab2..c511febb460c89 100644 --- a/selfdrive/car/volkswagen/values.py +++ b/selfdrive/car/volkswagen/values.py @@ -65,6 +65,7 @@ class CAR: SKODA_KODIAQ_MK1 = "SKODA KODIAQ 1ST GEN" # Chassis NS, Mk1 Skoda Kodiaq SKODA_SCALA_MK1 = "SKODA SCALA 1ST GEN" # Chassis NW, Mk1 Skoda Scala and Skoda Kamiq SKODA_SUPERB_MK3 = "SKODA SUPERB 3RD GEN" # Chassis 3V/NP, Mk3 Skoda Superb and variants + SKODA_OCTAVIA_MK3 = "SKODA OCTAVIA 3RD GEN" # Chassis NE, Mk3 Skoda Octavia and variants FW_VERSIONS = { CAR.ATLAS_MK1: { @@ -349,6 +350,28 @@ class CAR: b'\xf1\x872Q0907572Q \xf1\x890342', ], }, + CAR.SKODA_OCTAVIA_MK3: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704E906027HD\xf1\x893742', + b'\xf1\x8704L906021DT\xf1\x898127', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870CW300043B \xf1\x891601', + b'\xf1\x870D9300041P \xf1\x894507', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x873Q0959655AC\xf1\x890200\xf1\x82\r11120011100010022212110200', + b'\xf1\x873Q0959655CN\xf1\x890720\xf1\x82\x0e3221003221002105755331052100', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521T00403A1', + b'\xf1\x875Q0909144R \xf1\x891061\xf1\x82\x0516A00604A1', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x875Q0907572D \xf1\x890304\xf1\x82\x0101', + b'\xf1\x875Q0907572P \xf1\x890682', + ], + }, CAR.SKODA_SCALA_MK1: { (Ecu.engine, 0x7e0, None): [ b'\xf1\x8704C906025AK\xf1\x897053', @@ -403,6 +426,7 @@ class CAR: CAR.AUDI_A3_MK3: dbc_dict('vw_mqb_2010', None), CAR.SEAT_ATECA_MK1: dbc_dict('vw_mqb_2010', None), CAR.SKODA_KODIAQ_MK1: dbc_dict('vw_mqb_2010', None), + CAR.SKODA_OCTAVIA_MK3: dbc_dict('vw_mqb_2010', None), CAR.SKODA_SCALA_MK1: dbc_dict('vw_mqb_2010', None), CAR.SKODA_SUPERB_MK3: dbc_dict('vw_mqb_2010', None), } diff --git a/selfdrive/debug/show_matching_cars.py b/selfdrive/debug/show_matching_cars.py index 81dff1f0602d57..79a23c1f8222a1 100755 --- a/selfdrive/debug/show_matching_cars.py +++ b/selfdrive/debug/show_matching_cars.py @@ -1,12 +1,12 @@ #!/usr/bin/env python3 -from selfdrive.car.fingerprints import eliminate_incompatible_cars, all_known_cars +from selfdrive.car.fingerprints import eliminate_incompatible_cars, all_legacy_fingerprint_cars import cereal.messaging as messaging # rav4 2019 and corolla tss2 fingerprint = {896: 8, 898: 8, 900: 6, 976: 1, 1541: 8, 902: 6, 905: 8, 810: 2, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1552: 8, 1553: 8, 1556: 8, 1571: 8, 921: 8, 1056: 8, 544: 4, 1570: 8, 1059: 1, 36: 8, 37: 8, 550: 8, 935: 8, 552: 4, 170: 8, 812: 8, 944: 8, 945: 8, 562: 6, 180: 8, 1077: 8, 951: 8, 1592: 8, 1076: 8, 186: 4, 955: 8, 956: 8, 1001: 8, 705: 8, 452: 8, 1788: 8, 464: 8, 824: 8, 466: 8, 467: 8, 761: 8, 728: 8, 1572: 8, 1114: 8, 933: 8, 800: 8, 608: 8, 865: 8, 610: 8, 1595: 8, 934: 8, 998: 5, 1745: 8, 1000: 8, 764: 8, 1002: 8, 999: 7, 1789: 8, 1649: 8, 1779: 8, 1568: 8, 1017: 8, 1786: 8, 1787: 8, 1020: 8, 426: 6, 1279: 8} -candidate_cars = all_known_cars() +candidate_cars = all_legacy_fingerprint_cars() for addr, l in fingerprint.items(): diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index 9ad92b9e277946..3849686123fda8 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -11,14 +11,13 @@ #include "selfdrive/common/visionimg.h" #include "selfdrive/common/watchdog.h" #include "selfdrive/hardware/hw.h" - #include "selfdrive/ui/paint.h" #include "selfdrive/ui/qt/qt_window.h" #include "selfdrive/ui/dashcam.h" #define BACKLIGHT_DT 0.25 #define BACKLIGHT_TS 2.00 -#define BACKLIGHT_OFFROAD 50 +#define BACKLIGHT_OFFROAD 75 // Projects a point in car to space to the corresponding point in full frame @@ -180,9 +179,6 @@ static void update_state(UIState *s) { } if (sm.updated("sensorEvents")) { for (auto sensor : sm["sensorEvents"].getSensorEvents()) { - if (!Hardware::TICI() && sensor.which() == cereal::SensorEventData::LIGHT) { - scene.light_sensor = sensor.getLight(); - } if (!scene.started && sensor.which() == cereal::SensorEventData::ACCELERATION) { auto accel = sensor.getAcceleration().getV(); if (accel.totalSize().wordCount){ // TODO: sometimes empty lists are received. Figure out why @@ -196,10 +192,18 @@ static void update_state(UIState *s) { } } } - if (Hardware::TICI() && sm.updated("roadCameraState")) { + if (sm.updated("roadCameraState")) { auto camera_state = sm["roadCameraState"].getRoadCameraState(); - float gain = camera_state.getGainFrac() * (camera_state.getGlobalGain() > 100 ? 2.5 : 1.0) / 10.0; - scene.light_sensor = std::clamp((1023.0 / 1757.0) * (1757.0 - camera_state.getIntegLines()) * (1.0 - gain), 0.0, 1023.0); + + float max_lines = Hardware::EON() ? 5408 : 1757; + float gain = camera_state.getGainFrac(); + + if (Hardware::TICI()) { + // gainFrac can go up to 4, with another 2.5x multiplier based on globalGain. Scale back to 0 - 1 + gain *= (camera_state.getGlobalGain() > 100 ? 2.5 : 1.0) / 10.0; + } + + scene.light_sensor = std::clamp((1023.0 / max_lines) * (max_lines - camera_state.getIntegLines() * gain), 0.0, 1023.0); } scene.started = sm["deviceState"].getDeviceState().getStarted() || scene.driver_view; } @@ -304,10 +308,7 @@ QUIState::QUIState(QObject *parent) : QObject(parent) { ui_state.sm = std::make_unique>({ "modelV2", "controlsState", "liveCalibration", "radarState", "deviceState", "liveLocationKalman", "pandaState", "carParams", "driverState", "driverMonitoringState", "sensorEvents", "carState", "ubloxGnss", - "gpsLocationExternal", -#ifdef QCOM2 - "roadCameraState", -#endif + "gpsLocationExternal", "roadCameraState", "carControl", "liveParameters"}); ui_state.fb_w = vwp_w; @@ -354,7 +355,7 @@ void QUIState::update() { Device::Device(QObject *parent) : brightness_filter(BACKLIGHT_OFFROAD, BACKLIGHT_TS, BACKLIGHT_DT), QObject(parent) { brightness_b = Params(true).get("BRIGHTNESS_B").value_or(10.0); - brightness_m = Params(true).get("BRIGHTNESS_M").value_or(0.1); + brightness_m = Params(true).get("BRIGHTNESS_M").value_or(2.6) / 26.0; } void Device::update(const UIState &s) { @@ -380,7 +381,7 @@ void Device::setAwake(bool on, bool reset) { void Device::updateBrightness(const UIState &s) { float clipped_brightness = std::min(100.0f, (s.scene.light_sensor * brightness_m) + brightness_b); - if (Hardware::TICI() && !s.scene.started) { + if (!s.scene.started) { clipped_brightness = BACKLIGHT_OFFROAD; } diff --git a/selfdrive/version.py b/selfdrive/version.py index b06841832b596a..4289d5ca9373bf 100644 --- a/selfdrive/version.py +++ b/selfdrive/version.py @@ -39,9 +39,12 @@ def get_git_remote(default: Optional[str] = None) -> Optional[str]: return run_cmd_default(["git", "config", "--get", "remote.origin.url"], default=default) -with open(os.path.join(os.path.dirname(os.path.abspath(__file__)), "common", "version.h")) as _versionf: - version = _versionf.read().split('"')[1] +def get_version(): + 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" From c590feb45202084ca62c9b37e511c66d1bb59ef4 Mon Sep 17 00:00:00 2001 From: neokii Date: Thu, 27 May 2021 11:09:59 +0900 Subject: [PATCH 18/27] merge changes from master-ci --- README.md | 3 +- RELEASES.md | 1 + common/transformations/camera.py | 11 +---- release/build_release2.sh | 2 +- selfdrive/athena/athenad.py | 12 +++++- selfdrive/camerad/snapshot/snapshot.py | 50 ++++++++++++++-------- selfdrive/car/car_helpers.py | 4 +- selfdrive/car/fingerprints.py | 5 +++ selfdrive/car/nissan/values.py | 2 +- selfdrive/car/tests/test_car_interfaces.py | 5 ++- selfdrive/car/volkswagen/interface.py | 5 +++ selfdrive/car/volkswagen/values.py | 24 +++++++++++ selfdrive/controls/controlsd.py | 3 +- selfdrive/debug/show_matching_cars.py | 4 +- selfdrive/ui/paint.cc | 3 +- selfdrive/ui/ui.cc | 29 +++++++------ selfdrive/version.py | 7 ++- 17 files changed, 115 insertions(+), 55 deletions(-) diff --git a/README.md b/README.md index 987151d63c0545..cec3c32dab4cbe 100644 --- a/README.md +++ b/README.md @@ -179,12 +179,13 @@ Community Maintained Cars and Features | Kia | Sorento 2018-19 | SCC + LKAS | Stock | 0mph | 0mph | | Kia | Stinger 2018 | SCC + LKAS | Stock | 0mph | 0mph | | Kia | Ceed 2019 | SCC + LKAS | Stock | 0mph | 0mph | -| Nissan | Altima 2020 | ProPILOT | Stock | 0mph | 0mph | +| Nissan | Altima 2019-20 | ProPILOT | Stock | 0mph | 0mph | | Nissan | Leaf 2018-20 | ProPILOT | Stock | 0mph | 0mph | | Nissan | Rogue 2018-20 | ProPILOT | Stock | 0mph | 0mph | | Nissan | X-Trail 2017 | ProPILOT | Stock | 0mph | 0mph | | SEAT | Ateca 2018 | Driver Assistance | Stock | 0mph | 0mph | | Škoda | Kodiaq 2018 | Driver Assistance | Stock | 0mph | 0mph | +| Škoda | Octavia 2015, 2019 | Driver Assistance | Stock | 0mph | 0mph | | Škoda | Scala 2020 | Driver Assistance | Stock | 0mph | 0mph | | Škoda | Superb 2015-18 | Driver Assistance | Stock | 0mph | 0mph | | Subaru | Ascent 2019 | EyeSight | Stock | 0mph | 0mph | diff --git a/RELEASES.md b/RELEASES.md index 4edc374c946cb7..5dbf50b1819500 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -4,6 +4,7 @@ Version 0.8.5 (2021-XX-XX) * Smart model-based Forward Collision Warning * Hyundai Elantra 2021 support thanks to CruiseBrantley! * Lexus UX Hybrid 2019 support thanks to brianhaugen2! + * Škoda Octavia 2015 & 2019 support thanks to jyoung8607! Version 0.8.4 (2021-05-17) ======================== diff --git a/common/transformations/camera.py b/common/transformations/camera.py index 9c365dc7e3adb8..29ce3277d77ead 100644 --- a/common/transformations/camera.py +++ b/common/transformations/camera.py @@ -5,14 +5,12 @@ ## -- hardcoded hardware params -- eon_f_focal_length = 910.0 -eon_d_focal_length = 860.0 -leon_d_focal_length = 650.0 +eon_d_focal_length = 650.0 tici_f_focal_length = 2648.0 tici_e_focal_length = tici_d_focal_length = 567.0 # probably wrong? magnification is not consistent across frame eon_f_frame_size = (1164, 874) -eon_d_frame_size = (1152, 864) -leon_d_frame_size = (816, 612) +eon_d_frame_size = (816, 612) tici_f_frame_size = tici_e_frame_size = tici_d_frame_size = (1928, 1208) # aka 'K' aka camera_frame_from_view_frame @@ -22,11 +20,6 @@ [0.0, 0.0, 1.0]]) eon_intrinsics = eon_fcam_intrinsics # xx -leon_dcam_intrinsics = np.array([ - [leon_d_focal_length, 0.0, float(leon_d_frame_size[0])/2], - [0.0, leon_d_focal_length, float(leon_d_frame_size[1])/2], - [0.0, 0.0, 1.0]]) - eon_dcam_intrinsics = np.array([ [eon_d_focal_length, 0.0, float(eon_d_frame_size[0])/2], [0.0, eon_d_focal_length, float(eon_d_frame_size[1])/2], diff --git a/release/build_release2.sh b/release/build_release2.sh index fe4936913f5936..eaf7b82f47da4e 100755 --- a/release/build_release2.sh +++ b/release/build_release2.sh @@ -49,7 +49,7 @@ popd # Build stuff ln -sfn /data/openpilot /data/pythonpath export PYTHONPATH="/data/openpilot:/data/openpilot/pyextra" -SCONS_CACHE=1 scons -j3 +selfdrive/manager/build.py # Run tests python selfdrive/manager/test/test_manager.py diff --git a/selfdrive/athena/athenad.py b/selfdrive/athena/athenad.py index 5d308f7a77aecd..c6d6b8f69b6f67 100755 --- a/selfdrive/athena/athenad.py +++ b/selfdrive/athena/athenad.py @@ -30,7 +30,7 @@ from selfdrive.loggerd.xattr_cache import getxattr, setxattr from selfdrive.swaglog import cloudlog, SWAGLOG_DIR import selfdrive.crash as crash -from selfdrive.version import dirty, origin, branch, commit +from selfdrive.version import dirty, origin, branch, commit, get_version, get_git_remote, get_git_branch, get_git_commit ATHENA_HOST = os.getenv('ATHENA_HOST', 'wss://athena.comma.ai') HANDLER_THREADS = int(os.getenv('HANDLER_THREADS', "4")) @@ -132,6 +132,16 @@ def getMessage(service=None, timeout=1000): return ret.to_dict() +@dispatcher.add_method +def getVersion(): + return { + "version": get_version(), + "remote": get_git_remote(), + "branch": get_git_branch(), + "commit": get_git_commit(), + } + + @dispatcher.add_method def setNavDestination(latitude=0, longitude=0): destination = { diff --git a/selfdrive/camerad/snapshot/snapshot.py b/selfdrive/camerad/snapshot/snapshot.py index eb7bb93af32f8e..b7dd300da160af 100755 --- a/selfdrive/camerad/snapshot/snapshot.py +++ b/selfdrive/camerad/snapshot/snapshot.py @@ -1,18 +1,21 @@ #!/usr/bin/env python3 import os -import signal import subprocess import time import numpy as np from PIL import Image +from typing import List import cereal.messaging as messaging -from common.basedir import BASEDIR from common.params import Params -from common.transformations.camera import eon_f_frame_size, eon_d_frame_size, leon_d_frame_size, tici_f_frame_size +from common.realtime import DT_MDL +from common.transformations.camera import eon_f_frame_size, eon_d_frame_size, tici_f_frame_size from selfdrive.hardware import TICI from selfdrive.controls.lib.alertmanager import set_offroad_alert +from selfdrive.manager.process_config import managed_processes + +LM_THRESH = 120 # defined in selfdrive/camerad/imgproc/utils.h def jpeg_write(fn, dat): @@ -29,8 +32,14 @@ def extract_image(dat, frame_sizes): return np.dstack([r, g, b]) -def get_snapshots(frame="roadCameraState", front_frame="driverCameraState"): - frame_sizes = [eon_f_frame_size, eon_d_frame_size, leon_d_frame_size, tici_f_frame_size] +def rois_in_focus(lapres: List[float]) -> float: + sz = len(lapres) + return sum([1. / sz for sharpness in + lapres if sharpness >= LM_THRESH]) + + +def get_snapshots(frame="roadCameraState", front_frame="driverCameraState", focus_perc_threshold=0.): + frame_sizes = [eon_f_frame_size, eon_d_frame_size, tici_f_frame_size] frame_sizes = {w * h: (w, h) for (w, h) in frame_sizes} sockets = [] @@ -39,10 +48,17 @@ def get_snapshots(frame="roadCameraState", front_frame="driverCameraState"): if front_frame is not None: sockets.append(front_frame) + # wait 4 sec from camerad startup for focus and exposure sm = messaging.SubMaster(sockets) - while min(sm.logMonoTime.values()) == 0: + while sm[sockets[0]].frameId < int(4. / DT_MDL): sm.update() + start_t = time.monotonic() + while time.monotonic() - start_t < 10: + sm.update() + if min(sm.rcv_frame.values()) > 1 and rois_in_focus(sm[frame].sharpnessScore) >= focus_perc_threshold: + break + rear = extract_image(sm[frame].image, frame_sizes) if frame is not None else None front = extract_image(sm[front_frame].image, frame_sizes) if front_frame is not None else None return rear, front @@ -63,7 +79,6 @@ def snapshot(): # Check if camerad is already started try: subprocess.check_call(["pgrep", "camerad"]) - print("Camerad already running") params.put_bool("IsTakingSnapshot", False) params.delete("Offroad_IsTakingSnapshot") @@ -71,23 +86,19 @@ def snapshot(): except subprocess.CalledProcessError: pass - env = os.environ.copy() - env["SEND_ROAD"] = "1" - env["SEND_WIDE_ROAD"] = "1" + os.environ["SEND_ROAD"] = "1" + os.environ["SEND_WIDE_ROAD"] = "1" if front_camera_allowed: - env["SEND_DRIVER"] = "1" - - proc = subprocess.Popen(os.path.join(BASEDIR, "selfdrive/camerad/camerad"), - cwd=os.path.join(BASEDIR, "selfdrive/camerad"), env=env) - time.sleep(3.0) + os.environ["SEND_DRIVER"] = "1" + managed_processes['camerad'].start() frame = "wideRoadCameraState" if TICI else "roadCameraState" front_frame = "driverCameraState" if front_camera_allowed else None - rear, front = get_snapshots(frame, front_frame) + focus_perc_threshold = 0. if TICI else 10 / 12. - proc.send_signal(signal.SIGINT) - proc.communicate() + rear, front = get_snapshots(frame, front_frame, focus_perc_threshold) + managed_processes['camerad'].stop() params.put_bool("IsTakingSnapshot", False) set_offroad_alert("Offroad_IsTakingSnapshot", False) @@ -103,6 +114,7 @@ def snapshot(): if pic is not None: print(pic.shape) jpeg_write("/tmp/back.jpg", pic) - jpeg_write("/tmp/front.jpg", fpic) + if fpic is not None: + jpeg_write("/tmp/front.jpg", fpic) else: print("Error taking snapshot") diff --git a/selfdrive/car/car_helpers.py b/selfdrive/car/car_helpers.py index d548f7e4a6a662..4f74ff72fa414d 100644 --- a/selfdrive/car/car_helpers.py +++ b/selfdrive/car/car_helpers.py @@ -2,7 +2,7 @@ from common.params import Params from common.basedir import BASEDIR from selfdrive.car.hyundai.values import CAR_FORCE_RECOGNITION -from selfdrive.car.fingerprints import eliminate_incompatible_cars, all_known_cars +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 from selfdrive.swaglog import cloudlog @@ -113,7 +113,7 @@ def fingerprint(logcan, sendcan, has_relay): Params().put("CarVin", vin) finger = gen_empty_fingerprint() - candidate_cars = {i: all_known_cars() for i in [0]} # attempt fingerprint on bus 0 only + candidate_cars = {i: all_legacy_fingerprint_cars() for i in [0, 1]} # attempt fingerprint on both bus 0 and 1 frame = 0 frame_fingerprint = 10 # 0.1s car_fingerprint = None diff --git a/selfdrive/car/fingerprints.py b/selfdrive/car/fingerprints.py index 9daa940792d81b..b09e14a429ffb9 100644 --- a/selfdrive/car/fingerprints.py +++ b/selfdrive/car/fingerprints.py @@ -72,4 +72,9 @@ def eliminate_incompatible_cars(msg, candidate_cars): def all_known_cars(): """Returns a list of all known car strings.""" + return list({*FW_VERSIONS.keys(), *_FINGERPRINTS.keys()}) + + +def all_legacy_fingerprint_cars(): + """Returns a list of all known car strings, FPv1 only.""" return list(_FINGERPRINTS.keys()) diff --git a/selfdrive/car/nissan/values.py b/selfdrive/car/nissan/values.py index 1bd8d8d80f4a96..3c91d3d22403de 100644 --- a/selfdrive/car/nissan/values.py +++ b/selfdrive/car/nissan/values.py @@ -50,7 +50,7 @@ class CAR: ], CAR.ALTIMA: [ { - 2: 5, 42: 6, 346: 6, 347: 5, 348: 8, 349: 7, 386: 8, 397: 8, 398: 8, 520: 2, 523: 6, 548: 8, 634: 7, 645: 8, 658: 8, 665: 8, 666: 8, 674: 2, 682: 8, 683: 8, 689: 8, 723: 8, 758: 3, 772: 8, 773: 6, 774: 7, 775: 8, 776: 6, 777: 7, 778: 6, 783: 3, 851: 8, 855: 5, 1001: 6, 1041: 8, 1042: 8, 1055: 3, 1100: 7, 1104: 4, 1105: 6, 1107: 4, 1108: 8, 1110: 7, 1111: 7, 1227: 8, 1228: 8, 1229: 8, 1232: 8, 1247: 4, 1266: 8, 1273: 7, 1306: 1, 1342: 1, 1376: 8, 1401: 8, 1497: 3, 1514: 6, 1526: 8, 1527: 5, 1792: 8, 1821: 8, 1823: 8, 1837: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 1988: 8, 2000: 8, 2001: 8, 2004: 8, 2005: 8, 2015: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8 + 2: 5, 42: 6, 346: 6, 347: 5, 348: 8, 349: 7, 361: 8, 386: 8, 389: 8, 397: 8, 398: 8, 403: 8, 438: 8, 451: 8, 517: 8, 520: 2, 522: 8, 523: 6, 539: 8, 541: 7, 542: 8, 543: 8, 544: 8, 545: 8, 546: 8, 547: 8, 548: 8, 570: 8, 576: 8, 577: 8, 582: 8, 583: 8, 584: 8, 586: 8, 587: 8, 588: 8, 589: 8, 590: 8, 591: 8, 592: 8, 600: 8, 601: 8, 610: 8, 611: 8, 612: 8, 614: 8, 615: 8, 616: 8, 617: 8, 622: 8, 623: 8, 634: 7, 638: 8, 645: 8, 648: 5, 654: 6, 658: 8, 659: 8, 660: 8, 661: 8, 665: 8, 666: 8, 674: 2, 675: 8, 676: 8, 682: 8, 683: 8, 684: 8, 685: 8, 686: 8, 687: 8, 689: 8, 690: 8, 703: 8, 708: 7, 709: 7, 711: 7, 712: 7, 713: 7, 714: 8, 715: 8, 716: 8, 717: 7, 718: 7, 719: 7, 720: 7, 723: 8, 726: 7, 727: 7, 728: 7, 735: 8, 746: 8, 748: 6, 749: 6, 750: 8, 758: 3, 772: 8, 773: 6, 774: 7, 775: 8, 776: 6, 777: 7, 778: 6, 779: 7, 781: 7, 782: 7, 783: 3, 851: 8, 855: 5, 1001: 6, 1041: 8, 1042: 8, 1055: 3, 1100: 7, 1104: 4, 1105: 6, 1107: 4, 1108: 8, 1110: 7, 1111: 7, 1144: 7, 1145: 7, 1227: 8, 1228: 8, 1229: 8, 1232: 8, 1247: 4, 1258: 8, 1259: 8, 1266: 8, 1273: 7, 1306: 1, 1314: 8, 1323: 8, 1324: 8, 1342: 1, 1376: 8, 1401: 8, 1454: 8, 1497: 3, 1514: 6, 1526: 8, 1527: 5, 1792: 8, 1821: 8, 1823: 8, 1837: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 1988: 8, 2000: 8, 2001: 8, 2004: 8, 2005: 8, 2015: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8 }, ] } diff --git a/selfdrive/car/tests/test_car_interfaces.py b/selfdrive/car/tests/test_car_interfaces.py index 7f603cb42d5057..93dc05c8386561 100755 --- a/selfdrive/car/tests/test_car_interfaces.py +++ b/selfdrive/car/tests/test_car_interfaces.py @@ -13,7 +13,10 @@ class TestCarInterfaces(unittest.TestCase): @parameterized.expand([(car,) for car in all_known_cars()]) def test_car_interfaces(self, car_name): print(car_name) - fingerprint = FINGERPRINTS[car_name][0] + if car_name in FINGERPRINTS: + fingerprint = FINGERPRINTS[car_name][0] + else: + fingerprint = {} CarInterface, CarController, CarState = interfaces[car_name] fingerprints = { diff --git a/selfdrive/car/volkswagen/interface.py b/selfdrive/car/volkswagen/interface.py index 9211264aacddc2..e6a1971a1433c0 100644 --- a/selfdrive/car/volkswagen/interface.py +++ b/selfdrive/car/volkswagen/interface.py @@ -97,6 +97,11 @@ def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=None): ret.mass = 1569 + STD_CARGO_KG ret.wheelbase = 2.79 + elif candidate == CAR.SKODA_OCTAVIA_MK3: + # Averages of all 5E/NE Octavia variants + ret.mass = 1388 + STD_CARGO_KG + ret.wheelbase = 2.68 + elif candidate == CAR.SKODA_SCALA_MK1: # Averages of all NW Scala variants ret.mass = 1192 + STD_CARGO_KG diff --git a/selfdrive/car/volkswagen/values.py b/selfdrive/car/volkswagen/values.py index 4768bbd16cdab2..c511febb460c89 100644 --- a/selfdrive/car/volkswagen/values.py +++ b/selfdrive/car/volkswagen/values.py @@ -65,6 +65,7 @@ class CAR: SKODA_KODIAQ_MK1 = "SKODA KODIAQ 1ST GEN" # Chassis NS, Mk1 Skoda Kodiaq SKODA_SCALA_MK1 = "SKODA SCALA 1ST GEN" # Chassis NW, Mk1 Skoda Scala and Skoda Kamiq SKODA_SUPERB_MK3 = "SKODA SUPERB 3RD GEN" # Chassis 3V/NP, Mk3 Skoda Superb and variants + SKODA_OCTAVIA_MK3 = "SKODA OCTAVIA 3RD GEN" # Chassis NE, Mk3 Skoda Octavia and variants FW_VERSIONS = { CAR.ATLAS_MK1: { @@ -349,6 +350,28 @@ class CAR: b'\xf1\x872Q0907572Q \xf1\x890342', ], }, + CAR.SKODA_OCTAVIA_MK3: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704E906027HD\xf1\x893742', + b'\xf1\x8704L906021DT\xf1\x898127', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870CW300043B \xf1\x891601', + b'\xf1\x870D9300041P \xf1\x894507', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x873Q0959655AC\xf1\x890200\xf1\x82\r11120011100010022212110200', + b'\xf1\x873Q0959655CN\xf1\x890720\xf1\x82\x0e3221003221002105755331052100', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521T00403A1', + b'\xf1\x875Q0909144R \xf1\x891061\xf1\x82\x0516A00604A1', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x875Q0907572D \xf1\x890304\xf1\x82\x0101', + b'\xf1\x875Q0907572P \xf1\x890682', + ], + }, CAR.SKODA_SCALA_MK1: { (Ecu.engine, 0x7e0, None): [ b'\xf1\x8704C906025AK\xf1\x897053', @@ -403,6 +426,7 @@ class CAR: CAR.AUDI_A3_MK3: dbc_dict('vw_mqb_2010', None), CAR.SEAT_ATECA_MK1: dbc_dict('vw_mqb_2010', None), CAR.SKODA_KODIAQ_MK1: dbc_dict('vw_mqb_2010', None), + CAR.SKODA_OCTAVIA_MK3: dbc_dict('vw_mqb_2010', None), CAR.SKODA_SCALA_MK1: dbc_dict('vw_mqb_2010', None), CAR.SKODA_SUPERB_MK3: dbc_dict('vw_mqb_2010', None), } diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 005d8b1c8c0211..1f6d558919602f 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -202,7 +202,8 @@ def update_events(self, CS): if self.sm['deviceState'].freeSpacePercent < 7: # under 7% of space free no enable allowed self.events.add(EventName.outOfSpace) - if self.sm['deviceState'].memoryUsagePercent > 90: + # TODO: make tici threshold the same + if self.sm['deviceState'].memoryUsagePercent > (90 if TICI else 65): self.events.add(EventName.lowMemory) # Alert if fan isn't spinning for 5 seconds diff --git a/selfdrive/debug/show_matching_cars.py b/selfdrive/debug/show_matching_cars.py index 81dff1f0602d57..79a23c1f8222a1 100755 --- a/selfdrive/debug/show_matching_cars.py +++ b/selfdrive/debug/show_matching_cars.py @@ -1,12 +1,12 @@ #!/usr/bin/env python3 -from selfdrive.car.fingerprints import eliminate_incompatible_cars, all_known_cars +from selfdrive.car.fingerprints import eliminate_incompatible_cars, all_legacy_fingerprint_cars import cereal.messaging as messaging # rav4 2019 and corolla tss2 fingerprint = {896: 8, 898: 8, 900: 6, 976: 1, 1541: 8, 902: 6, 905: 8, 810: 2, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1552: 8, 1553: 8, 1556: 8, 1571: 8, 921: 8, 1056: 8, 544: 4, 1570: 8, 1059: 1, 36: 8, 37: 8, 550: 8, 935: 8, 552: 4, 170: 8, 812: 8, 944: 8, 945: 8, 562: 6, 180: 8, 1077: 8, 951: 8, 1592: 8, 1076: 8, 186: 4, 955: 8, 956: 8, 1001: 8, 705: 8, 452: 8, 1788: 8, 464: 8, 824: 8, 466: 8, 467: 8, 761: 8, 728: 8, 1572: 8, 1114: 8, 933: 8, 800: 8, 608: 8, 865: 8, 610: 8, 1595: 8, 934: 8, 998: 5, 1745: 8, 1000: 8, 764: 8, 1002: 8, 999: 7, 1789: 8, 1649: 8, 1779: 8, 1568: 8, 1017: 8, 1786: 8, 1787: 8, 1020: 8, 426: 6, 1279: 8} -candidate_cars = all_known_cars() +candidate_cars = all_legacy_fingerprint_cars() for addr, l in fingerprint.items(): diff --git a/selfdrive/ui/paint.cc b/selfdrive/ui/paint.cc index 55d9863aa72dbb..4fe8f5b7b4f10c 100644 --- a/selfdrive/ui/paint.cc +++ b/selfdrive/ui/paint.cc @@ -135,13 +135,14 @@ static void draw_lead_custom(UIState *s, const cereal::RadarState::LeadData::Rea x = std::clamp(x, 0.f, s->viz_rect.right() - sz / 2); if(d_rel < 30) { - const float c = 0.77f; + const float c = 0.7f; float r = d_rel * ((1.f - c) / 30.f) + c; if(r > 0.f) y = y * r; } y = std::fmin(s->viz_rect.bottom() - sz * .6, y); + y = std::fmin(s->viz_rect.bottom() * 0.8f, y); float bg_alpha = 1.0f; float img_alpha = 1.0f; diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index 9ad92b9e277946..3849686123fda8 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -11,14 +11,13 @@ #include "selfdrive/common/visionimg.h" #include "selfdrive/common/watchdog.h" #include "selfdrive/hardware/hw.h" - #include "selfdrive/ui/paint.h" #include "selfdrive/ui/qt/qt_window.h" #include "selfdrive/ui/dashcam.h" #define BACKLIGHT_DT 0.25 #define BACKLIGHT_TS 2.00 -#define BACKLIGHT_OFFROAD 50 +#define BACKLIGHT_OFFROAD 75 // Projects a point in car to space to the corresponding point in full frame @@ -180,9 +179,6 @@ static void update_state(UIState *s) { } if (sm.updated("sensorEvents")) { for (auto sensor : sm["sensorEvents"].getSensorEvents()) { - if (!Hardware::TICI() && sensor.which() == cereal::SensorEventData::LIGHT) { - scene.light_sensor = sensor.getLight(); - } if (!scene.started && sensor.which() == cereal::SensorEventData::ACCELERATION) { auto accel = sensor.getAcceleration().getV(); if (accel.totalSize().wordCount){ // TODO: sometimes empty lists are received. Figure out why @@ -196,10 +192,18 @@ static void update_state(UIState *s) { } } } - if (Hardware::TICI() && sm.updated("roadCameraState")) { + if (sm.updated("roadCameraState")) { auto camera_state = sm["roadCameraState"].getRoadCameraState(); - float gain = camera_state.getGainFrac() * (camera_state.getGlobalGain() > 100 ? 2.5 : 1.0) / 10.0; - scene.light_sensor = std::clamp((1023.0 / 1757.0) * (1757.0 - camera_state.getIntegLines()) * (1.0 - gain), 0.0, 1023.0); + + float max_lines = Hardware::EON() ? 5408 : 1757; + float gain = camera_state.getGainFrac(); + + if (Hardware::TICI()) { + // gainFrac can go up to 4, with another 2.5x multiplier based on globalGain. Scale back to 0 - 1 + gain *= (camera_state.getGlobalGain() > 100 ? 2.5 : 1.0) / 10.0; + } + + scene.light_sensor = std::clamp((1023.0 / max_lines) * (max_lines - camera_state.getIntegLines() * gain), 0.0, 1023.0); } scene.started = sm["deviceState"].getDeviceState().getStarted() || scene.driver_view; } @@ -304,10 +308,7 @@ QUIState::QUIState(QObject *parent) : QObject(parent) { ui_state.sm = std::make_unique>({ "modelV2", "controlsState", "liveCalibration", "radarState", "deviceState", "liveLocationKalman", "pandaState", "carParams", "driverState", "driverMonitoringState", "sensorEvents", "carState", "ubloxGnss", - "gpsLocationExternal", -#ifdef QCOM2 - "roadCameraState", -#endif + "gpsLocationExternal", "roadCameraState", "carControl", "liveParameters"}); ui_state.fb_w = vwp_w; @@ -354,7 +355,7 @@ void QUIState::update() { Device::Device(QObject *parent) : brightness_filter(BACKLIGHT_OFFROAD, BACKLIGHT_TS, BACKLIGHT_DT), QObject(parent) { brightness_b = Params(true).get("BRIGHTNESS_B").value_or(10.0); - brightness_m = Params(true).get("BRIGHTNESS_M").value_or(0.1); + brightness_m = Params(true).get("BRIGHTNESS_M").value_or(2.6) / 26.0; } void Device::update(const UIState &s) { @@ -380,7 +381,7 @@ void Device::setAwake(bool on, bool reset) { void Device::updateBrightness(const UIState &s) { float clipped_brightness = std::min(100.0f, (s.scene.light_sensor * brightness_m) + brightness_b); - if (Hardware::TICI() && !s.scene.started) { + if (!s.scene.started) { clipped_brightness = BACKLIGHT_OFFROAD; } diff --git a/selfdrive/version.py b/selfdrive/version.py index b06841832b596a..4289d5ca9373bf 100644 --- a/selfdrive/version.py +++ b/selfdrive/version.py @@ -39,9 +39,12 @@ def get_git_remote(default: Optional[str] = None) -> Optional[str]: return run_cmd_default(["git", "config", "--get", "remote.origin.url"], default=default) -with open(os.path.join(os.path.dirname(os.path.abspath(__file__)), "common", "version.h")) as _versionf: - version = _versionf.read().split('"')[1] +def get_version(): + 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" From e92c77735c18c9b6bd0e1b0e3abd7615fa972b92 Mon Sep 17 00:00:00 2001 From: neokii Date: Thu, 27 May 2021 18:05:29 +0900 Subject: [PATCH 19/27] fix online --- selfdrive/ui/qt/sidebar.cc | 12 +++--------- 1 file changed, 3 insertions(+), 9 deletions(-) diff --git a/selfdrive/ui/qt/sidebar.cc b/selfdrive/ui/qt/sidebar.cc index 32769075b40c4a..2fc403ad0710c0 100644 --- a/selfdrive/ui/qt/sidebar.cc +++ b/selfdrive/ui/qt/sidebar.cc @@ -58,15 +58,9 @@ void Sidebar::updateState(const UIState &s) { setProperty("netStrength", signal_imgs[deviceState.getNetworkStrength()]); setProperty("wifiAddr", deviceState.getWifiIpAddress().cStr()); - auto last_ping = deviceState.getLastAthenaPingTime(); - if (last_ping == 0) { - setProperty("connectStr", "OFFLINE"); - setProperty("connectStatus", warning_color); - } else { - bool online = true;//nanos_since_boot() - last_ping < 80e9; - setProperty("connectStr", online ? "ONLINE" : "ERROR"); - setProperty("connectStatus", online ? good_color : danger_color); - } + bool online = net_type != network_type[cereal::DeviceState::NetworkType::NONE]; + setProperty("connectStr", online ? "ONLINE" : "OFFLINE"); + setProperty("connectStatus", online ? good_color : danger_color); QColor tempStatus = danger_color; auto ts = deviceState.getThermalStatus(); From 93befc44804cb3e8fec66290ebaf4955ec0b5da7 Mon Sep 17 00:00:00 2001 From: neokii Date: Thu, 27 May 2021 20:35:04 +0900 Subject: [PATCH 20/27] tune scc --- selfdrive/car/hyundai/interface.py | 2 +- selfdrive/car/hyundai/scc_smoother.py | 4 ++-- selfdrive/controls/lib/long_mpc.py | 3 ++- 3 files changed, 5 insertions(+), 4 deletions(-) diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 32230e47c3f31f..cfe6dae9854f02 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -68,7 +68,7 @@ def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, # longitudinal ret.longitudinalTuning.kpBP = [0, 10. * CV.KPH_TO_MS, 20. * CV.KPH_TO_MS, 40. * CV.KPH_TO_MS, 70. * CV.KPH_TO_MS, 100. * CV.KPH_TO_MS, 130. * CV.KPH_TO_MS] - ret.longitudinalTuning.kpV = [0.95, 0.75, 0.57, 0.45, 0.4, 0.34, 0.25] + ret.longitudinalTuning.kpV = [0.95, 0.75, 0.57, 0.45, 0.4, 0.34, 0.27] ret.longitudinalTuning.kiBP = [0.] ret.longitudinalTuning.kiV = [0.015] ret.longitudinalTuning.kf = 0.9 diff --git a/selfdrive/car/hyundai/scc_smoother.py b/selfdrive/car/hyundai/scc_smoother.py index a8898ea51be583..8a6414b1cb0eb8 100644 --- a/selfdrive/car/hyundai/scc_smoother.py +++ b/selfdrive/car/hyundai/scc_smoother.py @@ -266,10 +266,10 @@ def get_long_lead_speed(self, CS, clu11_speed, sm): if lead is not None: d = lead.dRel - 5. #cruise_gap = clip(CS.cruise_gap, 1., 4.) - if 0. < d < -lead.vRel * (9. + 1.) * 2. and lead.vRel < -1.: + if 0. < d < -lead.vRel * (9. + 3.) * 2. and lead.vRel < -1.: t = d / lead.vRel accel = -(lead.vRel / t) * self.speed_conv_to_clu - accel *= 1.3 + accel *= 1.4 if accel < 0.: target_speed = clu11_speed + accel diff --git a/selfdrive/controls/lib/long_mpc.py b/selfdrive/controls/lib/long_mpc.py index a942085e2b6323..01e245b3263522 100644 --- a/selfdrive/controls/lib/long_mpc.py +++ b/selfdrive/controls/lib/long_mpc.py @@ -83,7 +83,8 @@ def update(self, CS, lead): v_lead = max(0.0, lead.vLead) a_lead = lead.aLeadK - dist_cost = interp(lead.dRel, [5., 10.], [MPC_COST_LONG.DISTANCE/1.5, MPC_COST_LONG.DISTANCE]) + dist_cost = interp(lead.dRel, [4., 20.], [MPC_COST_LONG.DISTANCE/2.0, MPC_COST_LONG.DISTANCE]) + dist_cost = interp(v_ego, [80.*CV.KPH_TO_MS, 100.*CV.KPH_TO_MS], [dist_cost, MPC_COST_LONG.DISTANCE]) self.libmpc.set_weights(MPC_COST_LONG.TTC, dist_cost, MPC_COST_LONG.ACCELERATION, MPC_COST_LONG.JERK) if (v_lead < 0.1 or -a_lead / 2.0 > v_lead): From 91e4324b66d20768a6748c76f47084852e54f557 Mon Sep 17 00:00:00 2001 From: neokii Date: Fri, 28 May 2021 18:02:09 +0900 Subject: [PATCH 21/27] sync margin --- selfdrive/car/hyundai/scc_smoother.py | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/selfdrive/car/hyundai/scc_smoother.py b/selfdrive/car/hyundai/scc_smoother.py index 8a6414b1cb0eb8..63e0d5e618101c 100644 --- a/selfdrive/car/hyundai/scc_smoother.py +++ b/selfdrive/car/hyundai/scc_smoother.py @@ -10,6 +10,8 @@ from selfdrive.controls.lib.lane_planner import TRAJECTORY_SIZE from selfdrive.road_speed_limiter import road_speed_limiter_get_max_speed, road_speed_limiter_get_active +SYNC_MARGIN = 3. + # do not modify MIN_SET_SPEED_KPH = V_CRUISE_MIN MAX_SET_SPEED_KPH = V_CRUISE_MAX @@ -307,8 +309,8 @@ def cal_target_speed(self, CS, clu11_speed, controls): if not self.longcontrol: if CS.gas_pressed and self.sync_set_speed_while_gas_pressed and CS.cruise_buttons == Buttons.NONE: - if clu11_speed + 2. > self.kph_to_clu(controls.v_cruise_kph): - set_speed = clip(clu11_speed + 2., self.min_set_speed_clu, self.max_set_speed_clu) + if clu11_speed + SYNC_MARGIN > self.kph_to_clu(controls.v_cruise_kph): + set_speed = clip(clu11_speed + SYNC_MARGIN, self.min_set_speed_clu, self.max_set_speed_clu) controls.v_cruise_kph = set_speed * self.speed_conv_to_ms * CV.MS_TO_KPH self.target_speed = self.kph_to_clu(controls.v_cruise_kph) @@ -318,8 +320,8 @@ def cal_target_speed(self, CS, clu11_speed, controls): elif CS.cruiseState_enabled: if CS.gas_pressed and self.sync_set_speed_while_gas_pressed and CS.cruise_buttons == Buttons.NONE: - if clu11_speed + 2. > self.kph_to_clu(controls.v_cruise_kph): - set_speed = clip(clu11_speed + 2., self.min_set_speed_clu, self.max_set_speed_clu) + if clu11_speed + SYNC_MARGIN > self.kph_to_clu(controls.v_cruise_kph): + set_speed = clip(clu11_speed + SYNC_MARGIN, self.min_set_speed_clu, self.max_set_speed_clu) self.target_speed = set_speed def update_max_speed(self, max_speed): From b05b7d87611c7e1b283c8cdebd11cf23283f5ad3 Mon Sep 17 00:00:00 2001 From: neokii Date: Sat, 29 May 2021 10:20:45 +0900 Subject: [PATCH 22/27] tune scc --- selfdrive/car/hyundai/interface.py | 4 ++-- selfdrive/controls/lib/long_mpc.py | 6 +++--- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index cfe6dae9854f02..192c8a9e0f8374 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -68,7 +68,7 @@ def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, # longitudinal ret.longitudinalTuning.kpBP = [0, 10. * CV.KPH_TO_MS, 20. * CV.KPH_TO_MS, 40. * CV.KPH_TO_MS, 70. * CV.KPH_TO_MS, 100. * CV.KPH_TO_MS, 130. * CV.KPH_TO_MS] - ret.longitudinalTuning.kpV = [0.95, 0.75, 0.57, 0.45, 0.4, 0.34, 0.27] + ret.longitudinalTuning.kpV = [0.93, 0.7, 0.52, 0.45, 0.4, 0.34, 0.27] ret.longitudinalTuning.kiBP = [0.] ret.longitudinalTuning.kiV = [0.015] ret.longitudinalTuning.kf = 0.9 @@ -76,7 +76,7 @@ def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, ret.longitudinalTuning.deadzoneV = [0., 0.015] ret.gasMaxBP = [0., 10. * CV.KPH_TO_MS, 20. * CV.KPH_TO_MS, 70. * CV.KPH_TO_MS, 130. * CV.KPH_TO_MS] - ret.gasMaxV = [0.43, 0.3, 0.22, 0.14, 0.11] + ret.gasMaxV = [0.43, 0.23, 0.2, 0.14, 0.11] ret.brakeMaxBP = [0, 70. * CV.KPH_TO_MS, 130. * CV.KPH_TO_MS] ret.brakeMaxV = [1.35, 1.3, 1.] diff --git a/selfdrive/controls/lib/long_mpc.py b/selfdrive/controls/lib/long_mpc.py index 01e245b3263522..1d30a40d6bd2d1 100644 --- a/selfdrive/controls/lib/long_mpc.py +++ b/selfdrive/controls/lib/long_mpc.py @@ -16,7 +16,7 @@ CRUISE_GAP_V = [1.2, 1.5, 2.1, 2.73] AUTO_TR_BP = [40.*CV.KPH_TO_MS, 60.*CV.KPH_TO_MS, 80.*CV.KPH_TO_MS, 100.*CV.KPH_TO_MS, 130.*CV.KPH_TO_MS] -AUTO_TR_V = [1.1, 1.25, 1.6, 2., 2.7] +AUTO_TR_V = [1.2, 1.35, 1.6, 2., 2.7] AUTO_TR_ENABLED = True AUTO_TR_CRUISE_GAP = 1 @@ -83,8 +83,8 @@ def update(self, CS, lead): v_lead = max(0.0, lead.vLead) a_lead = lead.aLeadK - dist_cost = interp(lead.dRel, [4., 20.], [MPC_COST_LONG.DISTANCE/2.0, MPC_COST_LONG.DISTANCE]) - dist_cost = interp(v_ego, [80.*CV.KPH_TO_MS, 100.*CV.KPH_TO_MS], [dist_cost, MPC_COST_LONG.DISTANCE]) + dist_cost = interp(lead.dRel, [4., 20.], [MPC_COST_LONG.DISTANCE/1.75, MPC_COST_LONG.DISTANCE]) + dist_cost = interp(v_ego, [60.*CV.KPH_TO_MS, 80.*CV.KPH_TO_MS], [dist_cost, MPC_COST_LONG.DISTANCE]) self.libmpc.set_weights(MPC_COST_LONG.TTC, dist_cost, MPC_COST_LONG.ACCELERATION, MPC_COST_LONG.JERK) if (v_lead < 0.1 or -a_lead / 2.0 > v_lead): From c9f3bd3ffaa78a8b3a2ab7f001159525ff3b7dcb Mon Sep 17 00:00:00 2001 From: neokii Date: Sun, 30 May 2021 15:35:39 +0900 Subject: [PATCH 23/27] tune scc --- cereal/car.capnp | 7 ++++--- selfdrive/car/hyundai/interface.py | 9 +++++---- selfdrive/car/interfaces.py | 3 ++- selfdrive/controls/lib/latcontrol_pid.py | 2 +- selfdrive/controls/lib/longcontrol.py | 9 +++------ selfdrive/controls/lib/pid.py | 10 ++++++++-- 6 files changed, 23 insertions(+), 17 deletions(-) diff --git a/cereal/car.capnp b/cereal/car.capnp index e7d25f48ceb1d2..89cfb4a05594d0 100644 --- a/cereal/car.capnp +++ b/cereal/car.capnp @@ -475,9 +475,10 @@ struct CarParams { kpV @1 :List(Float32); kiBP @2 :List(Float32); kiV @3 :List(Float32); - kf @4 :Float32; - deadzoneBP @5 :List(Float32); - deadzoneV @6 :List(Float32); + kfBP @4 :List(Float32); + kfV @5 :List(Float32); + deadzoneBP @6 :List(Float32); + deadzoneV @7 :List(Float32); } struct LateralINDITuning { diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 192c8a9e0f8374..2d35a0c2d5d72d 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -68,15 +68,16 @@ def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, # longitudinal ret.longitudinalTuning.kpBP = [0, 10. * CV.KPH_TO_MS, 20. * CV.KPH_TO_MS, 40. * CV.KPH_TO_MS, 70. * CV.KPH_TO_MS, 100. * CV.KPH_TO_MS, 130. * CV.KPH_TO_MS] - ret.longitudinalTuning.kpV = [0.93, 0.7, 0.52, 0.45, 0.4, 0.34, 0.27] + ret.longitudinalTuning.kpV = [0.93, 0.7, 0.52, 0.45, 0.4, 0.33, 0.25] ret.longitudinalTuning.kiBP = [0.] ret.longitudinalTuning.kiV = [0.015] - ret.longitudinalTuning.kf = 0.9 + ret.longitudinalTuning.kfBP = [50. * CV.KPH_TO_MS, 100. * CV.KPH_TO_MS] + ret.longitudinalTuning.kfV = [0.5, 0.3] ret.longitudinalTuning.deadzoneBP = [0., 100. * CV.KPH_TO_MS] ret.longitudinalTuning.deadzoneV = [0., 0.015] - ret.gasMaxBP = [0., 10. * CV.KPH_TO_MS, 20. * CV.KPH_TO_MS, 70. * CV.KPH_TO_MS, 130. * CV.KPH_TO_MS] - ret.gasMaxV = [0.43, 0.23, 0.2, 0.14, 0.11] + ret.gasMaxBP = [0., 10. * CV.KPH_TO_MS, 20. * CV.KPH_TO_MS, 50. * CV.KPH_TO_MS, 70. * CV.KPH_TO_MS, 130. * CV.KPH_TO_MS] + ret.gasMaxV = [0.45, 0.3, 0.24, 0.165, 0.13, 0.11] ret.brakeMaxBP = [0, 70. * CV.KPH_TO_MS, 130. * CV.KPH_TO_MS] ret.brakeMaxV = [1.35, 1.3, 1.] diff --git a/selfdrive/car/interfaces.py b/selfdrive/car/interfaces.py index 24e85edf3bcc95..06d33dcfcb5e18 100644 --- a/selfdrive/car/interfaces.py +++ b/selfdrive/car/interfaces.py @@ -83,7 +83,8 @@ def get_std_params(candidate, fingerprint, has_relay): ret.longitudinalTuning.kpV = [1.] ret.longitudinalTuning.kiBP = [0.] ret.longitudinalTuning.kiV = [1.] - ret.longitudinalTuning.kf = 1.0 + ret.longitudinalTuning.kfBP = [0.] + ret.longitudinalTuning.kfV = [1.] return ret # returns a car.CarState, pass in car.CarControl diff --git a/selfdrive/controls/lib/latcontrol_pid.py b/selfdrive/controls/lib/latcontrol_pid.py index 65f2c6fbfc0fc6..873de6bad07885 100644 --- a/selfdrive/controls/lib/latcontrol_pid.py +++ b/selfdrive/controls/lib/latcontrol_pid.py @@ -9,7 +9,7 @@ class LatControlPID(): def __init__(self, CP): self.pid = PIController((CP.lateralTuning.pid.kpBP, CP.lateralTuning.pid.kpV), (CP.lateralTuning.pid.kiBP, CP.lateralTuning.pid.kiV), - k_f=CP.lateralTuning.pid.kf, pos_limit=1.0, neg_limit=-1.0, + k_f=[0., CP.lateralTuning.pid.kf], pos_limit=1.0, neg_limit=-1.0, sat_limit=CP.steerLimitTimer) def reset(self): diff --git a/selfdrive/controls/lib/longcontrol.py b/selfdrive/controls/lib/longcontrol.py index 06742b30311f37..30939f14d4ef7a 100644 --- a/selfdrive/controls/lib/longcontrol.py +++ b/selfdrive/controls/lib/longcontrol.py @@ -58,7 +58,7 @@ def __init__(self, CP, compute_gb): self.long_control_state = LongCtrlState.off # initialized to off self.pid = PIController((CP.longitudinalTuning.kpBP, CP.longitudinalTuning.kpV), (CP.longitudinalTuning.kiBP, CP.longitudinalTuning.kiV), - CP.longitudinalTuning.kf, + (CP.longitudinalTuning.kfBP, CP.longitudinalTuning.kfV), rate=RATE, sat_limit=0.8, convert=compute_gb) @@ -87,8 +87,8 @@ def update(self, active, CS, v_target, v_target_future, a_target, CP, radarState else: following = False - if not following: - gas_max *= 0.9 + #if not following: + # gas_max *= 0.9 self.long_control_state = long_control_state_trans(active, self.long_control_state, CS.vEgo, v_target_future, self.v_pid, output_gb, @@ -111,9 +111,6 @@ def update(self, active, CS, v_target, v_target_future, a_target, CP, radarState prevent_overshoot = not CP.stoppingControl and CS.vEgo < 1.5 and v_target_future < 0.7 deadzone = interp(v_ego_pid, CP.longitudinalTuning.deadzoneBP, CP.longitudinalTuning.deadzoneV) - if d_rel > 0.: - a_target *= interp(d_rel, [10., 80.], [1.0, 0.75]) - output_gb = self.pid.update(self.v_pid, v_ego_pid, speed=v_ego_pid, deadzone=deadzone, feedforward=a_target, freeze_integrator=prevent_overshoot) if prevent_overshoot: diff --git a/selfdrive/controls/lib/pid.py b/selfdrive/controls/lib/pid.py index 916b95c9ea0c4b..c18f6b7f21d27f 100644 --- a/selfdrive/controls/lib/pid.py +++ b/selfdrive/controls/lib/pid.py @@ -11,10 +11,12 @@ def apply_deadzone(error, deadzone): return error class PIController(): - def __init__(self, k_p, k_i, k_f=1., pos_limit=None, neg_limit=None, rate=100, sat_limit=0.8, convert=None): + def __init__(self, k_p, k_i, k_f=None, pos_limit=None, neg_limit=None, rate=100, sat_limit=0.8, convert=None): + if k_f is None: + k_f = [0., 1.] self._k_p = k_p # proportional gain self._k_i = k_i # integral gain - self.k_f = k_f # feedforward gain + self._k_f = k_f # feedforward gain self.pos_limit = pos_limit self.neg_limit = neg_limit @@ -35,6 +37,10 @@ def k_p(self): def k_i(self): return interp(self.speed, self._k_i[0], self._k_i[1]) + @property + def k_f(self): + return interp(self.speed, self._k_f[0], self._k_f[1]) + def _check_saturation(self, control, check_saturation, error): saturated = (control < self.neg_limit) or (control > self.pos_limit) From 8f1bd923934e6d62099c507e7f692b439b687272 Mon Sep 17 00:00:00 2001 From: neokii Date: Sun, 30 May 2021 21:30:08 +0900 Subject: [PATCH 24/27] merge changes from master-ci --- Jenkinsfile | 6 +- README.md | 3 +- RELEASES.md | 1 + SConstruct | 11 +- cereal/SConscript | 6 +- cereal/visionipc/visionbuf.cc | 2 +- phonelibs/mapbox-gl-native-qt/.gitattributes | 2 - phonelibs/mapbox-gl-native-qt/build.sh | 7 - phonelibs/mapbox-gl-native-qt/include/QMapbox | 1 - .../mapbox-gl-native-qt/include/QMapboxGL | 1 - .../mapbox-gl-native-qt/include/qmapbox.hpp | 147 ---------- .../mapbox-gl-native-qt/include/qmapboxgl.hpp | 277 ------------------ phonelibs/qt-plugins/.gitattributes | 1 - phonelibs/qt-plugins/build_qtlocation.sh | 8 - release/build_release2.sh | 2 +- selfdrive/camerad/SConscript | 7 +- selfdrive/camerad/cameras/camera_common.cc | 2 +- selfdrive/camerad/main.cc | 2 +- selfdrive/car/fw_versions.py | 12 + selfdrive/car/mazda/values.py | 119 +++++--- selfdrive/car/volkswagen/interface.py | 5 + selfdrive/car/volkswagen/values.py | 22 ++ selfdrive/common/SConscript | 2 +- selfdrive/common/version.h | 2 +- selfdrive/debug/test_fw_query_on_routes.py | 6 +- selfdrive/locationd/calibrationd.py | 18 +- selfdrive/modeld/SConscript | 14 +- selfdrive/modeld/modeld | 17 +- selfdrive/ui/SConscript | 3 +- selfdrive/ui/qt/offroad/settings.cc | 22 +- selfdrive/ui/qt/offroad/settings.h | 8 +- selfdrive/ui/qt/util.h | 22 ++ selfdrive/ui/qt/widgets/controls.h | 2 +- selfdrive/ui/qt/widgets/scrollview.h | 2 +- selfdrive/ui/qt/widgets/setup.h | 2 +- selfdrive/ui/ui.cc | 4 +- selfdrive/ui/ui.h | 2 - selfdrive/updated.py | 11 +- 38 files changed, 226 insertions(+), 555 deletions(-) delete mode 100644 phonelibs/mapbox-gl-native-qt/.gitattributes delete mode 100755 phonelibs/mapbox-gl-native-qt/build.sh delete mode 100644 phonelibs/mapbox-gl-native-qt/include/QMapbox delete mode 100644 phonelibs/mapbox-gl-native-qt/include/QMapboxGL delete mode 100644 phonelibs/mapbox-gl-native-qt/include/qmapbox.hpp delete mode 100644 phonelibs/mapbox-gl-native-qt/include/qmapboxgl.hpp delete mode 100644 phonelibs/qt-plugins/.gitattributes delete mode 100755 phonelibs/qt-plugins/build_qtlocation.sh diff --git a/Jenkinsfile b/Jenkinsfile index dddccf4d360792..127051fa8d7be4 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -78,7 +78,7 @@ pipeline { when { not { anyOf { - branch 'master-ci'; branch 'devel'; branch 'devel-staging'; branch 'release2'; branch 'release2-staging'; branch 'dashcam'; branch 'dashcam-staging'; branch 'testing-closet*' + branch 'master-ci'; branch 'devel'; branch 'devel-staging'; branch 'release2'; branch 'release2-staging'; branch 'dashcam'; branch 'dashcam-staging'; branch 'testing-closet*'; branch 'hotfix-*' } } } @@ -138,8 +138,8 @@ pipeline { stage('Replay Tests') { steps { phone_steps("eon2", [ - ["build QCOM_REPLAY", "cd selfdrive/manager && QCOM_REPLAY=1 ./build.py"], - ["camerad/modeld replay", "cd selfdrive/test/process_replay && ./camera_replay.py"], + ["build", "cd selfdrive/manager && ./build.py"], + ["model replay", "cd selfdrive/test/process_replay && ./model_replay.py"], ]) } } diff --git a/README.md b/README.md index cec3c32dab4cbe..39f094ee95e67a 100644 --- a/README.md +++ b/README.md @@ -184,6 +184,7 @@ Community Maintained Cars and Features | Nissan | Rogue 2018-20 | ProPILOT | Stock | 0mph | 0mph | | Nissan | X-Trail 2017 | ProPILOT | Stock | 0mph | 0mph | | SEAT | Ateca 2018 | Driver Assistance | Stock | 0mph | 0mph | +| SEAT | Leon 2020 | Driver Assistance | Stock | 0mph | 0mph | | Škoda | Kodiaq 2018 | Driver Assistance | Stock | 0mph | 0mph | | Škoda | Octavia 2015, 2019 | Driver Assistance | Stock | 0mph | 0mph | | Škoda | Scala 2020 | Driver Assistance | Stock | 0mph | 0mph | @@ -387,4 +388,4 @@ NO WARRANTY EXPRESSED OR IMPLIED.** [![Total alerts](https://img.shields.io/lgtm/alerts/g/commaai/openpilot.svg?logo=lgtm&logoWidth=18)](https://lgtm.com/projects/g/commaai/openpilot/alerts/) [![Language grade: Python](https://img.shields.io/lgtm/grade/python/g/commaai/openpilot.svg?logo=lgtm&logoWidth=18)](https://lgtm.com/projects/g/commaai/openpilot/context:python) [![Language grade: C/C++](https://img.shields.io/lgtm/grade/cpp/g/commaai/openpilot.svg?logo=lgtm&logoWidth=18)](https://lgtm.com/projects/g/commaai/openpilot/context:cpp) -[![codecov](https://codecov.io/gh/commaai/openpilot/branch/master/graph/badge.svg)](https://codecov.io/gh/commaai/openpilot) \ No newline at end of file +[![codecov](https://codecov.io/gh/commaai/openpilot/branch/master/graph/badge.svg)](https://codecov.io/gh/commaai/openpilot) diff --git a/RELEASES.md b/RELEASES.md index 5dbf50b1819500..b1dd47e773f0eb 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -4,6 +4,7 @@ Version 0.8.5 (2021-XX-XX) * Smart model-based Forward Collision Warning * Hyundai Elantra 2021 support thanks to CruiseBrantley! * Lexus UX Hybrid 2019 support thanks to brianhaugen2! + * SEAT Leon 2020 support thanks to jyoung8607! * Škoda Octavia 2015 & 2019 support thanks to jyoung8607! Version 0.8.4 (2021-05-17) diff --git a/SConstruct b/SConstruct index 4a2a1748176347..aad66d7141a569 100644 --- a/SConstruct +++ b/SConstruct @@ -37,6 +37,10 @@ AddOption('--mpc-generate', action='store_true', help='regenerates the mpc sources') +AddOption('--snpe', + action='store_true', + help='use SNPE on PC') + AddOption('--external-sconscript', action='store', metavar='FILE', @@ -51,7 +55,6 @@ if arch == "aarch64" and TICI: arch = "larch64" USE_WEBCAM = os.getenv("USE_WEBCAM") is not None -QCOM_REPLAY = arch == "aarch64" and os.getenv("QCOM_REPLAY") is not None lenv = { "PATH": os.environ['PATH'], @@ -98,10 +101,6 @@ if arch == "aarch64" or arch == "larch64": cflags = ["-DQCOM", "-mcpu=cortex-a57"] cxxflags = ["-DQCOM", "-mcpu=cortex-a57"] rpath = [] - - if QCOM_REPLAY: - cflags += ["-DQCOM_REPLAY"] - cxxflags += ["-DQCOM_REPLAY"] else: cflags = [] cxxflags = [] @@ -337,7 +336,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', 'QCOM_REPLAY') +Export('env', 'qt_env', 'arch', 'real_arch', 'SHARED', 'USE_WEBCAM') # cereal and messaging are shared with the system SConscript(['cereal/SConscript']) diff --git a/cereal/SConscript b/cereal/SConscript index b2079899886215..053628a5d6e074 100644 --- a/cereal/SConscript +++ b/cereal/SConscript @@ -1,4 +1,4 @@ -Import('env', 'envCython', 'arch', 'QCOM_REPLAY') +Import('env', 'envCython', 'arch') import shutil @@ -60,7 +60,7 @@ vipc_sources = [ 'visionipc/visionbuf.cc', ] -if arch in ["aarch64", "larch64"] and (not QCOM_REPLAY): +if arch in ["aarch64", "larch64"]: vipc_sources += ['visionipc/visionbuf_ion.cc'] else: vipc_sources += ['visionipc/visionbuf_cl.cc'] @@ -70,6 +70,8 @@ vipc = env.Library('visionipc', vipc_objects) libs = envCython["LIBS"]+["OpenCL", "zmq", vipc, messaging_lib] +if arch == "aarch64": + libs += ["adreno_utils"] if arch == "Darwin": del libs[libs.index('OpenCL')] envCython['FRAMEWORKS'] += ['OpenCL'] diff --git a/cereal/visionipc/visionbuf.cc b/cereal/visionipc/visionbuf.cc index 64693b572a5ec1..39c5219133547e 100644 --- a/cereal/visionipc/visionbuf.cc +++ b/cereal/visionipc/visionbuf.cc @@ -15,7 +15,7 @@ extern "C" void compute_aligned_width_and_height(int width, #endif void visionbuf_compute_aligned_width_and_height(int width, int height, int *aligned_w, int *aligned_h) { -#if defined(QCOM) && !defined(QCOM_REPLAY) +#ifdef QCOM compute_aligned_width_and_height(ALIGN(width, 32), ALIGN(height, 32), 3, 0, 0, 512, aligned_w, aligned_h); #else *aligned_w = width; *aligned_h = height; diff --git a/phonelibs/mapbox-gl-native-qt/.gitattributes b/phonelibs/mapbox-gl-native-qt/.gitattributes deleted file mode 100644 index 323c737ba1ecce..00000000000000 --- a/phonelibs/mapbox-gl-native-qt/.gitattributes +++ /dev/null @@ -1,2 +0,0 @@ -x86_64 filter=lfs diff=lfs merge=lfs -text -larch64 filter=lfs diff=lfs merge=lfs -text diff --git a/phonelibs/mapbox-gl-native-qt/build.sh b/phonelibs/mapbox-gl-native-qt/build.sh deleted file mode 100755 index f2936fad3db3fe..00000000000000 --- a/phonelibs/mapbox-gl-native-qt/build.sh +++ /dev/null @@ -1,7 +0,0 @@ -#!/usr/bin/env sh -cd /tmp -git clone --recursive https://github.com/commaai/mapbox-gl-native.git -cd mapbox-gl-native -mkdir build && cd build -cmake -DMBGL_WITH_QT=ON .. -make -j$(nproc) mbgl-qt diff --git a/phonelibs/mapbox-gl-native-qt/include/QMapbox b/phonelibs/mapbox-gl-native-qt/include/QMapbox deleted file mode 100644 index a8479c09aa7fb7..00000000000000 --- a/phonelibs/mapbox-gl-native-qt/include/QMapbox +++ /dev/null @@ -1 +0,0 @@ -#include "qmapbox.hpp" diff --git a/phonelibs/mapbox-gl-native-qt/include/QMapboxGL b/phonelibs/mapbox-gl-native-qt/include/QMapboxGL deleted file mode 100644 index 15b55a9abe98f8..00000000000000 --- a/phonelibs/mapbox-gl-native-qt/include/QMapboxGL +++ /dev/null @@ -1 +0,0 @@ -#include "qmapboxgl.hpp" diff --git a/phonelibs/mapbox-gl-native-qt/include/qmapbox.hpp b/phonelibs/mapbox-gl-native-qt/include/qmapbox.hpp deleted file mode 100644 index 3acc9d55e0118d..00000000000000 --- a/phonelibs/mapbox-gl-native-qt/include/qmapbox.hpp +++ /dev/null @@ -1,147 +0,0 @@ -#ifndef QMAPBOX_H -#define QMAPBOX_H - -#include -#include -#include -#include -#include - -// This header follows the Qt coding style: https://wiki.qt.io/Qt_Coding_Style - -#if !defined(QT_MAPBOXGL_STATIC) -# if defined(QT_BUILD_MAPBOXGL_LIB) -# define Q_MAPBOXGL_EXPORT Q_DECL_EXPORT -# else -# define Q_MAPBOXGL_EXPORT Q_DECL_IMPORT -# endif -#else -# define Q_MAPBOXGL_EXPORT -#endif - -namespace QMapbox { - -typedef QPair Coordinate; -typedef QPair CoordinateZoom; -typedef QPair ProjectedMeters; - -typedef QVector Coordinates; -typedef QVector CoordinatesCollection; - -typedef QVector CoordinatesCollections; - -struct Q_MAPBOXGL_EXPORT Feature { - enum Type { - PointType = 1, - LineStringType, - PolygonType - }; - - /*! Class constructor. */ - Feature(Type type_ = PointType, const CoordinatesCollections& geometry_ = CoordinatesCollections(), - const QVariantMap& properties_ = QVariantMap(), const QVariant& id_ = QVariant()) - : type(type_), geometry(geometry_), properties(properties_), id(id_) {} - - Type type; - CoordinatesCollections geometry; - QVariantMap properties; - QVariant id; -}; - -struct Q_MAPBOXGL_EXPORT ShapeAnnotationGeometry { - enum Type { - LineStringType = 1, - PolygonType, - MultiLineStringType, - MultiPolygonType - }; - - /*! Class constructor. */ - ShapeAnnotationGeometry(Type type_ = LineStringType, const CoordinatesCollections& geometry_ = CoordinatesCollections()) - : type(type_), geometry(geometry_) {} - - Type type; - CoordinatesCollections geometry; -}; - -struct Q_MAPBOXGL_EXPORT SymbolAnnotation { - Coordinate geometry; - QString icon; -}; - -struct Q_MAPBOXGL_EXPORT LineAnnotation { - /*! Class constructor. */ - LineAnnotation(const ShapeAnnotationGeometry& geometry_ = ShapeAnnotationGeometry(), float opacity_ = 1.0f, - float width_ = 1.0f, const QColor& color_ = Qt::black) - : geometry(geometry_), opacity(opacity_), width(width_), color(color_) {} - - ShapeAnnotationGeometry geometry; - float opacity; - float width; - QColor color; -}; - -struct Q_MAPBOXGL_EXPORT FillAnnotation { - /*! Class constructor. */ - FillAnnotation(const ShapeAnnotationGeometry& geometry_ = ShapeAnnotationGeometry(), float opacity_ = 1.0f, - const QColor& color_ = Qt::black, const QVariant& outlineColor_ = QVariant()) - : geometry(geometry_), opacity(opacity_), color(color_), outlineColor(outlineColor_) {} - - ShapeAnnotationGeometry geometry; - float opacity; - QColor color; - QVariant outlineColor; -}; - -typedef QVariant Annotation; -typedef quint32 AnnotationID; -typedef QVector AnnotationIDs; - -enum NetworkMode { - Online, // Default - Offline, -}; - -Q_MAPBOXGL_EXPORT QVector >& defaultStyles(); - -Q_MAPBOXGL_EXPORT NetworkMode networkMode(); -Q_MAPBOXGL_EXPORT void setNetworkMode(NetworkMode); - -// This struct is a 1:1 copy of mbgl::CustomLayerRenderParameters. -struct Q_MAPBOXGL_EXPORT CustomLayerRenderParameters { - double width; - double height; - double latitude; - double longitude; - double zoom; - double bearing; - double pitch; - double fieldOfView; -}; - -class Q_MAPBOXGL_EXPORT CustomLayerHostInterface { -public: - virtual ~CustomLayerHostInterface() = default; - virtual void initialize() = 0; - virtual void render(const CustomLayerRenderParameters&) = 0; - virtual void deinitialize() = 0; -}; - -Q_MAPBOXGL_EXPORT double metersPerPixelAtLatitude(double latitude, double zoom); -Q_MAPBOXGL_EXPORT ProjectedMeters projectedMetersForCoordinate(const Coordinate &); -Q_MAPBOXGL_EXPORT Coordinate coordinateForProjectedMeters(const ProjectedMeters &); - -} // namespace QMapbox - -Q_DECLARE_METATYPE(QMapbox::Coordinate); -Q_DECLARE_METATYPE(QMapbox::Coordinates); -Q_DECLARE_METATYPE(QMapbox::CoordinatesCollection); -Q_DECLARE_METATYPE(QMapbox::CoordinatesCollections); -Q_DECLARE_METATYPE(QMapbox::Feature); - -Q_DECLARE_METATYPE(QMapbox::SymbolAnnotation); -Q_DECLARE_METATYPE(QMapbox::ShapeAnnotationGeometry); -Q_DECLARE_METATYPE(QMapbox::LineAnnotation); -Q_DECLARE_METATYPE(QMapbox::FillAnnotation); - -#endif // QMAPBOX_H diff --git a/phonelibs/mapbox-gl-native-qt/include/qmapboxgl.hpp b/phonelibs/mapbox-gl-native-qt/include/qmapboxgl.hpp deleted file mode 100644 index 337991aa1c1360..00000000000000 --- a/phonelibs/mapbox-gl-native-qt/include/qmapboxgl.hpp +++ /dev/null @@ -1,277 +0,0 @@ -#ifndef QMAPBOXGL_H -#define QMAPBOXGL_H - -#include -#include -#include -#include -#include -#include -#include -#include - -#include - -class QMapboxGLPrivate; - -// This header follows the Qt coding style: https://wiki.qt.io/Qt_Coding_Style - -class Q_MAPBOXGL_EXPORT QMapboxGLSettings -{ -public: - QMapboxGLSettings(); - - enum GLContextMode { - UniqueGLContext = 0, - SharedGLContext - }; - - enum MapMode { - Continuous = 0, - Static - }; - - enum ConstrainMode { - NoConstrain = 0, - ConstrainHeightOnly, - ConstrainWidthAndHeight - }; - - enum ViewportMode { - DefaultViewport = 0, - FlippedYViewport - }; - - GLContextMode contextMode() const; - void setContextMode(GLContextMode); - - MapMode mapMode() const; - void setMapMode(MapMode); - - ConstrainMode constrainMode() const; - void setConstrainMode(ConstrainMode); - - ViewportMode viewportMode() const; - void setViewportMode(ViewportMode); - - unsigned cacheDatabaseMaximumSize() const; - void setCacheDatabaseMaximumSize(unsigned); - - QString cacheDatabasePath() const; - void setCacheDatabasePath(const QString &); - - QString assetPath() const; - void setAssetPath(const QString &); - - QString accessToken() const; - void setAccessToken(const QString &); - - QString apiBaseUrl() const; - void setApiBaseUrl(const QString &); - - QString localFontFamily() const; - void setLocalFontFamily(const QString &); - - std::function resourceTransform() const; - void setResourceTransform(const std::function &); - -private: - GLContextMode m_contextMode; - MapMode m_mapMode; - ConstrainMode m_constrainMode; - ViewportMode m_viewportMode; - - unsigned m_cacheMaximumSize; - QString m_cacheDatabasePath; - QString m_assetPath; - QString m_accessToken; - QString m_apiBaseUrl; - QString m_localFontFamily; - std::function m_resourceTransform; -}; - -struct Q_MAPBOXGL_EXPORT QMapboxGLCameraOptions { - QVariant center; // Coordinate - QVariant anchor; // QPointF - QVariant zoom; // double - QVariant bearing; // double - QVariant pitch; // double -}; - -class Q_MAPBOXGL_EXPORT QMapboxGL : public QObject -{ - Q_OBJECT - Q_PROPERTY(double latitude READ latitude WRITE setLatitude) - Q_PROPERTY(double longitude READ longitude WRITE setLongitude) - Q_PROPERTY(double zoom READ zoom WRITE setZoom) - Q_PROPERTY(double bearing READ bearing WRITE setBearing) - Q_PROPERTY(double pitch READ pitch WRITE setPitch) - Q_PROPERTY(QString styleJson READ styleJson WRITE setStyleJson) - Q_PROPERTY(QString styleUrl READ styleUrl WRITE setStyleUrl) - Q_PROPERTY(double scale READ scale WRITE setScale) - Q_PROPERTY(QMapbox::Coordinate coordinate READ coordinate WRITE setCoordinate) - Q_PROPERTY(QMargins margins READ margins WRITE setMargins) - -public: - enum MapChange { - MapChangeRegionWillChange = 0, - MapChangeRegionWillChangeAnimated, - MapChangeRegionIsChanging, - MapChangeRegionDidChange, - MapChangeRegionDidChangeAnimated, - MapChangeWillStartLoadingMap, - MapChangeDidFinishLoadingMap, - MapChangeDidFailLoadingMap, - MapChangeWillStartRenderingFrame, - MapChangeDidFinishRenderingFrame, - MapChangeDidFinishRenderingFrameFullyRendered, - MapChangeWillStartRenderingMap, - MapChangeDidFinishRenderingMap, - MapChangeDidFinishRenderingMapFullyRendered, - MapChangeDidFinishLoadingStyle, - MapChangeSourceDidChange - }; - - enum MapLoadingFailure { - StyleParseFailure, - StyleLoadFailure, - NotFoundFailure, - UnknownFailure - }; - - // Determines the orientation of the map. - enum NorthOrientation { - NorthUpwards, // Default - NorthRightwards, - NorthDownwards, - NorthLeftwards, - }; - - QMapboxGL(QObject* parent = 0, - const QMapboxGLSettings& = QMapboxGLSettings(), - const QSize& size = QSize(), - qreal pixelRatio = 1); - virtual ~QMapboxGL(); - - QString styleJson() const; - QString styleUrl() const; - - void setStyleJson(const QString &); - void setStyleUrl(const QString &); - - double latitude() const; - void setLatitude(double latitude); - - double longitude() const; - void setLongitude(double longitude); - - double scale() const; - void setScale(double scale, const QPointF ¢er = QPointF()); - - double zoom() const; - void setZoom(double zoom); - - double minimumZoom() const; - double maximumZoom() const; - - double bearing() const; - void setBearing(double degrees); - void setBearing(double degrees, const QPointF ¢er); - - double pitch() const; - void setPitch(double pitch); - void pitchBy(double pitch); - - NorthOrientation northOrientation() const; - void setNorthOrientation(NorthOrientation); - - QMapbox::Coordinate coordinate() const; - void setCoordinate(const QMapbox::Coordinate &); - void setCoordinateZoom(const QMapbox::Coordinate &, double zoom); - - void jumpTo(const QMapboxGLCameraOptions&); - - void setGestureInProgress(bool inProgress); - - void setTransitionOptions(qint64 duration, qint64 delay = 0); - - void addAnnotationIcon(const QString &name, const QImage &sprite); - - QMapbox::AnnotationID addAnnotation(const QMapbox::Annotation &); - void updateAnnotation(QMapbox::AnnotationID, const QMapbox::Annotation &); - void removeAnnotation(QMapbox::AnnotationID); - - bool setLayoutProperty(const QString &layer, const QString &property, const QVariant &value); - bool setPaintProperty(const QString &layer, const QString &property, const QVariant &value); - - bool isFullyLoaded() const; - - void moveBy(const QPointF &offset); - void scaleBy(double scale, const QPointF ¢er = QPointF()); - void rotateBy(const QPointF &first, const QPointF &second); - - void resize(const QSize &size); - - double metersPerPixelAtLatitude(double latitude, double zoom) const; - QMapbox::ProjectedMeters projectedMetersForCoordinate(const QMapbox::Coordinate &) const; - QMapbox::Coordinate coordinateForProjectedMeters(const QMapbox::ProjectedMeters &) const; - QPointF pixelForCoordinate(const QMapbox::Coordinate &) const; - QMapbox::Coordinate coordinateForPixel(const QPointF &) const; - - QMapbox::CoordinateZoom coordinateZoomForBounds(const QMapbox::Coordinate &sw, QMapbox::Coordinate &ne) const; - QMapbox::CoordinateZoom coordinateZoomForBounds(const QMapbox::Coordinate &sw, QMapbox::Coordinate &ne, double bearing, double pitch); - - void setMargins(const QMargins &margins); - QMargins margins() const; - - void addSource(const QString &sourceID, const QVariantMap& params); - bool sourceExists(const QString &sourceID); - void updateSource(const QString &sourceID, const QVariantMap& params); - void removeSource(const QString &sourceID); - - void addImage(const QString &name, const QImage &sprite); - void removeImage(const QString &name); - - void addCustomLayer(const QString &id, - QScopedPointer& host, - const QString& before = QString()); - void addLayer(const QVariantMap ¶ms, const QString& before = QString()); - bool layerExists(const QString &id); - void removeLayer(const QString &id); - - QVector layerIds() const; - - void setFilter(const QString &layer, const QVariant &filter); - QVariant getFilter(const QString &layer) const; - // When rendering on a different thread, - // should be called on the render thread. - void createRenderer(); - void destroyRenderer(); - void setFramebufferObject(quint32 fbo, const QSize &size); - -public slots: - void render(); - void connectionEstablished(); - - // Commit changes, load all the resources - // and renders the map when completed. - void startStaticRender(); - -signals: - void needsRendering(); - void mapChanged(QMapboxGL::MapChange); - void mapLoadingFailed(QMapboxGL::MapLoadingFailure, const QString &reason); - void copyrightsChanged(const QString ©rightsHtml); - - void staticRenderFinished(const QString &error); - -private: - Q_DISABLE_COPY(QMapboxGL) - - QMapboxGLPrivate *d_ptr; -}; - -Q_DECLARE_METATYPE(QMapboxGL::MapChange); -Q_DECLARE_METATYPE(QMapboxGL::MapLoadingFailure); - -#endif // QMAPBOXGL_H diff --git a/phonelibs/qt-plugins/.gitattributes b/phonelibs/qt-plugins/.gitattributes deleted file mode 100644 index e74eb23bf4c8c0..00000000000000 --- a/phonelibs/qt-plugins/.gitattributes +++ /dev/null @@ -1 +0,0 @@ -x86_64 filter=lfs diff=lfs merge=lfs -text diff --git a/phonelibs/qt-plugins/build_qtlocation.sh b/phonelibs/qt-plugins/build_qtlocation.sh deleted file mode 100755 index 09e6182d1f83be..00000000000000 --- a/phonelibs/qt-plugins/build_qtlocation.sh +++ /dev/null @@ -1,8 +0,0 @@ -#!/usr/bin/env sh - -# Qtlocation plugin with extra fields parsed from api response -cd /tmp -git clone https://github.com/commaai/qtlocation.git -cd qtlocation -qmake -make -j$(nproc) diff --git a/release/build_release2.sh b/release/build_release2.sh index eaf7b82f47da4e..fe4936913f5936 100755 --- a/release/build_release2.sh +++ b/release/build_release2.sh @@ -49,7 +49,7 @@ popd # Build stuff ln -sfn /data/openpilot /data/pythonpath export PYTHONPATH="/data/openpilot:/data/openpilot/pyextra" -selfdrive/manager/build.py +SCONS_CACHE=1 scons -j3 # Run tests python selfdrive/manager/test/test_manager.py diff --git a/selfdrive/camerad/SConscript b/selfdrive/camerad/SConscript index a26c20dd59e996..c12d2540748be3 100644 --- a/selfdrive/camerad/SConscript +++ b/selfdrive/camerad/SConscript @@ -1,13 +1,10 @@ -Import('env', 'arch', 'cereal', 'messaging', 'common', 'gpucommon', 'visionipc', 'USE_WEBCAM', 'QCOM_REPLAY') +Import('env', 'arch', 'cereal', 'messaging', 'common', 'gpucommon', 'visionipc', 'USE_WEBCAM') libs = ['m', 'pthread', common, 'jpeg', 'OpenCL', cereal, messaging, 'zmq', 'capnp', 'kj', visionipc, gpucommon] if arch == "aarch64": libs += ['gsl', 'CB', 'adreno_utils', 'EGL', 'GLESv3', 'cutils', 'ui'] - if QCOM_REPLAY: - cameras = ['cameras/camera_frame_stream.cc'] - else: - cameras = ['cameras/camera_qcom.cc'] + cameras = ['cameras/camera_qcom.cc'] elif arch == "larch64": libs += ['atomic'] cameras = ['cameras/camera_qcom2.cc'] diff --git a/selfdrive/camerad/cameras/camera_common.cc b/selfdrive/camerad/cameras/camera_common.cc index 6294c1580eb762..cf629bde3d6efc 100644 --- a/selfdrive/camerad/cameras/camera_common.cc +++ b/selfdrive/camerad/cameras/camera_common.cc @@ -17,7 +17,7 @@ #include "selfdrive/common/util.h" #include "selfdrive/hardware/hw.h" -#if defined(QCOM) && !defined(QCOM_REPLAY) +#ifdef QCOM #include "selfdrive/camerad/cameras/camera_qcom.h" #elif QCOM2 #include "selfdrive/camerad/cameras/camera_qcom2.h" diff --git a/selfdrive/camerad/main.cc b/selfdrive/camerad/main.cc index 6cfa85bdb66c4e..9636fd27b1086c 100644 --- a/selfdrive/camerad/main.cc +++ b/selfdrive/camerad/main.cc @@ -15,7 +15,7 @@ #include "selfdrive/common/util.h" #include "selfdrive/hardware/hw.h" -#if defined(QCOM) && !defined(QCOM_REPLAY) +#ifdef QCOM #include "selfdrive/camerad/cameras/camera_qcom.h" #elif QCOM2 #include "selfdrive/camerad/cameras/camera_qcom2.h" diff --git a/selfdrive/car/fw_versions.py b/selfdrive/car/fw_versions.py index edf777af474ede..6ad40a2f08cce9 100755 --- a/selfdrive/car/fw_versions.py +++ b/selfdrive/car/fw_versions.py @@ -69,6 +69,11 @@ def p16(val): DEFAULT_RX_OFFSET = 0x8 VOLKSWAGEN_RX_OFFSET = 0x6a +MAZDA_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ + p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_ECU_SOFTWARE_NUMBER) +MAZDA_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ + p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_ECU_SOFTWARE_NUMBER) + # brand, request, response, response offset REQUESTS = [ # Hyundai @@ -129,6 +134,13 @@ def p16(val): [VOLKSWAGEN_VERSION_RESPONSE], DEFAULT_RX_OFFSET, ), + # Mazda + ( + "mazda", + [MAZDA_VERSION_REQUEST], + [MAZDA_VERSION_RESPONSE], + DEFAULT_RX_OFFSET, + ) ] diff --git a/selfdrive/car/mazda/values.py b/selfdrive/car/mazda/values.py index 60b9a8b584739a..bd164e9cc57c30 100644 --- a/selfdrive/car/mazda/values.py +++ b/selfdrive/car/mazda/values.py @@ -33,42 +33,91 @@ class Buttons: RESUME = 3 CANCEL = 4 -FINGERPRINTS = { - CAR.CX5: [ - # CX-5 2017 GT - { - 64: 8, 70: 8, 80: 8, 117: 8, 118: 8, 120: 8, 121: 8, 130: 8, 134: 8, 145: 8, 154: 8, 155: 8, 157: 8, 158: 8, 159: 8, 253: 8, 304: 8, 305: 8, 357: 8, 358: 8, 359: 8, 512: 8, 514: 8, 515: 8, 529: 8, 533: 8, 535: 8, 539: 8, 540: 8, 541: 8, 542: 8, 543: 8, 552: 8, 576: 8, 577: 8, 578: 8, 579: 8, 580: 8, 581: 8, 582: 8, 605: 8, 606: 8, 607: 8, 608: 8, 628: 8, 832: 8, 836: 8, 863: 8, 865: 8, 866: 8, 867: 8, 868: 8, 869: 8, 870: 8, 976: 8, 977: 8, 978: 8, 1034: 8, 1045: 8, 1056: 8, 1061: 8, 1067: 8, 1070: 8, 1078: 8, 1080: 8, 1085: 8, 1086: 8, 1088: 8, 1093: 8, 1108: 8, 1114: 8, 1115: 8, 1116: 8, 1139: 8, 1143: 8, 1147: 8, 1154: 8, 1157: 8, 1160: 8, 1163: 8, 1166: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1183: 8, 1233: 8, 1236: 8, 1237: 8, 1238: 8, 1239: 8, 1241: 8, 1242: 8, 1243: 8, 1244: 8, 1264: 8, 1266: 8, 1267: 8, 1269: 8, 1270: 8, 1271: 8, 1272: 8, 1274: 8, 1275: 8, 1277: 8, 1278: 8, 1409: 8, 1416: 8, 1425: 8, 1430: 8, 1435: 8, 1440: 8, 1446: 8, 1456: 8, 1479: 8 - }, - # CX-5 2019 GTR - { - 64: 8, 70: 8, 80: 8, 117: 8, 118: 8, 120: 8, 121: 8, 130: 8, 134: 8, 145: 8, 154: 8, 155: 8, 157: 8, 158: 8, 159: 8, 253: 8, 254: 8, 304: 8, 305: 8, 357: 8, 358: 8, 359: 8, 512: 8, 514: 8, 515: 8, 529: 8, 533: 8, 535: 8, 539: 8, 540: 8, 541: 8, 542: 8, 543: 8, 552: 8, 576: 8, 577: 8, 578: 8, 579: 8, 580: 8, 581: 8, 582: 8, 605: 8, 606: 8, 607: 8, 608: 8, 628: 8, 736: 8, 832: 8, 836: 8, 863: 8, 865: 8, 866: 8, 867: 8, 868: 8, 869: 8, 870: 8, 976: 8, 977: 8, 978: 8, 1034: 8, 1045: 8, 1056: 8, 1061: 8, 1067: 8, 1078: 8, 1080: 8, 1085: 8, 1086: 8, 1088: 8, 1093: 8, 1108: 8, 1114: 8, 1115: 8, 1116: 8, 1139: 8, 1143: 8, 1147: 8, 1154: 8, 1157: 8, 1160: 8, 1163: 8, 1166: 8, 1170: 8, 1171: 8, 1173: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1183: 8, 1233: 8, 1236: 8, 1237: 8, 1238: 8, 1239: 8, 1241: 8, 1242: 8, 1244: 8, 1260: 8, 1264: 8, 1266: 8, 1267: 8, 1269: 8, 1270: 8, 1271: 8, 1272: 8, 1274: 8, 1277: 8, 1278: 8, 1409: 8, 1416: 8, 1425: 8, 1430: 8, 1435: 8, 1440: 8, 1446: 8, 1456: 8, 1479: 8, 1776: 8, 1792: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 2015: 8, 2016: 8, 2024: 8 - } - ], - - CAR.CX9: [ - # CX-9 2017 Australia - old CAM connector - { - 64: 8, 70: 8, 80: 8, 117: 8, 118: 8, 120: 8, 121: 8, 130: 8, 134: 8, 138: 8, 145: 8, 154: 8, 155: 8, 157: 8, 158: 8, 159: 8, 253: 8, 304: 8, 305: 8, 357: 8, 358: 8, 359: 8, 512: 8, 514: 8, 515: 8, 522: 8, 529: 8, 533: 8, 535: 8, 539: 8, 540: 8, 541: 8, 542: 8, 543: 8, 552: 8, 576: 8, 577: 8, 578: 8, 579: 8, 580: 8, 581: 8, 582: 8, 583: 8, 605: 8, 606: 8, 628: 8, 832: 8, 976: 8, 977: 8, 978: 8, 1034: 8, 1045: 8, 1056: 8, 1061: 8, 1067: 8, 1078: 8, 1085: 8, 1086: 8, 1088: 8, 1093: 8, 1108: 8, 1114: 8, 1115: 8, 1116: 8, 1139: 8, 1143: 8, 1147: 8, 1154: 8, 1157: 8, 1160: 8, 1163: 8, 1166: 8, 1170: 8, 1177: 8, 1180: 8, 1183: 8, 1233: 8, 1236: 8, 1237: 8, 1238: 8, 1239: 8, 1241: 8, 1242: 8, 1243: 8, 1244: 8, 1247: 8, 1264: 8, 1266: 8, 1267: 8, 1269: 8, 1271: 8, 1272: 8, 1274: 8, 1277: 8, 1278: 8, 1409: 8, 1416: 8, 1425: 8, 1430: 8, 1435: 8, 1440: 8, 1446: 8, 1456: 8, 1479: 8 - }, - - # CX-9 2016 - old CAM connector - { - 64: 8, 70: 8, 80: 8, 117: 8, 118: 8, 120: 8, 121: 8, 130: 8, 134: 8, 145: 8, 154: 8, 155: 8, 157: 8, 158: 8, 159: 8, 253: 8, 304: 8, 305: 8, 357: 8, 358: 8, 359: 8, 512: 8, 514: 8, 515: 8, 529: 8, 533: 8, 535: 8, 539: 8, 540: 8, 541: 8, 542: 8, 543: 8, 552: 8, 576: 8, 577: 8, 578: 8, 579: 8, 580: 8, 581: 8, 582: 8, 583: 8, 605: 8, 606: 8, 608: 8, 628: 8, 832: 8, 836: 8, 976: 8, 977: 8, 978: 8, 1034: 8, 1045: 8, 1056: 8, 1061: 8, 1067: 8, 1078: 8, 1080: 8, 1085: 8, 1086: 8, 1088: 8, 1093: 8, 1108: 8, 1114: 8, 1115: 8, 1116: 8, 1139: 8, 1143: 8, 1147: 8, 1154: 8, 1157: 8, 1160: 8, 1163: 8, 1166: 8, 1170: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1183: 8, 1233: 8, 1236: 8, 1237: 8, 1238: 8, 1239: 8, 1241: 8, 1242: 8, 1244: 8, 1264: 8, 1266: 8, 1267: 8, 1269: 8, 1271: 8, 1272: 8, 1274: 8, 1277: 8, 1278: 8, 1409: 8, 1416: 8, 1425: 8, 1430: 8, 1435: 8, 1440: 8, 1446: 8, 1456: 8, 1479: 8, 1792: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 1988: 8, 1996: 8, 2000: 8, 2001: 8, 2004: 8, 2015: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8 - } - ], - - CAR.Mazda3: [ - # Mazda 3 2017 - { - 19: 5, 80: 8, 117: 8, 118: 8, 120: 8, 121: 8, 130: 8, 134: 8, 138: 8, 145: 8, 154: 8, 155: 8, 157: 8, 158: 8, 159: 8, 253: 8, 304: 8, 305: 8, 357: 8, 358: 8, 359: 8, 512: 8, 514: 8, 515: 8, 522: 8, 529: 8, 533: 8, 535: 8, 539: 8, 540: 8, 541: 8, 542: 8, 543: 8, 552: 8, 576: 8, 577: 8, 578: 8, 579: 8, 580: 8, 581: 8, 582: 8, 605: 8, 606: 8, 607: 8, 628: 8, 832: 8, 863: 8, 865: 8, 866: 8, 867: 8, 868: 8, 869: 8, 870: 8, 976: 8, 977: 8, 978: 8, 1034: 8, 1045: 8, 1056: 8, 1061: 8, 1067: 8, 1070: 8, 1078: 8, 1086: 8, 1088: 8, 1093: 8, 1108: 8, 1114: 8, 1115: 8, 1116: 8, 1143: 8, 1147: 8, 1154: 8, 1157: 8, 1160: 8, 1163: 8, 1166: 8, 1169: 8, 1170: 8, 1173: 8, 1177: 8, 1180: 8, 1182: 8, 1183: 8, 1232: 8, 1233: 8, 1234: 8, 1235: 8, 1236: 8, 1237: 8, 1238: 8, 1239: 8,1240: 8, 1241: 8, 1242: 8, 1243: 8, 1244: 8, 1246: 8, 1247: 8, 1264: 8, 1266: 8, 1267: 8, 1269: 8, 1270: 8, 1271: 8, 1272: 8, 1274: 8, 1275: 8, 1277: 8, 1278: 8, 1409: 8, 1416: 8, 1425: 8, 1430: 8, 1435: 8, 1440: 8, 1456: 8, 1479: 8, 2015: 8, 2024: 8, 2025: 8 - }, - - # Mazda 6 2017 GT - { - 64: 8, 70: 8, 80: 8, 117: 8, 118: 8, 120: 8, 121: 8, 130: 8, 134: 8, 145: 8, 154: 8, 155: 8, 157: 8, 158: 8, 159: 8, 253: 8, 304: 8, 305: 8, 357: 8, 358: 8, 359: 8, 512: 8, 514: 8, 515: 8, 529: 8, 533: 8, 535: 8, 539: 8, 540: 8, 541: 8, 542: 8, 543: 8, 552: 8, 576: 8, 577: 8, 578: 8, 579: 8, 580: 8, 581: 8, 582: 8, 605: 8, 606: 8, 607: 8, 628: 8, 832: 8, 836: 8, 863: 8, 865: 8, 866: 8, 867: 8, 868: 8, 869: 8, 870: 8, 976: 8, 977: 8, 978: 8, 1034: 8, 1045: 8, 1056: 8, 1061: 8, 1067: 8, 1070: 8, 1078: 8, 1080: 8, 1085: 8, 1086: 8, 1088: 8, 1093: 8, 1108: 8, 1114: 8, 1115: 8, 1116: 8, 1143: 8, 1147: 8, 1154: 8, 1157: 8, 1160: 8, 1163: 8, 1166: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1182: 8, 1183: 8, 1233: 8, 1236: 8, 1237: 8, 1238: 8, 1239: 8, 1241: 8, 1242: 8, 1243: 8, 1244: 8, 1264: 8, 1266: 8, 1267: 8, 1269: 8, 1270: 8, 1271: 8, 1272: 8, 1274: 8, 1275: 8, 1277: 8, 1278: 8, 1409: 8, 1416: 8, 1425: 8, 1430: 8, 1435: 8, 1440: 8, 1456: 8, 1479: 8 - } - ], +FW_VERSIONS = { + CAR.CX5: { + (Ecu.eps, 0x730, None): [ + b'KJ01-3210X-G-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'KJ01-3210X-M-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'PYNF-188K2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX38-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX2G-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'K123-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'K131-67XK2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'K131-67XK2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.esp, 0x760, None): [ + b'K123-437K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'KN0W-437K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'KBJ5-437K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'B61L-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'B61L-67XK2-V\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-N\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.transmission, 0x7e1, None): [ + b'PYNC-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX39-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYB2-21PS1-G\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + + CAR.CX9 : { + (Ecu.eps, 0x730, None): [ + b'KJ01-3210X-L-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'PX23-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXN8-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'K131-67XK2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'K131-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.esp, 0x760, None): [ + b'TN40-437K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'TA0B-437K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'B61L-67XK2-V\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-K\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.transmission, 0x7e1, None): [ + b'PYD5-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXM7-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + + CAR.Mazda3: { + (Ecu.eps, 0x730, None): [ + b'K070-3210X-C-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'KR11-3210X-K-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'P5JD-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYKC-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'K131-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'B63C-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.esp, 0x760, None): [ + b'B45A-437AS-0-08\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'B61L-67XK2-P\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'B61L-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.transmission, 0x7e1, None): [ + b'P52G-21PS1-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYKE-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + } } diff --git a/selfdrive/car/volkswagen/interface.py b/selfdrive/car/volkswagen/interface.py index e6a1971a1433c0..c2a4a05a1d1302 100644 --- a/selfdrive/car/volkswagen/interface.py +++ b/selfdrive/car/volkswagen/interface.py @@ -92,6 +92,11 @@ def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=None): ret.mass = 1900 + STD_CARGO_KG ret.wheelbase = 2.64 + elif candidate == CAR.SEAT_LEON_MK3: + # Averages of all 5F Leon variants + ret.mass = 1227 + STD_CARGO_KG + ret.wheelbase = 2.64 + elif candidate == CAR.SKODA_KODIAQ_MK1: # Averages of all 5N Kodiaq variants ret.mass = 1569 + STD_CARGO_KG diff --git a/selfdrive/car/volkswagen/values.py b/selfdrive/car/volkswagen/values.py index c511febb460c89..5ded530d448e26 100644 --- a/selfdrive/car/volkswagen/values.py +++ b/selfdrive/car/volkswagen/values.py @@ -53,6 +53,7 @@ class CANBUS: # Check the 7th and 8th characters of the VIN before adding a new CAR. If the # chassis code is already listed below, don't add a new CAR, just add to the # FW_VERSIONS for that existing CAR. +# Exception: SEAT Leon and SEAT Ateca share a chassis code class CAR: ATLAS_MK1 = "VOLKSWAGEN ATLAS 1ST GEN" # Chassis CA, Mk1 VW Atlas and Atlas Cross Sport @@ -62,6 +63,7 @@ class CAR: TIGUAN_MK2 = "VOLKSWAGEN TIGUAN 2ND GEN" # Chassis AD/BW, Mk2 VW Tiguan and variants AUDI_A3_MK3 = "AUDI A3 3RD GEN" # Chassis 8V/FF, Mk3 Audi A3 and variants SEAT_ATECA_MK1 = "SEAT ATECA 1ST GEN" # Chassis 5F, Mk1 SEAT Ateca and CUPRA Ateca + SEAT_LEON_MK3 = "SEAT LEON 3RD GEN" # Chassis 5F, Mk3 SEAT Leon and variants SKODA_KODIAQ_MK1 = "SKODA KODIAQ 1ST GEN" # Chassis NS, Mk1 Skoda Kodiaq SKODA_SCALA_MK1 = "SKODA SCALA 1ST GEN" # Chassis NW, Mk1 Skoda Scala and Skoda Kamiq SKODA_SUPERB_MK3 = "SKODA SUPERB 3RD GEN" # Chassis 3V/NP, Mk3 Skoda Superb and variants @@ -71,6 +73,7 @@ class CAR: CAR.ATLAS_MK1: { (Ecu.engine, 0x7e0, None): [ b'\xf1\x8703H906026AA\xf1\x899970', + b'\xf1\x8703H906026F \xf1\x896696', b'\xf1\x8703H906026F \xf1\x899970', ], (Ecu.transmission, 0x7e1, None): [ @@ -87,6 +90,7 @@ class CAR: ], (Ecu.fwdRadar, 0x757, None): [ b'\xf1\x875Q0907572H \xf1\x890620', + b'\xf1\x875Q0907572J \xf1\x890654', b'\xf1\x875Q0907572P \xf1\x890682', ], }, @@ -325,6 +329,23 @@ class CAR: b'\xf1\x872Q0907572M \xf1\x890233', ], }, + CAR.SEAT_LEON_MK3: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8705E906018AS\xf1\x899596', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870CW300050J \xf1\x891908', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x873Q0959655CM\xf1\x890720\xf1\x82\0161312001313001305171311052900', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\00521N01342A1', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x875Q0907572P \xf1\x890682', + ], + }, CAR.SKODA_KODIAQ_MK1: { (Ecu.engine, 0x7e0, None): [ b'\xf1\x8704E906027DD\xf1\x893123', @@ -425,6 +446,7 @@ class CAR: CAR.TIGUAN_MK2: dbc_dict('vw_mqb_2010', None), CAR.AUDI_A3_MK3: dbc_dict('vw_mqb_2010', None), CAR.SEAT_ATECA_MK1: dbc_dict('vw_mqb_2010', None), + CAR.SEAT_LEON_MK3: dbc_dict('vw_mqb_2010', None), CAR.SKODA_KODIAQ_MK1: dbc_dict('vw_mqb_2010', None), CAR.SKODA_OCTAVIA_MK3: dbc_dict('vw_mqb_2010', None), CAR.SKODA_SCALA_MK1: dbc_dict('vw_mqb_2010', None), diff --git a/selfdrive/common/SConscript b/selfdrive/common/SConscript index 5d59005006d754..8f6c1dc18e9bcb 100644 --- a/selfdrive/common/SConscript +++ b/selfdrive/common/SConscript @@ -1,4 +1,4 @@ -Import('env', 'arch', 'SHARED', 'QCOM_REPLAY') +Import('env', 'arch', 'SHARED') if SHARED: fxn = env.SharedLibrary diff --git a/selfdrive/common/version.h b/selfdrive/common/version.h index aa2c9e85b84a6e..800d8e6d351ca5 100644 --- a/selfdrive/common/version.h +++ b/selfdrive/common/version.h @@ -1 +1 @@ -#define COMMA_VERSION "0.8.5-d6fcf6fa8-2021-05-22T00:11:34" +#define COMMA_VERSION "0.8.5-3c058e0b6-2021-05-30T08:27:49" diff --git a/selfdrive/debug/test_fw_query_on_routes.py b/selfdrive/debug/test_fw_query_on_routes.py index 8eeacd277d2b5f..6a49a84d8bc67d 100755 --- a/selfdrive/debug/test_fw_query_on_routes.py +++ b/selfdrive/debug/test_fw_query_on_routes.py @@ -14,6 +14,7 @@ from selfdrive.car.honda.values import FW_VERSIONS as HONDA_FW_VERSIONS from selfdrive.car.hyundai.values import FW_VERSIONS as HYUNDAI_FW_VERSIONS from selfdrive.car.volkswagen.values import FW_VERSIONS as VW_FW_VERSIONS +from selfdrive.car.mazda.values import FW_VERSIONS as MAZDA_FW_VERSIONS NO_API = "NO_API" in os.environ @@ -21,14 +22,13 @@ SUPPORTED_CARS |= set(interface_names['honda']) SUPPORTED_CARS |= set(interface_names['hyundai']) SUPPORTED_CARS |= set(interface_names['volkswagen']) - +SUPPORTED_CARS |= set(interface_names['mazda']) try: from xx.pipeline.c.CarState import migration except ImportError: migration = {} - if __name__ == "__main__": parser = argparse.ArgumentParser(description='Run FW fingerprint on Qlog of route or list of routes') parser.add_argument('route', help='Route or file with list of routes') @@ -120,7 +120,7 @@ print("Mismatches") found = False - for car_fws in [TOYOTA_FW_VERSIONS, HONDA_FW_VERSIONS, HYUNDAI_FW_VERSIONS, VW_FW_VERSIONS]: + for car_fws in [TOYOTA_FW_VERSIONS, HONDA_FW_VERSIONS, HYUNDAI_FW_VERSIONS, VW_FW_VERSIONS, MAZDA_FW_VERSIONS]: if live_fingerprint in car_fws: found = True expected = car_fws[live_fingerprint] diff --git a/selfdrive/locationd/calibrationd.py b/selfdrive/locationd/calibrationd.py index e8e4f32df00bb6..d3ad0196983a68 100755 --- a/selfdrive/locationd/calibrationd.py +++ b/selfdrive/locationd/calibrationd.py @@ -7,12 +7,10 @@ ''' import os -import capnp import copy -import json import numpy as np import cereal.messaging as messaging -from cereal import car, log +from cereal import log from selfdrive.hardware import TICI from common.params import Params, put_nonblocking from common.transformations.model import model_height @@ -68,25 +66,13 @@ def __init__(self, param_put=False): rpy_init = RPY_INIT valid_blocks = 0 - cached_params = params.get("CarParamsCache") - if cached_params is not None: - CP = car.CarParams.from_bytes(params.get("CarParams", block=True)) - cached_params = car.CarParams.from_bytes(cached_params) - if cached_params.carFingerprint != CP.carFingerprint: - calibration_params = None - if param_put and calibration_params: try: msg = log.Event.from_bytes(calibration_params) rpy_init = list(msg.liveCalibration.rpyCalib) valid_blocks = msg.liveCalibration.validBlocks - except (ValueError, capnp.lib.capnp.KjException): - # TODO: remove this after next release - calibration_params = json.loads(calibration_params) - rpy_init = calibration_params["calib_radians"] - valid_blocks = calibration_params['valid_blocks'] except Exception: - cloudlog.exception("CalibrationParams file found but error encountered") + cloudlog.exception("Error reading cached CalibrationParams") self.reset(rpy_init, valid_blocks) self.update_status() diff --git a/selfdrive/modeld/SConscript b/selfdrive/modeld/SConscript index 19c57f1dd76816..a0548ee362d065 100644 --- a/selfdrive/modeld/SConscript +++ b/selfdrive/modeld/SConscript @@ -37,12 +37,13 @@ if arch == "aarch64" or arch == "larch64": else: libs += ['pthread'] - # for onnx support - common_src += ['runners/onnxmodel.cc'] + if not GetOption('snpe'): + # for onnx support + common_src += ['runners/onnxmodel.cc'] - # tell runners to use onnx - lenv['CFLAGS'].append("-DUSE_ONNX_MODEL") - lenv['CXXFLAGS'].append("-DUSE_ONNX_MODEL") + # tell runners to use onnx + lenv['CFLAGS'].append("-DUSE_ONNX_MODEL") + lenv['CXXFLAGS'].append("-DUSE_ONNX_MODEL") if arch == "Darwin": # fix OpenCL @@ -56,10 +57,9 @@ else: common_model = lenv.Object(common_src) - # build thneed model if arch == "aarch64" or arch == "larch64": - compiler = lenv.Program('thneed/compile', ["thneed/compile.cc" ]+common_model, LIBS=libs) + compiler = lenv.Program('thneed/compile', ["thneed/compile.cc"]+common_model, LIBS=libs) cmd = f"cd {Dir('.').abspath} && {compiler[0].abspath} ../../models/supercombo.dlc ../../models/supercombo.thneed --binary" lib_paths = ':'.join([Dir(p).abspath for p in lenv["LIBPATH"]]) diff --git a/selfdrive/modeld/modeld b/selfdrive/modeld/modeld index 66868595723991..a87221dbd1f857 100755 --- a/selfdrive/modeld/modeld +++ b/selfdrive/modeld/modeld @@ -1,12 +1,15 @@ #!/bin/sh + +DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" + if [ -d /system ]; then - if [ -f /TICI ]; then # QCOM2 - export LD_LIBRARY_PATH="/usr/lib/aarch64-linux-gnu:/data/pythonpath/phonelibs/snpe/larch64:$LD_LIBRARY_PATH" - else # QCOM - export LD_LIBRARY_PATH="/data/pythonpath/phonelibs/snpe/aarch64/:$LD_LIBRARY_PATH" - fi + if [ -f /TICI ]; then # QCOM2 + export LD_LIBRARY_PATH="/usr/lib/aarch64-linux-gnu:/data/pythonpath/phonelibs/snpe/larch64:$LD_LIBRARY_PATH" + else # QCOM + export LD_LIBRARY_PATH="/data/pythonpath/phonelibs/snpe/aarch64/:$LD_LIBRARY_PATH" + fi else - # PC - export LD_LIBRARY_PATH="$HOME/openpilot/phonelibs/snpe/x86_64-linux-clang:/openpilot/phonelibs/snpe/x86_64:$HOME/openpilot/phonelibs/snpe/x86_64:$LD_LIBRARY_PATH" + # PC + export LD_LIBRARY_PATH="$DIR/../../phonelibs/snpe/x86_64-linux-clang:$DIR/../..//openpilot/phonelibs/snpe/x86_64:$LD_LIBRARY_PATH" fi exec ./_modeld diff --git a/selfdrive/ui/SConscript b/selfdrive/ui/SConscript index c9fe988ca991e6..ec1867e9ff7487 100644 --- a/selfdrive/ui/SConscript +++ b/selfdrive/ui/SConscript @@ -74,10 +74,9 @@ if arch != 'aarch64' and "BUILD_SETUP" in os.environ: # build headless replay if arch == 'x86_64' and os.path.exists(Dir("#tools/").get_abspath()): - qt_env['CPPPATH'] += ["#tools/clib"] qt_env['CXXFLAGS'] += ["-Wno-deprecated-declarations"] - replay_lib_src = ["replay/replay.cc", "replay/filereader.cc", "#tools/clib/framereader.cc"] + replay_lib_src = ["replay/replay.cc", "replay/filereader.cc", "replay/framereader.cc"] replay_lib = qt_env.Library("qt_replay", replay_lib_src, LIBS=base_libs) replay_libs = [replay_lib, 'avutil', 'avcodec', 'avformat', 'swscale', 'bz2'] + qt_libs diff --git a/selfdrive/ui/qt/offroad/settings.cc b/selfdrive/ui/qt/offroad/settings.cc index ecdc54f81c49a3..87a78979fb77e9 100644 --- a/selfdrive/ui/qt/offroad/settings.cc +++ b/selfdrive/ui/qt/offroad/settings.cc @@ -16,6 +16,7 @@ #include "selfdrive/ui/qt/widgets/ssh_keys.h" #include "selfdrive/ui/qt/widgets/toggle.h" #include "selfdrive/ui/ui.h" +#include "selfdrive/ui/qt/util.h" TogglesPanel::TogglesPanel(QWidget *parent) : QWidget(parent) { QVBoxLayout *toggles_list = new QVBoxLayout(); @@ -233,13 +234,32 @@ void DeveloperPanel::showEvent(QShowEvent *event) { Params params = Params(); std::string brand = params.getBool("Passive") ? "dashcam" : "openpilot"; QList> dev_params = { - {"Version", brand + " v" + params.get("Version", false).substr(0, 14)}, {"Git Branch", params.get("GitBranch", false)}, {"Git Commit", params.get("GitCommit", false).substr(0, 10)}, {"Panda Firmware", params.get("PandaFirmwareHex", false)}, {"OS Version", Hardware::get_os_version()}, }; + QString version = QString::fromStdString(brand + " v" + params.get("Version", false).substr(0, 14)).trimmed(); + QDateTime lastUpdateDate = QDateTime::fromString(QString::fromStdString(params.get("LastUpdateTime", false)), Qt::ISODate); + QString lastUpdateTime = timeAgo(lastUpdateDate); + + if (labels.size() < dev_params.size()) { + versionLbl = new LabelControl("Version", version, QString::fromStdString(params.get("ReleaseNotes", false)).trimmed()); + layout()->addWidget(versionLbl); + layout()->addWidget(horizontal_line()); + + lastUpdateTimeLbl = new LabelControl("Last Update Check", lastUpdateTime, "The last time openpilot checked for an update."); + connect(lastUpdateTimeLbl, &LabelControl::showDescription, [=]() { + std::system("pkill -1 -f selfdrive.updated"); + }); + layout()->addWidget(lastUpdateTimeLbl); + layout()->addWidget(horizontal_line()); + } else { + versionLbl->setText(version); + lastUpdateTimeLbl->setText(lastUpdateTime); + } + for (int i = 0; i < dev_params.size(); i++) { const auto &[name, value] = dev_params[i]; QString val = QString::fromStdString(value).trimmed(); diff --git a/selfdrive/ui/qt/offroad/settings.h b/selfdrive/ui/qt/offroad/settings.h index 09a907c8e316e6..1d477c17a9042b 100644 --- a/selfdrive/ui/qt/offroad/settings.h +++ b/selfdrive/ui/qt/offroad/settings.h @@ -34,7 +34,11 @@ class DeveloperPanel : public QFrame { protected: void showEvent(QShowEvent *event) override; + +private: QList labels; + LabelControl *versionLbl; + LabelControl *lastUpdateTimeLbl; }; class SettingsWindow : public QFrame { @@ -44,8 +48,8 @@ class SettingsWindow : public QFrame { explicit SettingsWindow(QWidget *parent = 0) : QFrame(parent) {}; protected: - void hideEvent(QHideEvent *event); - void showEvent(QShowEvent *event); + void hideEvent(QHideEvent *event) override; + void showEvent(QShowEvent *event) override; signals: void closeSettings(); diff --git a/selfdrive/ui/qt/util.h b/selfdrive/ui/qt/util.h index f6eca88abd2797..1ccb56c380bd2c 100644 --- a/selfdrive/ui/qt/util.h +++ b/selfdrive/ui/qt/util.h @@ -20,3 +20,25 @@ inline void clearLayout(QLayout* layout) { delete item; } } + +inline QString timeAgo(const QDateTime &date) { + int diff = date.secsTo(QDateTime::currentDateTime()); + + QString s; + if (diff < 60) { + s = "now"; + } else if (diff < 60 * 60) { + int minutes = diff / 60; + s = QString("%1 minute%2 ago").arg(minutes).arg(minutes > 1 ? "s" : ""); + } else if (diff < 60 * 60 * 24) { + int hours = diff / (60 * 60); + s = QString("%1 hour%2 ago").arg(hours).arg(hours > 1 ? "s" : ""); + } else if (diff < 3600 * 24 * 7) { + int days = diff / (60 * 60 * 24); + s = QString("%1 day%2 ago").arg(days).arg(days > 1 ? "s" : ""); + } else { + s = date.date().toString(); + } + + return s; +} diff --git a/selfdrive/ui/qt/widgets/controls.h b/selfdrive/ui/qt/widgets/controls.h index 22e36ea4f49417..238817ca3e0fad 100644 --- a/selfdrive/ui/qt/widgets/controls.h +++ b/selfdrive/ui/qt/widgets/controls.h @@ -24,7 +24,7 @@ class AbstractControl : public QFrame { protected: AbstractControl(const QString &title, const QString &desc = "", const QString &icon = "", QWidget *parent = nullptr); - void hideEvent(QHideEvent *e); + void hideEvent(QHideEvent *e) override; QSize minimumSizeHint() const override { QSize size = QFrame::minimumSizeHint(); diff --git a/selfdrive/ui/qt/widgets/scrollview.h b/selfdrive/ui/qt/widgets/scrollview.h index aaec224e2f0c84..755ed646fa4b5c 100644 --- a/selfdrive/ui/qt/widgets/scrollview.h +++ b/selfdrive/ui/qt/widgets/scrollview.h @@ -9,5 +9,5 @@ class ScrollView : public QScrollArea { public: explicit ScrollView(QWidget *w = nullptr, QWidget *parent = nullptr); protected: - void hideEvent(QHideEvent *e); + void hideEvent(QHideEvent *e) override; }; diff --git a/selfdrive/ui/qt/widgets/setup.h b/selfdrive/ui/qt/widgets/setup.h index ad6e0dc8d3dd27..169dd594fdb1fb 100644 --- a/selfdrive/ui/qt/widgets/setup.h +++ b/selfdrive/ui/qt/widgets/setup.h @@ -16,7 +16,7 @@ class PairingQRWidget : public QWidget { private: QLabel* qrCode; void updateQrCode(QString text); - void showEvent(QShowEvent *event); + void showEvent(QShowEvent *event) override; private slots: void refresh(); diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index 3849686123fda8..bcd0d344f3becf 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -354,8 +354,6 @@ void QUIState::update() { } Device::Device(QObject *parent) : brightness_filter(BACKLIGHT_OFFROAD, BACKLIGHT_TS, BACKLIGHT_DT), QObject(parent) { - brightness_b = Params(true).get("BRIGHTNESS_B").value_or(10.0); - brightness_m = Params(true).get("BRIGHTNESS_M").value_or(2.6) / 26.0; } void Device::update(const UIState &s) { @@ -380,6 +378,8 @@ void Device::setAwake(bool on, bool reset) { } void Device::updateBrightness(const UIState &s) { + float brightness_b = 10; + float brightness_m = 0.1; float clipped_brightness = std::min(100.0f, (s.scene.light_sensor * brightness_m) + brightness_b); if (!s.scene.started) { clipped_brightness = BACKLIGHT_OFFROAD; diff --git a/selfdrive/ui/ui.h b/selfdrive/ui/ui.h index 8a2cfd186ddd5a..66d7db0458e57d 100644 --- a/selfdrive/ui/ui.h +++ b/selfdrive/ui/ui.h @@ -210,8 +210,6 @@ class Device : public QObject { int awake_timeout = 0; float accel_prev = 0; float gyro_prev = 0; - float brightness_b = 0; - float brightness_m = 0; float last_brightness = 0; FirstOrderFilter brightness_filter; diff --git a/selfdrive/updated.py b/selfdrive/updated.py index 6ec0b4208c1631..ad2d88010531d1 100755 --- a/selfdrive/updated.py +++ b/selfdrive/updated.py @@ -281,17 +281,12 @@ def check_git_fetch_result(fetch_txt): def check_for_update() -> Tuple[bool, bool]: setup_git_options(OVERLAY_MERGED) - fetch_output = None try: - fetch_output = run(["git", "fetch", "--dry-run"], OVERLAY_MERGED, low_priority=True) - return True, check_git_fetch_result(fetch_output) + git_fetch_output = run(["git", "fetch", "--dry-run"], OVERLAY_MERGED, low_priority=True) + return True, check_git_fetch_result(git_fetch_output) except subprocess.CalledProcessError: - # check for internet - if fetch_output is not None and fetch_output.startswith("fatal: unable to access") and \ - "Could not resolve host:" in str(fetch_output): - return False, False + return False, False - raise def fetch_update(wait_helper: WaitTimeHelper) -> bool: cloudlog.info("attempting git fetch inside staging overlay") From 980de6b142acb79b9e2f7f9c092a311f0d73d0e1 Mon Sep 17 00:00:00 2001 From: neokii Date: Mon, 31 May 2021 11:28:55 +0900 Subject: [PATCH 25/27] tune scc --- selfdrive/car/hyundai/interface.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 2d35a0c2d5d72d..81638a498eb4e9 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -72,12 +72,12 @@ def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, ret.longitudinalTuning.kiBP = [0.] ret.longitudinalTuning.kiV = [0.015] ret.longitudinalTuning.kfBP = [50. * CV.KPH_TO_MS, 100. * CV.KPH_TO_MS] - ret.longitudinalTuning.kfV = [0.5, 0.3] + ret.longitudinalTuning.kfV = [0.6, 0.35] ret.longitudinalTuning.deadzoneBP = [0., 100. * CV.KPH_TO_MS] ret.longitudinalTuning.deadzoneV = [0., 0.015] ret.gasMaxBP = [0., 10. * CV.KPH_TO_MS, 20. * CV.KPH_TO_MS, 50. * CV.KPH_TO_MS, 70. * CV.KPH_TO_MS, 130. * CV.KPH_TO_MS] - ret.gasMaxV = [0.45, 0.3, 0.24, 0.165, 0.13, 0.11] + ret.gasMaxV = [0.43, 0.3, 0.24, 0.165, 0.13, 0.11] ret.brakeMaxBP = [0, 70. * CV.KPH_TO_MS, 130. * CV.KPH_TO_MS] ret.brakeMaxV = [1.35, 1.3, 1.] From ca5b9e72b11a4a8eaf628d0168eda9f9cc6b3e3f Mon Sep 17 00:00:00 2001 From: neokii Date: Mon, 31 May 2021 14:36:20 +0900 Subject: [PATCH 26/27] tune scc --- selfdrive/controls/lib/long_mpc.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/controls/lib/long_mpc.py b/selfdrive/controls/lib/long_mpc.py index 1d30a40d6bd2d1..5d6ba3780c7fbf 100644 --- a/selfdrive/controls/lib/long_mpc.py +++ b/selfdrive/controls/lib/long_mpc.py @@ -83,7 +83,7 @@ def update(self, CS, lead): v_lead = max(0.0, lead.vLead) a_lead = lead.aLeadK - dist_cost = interp(lead.dRel, [4., 20.], [MPC_COST_LONG.DISTANCE/1.75, MPC_COST_LONG.DISTANCE]) + dist_cost = interp(lead.dRel, [4., 20.], [MPC_COST_LONG.DISTANCE/2., MPC_COST_LONG.DISTANCE]) dist_cost = interp(v_ego, [60.*CV.KPH_TO_MS, 80.*CV.KPH_TO_MS], [dist_cost, MPC_COST_LONG.DISTANCE]) self.libmpc.set_weights(MPC_COST_LONG.TTC, dist_cost, MPC_COST_LONG.ACCELERATION, MPC_COST_LONG.JERK) From d2e18e8e023bae30d4fc6f8f6a8a53be9243eef6 Mon Sep 17 00:00:00 2001 From: neokii Date: Mon, 31 May 2021 20:27:13 +0900 Subject: [PATCH 27/27] tune scc --- selfdrive/car/hyundai/interface.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 81638a498eb4e9..192b26c14db483 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -68,7 +68,7 @@ def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, # longitudinal ret.longitudinalTuning.kpBP = [0, 10. * CV.KPH_TO_MS, 20. * CV.KPH_TO_MS, 40. * CV.KPH_TO_MS, 70. * CV.KPH_TO_MS, 100. * CV.KPH_TO_MS, 130. * CV.KPH_TO_MS] - ret.longitudinalTuning.kpV = [0.93, 0.7, 0.52, 0.45, 0.4, 0.33, 0.25] + ret.longitudinalTuning.kpV = [0.93, 0.73, 0.54, 0.46, 0.4, 0.33, 0.25] ret.longitudinalTuning.kiBP = [0.] ret.longitudinalTuning.kiV = [0.015] ret.longitudinalTuning.kfBP = [50. * CV.KPH_TO_MS, 100. * CV.KPH_TO_MS] @@ -80,7 +80,7 @@ def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False, ret.gasMaxV = [0.43, 0.3, 0.24, 0.165, 0.13, 0.11] ret.brakeMaxBP = [0, 70. * CV.KPH_TO_MS, 130. * CV.KPH_TO_MS] - ret.brakeMaxV = [1.35, 1.3, 1.] + ret.brakeMaxV = [1.35, 1., 0.6] ret.stoppingBrakeRate = 0.15 # brake_travel/s while trying to stop ret.startingBrakeRate = 1.0 # brake_travel/s while releasing on restart