From 92b458c70990572dfefcf29e78c04bac822be56e Mon Sep 17 00:00:00 2001 From: Jason Wen <47793918+sunnyhaibin@users.noreply.github.com> Date: Mon, 24 Oct 2022 21:40:01 -0400 Subject: [PATCH 01/59] HKG: Add FW and Remove from dashcamOnly for 2019 Elantra GT i30 (#25951) * HKG: Add FW for 2019 Elantra GT i30 * Add test route * remove can fp * revert that * actually shares the same platform with the ceed * marketed as Elantra i30 * stash * Revert "stash" This reverts commit 03b164c9dbad53ff22a961d7a93848b8c91d1722. * add car infos * gen docs * combine with elantra * legacy again * update docs Co-authored-by: Adeeb Shihadeh Co-authored-by: Shane Smiskol --- docs/CARS.md | 4 ++- selfdrive/car/hyundai/interface.py | 4 +-- selfdrive/car/hyundai/values.py | 42 +++++++++++++---------- selfdrive/car/tests/routes.py | 2 +- selfdrive/car/torque_data/substitute.yaml | 1 - 5 files changed, 30 insertions(+), 23 deletions(-) diff --git a/docs/CARS.md b/docs/CARS.md index a03da5ca6a..13ac13fe66 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -4,7 +4,7 @@ A supported vehicle is one that just works when you install a comma three. All supported cars provide a better experience than any stock system. -# 209 Supported Cars +# 211 Supported Cars |Make|Model|Supported Package|ACC|No ACC accel below|No ALC below|Steering Torque|Resume from stop|Harness| |---|---|---|:---:|:---:|:---:|:---:|:---:|:---:| @@ -55,8 +55,10 @@ A supported vehicle is one that just works when you install a comma three. All s |Honda|Ridgeline 2017-22|Honda Sensing|openpilot|25 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Nidec| |Hyundai|Elantra 2017-19|Smart Cruise Control (SCC)|Stock|19 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai B| |Hyundai|Elantra 2021-22|Smart Cruise Control (SCC)|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai K| +|Hyundai|Elantra GT 2017-19|Smart Cruise Control (SCC)|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai E| |Hyundai|Elantra Hybrid 2021-23|Smart Cruise Control (SCC)|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai K| |Hyundai|Genesis 2015-16|Smart Cruise Control (SCC)|Stock|19 mph|37 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai J| +|Hyundai|i30 2019|Smart Cruise Control (SCC)|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai E| |Hyundai|Ioniq 5 (with HDA II) 2022|Highway Driving Assist II|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai Q| |Hyundai|Ioniq 5 (without HDA II) 2022|Highway Driving Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai K| |Hyundai|Ioniq Electric 2019|Smart Cruise Control (SCC)|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C| diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index b1fa8d9e1d..114d124a38 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -31,7 +31,7 @@ class CarInterface(CarInterfaceBase): # These cars have been put into dashcam only due to both a lack of users and test coverage. # These cars likely still work fine. Once a user confirms each car works and a test route is # added to selfdrive/car/tests/routes.py, we can remove it from this list. - ret.dashcamOnly = candidate in {CAR.KIA_OPTIMA_H, CAR.ELANTRA_GT_I30} + ret.dashcamOnly = candidate in {CAR.KIA_OPTIMA_H, } if candidate in CANFD_CAR: # detect HDA2 with ADAS Driving ECU @@ -75,7 +75,7 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 15.6 * 1.15 tire_stiffness_factor = 0.63 CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) - elif candidate in (CAR.ELANTRA, CAR.ELANTRA_GT_I30): + elif candidate == CAR.ELANTRA: ret.lateralTuning.pid.kf = 0.00006 ret.mass = 1275. + STD_CARGO_KG ret.wheelbase = 2.7 diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 96c4201773..29d0cb3dce 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -34,7 +34,7 @@ class CarControllerParams: # To determine the limit for your car, find the maximum value that the stock LKAS will request. # If the max stock LKAS request is <384, add your car to this list. - elif CP.carFingerprint in (CAR.GENESIS_G80, CAR.GENESIS_G90, CAR.ELANTRA, CAR.HYUNDAI_GENESIS, CAR.ELANTRA_GT_I30, CAR.IONIQ, + elif CP.carFingerprint in (CAR.GENESIS_G80, CAR.GENESIS_G90, CAR.ELANTRA, CAR.HYUNDAI_GENESIS, CAR.IONIQ, CAR.IONIQ_EV_LTD, CAR.SANTA_FE_PHEV_2022, CAR.SONATA_LF, CAR.KIA_FORTE, CAR.KIA_NIRO_PHEV, CAR.KIA_OPTIMA_H, CAR.KIA_SORENTO): self.STEER_MAX = 255 @@ -54,7 +54,6 @@ class CAR: ELANTRA = "HYUNDAI ELANTRA 2017" ELANTRA_2021 = "HYUNDAI ELANTRA 2021" ELANTRA_HEV_2021 = "HYUNDAI ELANTRA HYBRID 2021" - ELANTRA_GT_I30 = "HYUNDAI I30 N LINE 2019 & GT 2018 DCT" HYUNDAI_GENESIS = "HYUNDAI GENESIS 2015-2016" IONIQ = "HYUNDAI IONIQ HYBRID 2017-2019" IONIQ_HEV_2022 = "HYUNDAI IONIQ HYBRID 2020-2022" @@ -108,13 +107,13 @@ class HyundaiCarInfo(CarInfo): CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = { - CAR.ELANTRA: HyundaiCarInfo("Hyundai Elantra 2017-19", min_enable_speed=19 * CV.MPH_TO_MS, harness=Harness.hyundai_b), - CAR.ELANTRA_2021: HyundaiCarInfo("Hyundai Elantra 2021-22", video_link="https://youtu.be/_EdYQtV52-c", harness=Harness.hyundai_k), - CAR.ELANTRA_HEV_2021: HyundaiCarInfo("Hyundai Elantra Hybrid 2021-23", video_link="https://youtu.be/_EdYQtV52-c", harness=Harness.hyundai_k), - CAR.ELANTRA_GT_I30: [ + CAR.ELANTRA: [ + HyundaiCarInfo("Hyundai Elantra 2017-19", min_enable_speed=19 * CV.MPH_TO_MS, harness=Harness.hyundai_b), HyundaiCarInfo("Hyundai Elantra GT 2017-19", harness=Harness.hyundai_e), HyundaiCarInfo("Hyundai i30 2019", harness=Harness.hyundai_e), ], + CAR.ELANTRA_2021: HyundaiCarInfo("Hyundai Elantra 2021-22", video_link="https://youtu.be/_EdYQtV52-c", harness=Harness.hyundai_k), + CAR.ELANTRA_HEV_2021: HyundaiCarInfo("Hyundai Elantra Hybrid 2021-23", video_link="https://youtu.be/_EdYQtV52-c", harness=Harness.hyundai_k), CAR.HYUNDAI_GENESIS: HyundaiCarInfo("Hyundai Genesis 2015-16", min_enable_speed=19 * CV.MPH_TO_MS, harness=Harness.hyundai_j), # TODO: check 2015 packages CAR.IONIQ: HyundaiCarInfo("Hyundai Ioniq Hybrid 2017-19", harness=Harness.hyundai_c), CAR.IONIQ_HEV_2022: HyundaiCarInfo("Hyundai Ioniq Hybrid 2020-22", harness=Harness.hyundai_h), # TODO: confirm 2020-21 harness @@ -199,15 +198,6 @@ FINGERPRINTS = { CAR.ELANTRA: [{ 66: 8, 67: 8, 68: 8, 127: 8, 273: 8, 274: 8, 275: 8, 339: 8, 356: 4, 399: 8, 512: 6, 544: 8, 593: 8, 608: 8, 688: 5, 790: 8, 809: 8, 897: 8, 832: 8, 899: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1170: 8, 1265: 4, 1280: 1, 1282: 4, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1314: 8, 1322: 8, 1345: 8, 1349: 8, 1351: 8, 1353: 8, 1363: 8, 1366: 8, 1367: 8, 1369: 8, 1407: 8, 1415: 8, 1419: 8, 1425: 2, 1427: 6, 1440: 8, 1456: 4, 1472: 8, 1486: 8, 1487: 8, 1491: 8, 1530: 8, 1532: 5, 2001: 8, 2003: 8, 2004: 8, 2009: 8, 2012: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8 }], - CAR.ELANTRA_GT_I30: [{ - 66: 8, 67: 8, 68: 8, 127: 8, 128: 8, 129: 8, 273: 8, 274: 8, 275: 8, 339: 8, 354: 3, 356: 4, 399: 8, 512: 6, 544: 8, 593: 8, 608: 8, 688: 5, 790: 8, 809: 8, 884: 8, 897: 8, 899: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1151: 6, 1168: 7, 1170: 8, 1193: 8, 1265: 4, 1280: 1, 1282: 4, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1345: 8, 1348: 8, 1349: 8, 1351: 8, 1353: 8, 1356: 8, 1363: 8, 1365: 8, 1366: 8, 1367: 8, 1369: 8, 1407: 8, 1414: 3, 1415: 8, 1427: 6, 1440: 8, 1456: 4, 1470: 8, 1486: 8, 1487: 8, 1491: 8, 1530: 8, 1952: 8, 1960: 8, 1988: 8, 2000: 8, 2001: 8, 2005: 8, 2008: 8, 2009: 8, 2013: 8, 2017: 8, 2025: 8 - }, - { - 66: 8, 67: 8, 68: 8, 127: 8, 128: 8, 129: 8, 273: 8, 274: 8, 275: 8, 339: 8, 354: 3, 356: 4, 399: 8, 512: 6, 544: 8, 593: 8, 608: 8, 688: 5, 790: 8, 809: 8, 832: 8, 897: 8, 899: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1151: 6, 1168: 7, 1170: 8, 1265: 4, 1280: 1, 1282: 4, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1349: 8, 1351: 8, 1353: 8, 1356: 8, 1363: 8, 1366: 8, 1367: 8, 1369: 8, 1407: 8, 1414: 3, 1415: 8, 1419: 8, 1440: 8, 1456: 4, 1470: 8, 1486: 8, 1487: 8, 1491: 8, 1530: 8 - }, - { - 66: 8, 67: 8, 68: 8, 127: 8, 128: 8, 129: 8, 273: 8, 274: 8, 275: 8, 339: 8, 354: 3, 356: 4, 399: 8, 512: 6, 544: 8, 593: 8, 608: 8, 688: 5, 790: 8, 809: 8, 832: 8, 897: 8, 899: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1151: 6, 1168: 7, 1170: 8, 1265: 4, 1280: 1, 1282: 4, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1349: 8, 1351: 8, 1353: 8, 1356: 8, 1363: 8, 1366: 8, 1367: 8, 1369: 8, 1407: 8, 1414: 3, 1419: 8, 1427: 6, 1440: 8, 1456: 4, 1470: 8, 1486: 8, 1487: 8, 1491: 8, 1960: 8, 1990: 8, 1998: 8, 2000: 8, 2001: 8, 2004: 8, 2005: 8, 2008: 8, 2009: 8, 2012: 8, 2013: 8, 2015: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8 - }], CAR.HYUNDAI_GENESIS: [{ 67: 8, 68: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 7, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 5, 897: 8, 902: 8, 903: 6, 916: 8, 1024: 2, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1168: 7, 1170: 8, 1173: 8, 1184: 8, 1265: 4, 1280: 1, 1287: 4, 1292: 8, 1312: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1334: 8, 1335: 8, 1342: 6, 1345: 8, 1363: 8, 1369: 8, 1370: 8, 1371: 8, 1378: 4, 1384: 5, 1407: 8, 1419: 8, 1427: 6, 1434: 2, 1456: 4 }, @@ -1214,6 +1204,23 @@ FW_VERSIONS = { b'\xf1\x87\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xf1\x816T6B8051\x00\x00\xf1\x006T6H0_C2\x00\x006T6B8051\x00\x00TJFSG24NH27\xa7\xc2\xb4', ], }, + CAR.ELANTRA: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00PD LKAS AT USA LHD 1.01 1.01 95740-G3100 A54', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x006U2V0_C2\x00\x006U2VA051\x00\x00DPD0H16NS0e\x0e\xcd\x8e', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00PD MDPS C 1.00 1.04 56310/G3300 4PDDC104', + ], + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00PD ESC \x0b 104\x18\t\x03 58920-G3350', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00PD__ SCC F-CUP 1.00 1.00 96400-G3300 ', + ], + }, CAR.ELANTRA_2021: { (Ecu.fwdRadar, 0x7d0, None): [ b'\xf1\x00CN7_ SCC F-CUP 1.00 1.01 99110-AA000 ', @@ -1394,12 +1401,12 @@ CHECKSUM = { FEATURES = { # which message has the gear - "use_cluster_gears": {CAR.ELANTRA, CAR.ELANTRA_GT_I30, CAR.KONA}, + "use_cluster_gears": {CAR.ELANTRA, CAR.KONA}, "use_tcu_gears": {CAR.KIA_OPTIMA_G4, CAR.KIA_OPTIMA_G4_FL, CAR.SONATA_LF, CAR.VELOSTER, CAR.TUCSON}, "use_elect_gears": {CAR.KIA_NIRO_EV, CAR.KIA_NIRO_PHEV, CAR.KIA_NIRO_HEV_2021, CAR.KIA_OPTIMA_H, CAR.IONIQ_EV_LTD, CAR.KONA_EV, CAR.IONIQ, CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.ELANTRA_HEV_2021, CAR.SONATA_HYBRID, CAR.KONA_HEV, CAR.IONIQ_HEV_2022, CAR.SANTA_FE_HEV_2022, CAR.SANTA_FE_PHEV_2022, CAR.IONIQ_PHEV_2019, CAR.KONA_EV_2022}, # these cars use the FCA11 message for the AEB and FCW signals, all others use SCC12 - "use_fca": {CAR.SONATA, CAR.SONATA_HYBRID, CAR.ELANTRA, CAR.ELANTRA_2021, CAR.ELANTRA_HEV_2021, CAR.ELANTRA_GT_I30, CAR.KIA_STINGER, CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.KONA_EV, CAR.KIA_FORTE, CAR.KIA_NIRO_EV, CAR.PALISADE, CAR.GENESIS_G70, CAR.GENESIS_G70_2020, CAR.KONA, CAR.SANTA_FE, CAR.KIA_SELTOS, CAR.KONA_HEV, CAR.SANTA_FE_2022, CAR.KIA_K5_2021, CAR.IONIQ_HEV_2022, CAR.SANTA_FE_HEV_2022, CAR.SANTA_FE_PHEV_2022, CAR.TUCSON, CAR.KONA_EV_2022}, + "use_fca": {CAR.SONATA, CAR.SONATA_HYBRID, CAR.ELANTRA, CAR.ELANTRA_2021, CAR.ELANTRA_HEV_2021, CAR.KIA_STINGER, CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.KONA_EV, CAR.KIA_FORTE, CAR.KIA_NIRO_EV, CAR.PALISADE, CAR.GENESIS_G70, CAR.GENESIS_G70_2020, CAR.KONA, CAR.SANTA_FE, CAR.KIA_SELTOS, CAR.KONA_HEV, CAR.SANTA_FE_2022, CAR.KIA_K5_2021, CAR.IONIQ_HEV_2022, CAR.SANTA_FE_HEV_2022, CAR.SANTA_FE_PHEV_2022, CAR.TUCSON, CAR.KONA_EV_2022}, } CANFD_CAR = {CAR.KIA_EV6, CAR.IONIQ_5, CAR.TUCSON_HYBRID_4TH_GEN, CAR.KIA_SPORTAGE_HYBRID_5TH_GEN} @@ -1419,7 +1426,6 @@ DBC = { CAR.ELANTRA: dbc_dict('hyundai_kia_generic', None), CAR.ELANTRA_2021: dbc_dict('hyundai_kia_generic', None), CAR.ELANTRA_HEV_2021: dbc_dict('hyundai_kia_generic', None), - CAR.ELANTRA_GT_I30: dbc_dict('hyundai_kia_generic', None), CAR.GENESIS_G70: dbc_dict('hyundai_kia_generic', None), CAR.GENESIS_G70_2020: dbc_dict('hyundai_kia_generic', 'hyundai_kia_mando_front_radar_generated'), CAR.GENESIS_G80: dbc_dict('hyundai_kia_generic', None), diff --git a/selfdrive/car/tests/routes.py b/selfdrive/car/tests/routes.py index 8c4efe3061..326d80b822 100644 --- a/selfdrive/car/tests/routes.py +++ b/selfdrive/car/tests/routes.py @@ -23,7 +23,6 @@ non_tested_cars = [ GM.MALIBU, GM.EQUINOX, GM.BOLT_EV, - HYUNDAI.ELANTRA_GT_I30, HYUNDAI.GENESIS_G90, HYUNDAI.KIA_OPTIMA_H, ] @@ -119,6 +118,7 @@ routes = [ CarTestRoute("34a875f29f69841a|2021-07-29--13-02-09", HYUNDAI.KIA_NIRO_HEV_2021), CarTestRoute("50a2212c41f65c7b|2021-05-24--16-22-06", HYUNDAI.KIA_FORTE), CarTestRoute("c5ac319aa9583f83|2021-06-01--18-18-31", HYUNDAI.ELANTRA), + CarTestRoute("734ef96182ddf940|2022-10-02--16-41-44", HYUNDAI.ELANTRA), # 2019 Elantra GT CarTestRoute("82e9cdd3f43bf83e|2021-05-15--02-42-51", HYUNDAI.ELANTRA_2021), CarTestRoute("715ac05b594e9c59|2021-06-20--16-21-07", HYUNDAI.ELANTRA_HEV_2021), CarTestRoute("7120aa90bbc3add7|2021-08-02--07-12-31", HYUNDAI.SONATA_HYBRID), diff --git a/selfdrive/car/torque_data/substitute.yaml b/selfdrive/car/torque_data/substitute.yaml index f5e3d1d61d..acd7526003 100644 --- a/selfdrive/car/torque_data/substitute.yaml +++ b/selfdrive/car/torque_data/substitute.yaml @@ -26,7 +26,6 @@ KIA SELTOS 2021: HYUNDAI SONATA 2020 KIA NIRO HYBRID 2019: KIA NIRO EV 2020 KIA NIRO HYBRID 2021: KIA NIRO EV 2020 HYUNDAI VELOSTER 2019: HYUNDAI SONATA 2019 -HYUNDAI I30 N LINE 2019 & GT 2018 DCT: HYUNDAI SONATA 2019 HYUNDAI KONA 2020: HYUNDAI KONA ELECTRIC 2019 HYUNDAI KONA HYBRID 2020: HYUNDAI KONA ELECTRIC 2019 HYUNDAI KONA ELECTRIC 2022: HYUNDAI KONA ELECTRIC 2019 From e9fcef99e1edace1d4950c9ac58de0b535926709 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 24 Oct 2022 19:08:20 -0700 Subject: [PATCH 02/59] FPv2 tests: test all addrs map to one ECU (#26151) * add test * fix mapping --- selfdrive/car/honda/values.py | 10 +++++----- selfdrive/car/tests/test_fw_fingerprint.py | 11 +++++++++++ 2 files changed, 16 insertions(+), 5 deletions(-) diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py index 638008934a..e0810e0bbb 100644 --- a/selfdrive/car/honda/values.py +++ b/selfdrive/car/honda/values.py @@ -446,7 +446,7 @@ FW_VERSIONS = { b'78109-TED-Q510\x00\x00', b'78109-TEG-A310\x00\x00', ], - (Ecu.fwdCamera, 0x18dab0f1, None): [ + (Ecu.fwdRadar, 0x18dab0f1, None): [ b'36161-TBA-A020\x00\x00', b'36161-TBA-A030\x00\x00', b'36161-TBA-A040\x00\x00', @@ -964,7 +964,7 @@ FW_VERSIONS = { b'77959-THR-A110\x00\x00', b'77959-THR-X010\x00\x00', ], - (Ecu.fwdCamera, 0x18dab0f1, None): [ + (Ecu.fwdRadar, 0x18dab0f1, None): [ b'36161-THR-A020\x00\x00', b'36161-THR-A030\x00\x00', b'36161-THR-A110\x00\x00', @@ -1068,7 +1068,7 @@ FW_VERSIONS = { b'39990-TG7-A070\x00\x00', b'39990-TGS-A230\x00\x00', ], - (Ecu.fwdCamera, 0x18dab0f1, None): [ + (Ecu.fwdRadar, 0x18dab0f1, None): [ b'36161-TG7-A310\x00\x00', b'36161-TG7-A520\x00\x00', b'36161-TG7-A630\x00\x00', @@ -1176,7 +1176,7 @@ FW_VERSIONS = { b'57114-TX5-A220\x00\x00', b'57114-TX4-A220\x00\x00', ], - (Ecu.fwdCamera, 0x18dab0f1, None): [ + (Ecu.fwdRadar, 0x18dab0f1, None): [ b'36161-TX5-A030\x00\x00', b'36161-TX4-A030\x00\x00', ], @@ -1273,7 +1273,7 @@ FW_VERSIONS = { b'39990-T6Z-A030\x00\x00', b'39990-T6Z-A050\x00\x00', ], - (Ecu.fwdCamera, 0x18dab0f1, None): [ + (Ecu.fwdRadar, 0x18dab0f1, None): [ b'36161-T6Z-A020\x00\x00', b'36161-T6Z-A310\x00\x00', b'36161-T6Z-A420\x00\x00', diff --git a/selfdrive/car/tests/test_fw_fingerprint.py b/selfdrive/car/tests/test_fw_fingerprint.py index b9926301f1..2e43103852 100755 --- a/selfdrive/car/tests/test_fw_fingerprint.py +++ b/selfdrive/car/tests/test_fw_fingerprint.py @@ -1,6 +1,7 @@ #!/usr/bin/env python3 import random import unittest +from collections import defaultdict from parameterized import parameterized from cereal import car @@ -44,6 +45,16 @@ class TestFwFingerprint(unittest.TestCase): duplicates = {fw for fw in ecu_fw if ecu_fw.count(fw) > 1} self.assertFalse(len(duplicates), f"{car_model}: Duplicate FW versions: Ecu.{ECU_NAME[ecu[0]]}, {duplicates}") + def test_all_addrs_map_to_one_ecu(self): + for brand, cars in VERSIONS.items(): + addr_to_ecu = defaultdict(set) + for ecus in cars.values(): + for ecu_type, addr, sub_addr in ecus.keys(): + addr_to_ecu[(addr, sub_addr)].add(ecu_type) + ecus_for_addr = addr_to_ecu[(addr, sub_addr)] + ecu_strings = ", ".join([f'Ecu.{ECU_NAME[ecu]}' for ecu in ecus_for_addr]) + self.assertLessEqual(len(ecus_for_addr), 1, f"{brand} has multiple ECUs that map to one address: {ecu_strings} -> ({hex(addr)}, {sub_addr})") + def test_data_collection_ecus(self): # Asserts no extra ECUs are in the fingerprinting database for brand, config in FW_QUERY_CONFIGS.items(): From a22ce68699ef4d6714a2921f19ed7d793ea619a5 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 24 Oct 2022 19:37:18 -0700 Subject: [PATCH 03/59] jenkins: disable camerad while new box is built --- Jenkinsfile | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Jenkinsfile b/Jenkinsfile index b9b9eda667..85b4880463 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -137,6 +137,7 @@ pipeline { } } + /* stage('camerad') { agent { docker { image 'ghcr.io/commaai/alpine-ssh'; args '--user=root' } } steps { @@ -147,6 +148,7 @@ pipeline { ]) } } + */ stage('replay') { agent { docker { image 'ghcr.io/commaai/alpine-ssh'; args '--user=root' } } From 506a150e735e72b5af53d800260a65a821b95949 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 24 Oct 2022 19:37:52 -0700 Subject: [PATCH 04/59] bump cereal --- cereal | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cereal b/cereal index 38133307b2..1d25fc3f20 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 38133307b2e6036e76684b39878e79212e545e06 +Subproject commit 1d25fc3f202d5ddeee97848480323e9b14f9bdfa From 15595fc8599f0ddf1e72ed02422e9f6d266db1f6 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Mon, 24 Oct 2022 20:17:05 -0700 Subject: [PATCH 05/59] Calibrationd: Calibrate wide from device (#26204) * Use calibrator to stabilize wide transform * Need array * Needs init * Needs to be arr * publish mshg * Check size * Update ref * fix calibration param read when no wide calib * need self! --- selfdrive/locationd/calibrationd.py | 34 +++++++++++++++++++++--- selfdrive/test/process_replay/ref_commit | 2 +- 2 files changed, 31 insertions(+), 5 deletions(-) diff --git a/selfdrive/locationd/calibrationd.py b/selfdrive/locationd/calibrationd.py index 9e6536f9b5..4e996bc3b9 100755 --- a/selfdrive/locationd/calibrationd.py +++ b/selfdrive/locationd/calibrationd.py @@ -31,6 +31,7 @@ INPUTS_NEEDED = 5 # Minimum blocks needed for valid calibration INPUTS_WANTED = 50 # We want a little bit more than we need for stability MAX_ALLOWED_SPREAD = np.radians(2) RPY_INIT = np.array([0.0,0.0,0.0]) +WIDE_FROM_DEVICE_EULER_INIT = np.array([0.0, 0.0, 0.0]) # These values are needed to accommodate biggest modelframe PITCH_LIMITS = np.array([-0.09074112085129739, 0.14907572052989657]) @@ -67,6 +68,7 @@ class Calibrator: calibration_params = params.get("CalibrationParams") self.wide_camera = params.get_bool('WideCameraOnly') rpy_init = RPY_INIT + wide_from_device_euler = WIDE_FROM_DEVICE_EULER_INIT valid_blocks = 0 if param_put and calibration_params: @@ -74,24 +76,34 @@ class Calibrator: msg = log.Event.from_bytes(calibration_params) rpy_init = np.array(msg.liveCalibration.rpyCalib) valid_blocks = msg.liveCalibration.validBlocks + wide_from_device_euler = np.array(msg.liveCalibration.wideFromDeviceEuler) except Exception: cloudlog.exception("Error reading cached CalibrationParams") - self.reset(rpy_init, valid_blocks) + self.reset(rpy_init, valid_blocks, wide_from_device_euler) self.update_status() - def reset(self, rpy_init: np.ndarray = RPY_INIT, valid_blocks: int = 0, smooth_from: Optional[np.ndarray] = None) -> None: + def reset(self, rpy_init: np.ndarray = RPY_INIT, + valid_blocks: int = 0, + wide_from_device_euler_init: np.ndarray = WIDE_FROM_DEVICE_EULER_INIT, + smooth_from: Optional[np.ndarray] = None) -> None: if not np.isfinite(rpy_init).all(): self.rpy = RPY_INIT.copy() else: self.rpy = rpy_init.copy() + if not np.isfinite(wide_from_device_euler_init).all() or len(wide_from_device_euler_init) != 3: + self.wide_from_device_euler = WIDE_FROM_DEVICE_EULER_INIT.copy() + else: + self.wide_from_device_euler = wide_from_device_euler_init.copy() + if not np.isfinite(valid_blocks) or valid_blocks < 0: self.valid_blocks = 0 else: self.valid_blocks = valid_blocks self.rpys = np.tile(self.rpy, (INPUTS_WANTED, 1)) + self.wide_from_device_eulers = np.tile(self.wide_from_device_euler, (INPUTS_WANTED, 1)) self.idx = 0 self.block_idx = 0 @@ -113,6 +125,7 @@ class Calibrator: def update_status(self) -> None: valid_idxs = self.get_valid_idxs() if valid_idxs: + self.wide_from_device_euler = np.mean(self.wide_from_device_eulers[valid_idxs], axis=0) rpys = self.rpys[valid_idxs] self.rpy = np.mean(rpys, axis=0) max_rpy_calib = np.array(np.max(rpys, axis=0)) @@ -146,7 +159,10 @@ class Calibrator: else: return self.rpy - def handle_cam_odom(self, trans: List[float], rot: List[float], trans_std: List[float]) -> Optional[np.ndarray]: + def handle_cam_odom(self, trans: List[float], + rot: List[float], + wide_from_device_euler: List[float], + trans_std: List[float]) -> Optional[np.ndarray]: self.old_rpy_weight = min(0.0, self.old_rpy_weight - 1/SMOOTH_CYCLES) straight_and_fast = ((self.v_ego > MIN_SPEED_FILTER) and (trans[0] > MIN_SPEED_FILTER) and (abs(rot[2]) < MAX_YAW_RATE_FILTER)) @@ -165,7 +181,15 @@ class Calibrator: new_rpy = euler_from_rot(rot_from_euler(self.get_smooth_rpy()).dot(rot_from_euler(observed_rpy))) new_rpy = sanity_clip(new_rpy) - self.rpys[self.block_idx] = (self.idx*self.rpys[self.block_idx] + (BLOCK_SIZE - self.idx) * new_rpy) / float(BLOCK_SIZE) + if len(wide_from_device_euler) == 3: + new_wide_from_device_euler = np.array(wide_from_device_euler) + else: + new_wide_from_device_euler = WIDE_FROM_DEVICE_EULER_INIT + + self.rpys[self.block_idx] = (self.idx*self.rpys[self.block_idx] + + (BLOCK_SIZE - self.idx) * new_rpy) / float(BLOCK_SIZE) + self.wide_from_device_eulers[self.block_idx] = (self.idx*self.wide_from_device_eulers[self.block_idx] + + (BLOCK_SIZE - self.idx) * new_wide_from_device_euler) / float(BLOCK_SIZE) self.idx = (self.idx + 1) % BLOCK_SIZE if self.idx == 0: self.block_idx += 1 @@ -187,6 +211,7 @@ class Calibrator: liveCalibration.calPerc = min(100 * (self.valid_blocks * BLOCK_SIZE + self.idx) // (INPUTS_NEEDED * BLOCK_SIZE), 100) liveCalibration.rpyCalib = smooth_rpy.tolist() liveCalibration.rpyCalibSpread = self.calib_spread.tolist() + liveCalibration.wideFromDeviceEuler = self.wide_from_device_euler.tolist() if self.not_car: liveCalibration.validBlocks = INPUTS_NEEDED @@ -223,6 +248,7 @@ def calibrationd_thread(sm: Optional[messaging.SubMaster] = None, pm: Optional[m calibrator.handle_v_ego(sm['carState'].vEgo) new_rpy = calibrator.handle_cam_odom(sm['cameraOdometry'].trans, sm['cameraOdometry'].rot, + sm['cameraOdometry'].wideFromDeviceEuler, sm['cameraOdometry'].transStd) if DEBUG and new_rpy is not None: diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 230e81d949..d03b897f9d 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -f5a352666728344ca5065bb44c47c1f5650b4243 +a5c77655fba5563e8128fb655f69b1bbd02198aa From 27e315e58f5273da79803ad95737fc15483fef21 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 25 Oct 2022 00:12:49 -0700 Subject: [PATCH 06/59] GM: reduce LKAS faults while inactive (#26196) * send at 10hz when inactive * try to make it fine to switch rates * fix rate * todododo * fine if we skip, we usually send too early * clean up * this may be required, 50Hz is not really needed to sync/initialize * preserves previous behavior (not sure if this makes sense) * Revert "preserves previous behavior (not sure if this makes sense)" This reverts commit 3b297bca72307b5cba09bec4e2cd8e0f2761af42. * Revert "this may be required, 50Hz is not really needed to sync/initialize" This reverts commit a6b4693814214d3f508db922f3b371c402a13995. * rm com * Update ref_commit * gate behind GM Cam * common logic * bet * update refs --- selfdrive/car/gm/carcontroller.py | 16 ++++++++++++---- selfdrive/car/gm/values.py | 3 ++- selfdrive/test/process_replay/ref_commit | 2 +- 3 files changed, 15 insertions(+), 6 deletions(-) diff --git a/selfdrive/car/gm/carcontroller.py b/selfdrive/car/gm/carcontroller.py index b56b3bfca6..a75eb89f25 100644 --- a/selfdrive/car/gm/carcontroller.py +++ b/selfdrive/car/gm/carcontroller.py @@ -22,6 +22,7 @@ class CarController: self.apply_gas = 0 self.apply_brake = 0 self.frame = 0 + self.last_steer_frame = 0 self.last_button_frame = 0 self.cancel_counter = 0 @@ -46,15 +47,21 @@ class CarController: # Send CAN commands. can_sends = [] - # Steering (50Hz) + # Steering (Active: 50Hz, inactive: 10Hz) + # Attempt to sync with camera on startup at 50Hz, first few msgs are blocked + init_lka_counter = not self.sent_lka_steering_cmd and self.CP.networkLocation == NetworkLocation.fwdCamera + steer_step = self.params.INACTIVE_STEER_STEP + if CC.latActive or init_lka_counter: + steer_step = self.params.ACTIVE_STEER_STEP + # Avoid GM EPS faults when transmitting messages too close together: skip this transmit if we just received the # next Panda loopback confirmation in the current CS frame. if CS.loopback_lka_steering_cmd_updated: self.lka_steering_cmd_counter += 1 self.sent_lka_steering_cmd = True - elif (self.frame % self.params.STEER_STEP) == 0: - # Initialize ASCMLKASteeringCmd counter using the camera - if not self.sent_lka_steering_cmd and self.CP.networkLocation == NetworkLocation.fwdCamera: + elif (self.frame - self.last_steer_frame) >= steer_step: + # Initialize ASCMLKASteeringCmd counter using the camera until we get a msg on the bus + if init_lka_counter: self.lka_steering_cmd_counter = CS.camera_lka_steering_cmd_counter + 1 if CC.latActive: @@ -63,6 +70,7 @@ class CarController: else: apply_steer = 0 + self.last_steer_frame = self.frame self.apply_steer_last = apply_steer idx = self.lka_steering_cmd_counter % 4 can_sends.append(gmcan.create_steering_control(self.packer_pt, CanBus.POWERTRAIN, apply_steer, idx, CC.latActive)) diff --git a/selfdrive/car/gm/values.py b/selfdrive/car/gm/values.py index f8f9e7f043..85e291aaf6 100644 --- a/selfdrive/car/gm/values.py +++ b/selfdrive/car/gm/values.py @@ -11,7 +11,8 @@ Ecu = car.CarParams.Ecu class CarControllerParams: STEER_MAX = 300 # GM limit is 3Nm. Used by carcontroller to generate LKA output - STEER_STEP = 2 # Control frames per command (50hz) + ACTIVE_STEER_STEP = 2 # Active control frames per command (50hz) + INACTIVE_STEER_STEP = 10 # Inactive control frames per command (10hz) STEER_DELTA_UP = 7 # Delta rates require review due to observed EPS weakness STEER_DELTA_DOWN = 17 STEER_DRIVER_ALLOWANCE = 50 diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index d03b897f9d..604abd666c 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -a5c77655fba5563e8128fb655f69b1bbd02198aa +9d042d06f61c8f48e8c7a4e30001630c14712272 \ No newline at end of file From bc7fc481d57cbdfb8c727a38ba5a32e856315df0 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 25 Oct 2022 11:33:02 -0700 Subject: [PATCH 07/59] pj: update thermal layout + layout test (#26224) --- tools/plotjuggler/layouts/thermal_debug.xml | 93 +++++++++++---------- tools/plotjuggler/test_plotjuggler.py | 22 ++++- 2 files changed, 68 insertions(+), 47 deletions(-) diff --git a/tools/plotjuggler/layouts/thermal_debug.xml b/tools/plotjuggler/layouts/thermal_debug.xml index cebda81753..c10b78f1c5 100644 --- a/tools/plotjuggler/layouts/thermal_debug.xml +++ b/tools/plotjuggler/layouts/thermal_debug.xml @@ -1,82 +1,83 @@ - + - + - - + + - - - - - - - - + + + + + + + + - - + + - - - - + + + + - - + + - + - + - - + + - + - - + + - + + - - + + - + - + - - + + - - - - + + + + - - + + - - - - + + + + @@ -92,8 +93,8 @@ - - + + diff --git a/tools/plotjuggler/test_plotjuggler.py b/tools/plotjuggler/test_plotjuggler.py index edaec9c80a..8fc032042a 100755 --- a/tools/plotjuggler/test_plotjuggler.py +++ b/tools/plotjuggler/test_plotjuggler.py @@ -1,5 +1,6 @@ #!/usr/bin/env python3 import os +import glob import signal import subprocess import time @@ -9,12 +10,14 @@ from common.basedir import BASEDIR from common.timeout import Timeout from tools.plotjuggler.juggle import install +PJ_DIR = os.path.join(BASEDIR, "tools/plotjuggler") + class TestPlotJuggler(unittest.TestCase): def test_demo(self): install() - pj = os.path.join(BASEDIR, "tools/plotjuggler/juggle.py") + pj = os.path.join(PJ_DIR, "juggle.py") p = subprocess.Popen(f'QT_QPA_PLATFORM=offscreen {pj} --demo None 1 --qlog', stderr=subprocess.PIPE, shell=True, start_new_session=True) @@ -29,5 +32,22 @@ class TestPlotJuggler(unittest.TestCase): self.assertEqual(p.poll(), None) os.killpg(os.getpgid(p.pid), signal.SIGTERM) + # TODO: also test that layouts successfully load + def test_layouts(self): + bad_strings = ( + # if a previously loaded file is defined, + # PJ will throw a warning when loading the layout + "fileInfo", + "previouslyLoaded_Datafiles", + ) + for fn in glob.glob(os.path.join(PJ_DIR, "layouts/*")): + name = os.path.basename(fn) + with self.subTest(layout=name): + with open(fn) as f: + layout = f.read() + violations = [s for s in bad_strings if s in layout] + assert len(violations) == 0, f"These should be stripped out of the layout: {str(violations)}" + + if __name__ == "__main__": unittest.main() From 6d30b1ee8314539f66eee000ac7a13ac7ccb506c Mon Sep 17 00:00:00 2001 From: Rewat S <76684800+taperec@users.noreply.github.com> Date: Wed, 26 Oct 2022 02:50:50 +0700 Subject: [PATCH 08/59] Multilang: add missing Thai translations (#26234) --- selfdrive/ui/translations/main_th.ts | 92 +++++----------------------- 1 file changed, 16 insertions(+), 76 deletions(-) diff --git a/selfdrive/ui/translations/main_th.ts b/selfdrive/ui/translations/main_th.ts index 5a8bf861df..95880e69c9 100644 --- a/selfdrive/ui/translations/main_th.ts +++ b/selfdrive/ui/translations/main_th.ts @@ -60,11 +60,11 @@ Cellular Metered - + ลดการส่งข้อมูลผ่านเซลลูล่าร์ Prevent large data uploads when on a metered connection - + ปิดการอัพโหลดข้อมูลขนาดใหญ่เมื่อเชื่อมต่อผ่านเซลลูล่าร์ @@ -802,54 +802,6 @@ location set SoftwarePanel - - Git Branch - Git Branch - - - Git Commit - Git Commit - - - OS Version - เวอร์ชันระบบปฏิบัติการ - - - Version - เวอร์ชั่น - - - Last Update Check - ตรวจสอบการอัปเดตล่าสุด - - - The last time openpilot successfully checked for an update. The updater only runs while the car is off. - ครั้งสุดท้ายที่ openpilot ตรวจสอบการอัปเดตสำเร็จ ตัวอัปเดตจะทำงานในขณะที่รถดับเครื่องอยู่เท่านั้น - - - Check for Update - ตรวจสอบการอัปเดต - - - CHECKING - กำลังตรวจสอบ - - - Switch Branch - เปลี่ยน Branch - - - ENTER - เปลี่ยน - - - The new branch will be pulled the next time the updater runs. - Branch ใหม่จะถูกติดตั้งในครั้งต่อไปที่ตัวอัปเดตทำงาน - - - Enter branch name - ใส่ชื่อ Branch - Uninstall %1 ถอนการติดตั้ง %1 @@ -862,45 +814,41 @@ location set Are you sure you want to uninstall? คุณแน่ใจหรือไม่ว่าต้องการถอนการติดตั้ง? - - failed to fetch update - โหลดข้อมูลอัปเดตไม่สำเร็จ - CHECK ตรวจสอบ Updates are only downloaded while the car is off. - + ตัวอัปเดตจะดำเนินการดาวน์โหลดเมื่อรถดับเครื่องยนต์อยู่เท่านั้น Current Version - + เวอร์ชั่นปัจจุบัน Download - + ดาวน์โหลด Install Update - + ติดตั้งตัวอัปเดต INSTALL - + ติดตั้ง Target Branch - + Branch ที่เลือก SELECT - + เลือก Select a branch - + เลือก Branch @@ -1026,37 +974,29 @@ location set Show map on left side when in split screen view. แสดงแผนที่ด้านซ้ายของหน้าจอเมื่ออยู่ในโหมดแบ่งหน้าจอ - - openpilot Longitudinal Control - openpilot การควบคุมการเร่งและลดความเร็ว - - - openpilot will disable the car's radar and will take over control of gas and brakes. Warning: this disables AEB! - openpilot จะปิดการใช้งานเรดาร์ของรถ และจะเข้าควบคุมการเร่งและเบรก คำเตือน: สิ่งนี้จะปิดระบบ AEB! - 🌮 End-to-end longitudinal (extremely alpha) 🌮 - + 🌮 ควบคุมเร่ง/เบรคแบบ End-to-end (อยู่ขั้นพัฒนา) 🌮 Experimental openpilot longitudinal control - + ทดลองใช้ระบบควบคุมการเร่ง/เบรคโดย openpilot <b>WARNING: openpilot longitudinal control is experimental for this car and will disable AEB.</b> - + <b>คำเตือน: การควบคุมการเร่ง/เบรคโดย openpilot สำหรับรถคันนี้ยังอยู่ในขั้นทดลอง และระบบเบรคฉุกเฉินอัตโนมัติ (AEB) จะถูกปิด</b> Let the driving model control the gas and brakes. openpilot will drive as it thinks a human would. Super experimental. - + ให้ openpilot ควบคุมการเร่ง/เบรคแบบ end-to-end โดย openpilot จะขับอย่างที่มนุษย์คิด ระบบยังอยู่ในขั้นทดลอง openpilot longitudinal control is not currently available for this car. - + ขณะนี้ยังไม่มีระบบควบคุมการเร่ง/เบรคโดย openpilot สำหรับรถคันนี้ Enable experimental longitudinal control to enable this. - + เปิดใช้งานระบบควบคุมการเร่ง/เบรคขั้นทดลอง เพื่อเปิดใช้งานสิ่งนี้ From 339253bc05179530e47509e548c482495fbc6e82 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 25 Oct 2022 13:51:23 -0700 Subject: [PATCH 09/59] Hyundai: CAN-FD blindspot signals (#26229) * Hyundai: CAN-FD blindspot signals * fix that * update refs --- opendbc | 2 +- selfdrive/car/hyundai/carstate.py | 12 ++++++++++++ selfdrive/car/hyundai/interface.py | 9 +++++++-- selfdrive/test/process_replay/ref_commit | 2 +- 4 files changed, 21 insertions(+), 4 deletions(-) diff --git a/opendbc b/opendbc index 7bd94e3ff4..a95b0ae8a5 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit 7bd94e3ff4a2890eb69118f0dfadb64f9d32d618 +Subproject commit a95b0ae8a5244a9d6311bf72aa2a7d63d41b4a9f diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py index e27432e23b..ec2b3059a3 100644 --- a/selfdrive/car/hyundai/carstate.py +++ b/selfdrive/car/hyundai/carstate.py @@ -187,6 +187,9 @@ class CarState(CarStateBase): ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_lamp(50, cp.vl["BLINKERS"]["LEFT_LAMP"], cp.vl["BLINKERS"]["RIGHT_LAMP"]) + if self.CP.enableBsm: + ret.leftBlindspot = cp.vl["BLINDSPOTS_REAR_CORNERS"]["FL_INDICATOR"] != 0 + ret.rightBlindspot = cp.vl["BLINDSPOTS_REAR_CORNERS"]["FR_INDICATOR"] != 0 ret.cruiseState.available = True self.is_metric = cp.vl["CLUSTER_INFO"]["DISTANCE_UNIT"] != 1 @@ -450,6 +453,15 @@ class CarState(CarStateBase): ("DOORS_SEATBELTS", 4), ] + if CP.enableBsm: + signals += [ + ("FL_INDICATOR", "BLINDSPOTS_REAR_CORNERS"), + ("FR_INDICATOR", "BLINDSPOTS_REAR_CORNERS"), + ] + checks += [ + ("BLINDSPOTS_REAR_CORNERS", 20), + ] + if CP.flags & HyundaiFlags.CANFD_HDA2 and not CP.openpilotLongitudinalControl: signals += [ ("CRUISE_STATUS", "CRUISE_INFO"), diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 114d124a38..147c766008 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -311,6 +311,13 @@ class CarInterface(CarInterfaceBase): ret.vEgoStarting = 0.1 ret.startAccel = 2.0 + # *** feature detection *** + if candidate in CANFD_CAR: + bus = 5 if ret.flags & HyundaiFlags.CANFD_HDA2 else 4 + ret.enableBsm = 0x1e5 in fingerprint[bus] + else: + ret.enableBsm = 0x58b in fingerprint[0] + # *** panda safety config *** if candidate in CANFD_CAR: ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.noOutput), @@ -321,8 +328,6 @@ class CarInterface(CarInterfaceBase): if ret.flags & HyundaiFlags.CANFD_ALT_BUTTONS: ret.safetyConfigs[1].safetyParam |= Panda.FLAG_HYUNDAI_CANFD_ALT_BUTTONS else: - ret.enableBsm = 0x58b in fingerprint[0] - if candidate in LEGACY_SAFETY_MODE_CAR: # these cars require a special panda safety mode due to missing counters and checksums in the messages ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.hyundaiLegacy)] diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 604abd666c..44eed18493 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -9d042d06f61c8f48e8c7a4e30001630c14712272 \ No newline at end of file +68457035e9223fcbd70bd40966d5a1d9fe4f1567 \ No newline at end of file From 4639862baecfc8ed708827580f441a34731ba137 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 25 Oct 2022 15:21:43 -0700 Subject: [PATCH 10/59] UI: show git commit date (#26240) * show version description while offroad * ui fixups * parse date * cleanup --- selfdrive/ui/qt/home.cc | 16 +++++----------- selfdrive/ui/qt/home.h | 6 +++++- selfdrive/ui/qt/offroad/software_settings.cc | 4 ++-- selfdrive/ui/qt/util.cc | 4 ---- selfdrive/ui/qt/util.h | 1 - selfdrive/ui/qt/widgets/controls.cc | 4 ++-- selfdrive/ui/qt/widgets/controls.h | 2 +- selfdrive/ui/qt/widgets/scrollview.cc | 2 ++ selfdrive/updated.py | 14 +++++++++++--- 9 files changed, 28 insertions(+), 25 deletions(-) diff --git a/selfdrive/ui/qt/home.cc b/selfdrive/ui/qt/home.cc index 78bc6aab40..3fe00e6ed9 100644 --- a/selfdrive/ui/qt/home.cc +++ b/selfdrive/ui/qt/home.cc @@ -1,11 +1,9 @@ #include "selfdrive/ui/qt/home.h" -#include #include #include #include -#include "common/params.h" #include "selfdrive/ui/qt/util.h" #include "selfdrive/ui/qt/widgets/drive_stats.h" #include "selfdrive/ui/qt/widgets/prime.h" @@ -109,22 +107,20 @@ OffroadHome::OffroadHome(QWidget* parent) : QFrame(parent) { header_layout->setContentsMargins(15, 15, 15, 0); header_layout->setSpacing(16); - date = new QLabel(); - header_layout->addWidget(date, 1, Qt::AlignHCenter | Qt::AlignLeft); - update_notif = new QPushButton(tr("UPDATE")); update_notif->setVisible(false); update_notif->setStyleSheet("background-color: #364DEF;"); QObject::connect(update_notif, &QPushButton::clicked, [=]() { center_layout->setCurrentIndex(1); }); - header_layout->addWidget(update_notif, 0, Qt::AlignHCenter | Qt::AlignRight); + header_layout->addWidget(update_notif, 0, Qt::AlignHCenter | Qt::AlignLeft); alert_notif = new QPushButton(); alert_notif->setVisible(false); alert_notif->setStyleSheet("background-color: #E22C2C;"); QObject::connect(alert_notif, &QPushButton::clicked, [=] { center_layout->setCurrentIndex(2); }); - header_layout->addWidget(alert_notif, 0, Qt::AlignHCenter | Qt::AlignRight); + header_layout->addWidget(alert_notif, 0, Qt::AlignHCenter | Qt::AlignLeft); - header_layout->addWidget(new QLabel(getBrandVersion()), 0, Qt::AlignHCenter | Qt::AlignRight); + version = new ElidedLabel(); + header_layout->addWidget(version, 0, Qt::AlignHCenter | Qt::AlignRight); main_layout->addLayout(header_layout); @@ -184,9 +180,7 @@ void OffroadHome::hideEvent(QHideEvent *event) { } void OffroadHome::refresh() { - QString locale_name = QString(uiState()->language).replace("main_", ""); - QString dateString = QLocale(locale_name).toString(QDateTime::currentDateTime(), "dddd, MMMM d"); - date->setText(dateString); + version->setText(getBrand() + " " + QString::fromStdString(params.get("UpdaterCurrentDescription"))); bool updateAvailable = update_widget->refresh(); int alerts = alerts_widget->refresh(); diff --git a/selfdrive/ui/qt/home.h b/selfdrive/ui/qt/home.h index 94f1330109..6636da56ec 100644 --- a/selfdrive/ui/qt/home.h +++ b/selfdrive/ui/qt/home.h @@ -7,10 +7,12 @@ #include #include +#include "common/params.h" #include "selfdrive/ui/qt/offroad/driverview.h" #include "selfdrive/ui/qt/body.h" #include "selfdrive/ui/qt/onroad.h" #include "selfdrive/ui/qt/sidebar.h" +#include "selfdrive/ui/qt/widgets/controls.h" #include "selfdrive/ui/qt/widgets/offroad_alerts.h" #include "selfdrive/ui/ui.h" @@ -25,8 +27,10 @@ private: void hideEvent(QHideEvent *event) override; void refresh(); + Params params; + QTimer* timer; - QLabel* date; + ElidedLabel* version; QStackedLayout* center_layout; UpdateAlert *update_widget; OffroadAlert* alerts_widget; diff --git a/selfdrive/ui/qt/offroad/software_settings.cc b/selfdrive/ui/qt/offroad/software_settings.cc index 4f048241c3..e08a02a4d6 100644 --- a/selfdrive/ui/qt/offroad/software_settings.cc +++ b/selfdrive/ui/qt/offroad/software_settings.cc @@ -145,11 +145,11 @@ void SoftwarePanel::updateLabels() { targetBranchBtn->setValue(QString::fromStdString(params.get("UpdaterTargetBranch"))); // current + new versions - versionLbl->setText(QString::fromStdString(params.get("UpdaterCurrentDescription")).left(40)); + versionLbl->setText(QString::fromStdString(params.get("UpdaterCurrentDescription"))); versionLbl->setDescription(QString::fromStdString(params.get("UpdaterCurrentReleaseNotes"))); installBtn->setVisible(!is_onroad && params.getBool("UpdateAvailable")); - installBtn->setValue(QString::fromStdString(params.get("UpdaterNewDescription")).left(35)); + installBtn->setValue(QString::fromStdString(params.get("UpdaterNewDescription"))); installBtn->setDescription(QString::fromStdString(params.get("UpdaterNewReleaseNotes"))); update(); diff --git a/selfdrive/ui/qt/util.cc b/selfdrive/ui/qt/util.cc index c5697c1045..59903e3376 100644 --- a/selfdrive/ui/qt/util.cc +++ b/selfdrive/ui/qt/util.cc @@ -21,10 +21,6 @@ QString getBrand() { return Params().getBool("Passive") ? QObject::tr("dashcam") : QObject::tr("openpilot"); } -QString getBrandVersion() { - return getBrand() + " v" + getVersion().left(14).trimmed(); -} - QString getUserAgent() { return "openpilot-" + getVersion(); } diff --git a/selfdrive/ui/qt/util.h b/selfdrive/ui/qt/util.h index 209f051963..61a27a8669 100644 --- a/selfdrive/ui/qt/util.h +++ b/selfdrive/ui/qt/util.h @@ -11,7 +11,6 @@ QString getVersion(); QString getBrand(); -QString getBrandVersion(); QString getUserAgent(); std::optional getDongleId(); QMap getSupportedLanguages(); diff --git a/selfdrive/ui/qt/widgets/controls.cc b/selfdrive/ui/qt/widgets/controls.cc index a1ebf57b07..d3b77935df 100644 --- a/selfdrive/ui/qt/widgets/controls.cc +++ b/selfdrive/ui/qt/widgets/controls.cc @@ -41,7 +41,7 @@ AbstractControl::AbstractControl(const QString &title, const QString &desc, cons hlayout->addWidget(title_label); // value next to control button - value = new QLabel(); + value = new ElidedLabel(); value->setAlignment(Qt::AlignRight | Qt::AlignVCenter); value->setStyleSheet("color: #aaaaaa"); hlayout->addWidget(value); @@ -70,7 +70,7 @@ AbstractControl::AbstractControl(const QString &title, const QString &desc, cons } void AbstractControl::hideEvent(QHideEvent *e) { - if(description != nullptr) { + if (description != nullptr) { description->hide(); } } diff --git a/selfdrive/ui/qt/widgets/controls.h b/selfdrive/ui/qt/widgets/controls.h index c42716828f..f11f9baf59 100644 --- a/selfdrive/ui/qt/widgets/controls.h +++ b/selfdrive/ui/qt/widgets/controls.h @@ -65,7 +65,7 @@ protected: QPushButton *title_label; private: - QLabel *value; + ElidedLabel *value; QLabel *description = nullptr; }; diff --git a/selfdrive/ui/qt/widgets/scrollview.cc b/selfdrive/ui/qt/widgets/scrollview.cc index bd4309d8d0..5536593016 100644 --- a/selfdrive/ui/qt/widgets/scrollview.cc +++ b/selfdrive/ui/qt/widgets/scrollview.cc @@ -3,6 +3,8 @@ #include #include +// TODO: disable horizontal scrolling and resize + ScrollView::ScrollView(QWidget *w, QWidget *parent) : QScrollArea(parent) { setWidget(w); setWidgetResizable(true); diff --git a/selfdrive/updated.py b/selfdrive/updated.py index 57f957cfff..c261a92a84 100755 --- a/selfdrive/updated.py +++ b/selfdrive/updated.py @@ -280,17 +280,25 @@ class Updater: # Write out current and new version info def get_description(basedir: str) -> str: + if not os.path.exists(basedir): + return "" + version = "" branch = "" commit = "" + commit_date = "" try: branch = self.get_branch(basedir) - commit = self.get_commit_hash(basedir) + commit = self.get_commit_hash(basedir)[:7] with open(os.path.join(basedir, "common", "version.h")) as f: version = f.read().split('"')[1] + + commit_unix_ts = run(["git", "show", "-s", "--format=%ct", "HEAD"], basedir).rstrip() + dt = datetime.datetime.fromtimestamp(int(commit_unix_ts)) + commit_date = dt.strftime("%b %d") except Exception: - pass - return f"{version} / {branch} / {commit[:7]}" + cloudlog.exception("updater.get_description") + return f"{version} / {branch} / {commit} / {commit_date}" self.params.put("UpdaterCurrentDescription", get_description(BASEDIR)) self.params.put("UpdaterCurrentReleaseNotes", parse_release_notes(BASEDIR)) self.params.put("UpdaterNewDescription", get_description(FINALIZED)) From 1be4150089a4ac9281879ddfaccd0f9447c14f3d Mon Sep 17 00:00:00 2001 From: Jafar Al-Gharaibeh Date: Tue, 25 Oct 2022 17:32:49 -0500 Subject: [PATCH 11/59] Mazda: Add CX-5 2023 to supported cars (#26182) * Mazda: Add CX-5 2023 to supported cars Signed-off-by: Jafar Al-Gharaibeh * add missing cam fw Signed-off-by: Jafar Al-Gharaibeh Co-authored-by: Adeeb Shihadeh --- selfdrive/car/mazda/values.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/selfdrive/car/mazda/values.py b/selfdrive/car/mazda/values.py index 921dc7a634..129273efee 100644 --- a/selfdrive/car/mazda/values.py +++ b/selfdrive/car/mazda/values.py @@ -43,7 +43,7 @@ CAR_INFO: Dict[str, Union[MazdaCarInfo, List[MazdaCarInfo]]] = { CAR.MAZDA3: MazdaCarInfo("Mazda 3 2017-18"), CAR.MAZDA6: MazdaCarInfo("Mazda 6 2017-20"), CAR.CX9_2021: MazdaCarInfo("Mazda CX-9 2021-22", video_link="https://youtu.be/dA3duO4a0O4"), - CAR.CX5_2022: MazdaCarInfo("Mazda CX-5 2022"), + CAR.CX5_2022: MazdaCarInfo("Mazda CX-5 2022-23"), } @@ -89,6 +89,7 @@ FW_VERSIONS = { ], (Ecu.fwdCamera, 0x706, None): [ b'GSH7-67XK2-S\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.transmission, 0x7e1, None): [ b'PYB2-21PS1-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', From 9091e737c8fea44158570e6e15668e30d518d4d3 Mon Sep 17 00:00:00 2001 From: Greg Hogan Date: Tue, 25 Oct 2022 15:51:39 -0700 Subject: [PATCH 12/59] controlsd: update is_metric live (#26228) * fix speed increment if units changed while driving * don't recreate params Co-authored-by: Adeeb Shihadeh --- selfdrive/controls/controlsd.py | 40 +++++++++++++++++---------------- 1 file changed, 21 insertions(+), 19 deletions(-) diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index cbc54eadb8..5172cc4044 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -82,13 +82,13 @@ class Controls: self.log_sock = messaging.sub_sock('androidLog') - params = Params() + self.params = Params() self.sm = sm if self.sm is None: ignore = ['testJoystick'] if SIMULATION: ignore += ['driverCameraState', 'managerState'] - if params.get_bool('WideCameraOnly'): + if self.params.get_bool('WideCameraOnly'): ignore += ['roadCameraState'] self.sm = messaging.SubMaster(['deviceState', 'pandaStates', 'peripheralState', 'modelV2', 'liveCalibration', 'driverMonitoringState', 'longitudinalPlan', 'lateralPlan', 'liveLocationKalman', @@ -105,22 +105,22 @@ class Controls: else: self.CI, self.CP = CI, CI.CP - self.joystick_mode = params.get_bool("JoystickDebugMode") or (self.CP.notCar and sm is None) + self.joystick_mode = self.params.get_bool("JoystickDebugMode") or (self.CP.notCar and sm is None) # set alternative experiences from parameters - self.disengage_on_accelerator = params.get_bool("DisengageOnAccelerator") + self.disengage_on_accelerator = self.params.get_bool("DisengageOnAccelerator") self.CP.alternativeExperience = 0 if not self.disengage_on_accelerator: self.CP.alternativeExperience |= ALTERNATIVE_EXPERIENCE.DISABLE_DISENGAGE_ON_GAS - if self.CP.dashcamOnly and params.get_bool("DashcamOverride"): + if self.CP.dashcamOnly and self.params.get_bool("DashcamOverride"): self.CP.dashcamOnly = False # read params - self.is_metric = params.get_bool("IsMetric") - self.is_ldw_enabled = params.get_bool("IsLdwEnabled") - openpilot_enabled_toggle = params.get_bool("OpenpilotEnabledToggle") - passive = params.get_bool("Passive") or not openpilot_enabled_toggle + self.is_metric = self.params.get_bool("IsMetric") + self.is_ldw_enabled = self.params.get_bool("IsLdwEnabled") + openpilot_enabled_toggle = self.params.get_bool("OpenpilotEnabledToggle") + passive = self.params.get_bool("Passive") or not openpilot_enabled_toggle # detect sound card presence and ensure successful init sounds_available = HARDWARE.get_sound_card_online() @@ -139,15 +139,15 @@ class Controls: # Write CarParams for radard cp_bytes = self.CP.to_bytes() - params.put("CarParams", cp_bytes) + self.params.put("CarParams", cp_bytes) put_nonblocking("CarParamsCache", cp_bytes) put_nonblocking("CarParamsPersistent", cp_bytes) # cleanup old params if not self.CP.experimentalLongitudinalAvailable: - params.remove("ExperimentalLongitudinalEnabled") + self.params.remove("ExperimentalLongitudinalEnabled") if not self.CP.openpilotLongitudinalControl: - params.remove("EndToEndLong") + self.params.remove("EndToEndLong") self.CC = car.CarControl.new_message() self.CS_prev = car.CarState.new_message() @@ -583,9 +583,9 @@ class Controls: """Given the state, this function returns a CarControl packet""" # Update VehicleModel - params = self.sm['liveParameters'] - x = max(params.stiffnessFactor, 0.1) - sr = max(params.steerRatio, 0.1) + lp = self.sm['liveParameters'] + x = max(lp.stiffnessFactor, 0.1) + sr = max(lp.steerRatio, 0.1) self.VM.update_params(x, sr) # Update Torque Params @@ -628,7 +628,7 @@ class Controls: lat_plan.psis, lat_plan.curvatures, lat_plan.curvatureRates) - actuators.steer, actuators.steeringAngleDeg, lac_log = self.LaC.update(CC.latActive, CS, self.VM, params, + actuators.steer, actuators.steeringAngleDeg, lac_log = self.LaC.update(CC.latActive, CS, self.VM, lp, self.last_actuators, self.steer_limited, self.desired_curvature, self.desired_curvature_rate, self.sm['liveLocationKalman']) else: @@ -768,10 +768,10 @@ class Controls: (self.state == State.softDisabling) # Curvature & Steering angle - params = self.sm['liveParameters'] + lp = self.sm['liveParameters'] - steer_angle_without_offset = math.radians(CS.steeringAngleDeg - params.angleOffsetDeg) - curvature = -self.VM.calc_curvature(steer_angle_without_offset, CS.vEgo, params.roll) + steer_angle_without_offset = math.radians(CS.steeringAngleDeg - lp.angleOffsetDeg) + curvature = -self.VM.calc_curvature(steer_angle_without_offset, CS.vEgo, lp.roll) # controlsState dat = messaging.new_message('controlsState') @@ -856,6 +856,8 @@ class Controls: start_time = sec_since_boot() self.prof.checkpoint("Ratekeeper", ignore=True) + self.is_metric = self.params.get_bool("IsMetric") + # Sample data from sockets and get a carState CS = self.data_sample() cloudlog.timestamp("Data sampled") From 87e26b09c17ba029b2054c256acae1c2413a3bd1 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 25 Oct 2022 15:57:29 -0700 Subject: [PATCH 13/59] update car docs --- docs/CARS.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/CARS.md b/docs/CARS.md index 13ac13fe66..2df2b96e24 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -122,7 +122,7 @@ A supported vehicle is one that just works when you install a comma three. All s |Lexus|RX Hybrid 2017-19|All|Stock[3](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Toyota| |Lexus|RX Hybrid 2020-21|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Toyota| |Lexus|UX Hybrid 2019-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Mazda|CX-5 2022|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Mazda| +|Mazda|CX-5 2022-23|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Mazda| |Mazda|CX-9 2021-22|All|Stock|0 mph|28 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Mazda| |Nissan|Altima 2019-20|ProPILOT Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Nissan B| |Nissan|Leaf 2018-22|ProPILOT Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Nissan A| From f6bab0cd678e3020c7b0e2257309df69f83de0f0 Mon Sep 17 00:00:00 2001 From: Vivek Aithal Date: Tue, 25 Oct 2022 16:09:36 -0700 Subject: [PATCH 14/59] [torqued] Extend to all Toyota and Hyundai cars (#26238) * extend to toyota and hyundai * remove all pid control in hyundai * remove indi tunes * remove toyota lat tunes * release notes * rm tunes.py Co-authored-by: Adeeb Shihadeh --- RELEASES.md | 1 + selfdrive/car/hyundai/interface.py | 94 +------------------------- selfdrive/car/toyota/interface.py | 38 ++++------- selfdrive/car/toyota/tunes.py | 102 ----------------------------- 4 files changed, 15 insertions(+), 220 deletions(-) delete mode 100644 selfdrive/car/toyota/tunes.py diff --git a/RELEASES.md b/RELEASES.md index b424259581..744168c8fb 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -6,6 +6,7 @@ Version 0.8.17 (2022-XX-XX) * New end-to-end distracted trigger * Self-tuning torque lateral controller parameters * Parameters learned live for each car +* Torque controller used on all Toyota, Lexus, Hyundai, Kia, and Genesis models * UI updates * Multi-language in navigation * Matched speeds shown on car's dash diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 147c766008..6a1d741dec 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -45,141 +45,92 @@ class CarInterface(CarInterfaceBase): ret.steerActuatorDelay = 0.1 # Default delay ret.steerLimitTimer = 0.4 tire_stiffness_factor = 1. + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) if candidate in (CAR.SANTA_FE, CAR.SANTA_FE_2022, CAR.SANTA_FE_HEV_2022, CAR.SANTA_FE_PHEV_2022): - ret.lateralTuning.pid.kf = 0.00005 ret.mass = 3982. * CV.LB_TO_KG + STD_CARGO_KG ret.wheelbase = 2.766 # Values from optimizer ret.steerRatio = 16.55 # 13.8 is spec end-to-end tire_stiffness_factor = 0.82 - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[9., 22.], [9., 22.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2, 0.35], [0.05, 0.09]] elif candidate in (CAR.SONATA, CAR.SONATA_HYBRID): ret.mass = 1513. + STD_CARGO_KG ret.wheelbase = 2.84 ret.steerRatio = 13.27 * 1.15 # 15% higher at the center seems reasonable tire_stiffness_factor = 0.65 - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) elif candidate == CAR.SONATA_LF: - ret.lateralTuning.pid.kf = 0.00005 ret.mass = 4497. * CV.LB_TO_KG ret.wheelbase = 2.804 ret.steerRatio = 13.27 * 1.15 # 15% higher at the center seems reasonable - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] elif candidate == CAR.PALISADE: - ret.lateralTuning.pid.kf = 0.00005 ret.mass = 1999. + STD_CARGO_KG ret.wheelbase = 2.90 ret.steerRatio = 15.6 * 1.15 tire_stiffness_factor = 0.63 - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) elif candidate == CAR.ELANTRA: - ret.lateralTuning.pid.kf = 0.00006 ret.mass = 1275. + STD_CARGO_KG ret.wheelbase = 2.7 ret.steerRatio = 15.4 # 14 is Stock | Settled Params Learner values are steerRatio: 15.401566348670535 tire_stiffness_factor = 0.385 # stiffnessFactor settled on 1.0081302973865127 - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] ret.minSteerSpeed = 32 * CV.MPH_TO_MS elif candidate == CAR.ELANTRA_2021: ret.mass = (2800. * CV.LB_TO_KG) + STD_CARGO_KG ret.wheelbase = 2.72 ret.steerRatio = 12.9 tire_stiffness_factor = 0.65 - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) elif candidate == CAR.ELANTRA_HEV_2021: ret.mass = (3017. * CV.LB_TO_KG) + STD_CARGO_KG ret.wheelbase = 2.72 ret.steerRatio = 12.9 tire_stiffness_factor = 0.65 - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) elif candidate == CAR.HYUNDAI_GENESIS: - ret.lateralTuning.pid.kf = 0.00005 ret.mass = 2060. + STD_CARGO_KG ret.wheelbase = 3.01 ret.steerRatio = 16.5 - ret.lateralTuning.init('indi') - ret.lateralTuning.indi.innerLoopGainBP = [0.] - ret.lateralTuning.indi.innerLoopGainV = [3.5] - ret.lateralTuning.indi.outerLoopGainBP = [0.] - ret.lateralTuning.indi.outerLoopGainV = [2.0] - ret.lateralTuning.indi.timeConstantBP = [0.] - ret.lateralTuning.indi.timeConstantV = [1.4] - ret.lateralTuning.indi.actuatorEffectivenessBP = [0.] - ret.lateralTuning.indi.actuatorEffectivenessV = [2.3] ret.minSteerSpeed = 60 * CV.KPH_TO_MS elif candidate in (CAR.KONA, CAR.KONA_EV, CAR.KONA_HEV, CAR.KONA_EV_2022): ret.mass = {CAR.KONA_EV: 1685., CAR.KONA_HEV: 1425., CAR.KONA_EV_2022: 1743.}.get(candidate, 1275.) + STD_CARGO_KG ret.wheelbase = 2.6 ret.steerRatio = 13.42 # Spec tire_stiffness_factor = 0.385 - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) elif candidate in (CAR.IONIQ, CAR.IONIQ_EV_LTD, CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.IONIQ_HEV_2022): - ret.lateralTuning.pid.kf = 0.00006 ret.mass = 1490. + STD_CARGO_KG # weight per hyundai site https://www.hyundaiusa.com/ioniq-electric/specifications.aspx ret.wheelbase = 2.7 ret.steerRatio = 13.73 # Spec tire_stiffness_factor = 0.385 - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] if candidate not in (CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.IONIQ_HEV_2022): ret.minSteerSpeed = 32 * CV.MPH_TO_MS elif candidate == CAR.IONIQ_PHEV_2019: ret.mass = 1550. + STD_CARGO_KG # weight per hyundai site https://www.hyundaiusa.com/us/en/vehicles/2019-ioniq-plug-in-hybrid/compare-specs ret.wheelbase = 2.7 ret.steerRatio = 13.73 - ret.lateralTuning.init('indi') - ret.lateralTuning.indi.innerLoopGainBP = [0.] - ret.lateralTuning.indi.innerLoopGainV = [2.5] - ret.lateralTuning.indi.outerLoopGainBP = [0.] - ret.lateralTuning.indi.outerLoopGainV = [3.5] - ret.lateralTuning.indi.timeConstantBP = [0.] - ret.lateralTuning.indi.timeConstantV = [1.4] - ret.lateralTuning.indi.actuatorEffectivenessBP = [0.] - ret.lateralTuning.indi.actuatorEffectivenessV = [1.8] ret.minSteerSpeed = 32 * CV.MPH_TO_MS elif candidate == CAR.VELOSTER: - ret.lateralTuning.pid.kf = 0.00005 ret.mass = 3558. * CV.LB_TO_KG ret.wheelbase = 2.80 ret.steerRatio = 13.75 * 1.15 tire_stiffness_factor = 0.5 - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] elif candidate == CAR.TUCSON: - ret.lateralTuning.pid.kf = 0.00005 ret.mass = 3520. * CV.LB_TO_KG ret.wheelbase = 2.67 ret.steerRatio = 14.00 * 1.15 tire_stiffness_factor = 0.385 - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] elif candidate == CAR.TUCSON_HYBRID_4TH_GEN: ret.mass = 1680. + STD_CARGO_KG # average of all 3 trims ret.wheelbase = 2.756 ret.steerRatio = 16. tire_stiffness_factor = 0.385 - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) # Kia elif candidate == CAR.KIA_SORENTO: - ret.lateralTuning.pid.kf = 0.00005 ret.mass = 1985. + STD_CARGO_KG ret.wheelbase = 2.78 ret.steerRatio = 14.4 * 1.1 # 10% higher at the center seems reasonable - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] elif candidate in (CAR.KIA_NIRO_EV, CAR.KIA_NIRO_PHEV, CAR.KIA_NIRO_HEV_2021): - ret.lateralTuning.pid.kf = 0.00006 ret.mass = 1737. + STD_CARGO_KG ret.wheelbase = 2.7 ret.steerRatio = 13.9 if CAR.KIA_NIRO_HEV_2021 else 13.73 # Spec tire_stiffness_factor = 0.385 - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] if candidate == CAR.KIA_NIRO_PHEV: ret.minSteerSpeed = 32 * CV.MPH_TO_MS elif candidate == CAR.KIA_SELTOS: @@ -187,15 +138,6 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.63 ret.steerRatio = 14.56 tire_stiffness_factor = 1 - ret.lateralTuning.init('indi') - ret.lateralTuning.indi.innerLoopGainBP = [0.] - ret.lateralTuning.indi.innerLoopGainV = [4.] - ret.lateralTuning.indi.outerLoopGainBP = [0.] - ret.lateralTuning.indi.outerLoopGainV = [3.] - ret.lateralTuning.indi.timeConstantBP = [0.] - ret.lateralTuning.indi.timeConstantV = [1.4] - ret.lateralTuning.indi.actuatorEffectivenessBP = [0.] - ret.lateralTuning.indi.actuatorEffectivenessV = [1.8] elif candidate in (CAR.KIA_OPTIMA_G4, CAR.KIA_OPTIMA_G4_FL, CAR.KIA_OPTIMA_H): ret.mass = 3558. * CV.LB_TO_KG ret.wheelbase = 2.80 @@ -203,92 +145,58 @@ class CarInterface(CarInterfaceBase): tire_stiffness_factor = 0.5 if candidate == CAR.KIA_OPTIMA_G4: ret.minSteerSpeed = 32 * CV.MPH_TO_MS - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) elif candidate == CAR.KIA_STINGER: - ret.lateralTuning.pid.kf = 0.00005 ret.mass = 1825. + STD_CARGO_KG ret.wheelbase = 2.78 ret.steerRatio = 14.4 * 1.15 # 15% higher at the center seems reasonable - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] elif candidate == CAR.KIA_FORTE: - ret.lateralTuning.pid.kf = 0.00005 ret.mass = 3558. * CV.LB_TO_KG ret.wheelbase = 2.80 ret.steerRatio = 13.75 tire_stiffness_factor = 0.5 - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] elif candidate == CAR.KIA_CEED: - ret.lateralTuning.pid.kf = 0.00005 ret.mass = 1450. + STD_CARGO_KG ret.wheelbase = 2.65 ret.steerRatio = 13.75 tire_stiffness_factor = 0.5 - ret.lateralTuning.pid.kf = 0.00005 - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] elif candidate == CAR.KIA_K5_2021: - ret.lateralTuning.pid.kf = 0.00005 ret.mass = 3228. * CV.LB_TO_KG ret.wheelbase = 2.85 ret.steerRatio = 13.27 # 2021 Kia K5 Steering Ratio (all trims) tire_stiffness_factor = 0.5 - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] elif candidate == CAR.KIA_EV6: ret.mass = 2055 + STD_CARGO_KG ret.wheelbase = 2.9 ret.steerRatio = 16. tire_stiffness_factor = 0.65 - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) elif candidate == CAR.IONIQ_5: ret.mass = 2012 + STD_CARGO_KG ret.wheelbase = 3.0 ret.steerRatio = 16. tire_stiffness_factor = 0.65 - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) elif candidate == CAR.KIA_SPORTAGE_HYBRID_5TH_GEN: ret.mass = 1767. + STD_CARGO_KG # SX Prestige trim support only ret.wheelbase = 2.756 ret.steerRatio = 13.6 - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) # Genesis elif candidate == CAR.GENESIS_G70: - ret.lateralTuning.init('indi') - ret.lateralTuning.indi.innerLoopGainBP = [0.] - ret.lateralTuning.indi.innerLoopGainV = [2.5] - ret.lateralTuning.indi.outerLoopGainBP = [0.] - ret.lateralTuning.indi.outerLoopGainV = [3.5] - ret.lateralTuning.indi.timeConstantBP = [0.] - ret.lateralTuning.indi.timeConstantV = [1.4] - ret.lateralTuning.indi.actuatorEffectivenessBP = [0.] - ret.lateralTuning.indi.actuatorEffectivenessV = [1.8] ret.steerActuatorDelay = 0.1 ret.mass = 1640.0 + STD_CARGO_KG ret.wheelbase = 2.84 ret.steerRatio = 13.56 elif candidate == CAR.GENESIS_G70_2020: - ret.lateralTuning.pid.kf = 0. - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.112], [0.004]] ret.mass = 3673.0 * CV.LB_TO_KG + STD_CARGO_KG ret.wheelbase = 2.83 ret.steerRatio = 12.9 elif candidate == CAR.GENESIS_G80: - ret.lateralTuning.pid.kf = 0.00005 ret.mass = 2060. + STD_CARGO_KG ret.wheelbase = 3.01 ret.steerRatio = 16.5 - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.16], [0.01]] elif candidate == CAR.GENESIS_G90: ret.mass = 2200 ret.wheelbase = 3.15 ret.steerRatio = 12.069 - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.16], [0.01]] # *** longitudinal control *** if candidate in CANFD_CAR: diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py index 28912645ac..0d5acbfff4 100644 --- a/selfdrive/car/toyota/interface.py +++ b/selfdrive/car/toyota/interface.py @@ -2,7 +2,6 @@ from cereal import car from common.conversions import Conversions as CV from panda import Panda -from selfdrive.car.toyota.tunes import LatTunes, LongTunes, set_long_tune, set_lat_tune from selfdrive.car.toyota.values import Ecu, CAR, ToyotaFlags, TSS2_CAR, RADAR_ACC_CAR, NO_DSU_CAR, MIN_ACC_SPEED, EPS_SCALE, EV_HYBRID_CAR, CarControllerParams from selfdrive.car import STD_CARGO_KG, scale_rot_inertia, scale_tire_stiffness, gen_empty_fingerprint, get_safety_config from selfdrive.car.interfaces import CarInterfaceBase @@ -74,7 +73,6 @@ class CarInterface(CarInterfaceBase): ret.wheelSpeedFactor = 1.035 tire_stiffness_factor = 0.5533 ret.mass = 4481. * CV.LB_TO_KG + STD_CARGO_KG # mean between min and max - set_lat_tune(ret.lateralTuning, LatTunes.PID_C) elif candidate in (CAR.CHR, CAR.CHRH): stop_and_go = True @@ -82,7 +80,6 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 13.6 tire_stiffness_factor = 0.7933 ret.mass = 3300. * CV.LB_TO_KG + STD_CARGO_KG - set_lat_tune(ret.lateralTuning, LatTunes.PID_F) elif candidate in (CAR.CAMRY, CAR.CAMRYH, CAR.CAMRY_TSS2, CAR.CAMRYH_TSS2): stop_and_go = True @@ -90,8 +87,6 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 13.7 tire_stiffness_factor = 0.7933 ret.mass = 3400. * CV.LB_TO_KG + STD_CARGO_KG # mean between normal and hybrid - if candidate not in (CAR.CAMRY_TSS2, CAR.CAMRYH_TSS2): - set_lat_tune(ret.lateralTuning, LatTunes.PID_C) elif candidate in (CAR.HIGHLANDER, CAR.HIGHLANDERH, CAR.HIGHLANDER_TSS2, CAR.HIGHLANDERH_TSS2): stop_and_go = True @@ -99,7 +94,6 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 16.0 tire_stiffness_factor = 0.8 ret.mass = 4516. * CV.LB_TO_KG + STD_CARGO_KG # mean between normal and hybrid - set_lat_tune(ret.lateralTuning, LatTunes.PID_G) elif candidate in (CAR.AVALON, CAR.AVALON_2019, CAR.AVALONH_2019, CAR.AVALON_TSS2, CAR.AVALONH_TSS2): # starting from 2019, all Avalon variants have stop and go @@ -109,7 +103,6 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 14.8 # Found at https://pressroom.toyota.com/releases/2016+avalon+product+specs.download tire_stiffness_factor = 0.7983 ret.mass = 3505. * CV.LB_TO_KG + STD_CARGO_KG # mean between normal and hybrid - set_lat_tune(ret.lateralTuning, LatTunes.PID_H) elif candidate in (CAR.RAV4_TSS2, CAR.RAV4_TSS2_2022, CAR.RAV4H_TSS2, CAR.RAV4H_TSS2_2022): stop_and_go = True @@ -117,14 +110,6 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 14.3 tire_stiffness_factor = 0.7933 ret.mass = 3585. * CV.LB_TO_KG + STD_CARGO_KG # Average between ICE and Hybrid - set_lat_tune(ret.lateralTuning, LatTunes.PID_D) - - # 2019+ RAV4 TSS2 uses two different steering racks and specific tuning seems to be necessary. - # See https://github.com/commaai/openpilot/pull/21429#issuecomment-873652891 - for fw in car_fw: - if fw.ecu == "eps" and (fw.fwVersion.startswith(b'\x02') or fw.fwVersion in [b'8965B42181\x00\x00\x00\x00\x00\x00']): - set_lat_tune(ret.lateralTuning, LatTunes.PID_I) - break elif candidate in (CAR.COROLLA_TSS2, CAR.COROLLAH_TSS2): stop_and_go = True @@ -139,7 +124,6 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 16.0 # not optimized tire_stiffness_factor = 0.444 # not optimized yet ret.mass = 3677. * CV.LB_TO_KG + STD_CARGO_KG # mean between min and max - set_lat_tune(ret.lateralTuning, LatTunes.PID_D) elif candidate == CAR.SIENNA: stop_and_go = True @@ -147,14 +131,12 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 15.5 tire_stiffness_factor = 0.444 ret.mass = 4590. * CV.LB_TO_KG + STD_CARGO_KG - set_lat_tune(ret.lateralTuning, LatTunes.PID_J) elif candidate in (CAR.LEXUS_IS, CAR.LEXUS_RC): ret.wheelbase = 2.79908 ret.steerRatio = 13.3 tire_stiffness_factor = 0.444 ret.mass = 3736.8 * CV.LB_TO_KG + STD_CARGO_KG - set_lat_tune(ret.lateralTuning, LatTunes.PID_L) elif candidate == CAR.LEXUS_CTH: stop_and_go = True @@ -162,7 +144,6 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 18.6 tire_stiffness_factor = 0.517 ret.mass = 3108 * CV.LB_TO_KG + STD_CARGO_KG # mean between min and max - set_lat_tune(ret.lateralTuning, LatTunes.PID_M) elif candidate in (CAR.LEXUS_NX, CAR.LEXUS_NXH, CAR.LEXUS_NX_TSS2, CAR.LEXUS_NXH_TSS2): stop_and_go = True @@ -170,7 +151,6 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 14.7 tire_stiffness_factor = 0.444 # not optimized yet ret.mass = 4070 * CV.LB_TO_KG + STD_CARGO_KG - set_lat_tune(ret.lateralTuning, LatTunes.PID_C) elif candidate == CAR.PRIUS_TSS2: stop_and_go = True @@ -178,7 +158,6 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 13.4 # True steerRatio from older prius tire_stiffness_factor = 0.6371 # hand-tune ret.mass = 3115. * CV.LB_TO_KG + STD_CARGO_KG - set_lat_tune(ret.lateralTuning, LatTunes.PID_N) elif candidate == CAR.MIRAI: stop_and_go = True @@ -186,7 +165,6 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 14.8 tire_stiffness_factor = 0.8 ret.mass = 4300. * CV.LB_TO_KG + STD_CARGO_KG - set_lat_tune(ret.lateralTuning, LatTunes.PID_C) elif candidate in (CAR.ALPHARD_TSS2, CAR.ALPHARDH_TSS2): stop_and_go = True @@ -194,7 +172,6 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 14.2 tire_stiffness_factor = 0.444 ret.mass = 4305. * CV.LB_TO_KG + STD_CARGO_KG - set_lat_tune(ret.lateralTuning, LatTunes.PID_J) ret.centerToFront = ret.wheelbase * 0.44 @@ -230,12 +207,23 @@ class CarInterface(CarInterfaceBase): # to a negative value, so it won't matter. ret.minEnableSpeed = -1. if (stop_and_go or ret.enableGasInterceptor) else MIN_ACC_SPEED + tune = ret.longitudinalTuning if candidate in TSS2_CAR or ret.enableGasInterceptor: - set_long_tune(ret.longitudinalTuning, LongTunes.TSS2) + tune.deadzoneBP = [0., 8.05] + tune.deadzoneV = [.0, .14] + tune.kpBP = [0., 5., 20.] + tune.kpV = [1.3, 1.0, 0.7] + tune.kiBP = [0., 5., 12., 20., 27.] + tune.kiV = [.35, .23, .20, .17, .1] if candidate in TSS2_CAR: ret.stoppingDecelRate = 0.3 # reach stopping target smoothly else: - set_long_tune(ret.longitudinalTuning, LongTunes.TSS) + tune.deadzoneBP = [0., 9.] + tune.deadzoneV = [.0, .15] + tune.kpBP = [0., 5., 35.] + tune.kiBP = [0., 35.] + tune.kpV = [3.6, 2.4, 1.5] + tune.kiV = [0.54, 0.36] return ret diff --git a/selfdrive/car/toyota/tunes.py b/selfdrive/car/toyota/tunes.py deleted file mode 100644 index b73ab4c8c9..0000000000 --- a/selfdrive/car/toyota/tunes.py +++ /dev/null @@ -1,102 +0,0 @@ -#!/usr/bin/env python3 -from enum import Enum - -class LongTunes(Enum): - TSS2 = 0 - TSS = 1 - -class LatTunes(Enum): - INDI_PRIUS = 0 - LQR_RAV4 = 1 - PID_A = 2 - PID_B = 3 - PID_C = 4 - PID_D = 5 - PID_E = 6 - PID_F = 7 - PID_G = 8 - PID_I = 9 - PID_H = 10 - PID_J = 11 - PID_K = 12 - PID_L = 13 - PID_M = 14 - PID_N = 15 - - -###### LONG ###### -def set_long_tune(tune, name): - # Improved longitudinal tune - if name == LongTunes.TSS2: - tune.deadzoneBP = [0., 8.05] - tune.deadzoneV = [.0, .14] - tune.kpBP = [0., 5., 20.] - tune.kpV = [1.3, 1.0, 0.7] - tune.kiBP = [0., 5., 12., 20., 27.] - tune.kiV = [.35, .23, .20, .17, .1] - # Default longitudinal tune - elif name == LongTunes.TSS: - tune.deadzoneBP = [0., 9.] - tune.deadzoneV = [.0, .15] - tune.kpBP = [0., 5., 35.] - tune.kiBP = [0., 35.] - tune.kpV = [3.6, 2.4, 1.5] - tune.kiV = [0.54, 0.36] - else: - raise NotImplementedError('This longitudinal tune does not exist') - - -###### LAT ###### -def set_lat_tune(tune, name, MAX_LAT_ACCEL=2.5, FRICTION=0.01, steering_angle_deadzone_deg=0.0, use_steering_angle=True): - if 'PID' in str(name): - tune.init('pid') - tune.pid.kiBP = [0.0] - tune.pid.kpBP = [0.0] - if name == LatTunes.PID_A: - tune.pid.kpV = [0.2] - tune.pid.kiV = [0.05] - tune.pid.kf = 0.00003 - elif name == LatTunes.PID_C: - tune.pid.kpV = [0.6] - tune.pid.kiV = [0.1] - tune.pid.kf = 0.00006 - elif name == LatTunes.PID_D: - tune.pid.kpV = [0.6] - tune.pid.kiV = [0.1] - tune.pid.kf = 0.00007818594 - elif name == LatTunes.PID_F: - tune.pid.kpV = [0.723] - tune.pid.kiV = [0.0428] - tune.pid.kf = 0.00006 - elif name == LatTunes.PID_G: - tune.pid.kpV = [0.18] - tune.pid.kiV = [0.015] - tune.pid.kf = 0.00012 - elif name == LatTunes.PID_H: - tune.pid.kpV = [0.17] - tune.pid.kiV = [0.03] - tune.pid.kf = 0.00006 - elif name == LatTunes.PID_I: - tune.pid.kpV = [0.15] - tune.pid.kiV = [0.05] - tune.pid.kf = 0.00004 - elif name == LatTunes.PID_J: - tune.pid.kpV = [0.19] - tune.pid.kiV = [0.02] - tune.pid.kf = 0.00007818594 - elif name == LatTunes.PID_L: - tune.pid.kpV = [0.3] - tune.pid.kiV = [0.05] - tune.pid.kf = 0.00006 - elif name == LatTunes.PID_M: - tune.pid.kpV = [0.3] - tune.pid.kiV = [0.05] - tune.pid.kf = 0.00007 - elif name == LatTunes.PID_N: - tune.pid.kpV = [0.35] - tune.pid.kiV = [0.15] - tune.pid.kf = 0.00007818594 - else: - raise NotImplementedError('This PID tune does not exist') - else: - raise NotImplementedError('This lateral tune does not exist') From dcde942d9fb05575dcc70f0b24f9c3c6b7c220ab Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Tue, 25 Oct 2022 16:53:24 -0700 Subject: [PATCH 15/59] Long control: add a_change cost in e2e mode (#26237) Add e2e cost --- selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py b/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py index 2aab4b71af..49eb5988e2 100644 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py @@ -253,7 +253,8 @@ class LongitudinalMpc: cost_weights = [X_EGO_OBSTACLE_COST, X_EGO_COST, V_EGO_COST, A_EGO_COST, a_change_cost, J_EGO_COST] constraint_cost_weights = [LIMIT_COST, LIMIT_COST, LIMIT_COST, DANGER_ZONE_COST] elif self.mode == 'blended': - cost_weights = [0., 0.1, 0.2, 5.0, 0.0, 1.0] + a_change_cost = 40.0 if prev_accel_constraint else 0 + cost_weights = [0., 0.1, 0.2, 5.0, a_change_cost, 1.0] constraint_cost_weights = [LIMIT_COST, LIMIT_COST, LIMIT_COST, 50.0] else: raise NotImplementedError(f'Planner mode {self.mode} not recognized in planner cost set') From 45b16570cfca88cef9f9cb82e6376527de786188 Mon Sep 17 00:00:00 2001 From: Igor Biletskyy Date: Tue, 25 Oct 2022 22:43:57 -0700 Subject: [PATCH 16/59] bump panda (#26244) --- panda | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/panda b/panda index 2db69bc941..bd8d2481dd 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 2db69bc94120a3c10f39cdedc9d83315f9ba801e +Subproject commit bd8d2481dd071df62263e093b2e332a2a404dc87 From 2b7290a14261ca0a745f4cd537de7cc9d11ccb12 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Wed, 26 Oct 2022 00:20:30 -0700 Subject: [PATCH 17/59] Model trained with more long noise (#26241) * d8501d20-bb59-4193-aa82-82b2737dedd6/449 d37d320d-7d78-479a-9be2-d58c75284307/700 * Update model ref --- selfdrive/modeld/models/supercombo.onnx | 4 ++-- selfdrive/test/process_replay/model_replay_ref_commit | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/selfdrive/modeld/models/supercombo.onnx b/selfdrive/modeld/models/supercombo.onnx index 21602ea70a..49a1c3a3b8 100644 --- a/selfdrive/modeld/models/supercombo.onnx +++ b/selfdrive/modeld/models/supercombo.onnx @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:9c119aa811a929b3a442dbe8e462a9d88e8bfb9f5809a4e737687fb7380d7e05 -size 45922882 +oid sha256:a41d42f92913e6cc3909e505b1220b16d31f7cfca5f8a4e82109577b4151b645 +size 45922983 diff --git a/selfdrive/test/process_replay/model_replay_ref_commit b/selfdrive/test/process_replay/model_replay_ref_commit index b5fd11fee8..5843a1e174 100644 --- a/selfdrive/test/process_replay/model_replay_ref_commit +++ b/selfdrive/test/process_replay/model_replay_ref_commit @@ -1 +1 @@ -46cb9c522e942d8b25deac90ffdee89efff60ce9 +d2f1711fd58d4f2c25b81bd332270da60ff9636d From b3e0a8c4e05f0c657d63d4825d50d43877b72768 Mon Sep 17 00:00:00 2001 From: Jason Wen <47793918+sunnyhaibin@users.noreply.github.com> Date: Wed, 26 Oct 2022 14:26:41 -0400 Subject: [PATCH 18/59] Hyundai: Add FW for 2022 Tucson Hybrid (#26239) * Hyundai: Add FW for 2022 Tucson Hybrid * Duplicated FW * Add cornerRadar FW (in a non-HDA too?) * Update selfdrive/car/hyundai/values.py Co-authored-by: Shane Smiskol --- selfdrive/car/hyundai/values.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 29d0cb3dce..98cb72293f 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -1379,6 +1379,7 @@ FW_VERSIONS = { CAR.TUCSON_HYBRID_4TH_GEN: { (Ecu.fwdCamera, 0x7c4, None): [ b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-N9240 14Q', + b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-N9220 14K', ], (Ecu.fwdRadar, 0x7d0, None): [ b'\xf1\x00NX4__ 1.00 1.00 99110-N9100 ', From 03ebc3bff57627843bde8b5ea758a54e8b96cb4e Mon Sep 17 00:00:00 2001 From: Vivek Aithal Date: Wed, 26 Oct 2022 11:45:21 -0700 Subject: [PATCH 19/59] [torqued] Update offline values (#26243) * update offline vals * update refs --- selfdrive/car/torque_data/params.yaml | 6 +++--- selfdrive/test/process_replay/ref_commit | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/selfdrive/car/torque_data/params.yaml b/selfdrive/car/torque_data/params.yaml index 160f605488..60b1662cee 100644 --- a/selfdrive/car/torque_data/params.yaml +++ b/selfdrive/car/torque_data/params.yaml @@ -35,7 +35,7 @@ HYUNDAI SANTA FE 2019: [3.0787027729757632, 2.6173437483495565, 0.12070193418239 HYUNDAI SANTA FE HYBRID 2022: [3.501877602644835, 2.729064118456137, 0.10384068104538963] HYUNDAI SANTA FE PlUG-IN HYBRID 2022: [1.6953050513611045, 1.5837614296206861, 0.12672855941458458] HYUNDAI SONATA 2019: [2.2200457811703953, 1.2967330275895228, 0.14039920986586393] -HYUNDAI SONATA 2020: [3.284505627881726, 2.1259108157250735, 0.08452048323586728] +HYUNDAI SONATA 2020: [2.9638737459977467, 2.1259108157250735, 0.07813665616927593] HYUNDAI SONATA HYBRID 2021: [2.8990264092395734, 2.061410192222139, 0.0899805488717382] JEEP GRAND CHEROKEE 2019: [1.7321233388827006, 1.289689569171081, 0.15046331002097185] JEEP GRAND CHEROKEE V6 2018: [1.8776598027756923, 1.4057367824262523, 0.11725947414922003] @@ -67,8 +67,8 @@ TOYOTA CAMRY 2021: [2.6922769557433055, 2.3476510120007434, 0.1450430192989234] TOYOTA CAMRY HYBRID 2018: [2.0974120828287774, 1.7996193116697359, 0.13823613467632756] TOYOTA CAMRY HYBRID 2021: [2.6426668350384457, 2.3901492458927986, 0.16103875108816076] TOYOTA COROLLA 2017: [3.117154369115421, 1.8438132575043773, 0.12289685869250652] -TOYOTA COROLLA HYBRID TSS2 2019: [2.3287672277252005, 1.8118712531729109, 0.2215868445753317] -TOYOTA COROLLA TSS2 2019: [2.4204464833010175, 1.9258612322678952, 0.20670411068012526] +TOYOTA COROLLA HYBRID TSS2 2019: [1.9079729107361805, 1.8118712531729109, 0.22251440891543514] +TOYOTA COROLLA TSS2 2019: [2.0742917676766712, 1.9258612322678952, 0.16888685704519352] TOYOTA HIGHLANDER 2017: [1.8696367437248915, 1.626293990451463, 0.17485372210240796] TOYOTA HIGHLANDER 2020: [2.022340166827233, 1.6183134804881791, 0.14592306380054457] TOYOTA HIGHLANDER HYBRID 2018: [1.9421825202382728, 1.6433903296845025, 0.16928956792275918] diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 44eed18493..ba0f30e5c3 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -68457035e9223fcbd70bd40966d5a1d9fe4f1567 \ No newline at end of file +8f2919ba4d8509432e93ff0a44f951254c1ff3fe \ No newline at end of file From d549e1899dbc7f28e0f27db51d875b30caa12ab0 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Thu, 27 Oct 2022 03:59:16 +0800 Subject: [PATCH 20/59] Cabana: use QLineEdit for double value (#26247) --- tools/cabana/signaledit.cc | 22 +++++++++++++--------- tools/cabana/signaledit.h | 5 ++--- 2 files changed, 15 insertions(+), 12 deletions(-) diff --git a/tools/cabana/signaledit.cc b/tools/cabana/signaledit.cc index 3926cda01f..1bb5e9e533 100644 --- a/tools/cabana/signaledit.cc +++ b/tools/cabana/signaledit.cc @@ -1,6 +1,7 @@ #include "tools/cabana/signaledit.h" #include +#include #include #include #include @@ -36,13 +37,16 @@ SignalForm::SignalForm(const Signal &sig, QWidget *parent) : QWidget(parent) { sign->setCurrentIndex(sig.is_signed ? 0 : 1); form_layout->addRow(tr("sign"), sign); - factor = new QDoubleSpinBox(); - factor->setDecimals(3); - factor->setValue(sig.factor); + auto double_validator = new QDoubleValidator(this); + + factor = new QLineEdit(); + factor->setValidator(double_validator); + factor->setText(QString::number(sig.factor)); form_layout->addRow(tr("Factor"), factor); - offset = new QSpinBox(); - offset->setValue(sig.offset); + offset = new QLineEdit(); + offset->setValidator(double_validator); + offset->setText(QString::number(sig.offset)); form_layout->addRow(tr("Offset"), offset); // TODO: parse the following parameters in opendbc @@ -50,11 +54,11 @@ SignalForm::SignalForm(const Signal &sig, QWidget *parent) : QWidget(parent) { form_layout->addRow(tr("Unit"), unit); comment = new QLineEdit(); form_layout->addRow(tr("Comment"), comment); - min_val = new QDoubleSpinBox(); - factor->setDecimals(3); + min_val = new QLineEdit(); + min_val->setValidator(double_validator); form_layout->addRow(tr("Minimum value"), min_val); - max_val = new QDoubleSpinBox(); - factor->setDecimals(3); + max_val = new QLineEdit(); + max_val->setValidator(double_validator); form_layout->addRow(tr("Maximum value"), max_val); val_desc = new QLineEdit(); form_layout->addRow(tr("Value descriptions"), val_desc); diff --git a/tools/cabana/signaledit.h b/tools/cabana/signaledit.h index 472453d4b1..71719852f1 100644 --- a/tools/cabana/signaledit.h +++ b/tools/cabana/signaledit.h @@ -16,9 +16,8 @@ class SignalForm : public QWidget { public: SignalForm(const Signal &sig, QWidget *parent); - QLineEdit *name, *unit, *comment, *val_desc; - QSpinBox *size, *offset; - QDoubleSpinBox *factor, *min_val, *max_val; + QLineEdit *name, *unit, *comment, *val_desc, *offset, *factor, *min_val, *max_val; + QSpinBox *size; QComboBox *sign, *endianness; }; From 728d96924924dd8d4e899ccaba0ed6bcc4a23417 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Thu, 27 Oct 2022 03:59:37 +0800 Subject: [PATCH 21/59] Cabana: limit X-axis range from settings (#26213) * limit X-axis range from settings * continue * update range if events merged * update line series by range * cleanup removeChart * cleanup updateAxisy --- tools/cabana/canmessages.cc | 83 ++++-------- tools/cabana/canmessages.h | 33 ++--- tools/cabana/chartswidget.cc | 256 +++++++++++++++++++---------------- tools/cabana/chartswidget.h | 28 +++- tools/cabana/historylog.cc | 5 +- tools/cabana/historylog.h | 1 + tools/cabana/mainwin.cc | 1 + tools/cabana/settings.cc | 15 +- tools/cabana/settings.h | 2 + tools/cabana/videowidget.cc | 5 +- tools/cabana/videowidget.h | 2 +- 11 files changed, 217 insertions(+), 214 deletions(-) diff --git a/tools/cabana/canmessages.cc b/tools/cabana/canmessages.cc index 1b46bd9da7..3ffc29916f 100644 --- a/tools/cabana/canmessages.cc +++ b/tools/cabana/canmessages.cc @@ -28,7 +28,7 @@ bool CANMessages::loadRoute(const QString &route, const QString &data_dir, bool replay = new Replay(route, {"can", "roadEncodeIdx", "carParams"}, {}, nullptr, use_qcam ? REPLAY_FLAG_QCAMERA : 0, data_dir, this); replay->setSegmentCacheLimit(settings.cached_segment_limit); replay->installEventFilter(event_filter, this); - QObject::connect(replay, &Replay::segmentsMerged, this, &CANMessages::segmentsMerged); + QObject::connect(replay, &Replay::segmentsMerged, this, &CANMessages::eventsMerged); if (replay->load()) { replay->start(); return true; @@ -63,41 +63,26 @@ QList CANMessages::findSignalValues(const QString &id, const Signal *si return ret; } -void CANMessages::process(QHash> *messages) { +void CANMessages::process(QHash *messages) { for (auto it = messages->begin(); it != messages->end(); ++it) { - auto &msgs = can_msgs[it.key()]; - const auto &new_msgs = it.value(); - if (new_msgs.size() == settings.can_msg_log_size || msgs.empty()) { - msgs = std::move(new_msgs); - } else { - msgs.insert(msgs.begin(), std::make_move_iterator(new_msgs.begin()), std::make_move_iterator(new_msgs.end())); - if (msgs.size() > settings.can_msg_log_size) { - msgs.resize(settings.can_msg_log_size); - } - } + can_msgs[it.key()] = it.value(); } delete messages; - - if (current_sec < begin_sec || current_sec > end_sec) { - // loop replay in selected range. - seekTo(begin_sec); - } else { - emit updated(); - } + emit updated(); } bool CANMessages::eventFilter(const Event *event) { + static std::unique_ptr> new_msgs; static double prev_update_ts = 0; - // drop packets when the GUI thread is calling seekTo. to make sure the current_sec is accurate. - if (!seeking && event->which == cereal::Event::Which::CAN) { - if (!received_msgs) { - received_msgs.reset(new QHash>); - received_msgs->reserve(1000); + + if (event->which == cereal::Event::Which::CAN) { + if (!new_msgs) { + new_msgs.reset(new QHash); + new_msgs->reserve(1000); } - current_sec = (event->mono_time - replay->routeStartTime()) / (double)1e9; - if (counters_begin_sec > current_sec) { - // clear counters + double current_sec = replay->currentSeconds(); + if (counters_begin_sec == 0) { counters.clear(); counters_begin_sec = current_sec; } @@ -105,8 +90,10 @@ bool CANMessages::eventFilter(const Event *event) { auto can_events = event->event.getCan(); for (const auto &c : can_events) { QString id = QString("%1:%2").arg(c.getSrc()).arg(c.getAddress(), 1, 16); - auto &list = (*received_msgs)[id]; - while (list.size() >= settings.can_msg_log_size) { + + std::lock_guard lk(lock); + auto &list = received_msgs[id]; + while (list.size() > settings.can_msg_log_size) { list.pop_back(); } CanData &data = list.emplace_front(); @@ -119,49 +106,27 @@ bool CANMessages::eventFilter(const Event *event) { if (double delta = (current_sec - counters_begin_sec); delta > 0) { data.freq = count / delta; } + (*new_msgs)[id] = data; } double ts = millis_since_boot(); if ((ts - prev_update_ts) > (1000.0 / settings.fps)) { prev_update_ts = ts; // use pointer to avoid data copy in queued connection. - emit received(received_msgs.release()); + emit received(new_msgs.release()); } } return true; } -void CANMessages::seekTo(double ts) { - seeking = true; - replay->seekTo(ts, false); - seeking = false; +const std::deque CANMessages::messages(const QString &id) { + std::lock_guard lk(lock); + return received_msgs[id]; } -void CANMessages::setRange(double min, double max) { - if (begin_sec != min || end_sec != max) { - begin_sec = min; - end_sec = max; - is_zoomed = begin_sec != event_begin_sec || end_sec != event_end_sec; - emit rangeChanged(min, max); - } -} - -void CANMessages::segmentsMerged() { - auto events = replay->events(); - if (!events || events->empty()) return; - - auto it = std::find_if(events->begin(), events->end(), [=](const Event *e) { return e->which == cereal::Event::Which::CAN; }); - event_begin_sec = it == events->end() ? 0 : ((*it)->mono_time - replay->routeStartTime()) / (double)1e9; - event_end_sec = double(events->back()->mono_time - replay->routeStartTime()) / 1e9; - if (!is_zoomed) { - begin_sec = event_begin_sec; - end_sec = event_end_sec; - } - emit eventsMerged(); -} - -void CANMessages::resetRange() { - setRange(event_begin_sec, event_end_sec); +void CANMessages::seekTo(double ts) { + replay->seekTo(ts, false); + counters_begin_sec = 0; } void CANMessages::settingChanged() { diff --git a/tools/cabana/canmessages.h b/tools/cabana/canmessages.h index d1bb1b73b6..5fbccdbe12 100644 --- a/tools/cabana/canmessages.h +++ b/tools/cabana/canmessages.h @@ -2,7 +2,7 @@ #include #include -#include +#include #include #include @@ -29,20 +29,16 @@ public: ~CANMessages(); bool loadRoute(const QString &route, const QString &data_dir, bool use_qcam); void seekTo(double ts); - void resetRange(); - void setRange(double min, double max); QList findSignalValues(const QString&id, const Signal* signal, double value, FindFlags flag, int max_count); bool eventFilter(const Event *event); - inline std::pair range() const { return {begin_sec, end_sec}; } inline QString route() const { return routeName; } inline QString carFingerprint() const { return replay->carFingerprint().c_str(); } inline double totalSeconds() const { return replay->totalSeconds(); } inline double routeStartTime() const { return replay->routeStartTime() / (double)1e9; } - inline double currentSec() const { return current_sec; } - inline bool isZoomed() const { return is_zoomed; } - inline const std::deque &messages(const QString &id) { return can_msgs[id]; } - inline const CanData &lastMessage(const QString &id) { return can_msgs[id].front(); } + inline double currentSec() const { return replay->currentSeconds(); } + const std::deque messages(const QString &id); + inline const CanData &lastMessage(const QString &id) { return can_msgs[id]; } inline const std::vector *events() const { return replay->events(); } inline void setSpeed(float speed) { replay->setSpeed(speed); } @@ -52,32 +48,23 @@ public: signals: void eventsMerged(); - void rangeChanged(double min, double max); void updated(); - void received(QHash> *); + void received(QHash *); public: - QMap> can_msgs; - std::unique_ptr>> received_msgs = nullptr; + QMap can_msgs; protected: - void process(QHash> *); - void segmentsMerged(); + void process(QHash *); void settingChanged(); - std::atomic current_sec = 0.; - std::atomic seeking = false; - - double begin_sec = 0; - double end_sec = 0; - double event_begin_sec = 0; - double event_end_sec = 0; - bool is_zoomed = false; QString routeName; Replay *replay = nullptr; - double counters_begin_sec = std::numeric_limits::max(); + std::mutex lock; + std::atomic counters_begin_sec = 0; QHash counters; + QHash> received_msgs; }; inline QString toHex(const QByteArray &dat) { diff --git a/tools/cabana/chartswidget.cc b/tools/cabana/chartswidget.cc index f0bef36f4a..ea44a4033c 100644 --- a/tools/cabana/chartswidget.cc +++ b/tools/cabana/chartswidget.cc @@ -1,6 +1,7 @@ #include "tools/cabana/chartswidget.h" #include +#include #include #include #include @@ -57,47 +58,85 @@ ChartsWidget::ChartsWidget(QWidget *parent) : QWidget(parent) { QObject::connect(dbc(), &DBCManager::DBCFileChanged, [this]() { removeAll(nullptr); }); QObject::connect(dbc(), &DBCManager::signalRemoved, this, &ChartsWidget::removeAll); - QObject::connect(dbc(), &DBCManager::signalUpdated, [this](const Signal *sig) { - for (auto chart : charts) { - if (chart->signal == sig) { - chart->chart_view->updateSeries(); - } - } - }); - QObject::connect(dbc(), &DBCManager::msgUpdated, [this](const QString &id) { - for (auto chart : charts) { - if (chart->id == id) - chart->updateTitle(); + QObject::connect(dbc(), &DBCManager::signalUpdated, this, &ChartsWidget::signalUpdated); + QObject::connect(dbc(), &DBCManager::msgUpdated, [this](const QString &msg_id) { + for (auto c : charts) { + if (c->id == msg_id) c->updateTitle(); } }); - - QObject::connect(can, &CANMessages::rangeChanged, [this]() { updateTitleBar(); }); - QObject::connect(reset_zoom_btn, &QPushButton::clicked, can, &CANMessages::resetRange); + QObject::connect(can, &CANMessages::eventsMerged, this, &ChartsWidget::eventsMerged); + QObject::connect(can, &CANMessages::updated, this, &ChartsWidget::updateState); QObject::connect(remove_all_btn, &QPushButton::clicked, [this]() { removeAll(); }); + QObject::connect(reset_zoom_btn, &QPushButton::clicked, this, &ChartsWidget::zoomReset); QObject::connect(dock_btn, &QPushButton::clicked, [this]() { emit dock(!docking); docking = !docking; updateTitleBar(); }); - QObject::connect(&settings, &Settings::changed, [this]() { - for (auto chart : charts) { - chart->setHeight(settings.chart_height); +} + +void ChartsWidget::eventsMerged() { + if (auto events = can->events(); events && !events->empty()) { + auto it = std::find_if(events->begin(), events->end(), [=](const Event *e) { return e->which == cereal::Event::Which::CAN; }); + event_range.first = it == events->end() ? 0 : (*it)->mono_time / (double)1e9 - can->routeStartTime(); + event_range.second = it == events->end() ? 0 : events->back()->mono_time / (double)1e9 - can->routeStartTime(); + if (display_range.first == 0 && event_range.second == 0) { + display_range.first = event_range.first; + display_range.second = std::min(event_range.first + settings.max_chart_x_range, event_range.second); } - }); + } +} + +void ChartsWidget::zoomIn(double min, double max) { + zoomed_range = {min, max}; + is_zoomed = zoomed_range != display_range; + updateTitleBar(); + emit rangeChanged(min, max, is_zoomed); + updateState(); +} + +void ChartsWidget::zoomReset() { + zoomIn(display_range.first, display_range.second); +} + +void ChartsWidget::updateState() { + if (charts.isEmpty()) return; + + const double current_sec = can->currentSec(); + if (is_zoomed) { + if (current_sec < zoomed_range.first || current_sec >= zoomed_range.second) { + can->seekTo(zoomed_range.first); + } + } else { + auto prev_range = display_range; + if (current_sec < display_range.first || current_sec >= (display_range.second - 5)) { + // line marker reached the end, or seeked to a timestamp out of range. + display_range.first = current_sec - 5; + } + display_range.first = std::max(display_range.first, event_range.first); + display_range.second = std::min(display_range.first + settings.max_chart_x_range, event_range.second); + if (prev_range != display_range) { + for (auto c : charts) + c->chart_view->updateSeries(display_range); + } + } + + const auto &range = is_zoomed ? zoomed_range : display_range; + for (auto c : charts) { + c->chart_view->setRange(range.first, range.second); + c->chart_view->updateLineMarker(current_sec); + } } void ChartsWidget::updateTitleBar() { title_bar->setVisible(!charts.isEmpty()); if (charts.isEmpty()) return; - // show select range - range_label->setVisible(can->isZoomed()); - reset_zoom_btn->setEnabled(can->isZoomed()); - if (can->isZoomed()) { - auto [min, max] = can->range(); - range_label->setText(tr("%1 - %2").arg(min, 0, 'f', 2).arg(max, 0, 'f', 2)); + range_label->setVisible(is_zoomed); + reset_zoom_btn->setEnabled(is_zoomed); + if (is_zoomed) { + range_label->setText(tr("%1 - %2").arg(zoomed_range.first, 0, 'f', 2).arg(zoomed_range.second, 0, 'f', 2)); } - title_label->setText(tr("Charts (%1)").arg(charts.size())); dock_btn->setText(docking ? "⬈" : "⬋"); dock_btn->setToolTip(docking ? tr("Undock charts") : tr("Dock charts")); @@ -107,23 +146,19 @@ void ChartsWidget::addChart(const QString &id, const Signal *sig) { auto it = std::find_if(charts.begin(), charts.end(), [=](auto c) { return c->id == id && c->signal == sig; }); if (it == charts.end()) { auto chart = new ChartWidget(id, sig, this); - QObject::connect(chart, &ChartWidget::remove, this, &ChartsWidget::removeChart); + chart->chart_view->updateSeries(display_range); + QObject::connect(chart, &ChartWidget::remove, [=]() { removeChart(chart); });; + QObject::connect(chart->chart_view, &ChartView::zoomIn, this, &ChartsWidget::zoomIn); + QObject::connect(chart->chart_view, &ChartView::zoomReset, this, &ChartsWidget::zoomReset); charts_layout->insertWidget(0, chart); charts.push_back(chart); } updateTitleBar(); } -void ChartsWidget::removeChart(const QString &msg_id, const Signal *sig) { - QMutableListIterator it(charts); - while (it.hasNext()) { - auto c = it.next(); - if (c->id == msg_id && c->signal == sig) { - c->deleteLater(); - it.remove(); - break; - } - } +void ChartsWidget::removeChart(ChartWidget *chart) { + charts.removeOne(chart); + chart->deleteLater(); updateTitleBar(); } @@ -139,6 +174,17 @@ void ChartsWidget::removeAll(const Signal *sig) { updateTitleBar(); } +void ChartsWidget::signalUpdated(const Signal *sig) { + for (auto c : charts) { + if (c->signal == sig) { + c->updateTitle(); + c->chart_view->updateSeries(display_range); + c->chart_view->setRange(display_range.first, display_range.second, true); + } + } +} + + bool ChartsWidget::eventFilter(QObject *obj, QEvent *event) { if (obj != this && event->type() == QEvent::Close) { emit dock_btn->clicked(); @@ -156,17 +202,19 @@ ChartWidget::ChartWidget(const QString &id, const Signal *sig, QWidget *parent) QWidget *header = new QWidget(this); header->setStyleSheet("background-color:white"); - QHBoxLayout *header_layout = new QHBoxLayout(header); + QGridLayout *header_layout = new QGridLayout(header); header_layout->setContentsMargins(11, 11, 11, 0); - title = new QLabel(tr("%1 %2").arg(dbc()->msg(id)->name.c_str()).arg(id)); - header_layout->addWidget(title); - header_layout->addStretch(); + msg_name_label = new QLabel(this); + msg_name_label->setTextFormat(Qt::RichText); + header_layout->addWidget(msg_name_label, 0, 0, Qt::AlignLeft); + sig_name_label = new QLabel(this); + sig_name_label->setStyleSheet("font-weight:bold"); + header_layout->addWidget(sig_name_label, 0, 1, Qt::AlignCenter); //, 0, Qt::AlignCenter); QPushButton *remove_btn = new QPushButton("✖", this); - remove_btn->setFixedSize(30, 30); + remove_btn->setFixedSize(20, 20); remove_btn->setToolTip(tr("Remove chart")); - QObject::connect(remove_btn, &QPushButton::clicked, [=]() { emit remove(id, sig); }); - header_layout->addWidget(remove_btn); + header_layout->addWidget(remove_btn, 0, 2, Qt::AlignRight); main_layout->addWidget(header); chart_view = new ChartView(id, sig, this); @@ -175,10 +223,15 @@ ChartWidget::ChartWidget(const QString &id, const Signal *sig, QWidget *parent) main_layout->addStretch(); setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Fixed); + updateTitle(); + + QObject::connect(remove_btn, &QPushButton::clicked, [=]() { emit remove(id, sig); }); + QObject::connect(&settings, &Settings::changed, [this]() { chart_view->setFixedHeight(settings.chart_height); }); } void ChartWidget::updateTitle() { - title->setText(tr("%1 %2").arg(dbc()->msg(id)->name.c_str()).arg(id)); + msg_name_label->setText(tr("%1 %2").arg(dbc()->msg(id)->name.c_str()).arg(id)); + sig_name_label->setText(signal->name.c_str()); } // ChartView @@ -186,15 +239,10 @@ void ChartWidget::updateTitle() { ChartView::ChartView(const QString &id, const Signal *sig, QWidget *parent) : id(id), signal(sig), QChartView(nullptr, parent) { QLineSeries *series = new QLineSeries(); - series->setUseOpenGL(true); QChart *chart = new QChart(); - chart->setTitle(sig->name.c_str()); chart->addSeries(series); chart->createDefaultAxes(); chart->legend()->hide(); - QFont font; - font.setBold(true); - chart->setTitleFont(font); chart->setMargins({0, 0, 0, 0}); chart->layout()->setContentsMargins(0, 0, 0, 0); @@ -220,16 +268,18 @@ ChartView::ChartView(const QString &id, const Signal *sig, QWidget *parent) timer->setSingleShot(true); timer->callOnTimeout(this, &ChartView::adjustChartMargins); - QObject::connect(can, &CANMessages::updated, this, &ChartView::updateState); - QObject::connect(can, &CANMessages::rangeChanged, this, &ChartView::rangeChanged); - QObject::connect(can, &CANMessages::eventsMerged, this, &ChartView::updateSeries); - QObject::connect(dynamic_cast(chart->axisX()), &QValueAxis::rangeChanged, can, &CANMessages::setRange); QObject::connect(chart, &QChart::plotAreaChanged, [=](const QRectF &plotArea) { // use a singleshot timer to avoid recursion call. timer->start(); }); +} - updateSeries(); +void ChartView::setRange(double min, double max, bool force_update) { + auto axis_x = dynamic_cast(chart()->axisX()); + if (force_update || (min != axis_x->min() || max != axis_x->max())) { + axis_x->setRange(min, max); + updateAxisY(); + } } void ChartView::adjustChartMargins() { @@ -241,18 +291,17 @@ void ChartView::adjustChartMargins() { } } -void ChartWidget::setHeight(int height) { - chart_view->setFixedHeight(height); -} - -void ChartView::updateState() { +void ChartView::updateLineMarker(double current_sec) { auto axis_x = dynamic_cast(chart()->axisX()); - int x = chart()->plotArea().left() + chart()->plotArea().width() * (can->currentSec() - axis_x->min()) / (axis_x->max() - axis_x->min()); - line_marker->setLine(x, 0, x, height()); + int x = chart()->plotArea().left() + + chart()->plotArea().width() * (current_sec - axis_x->min()) / (axis_x->max() - axis_x->min()); + if (int(line_marker->line().x1()) != x) { + line_marker->setLine(x, 0, x, height()); + chart()->update(); + } } -void ChartView::updateSeries() { - chart()->setTitle(signal->name.c_str()); +void ChartView::updateSeries(const std::pair &range) { auto events = can->events(); if (!events) return; @@ -261,15 +310,18 @@ void ChartView::updateSeries() { uint32_t address = l[1].toUInt(nullptr, 16); vals.clear(); - vals.reserve(3 * 60 * 100); - uint64_t route_start_time = can->routeStartTime(); - for (auto &evt : *events) { - if (evt->which == cereal::Event::Which::CAN) { - for (auto c : evt->event.getCan()) { + vals.reserve((range.second - range.first) * 100); // [n]minutes * 100hz + double route_start_time = can->routeStartTime(); + Event begin_event(cereal::Event::Which::INIT_DATA, (route_start_time + range.first) * 1e9); + auto begin = std::lower_bound(events->begin(), events->end(), &begin_event, Event::lessThan()); + double end_ns = (route_start_time + range.second) * 1e9; + for (auto it = begin; it != events->end() && (*it)->mono_time <= end_ns; ++it) { + if ((*it)->which == cereal::Event::Which::CAN) { + for (auto c : (*it)->event.getCan()) { if (bus == c.getSrc() && address == c.getAddress()) { auto dat = c.getDat(); double value = get_raw_value((uint8_t *)dat.begin(), dat.size(), *signal); - double ts = (evt->mono_time / (double)1e9) - route_start_time; // seconds + double ts = ((*it)->mono_time / (double)1e9) - route_start_time; // seconds vals.push_back({ts, value}); } } @@ -277,40 +329,20 @@ void ChartView::updateSeries() { } QLineSeries *series = (QLineSeries *)chart()->series()[0]; series->replace(vals); - series->setPointLabelsColor(Qt::black); - auto [begin, end] = can->range(); - chart()->axisX()->setRange(begin, end); - updateAxisY(); -} - -void ChartView::rangeChanged(qreal min, qreal max) { - auto axis_x = dynamic_cast(chart()->axisX()); - if (axis_x->min() != min || axis_x->max() != max) { - axis_x->setRange(min, max); - } - updateAxisY(); } // auto zoom on yaxis void ChartView::updateAxisY() { const auto axis_x = dynamic_cast(chart()->axisX()); const auto axis_y = dynamic_cast(chart()->axisY()); - // vals is a sorted list auto begin = std::lower_bound(vals.begin(), vals.end(), axis_x->min(), [](auto &p, double x) { return p.x() < x; }); if (begin == vals.end()) return; auto end = std::upper_bound(vals.begin(), vals.end(), axis_x->max(), [](double x, auto &p) { return x < p.x(); }); const auto [min, max] = std::minmax_element(begin, end, [](auto &p1, auto &p2) { return p1.y() < p2.y(); }); - if (min->y() == max->y()) { - if (max->y() < 0) { - axis_y->setRange(max->y(), 0); - } else { - axis_y->setRange(0, max->y() == 0 ? 1 : max->y()); - } - } else { - axis_y->setRange(min->y(), max->y()); - } + (min->y() == max->y()) ? axis_y->setRange(min->y() - 1, max->y() + 1) + : axis_y->setRange(min->y(), max->y()); } void ChartView::enterEvent(QEvent *event) { @@ -328,39 +360,35 @@ void ChartView::leaveEvent(QEvent *event) { void ChartView::mouseReleaseEvent(QMouseEvent *event) { auto rubber = findChild(); if (event->button() == Qt::LeftButton && rubber && rubber->isVisible()) { - auto [begin, end] = can->range(); + rubber->hide(); + QRectF rect = rubber->geometry().normalized(); + rect.translate(-chart()->plotArea().topLeft()); + const auto axis_x = dynamic_cast(chart()->axisX()); + double min = axis_x->min() + (rect.left() / chart()->plotArea().width()) * (axis_x->max() - axis_x->min()); + double max = axis_x->min() + (rect.right() / chart()->plotArea().width()) * (axis_x->max() - axis_x->min()); if (rubber->width() <= 0) { - double seek_to = begin + ((event->pos().x() - chart()->plotArea().x()) / chart()->plotArea().width()) * (end - begin); - can->seekTo(seek_to); - } else if (((double)rubber->width() / chart()->plotArea().width()) * (end - begin) < 0.5) { - // don't zoom if selected range is less than 0.5s - rubber->hide(); - event->accept(); - return; + // no rubber dragged, seek to mouse position + can->seekTo(min); + } else if ((max - min) >= 0.5) { + // zoom in if selected range is greater than 0.5s + emit zoomIn(min, max); } } else if (event->button() == Qt::RightButton) { - // reset zoom - if (can->isZoomed()) { - can->resetRange(); - event->accept(); - return; - } + emit zoomReset(); } - QChartView::mouseReleaseEvent(event); - line_marker->setVisible(true); + event->accept(); } void ChartView::mouseMoveEvent(QMouseEvent *ev) { auto rubber = findChild(); - bool show = !(rubber && rubber->isVisible()); - - if (show) { + bool dragging = rubber && rubber->isVisible(); + if (!dragging) { const auto plot_area = chart()->plotArea(); float x = std::clamp((float)ev->pos().x(), (float)plot_area.left(), (float)plot_area.right()); track_line->setLine(x, plot_area.top(), x, plot_area.bottom()); - auto [begin, end] = can->range(); - double sec = begin + ((x - plot_area.x()) / plot_area.width()) * (end - begin); + auto axis_x = dynamic_cast(chart()->axisX()); + double sec = axis_x->min() + ((x - plot_area.x()) / plot_area.width()) * (axis_x->max() - axis_x->min()); auto value = std::lower_bound(vals.begin(), vals.end(), sec, [](auto &p, double x) { return p.x() < x; }); value_text->setPos(x + 6, plot_area.bottom() - 25); if (value != vals.end()) { @@ -369,9 +397,5 @@ void ChartView::mouseMoveEvent(QMouseEvent *ev) { value_text->setText("(--, --)"); } } - - value_text->setVisible(show); - track_line->setVisible(show); - line_marker->setVisible(show); QChartView::mouseMoveEvent(ev); } diff --git a/tools/cabana/chartswidget.h b/tools/cabana/chartswidget.h index 5adbdfcd04..a7c6f4bbd3 100644 --- a/tools/cabana/chartswidget.h +++ b/tools/cabana/chartswidget.h @@ -20,7 +20,13 @@ class ChartView : public QChartView { public: ChartView(const QString &id, const Signal *sig, QWidget *parent = nullptr); - void updateSeries(); + void updateSeries(const std::pair &range); + void setRange(double min, double max, bool force_update = false); + void updateLineMarker(double current_sec); + +signals: + void zoomIn(double min, double max); + void zoomReset(); private: void mouseReleaseEvent(QMouseEvent *event) override; @@ -29,9 +35,7 @@ private: void leaveEvent(QEvent *event) override; void adjustChartMargins(); - void rangeChanged(qreal min, qreal max); void updateAxisY(); - void updateState(); QGraphicsLineItem *track_line; QGraphicsSimpleTextItem *value_text; @@ -47,7 +51,6 @@ Q_OBJECT public: ChartWidget(const QString &id, const Signal *sig, QWidget *parent); void updateTitle(); - void setHeight(int height); signals: void remove(const QString &msg_id, const Signal *sig); @@ -55,7 +58,8 @@ signals: public: QString id; const Signal *signal; - QLabel *title; + QLabel *msg_name_label; + QLabel *sig_name_label; ChartView *chart_view = nullptr; }; @@ -65,16 +69,21 @@ class ChartsWidget : public QWidget { public: ChartsWidget(QWidget *parent = nullptr); void addChart(const QString &id, const Signal *sig); - void removeChart(const QString &id, const Signal *sig); + void removeChart(ChartWidget *chart); signals: void dock(bool floating); + void rangeChanged(double min, double max, bool is_zommed); private: + void eventsMerged(); void updateState(); + void zoomIn(double min, double max); + void zoomReset(); + void signalUpdated(const Signal *sig); void updateTitleBar(); void removeAll(const Signal *sig = nullptr); - bool eventFilter(QObject *obj, QEvent *event); + bool eventFilter(QObject *obj, QEvent *event) override; QWidget *title_bar; QLabel *title_label; @@ -85,4 +94,9 @@ private: QPushButton *remove_all_btn; QVBoxLayout *charts_layout; QList charts; + + bool is_zoomed = false; + std::pair event_range; + std::pair display_range; + std::pair zoomed_range; }; diff --git a/tools/cabana/historylog.cc b/tools/cabana/historylog.cc index a20845f15f..8136d0577c 100644 --- a/tools/cabana/historylog.cc +++ b/tools/cabana/historylog.cc @@ -7,7 +7,7 @@ QVariant HistoryLogModel::data(const QModelIndex &index, int role) const { bool has_signal = dbc_msg && !dbc_msg->sigs.empty(); if (role == Qt::DisplayRole) { - const auto &m = can->messages(msg_id)[index.row()]; + const auto &m = messages[index.row()]; if (index.column() == 0) { return QString::number(m.ts, 'f', 2); } @@ -49,7 +49,8 @@ void HistoryLogModel::updateState() { if (msg_id.isEmpty()) return; int prev_row_count = row_count; - row_count = can->messages(msg_id).size(); + messages = can->messages(msg_id); + row_count = messages.size(); int delta = row_count - prev_row_count; if (delta > 0) { beginInsertRows({}, prev_row_count, row_count - 1); diff --git a/tools/cabana/historylog.h b/tools/cabana/historylog.h index bc6d1f9376..d39bcf9f1d 100644 --- a/tools/cabana/historylog.h +++ b/tools/cabana/historylog.h @@ -22,6 +22,7 @@ private: int row_count = 0; int column_count = 2; const Msg *dbc_msg = nullptr; + std::deque messages; }; class HistoryLog : public QWidget { diff --git a/tools/cabana/mainwin.cc b/tools/cabana/mainwin.cc index 65e7bb1af8..30c7e5e0a2 100644 --- a/tools/cabana/mainwin.cc +++ b/tools/cabana/mainwin.cc @@ -83,6 +83,7 @@ MainWindow::MainWindow() : QWidget() { QObject::connect(messages_widget, &MessagesWidget::msgSelectionChanged, detail_widget, &DetailWidget::setMessage); QObject::connect(detail_widget, &DetailWidget::showChart, charts_widget, &ChartsWidget::addChart); QObject::connect(charts_widget, &ChartsWidget::dock, this, &MainWindow::dockCharts); + QObject::connect(charts_widget, &ChartsWidget::rangeChanged, video_widget, &VideoWidget::rangeChanged); QObject::connect(settings_btn, &QPushButton::clicked, this, &MainWindow::setOption); QObject::connect(can, &CANMessages::eventsMerged, [=]() { fingerprint_label->setText(can->carFingerprint() ); }); diff --git a/tools/cabana/settings.cc b/tools/cabana/settings.cc index 0b36f25fbc..6e9d7f17cc 100644 --- a/tools/cabana/settings.cc +++ b/tools/cabana/settings.cc @@ -17,6 +17,7 @@ void Settings::save() { s.setValue("log_size", can_msg_log_size); s.setValue("cached_segment", cached_segment_limit); s.setValue("chart_height", chart_height); + s.setValue("max_chart_x_range", max_chart_x_range); emit changed(); } @@ -26,6 +27,7 @@ void Settings::load() { can_msg_log_size = s.value("log_size", 100).toInt(); cached_segment_limit = s.value("cached_segment", 3).toInt(); chart_height = s.value("chart_height", 200).toInt(); + max_chart_x_range = s.value("max_chart_x_range", 3 * 60).toInt(); } // SettingsDlg @@ -45,19 +47,25 @@ SettingsDlg::SettingsDlg(QWidget *parent) : QDialog(parent) { log_size->setRange(50, 500); log_size->setSingleStep(10); log_size->setValue(settings.can_msg_log_size); - form_layout->addRow(tr("Log size"), log_size); + form_layout->addRow(tr("Signal history log size"), log_size); cached_segment = new QSpinBox(this); cached_segment->setRange(3, 60); cached_segment->setSingleStep(1); cached_segment->setValue(settings.cached_segment_limit); - form_layout->addRow(tr("Cached segments limit"), cached_segment); + form_layout->addRow(tr("Cached segments limit(minute)"), cached_segment); + + max_chart_x_range = new QSpinBox(this); + max_chart_x_range->setRange(1, 60); + max_chart_x_range->setSingleStep(1); + max_chart_x_range->setValue(settings.max_chart_x_range / 60); + form_layout->addRow(tr("Chart's max X-axis range(minute)"), max_chart_x_range); chart_height = new QSpinBox(this); chart_height->setRange(100, 500); chart_height->setSingleStep(10); chart_height->setValue(settings.chart_height); - form_layout->addRow(tr("Chart height"), chart_height); + form_layout->addRow(tr("Chart's height"), chart_height); main_layout->addLayout(form_layout); @@ -74,6 +82,7 @@ void SettingsDlg::save() { settings.can_msg_log_size = log_size->value(); settings.cached_segment_limit = cached_segment->value(); settings.chart_height = chart_height->value(); + settings.max_chart_x_range = max_chart_x_range->value() * 60; settings.save(); accept(); } diff --git a/tools/cabana/settings.h b/tools/cabana/settings.h index 22542fc04c..fa97c49140 100644 --- a/tools/cabana/settings.h +++ b/tools/cabana/settings.h @@ -15,6 +15,7 @@ public: int can_msg_log_size = 100; int cached_segment_limit = 3; int chart_height = 200; + int max_chart_x_range = 3 * 60; // 3 minutes signals: void changed(); @@ -30,6 +31,7 @@ public: QSpinBox *log_size ; QSpinBox *cached_segment; QSpinBox *chart_height; + QSpinBox *max_chart_x_range; }; extern Settings settings; diff --git a/tools/cabana/videowidget.cc b/tools/cabana/videowidget.cc index 78965e3e8c..7180d5ac0f 100644 --- a/tools/cabana/videowidget.cc +++ b/tools/cabana/videowidget.cc @@ -57,7 +57,6 @@ VideoWidget::VideoWidget(QWidget *parent) : QWidget(parent) { setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed); - QObject::connect(can, &CANMessages::rangeChanged, this, &VideoWidget::rangeChanged); QObject::connect(can, &CANMessages::updated, this, &VideoWidget::updateState); QObject::connect(slider, &QSlider::sliderReleased, [this]() { can->seekTo(slider->value() / 1000.0); }); QObject::connect(slider, &QSlider::valueChanged, [=](int value) { time_label->setText(formatTime(value / 1000)); }); @@ -70,8 +69,8 @@ void VideoWidget::pause(bool pause) { can->pause(pause); } -void VideoWidget::rangeChanged(double min, double max) { - if (!can->isZoomed()) { +void VideoWidget::rangeChanged(double min, double max, bool is_zoomed) { + if (!is_zoomed) { min = 0; max = can->totalSeconds(); } diff --git a/tools/cabana/videowidget.h b/tools/cabana/videowidget.h index d6d036c461..51dae4c76f 100644 --- a/tools/cabana/videowidget.h +++ b/tools/cabana/videowidget.h @@ -26,9 +26,9 @@ class VideoWidget : public QWidget { public: VideoWidget(QWidget *parnet = nullptr); + void rangeChanged(double min, double max, bool is_zommed); protected: - void rangeChanged(double min, double max); void updateState(); void pause(bool pause); From 16b7d726b3ff404e4c8df8a3045ff75bbaf63719 Mon Sep 17 00:00:00 2001 From: Kurt Nistelberger Date: Wed, 26 Oct 2022 13:33:12 -0700 Subject: [PATCH 22/59] quectel no sim GPS support (#26227) * add no sim gps support * address comments * remove xtra assistance enabling Co-authored-by: Kurt Nistelberger --- selfdrive/sensord/rawgps/rawgpsd.py | 29 ++++++++++++++++++++++------- 1 file changed, 22 insertions(+), 7 deletions(-) diff --git a/selfdrive/sensord/rawgps/rawgpsd.py b/selfdrive/sensord/rawgps/rawgpsd.py index 5a6827a759..fa23a161c4 100755 --- a/selfdrive/sensord/rawgps/rawgpsd.py +++ b/selfdrive/sensord/rawgps/rawgpsd.py @@ -87,16 +87,24 @@ def try_setup_logs(diag, log_types): else: raise Exception(f"setup logs failed, {log_types=}") -def mmcli(cmd: str) -> None: +def at_cmd(cmd: str) -> None: for _ in range(5): try: - subprocess.check_call(f"mmcli -m any --timeout 30 {cmd}", shell=True) + subprocess.check_call(f"mmcli -m any --timeout 30 --command='{cmd}'", shell=True) break except subprocess.CalledProcessError: cloudlog.exception("rawgps.mmcli_command_failed") else: raise Exception(f"failed to execute mmcli command {cmd=}") + +def gps_enabled() -> bool: + try: + p = subprocess.check_output("mmcli -m any --command=\"AT+QGPS?\"", shell=True) + return b"QGPS: 1" in p + except subprocess.CalledProcessError as exc: + raise Exception("failed to execute QGPS mmcli command") from exc + def setup_quectel(diag: ModemDiag): # enable OEMDRE in the NV # TODO: it has to reboot for this to take effect @@ -108,11 +116,16 @@ def setup_quectel(diag: ModemDiag): setup_logs(diag, LOG_TYPES) + if gps_enabled(): + at_cmd("AT+QGPSEND") + # disable DPO power savings for more accuracy - mmcli("--command='AT+QGPSCFG=\"dpoenable\",0'") + at_cmd("AT+QGPSCFG=\"dpoenable\",0") # don't automatically turn on GNSS on powerup - mmcli("--command='AT+QGPSCFG=\"autogps\",0'") - mmcli("--location-enable-gps-raw --location-enable-gps-nmea") + at_cmd("AT+QGPSCFG=\"autogps\",0") + + at_cmd("AT+QGPSCFG=\"outport\",\"usbnmea\"") + at_cmd("AT+QGPS=1") # enable OEMDRE mode DIAG_SUBSYS_CMD_F = 75 @@ -134,7 +147,9 @@ def setup_quectel(diag: ModemDiag): )) def teardown_quectel(diag): - mmcli("--location-disable-gps-raw --location-disable-gps-nmea") + at_cmd("AT+QGPSCFG=\"outport\",\"none\"") + if gps_enabled(): + at_cmd("AT+QGPSEND") try_setup_logs(diag, []) @@ -156,7 +171,7 @@ def main() -> NoReturn: # wait for ModemManager to come up cloudlog.warning("waiting for modem to come up") while True: - ret = subprocess.call("mmcli -m any --timeout 10 --location-status", stdout=subprocess.DEVNULL, stderr=subprocess.DEVNULL, shell=True) + ret = subprocess.call("mmcli -m any --timeout 10 --command=\"AT+QGPS?\"", stdout=subprocess.DEVNULL, stderr=subprocess.DEVNULL, shell=True) if ret == 0: break time.sleep(0.1) From 9c9281458510f4e34ee5434138086075cf0c8838 Mon Sep 17 00:00:00 2001 From: Kurt Nistelberger Date: Wed, 26 Oct 2022 13:37:11 -0700 Subject: [PATCH 23/59] Improve GPS tests, add qcom tests (#26060) * first ignore * init gps test * make LimeGPS git clone * gps test v1 * add static signal gen script * remove LD_PRELOAD by using rpath, update values after testing * cleanUp * update fuzzy tests * finalize qcom gps tests * add downloader * finalize unit tests * inc limeGPS startup time * loosen init time * add ublox warmstart test * improve location tests Co-authored-by: Kurt Nistelberger --- tools/gpstest/fuzzy_testing.py | 19 +++-- tools/gpstest/remote_checker.py | 18 ++-- tools/gpstest/run_static_gps_signal.py | 83 ------------------- tools/gpstest/run_unittest.sh | 16 ++++ tools/gpstest/simulate_gps_signal.py | 102 +++++++++++++++++++++++ tools/gpstest/test_gps.py | 101 +++++++++++++++++------ tools/gpstest/test_gps_qcom.py | 109 +++++++++++++++++++++++++ 7 files changed, 327 insertions(+), 121 deletions(-) delete mode 100755 tools/gpstest/run_static_gps_signal.py create mode 100755 tools/gpstest/run_unittest.sh create mode 100755 tools/gpstest/simulate_gps_signal.py create mode 100644 tools/gpstest/test_gps_qcom.py diff --git a/tools/gpstest/fuzzy_testing.py b/tools/gpstest/fuzzy_testing.py index 216e7d0dde..df6691c558 100755 --- a/tools/gpstest/fuzzy_testing.py +++ b/tools/gpstest/fuzzy_testing.py @@ -66,7 +66,7 @@ def get_continuous_coords(lat, lon) -> Tuple[int, int]: return round(lat, 5), round(lon, 5) rc_p: Any = None -def exec_remote_checker(lat, lon, duration): +def exec_remote_checker(lat, lon, duration, ip_addr): global rc_p # TODO: good enough for testing remote_cmd = "export PYTHONPATH=/data/pythonpath:/data/pythonpath/pyextra && " @@ -74,8 +74,8 @@ def exec_remote_checker(lat, lon, duration): remote_cmd += f"timeout {duration} /usr/local/pyenv/shims/python tools/gpstest/remote_checker.py " remote_cmd += f"{lat} {lon}" - ssh_cmd = ['ssh', '-i', '/home/batman/openpilot/xx/phone/key/id_rsa', - 'comma@192.168.60.130'] + ssh_cmd = ["ssh", "-i", "/home/batman/openpilot/xx/phone/key/id_rsa", + f"comma@{ip_addr}"] ssh_cmd += [remote_cmd] rc_p = sp.Popen(ssh_cmd, stdout=sp.PIPE) @@ -84,8 +84,9 @@ def exec_remote_checker(lat, lon, duration): print(f"Checker Result: {rc_output.strip().decode('utf-8')}") -def run_remote_checker(spoof_proc, lat, lon, duration) -> bool: - checker_thread = threading.Thread(target=exec_remote_checker, args=(lat, lon, duration)) +def run_remote_checker(spoof_proc, lat, lon, duration, ip_addr) -> bool: + checker_thread = threading.Thread(target=exec_remote_checker, + args=(lat, lon, duration, ip_addr)) checker_thread.start() tcnt = 0 @@ -107,8 +108,12 @@ def run_remote_checker(spoof_proc, lat, lon, duration) -> bool: def main(): + if len(sys.argv) < 2: + print(f"usage: {sys.argv[0]} [-c]") + ip_addr = sys.argv[1] + continuous_mode = False - if len(sys.argv) == 2 and sys.argv[1] == '-c': + if len(sys.argv) == 3 and sys.argv[2] == '-c': print("Continuous Mode!") continuous_mode = True @@ -123,7 +128,7 @@ def main(): start_time = time.monotonic() # remote checker runs blocking - if not run_remote_checker(spoof_proc, lat, lon, duration): + if not run_remote_checker(spoof_proc, lat, lon, duration, ip_addr): # location could not be matched by ublox module pass diff --git a/tools/gpstest/remote_checker.py b/tools/gpstest/remote_checker.py index 84f6c0c3d9..a649a105c3 100644 --- a/tools/gpstest/remote_checker.py +++ b/tools/gpstest/remote_checker.py @@ -3,6 +3,7 @@ import sys import time from typing import List +from common.params import Params import cereal.messaging as messaging from selfdrive.manager.process_config import managed_processes @@ -12,30 +13,35 @@ procs: List[str] = []#"ubloxd", "pigeond"] def main(): - if len(sys.argv) < 3: + if len(sys.argv) != 4: print("args: ") return - sol_lat = float(sys.argv[1]) - sol_lon = float(sys.argv[2]) + quectel_mod = Params().get_bool("UbloxAvailable") + sol_lat = float(sys.argv[2]) + sol_lon = float(sys.argv[3]) for p in procs: managed_processes[p].start() time.sleep(0.5) # give time to startup - gps_sock = messaging.sub_sock('gpsLocationExternal', timeout=0.1) + socket = 'gpsLocation' if quectel_mod else 'gpsLocationExternal' + gps_sock = messaging.sub_sock(socket, timeout=0.1) # analyze until the location changed while True: events = messaging.drain_sock(gps_sock) for e in events: - lat = e.gpsLocationExternal.latitude - lon = e.gpsLocationExternal.longitude + loc = e.gpsLocation if quectel_mod else e.gpsLocationExternal + lat = loc.latitude + lon = loc.longitude if abs(lat - sol_lat) < DELTA and abs(lon - sol_lon) < DELTA: print("MATCH") return + time.sleep(0.1) + for p in procs: if not managed_processes[p].proc.is_alive(): print(f"ERROR: '{p}' died") diff --git a/tools/gpstest/run_static_gps_signal.py b/tools/gpstest/run_static_gps_signal.py deleted file mode 100755 index 3787038f13..0000000000 --- a/tools/gpstest/run_static_gps_signal.py +++ /dev/null @@ -1,83 +0,0 @@ -#!/usr/bin/env python3 -import os -import sys -import random -import datetime as dt -import subprocess as sp -from typing import Tuple - -from laika.downloader import download_nav -from laika.gps_time import GPSTime -from laika.helpers import ConstellationId - -cache_dir = '/tmp/gpstest/' - - -def download_rinex(): - # TODO: check if there is a better way to get the full brdc file for LimeGPS - gps_time = GPSTime.from_datetime(dt.datetime.utcnow()) - utc_time = dt.datetime.utcnow() - dt.timedelta(1) - gps_time = GPSTime.from_datetime(dt.datetime(utc_time.year, utc_time.month, utc_time.day)) - return download_nav(gps_time, cache_dir, ConstellationId.GPS) - - -def get_random_coords(lat, lon) -> Tuple[int, int]: - # jump around the world - # max values, lat: -90 to 90, lon: -180 to 180 - - lat_add = random.random()*20 + 10 - lon_add = random.random()*20 + 20 - - lat = ((lat + lat_add + 90) % 180) - 90 - lon = ((lon + lon_add + 180) % 360) - 180 - return round(lat, 5), round(lon, 5) - - -def check_availability() -> bool: - cmd = ["LimeSuite/builddir/LimeUtil/LimeUtil", "--find"] - output = sp.check_output(cmd) - - if output.strip() == b"": - return False - - print(f"Device: {output.strip().decode('utf-8')}") - return True - - -def main(): - if not os.path.exists('LimeGPS'): - print("LimeGPS not found run 'setup.sh' first") - return - - if not os.path.exists('LimeSuite'): - print("LimeSuite not found run 'setup.sh' first") - return - - if not check_availability(): - print("No limeSDR device found!") - return - - rinex_file = download_rinex() - lat, lon = get_random_coords(47.2020, 15.7403) - - if len(sys.argv) == 3: - lat = float(sys.argv[1]) - lon = float(sys.argv[2]) - - try: - print(f"starting LimeGPS, Location: {lat},{lon}") - cmd = ["LimeGPS/LimeGPS", "-e", rinex_file, "-l", f"{lat},{lon},100"] - sp.check_output(cmd, stderr=sp.PIPE) - except KeyboardInterrupt: - print("stopping LimeGPS") - except Exception as e: - out_stderr = e.stderr.decode('utf-8')# pylint:disable=no-member - if "Device is busy." in out_stderr: - print("GPS simulation is already running, Device is busy!") - return - - print(f"LimeGPS crashed: {str(e)}") - print(f"stderr:\n{e.stderr.decode('utf-8')}")# pylint:disable=no-member - -if __name__ == "__main__": - main() diff --git a/tools/gpstest/run_unittest.sh b/tools/gpstest/run_unittest.sh new file mode 100755 index 0000000000..d284fa74e5 --- /dev/null +++ b/tools/gpstest/run_unittest.sh @@ -0,0 +1,16 @@ +#!/bin/bash + +# NOTE: can only run inside limeGPS test box! + +# run limeGPS with random static location +timeout 300 ./simulate_gps_signal.py & +gps_PID=$? + +echo "starting limeGPS..." +sleep 10 + +# run unit tests (skipped when module not present) +python -m unittest test_gps.py +python -m unittest test_gps_qcom.py + +kill $gps_PID diff --git a/tools/gpstest/simulate_gps_signal.py b/tools/gpstest/simulate_gps_signal.py new file mode 100755 index 0000000000..f1e5ad2028 --- /dev/null +++ b/tools/gpstest/simulate_gps_signal.py @@ -0,0 +1,102 @@ +#!/usr/bin/env python3 +import os +import random +import argparse +import datetime as dt +import subprocess as sp +from typing import Tuple + +from laika.downloader import download_nav +from laika.gps_time import GPSTime +from laika.helpers import ConstellationId + +cache_dir = '/tmp/gpstest/' + + +def download_rinex(): + # TODO: check if there is a better way to get the full brdc file for LimeGPS + gps_time = GPSTime.from_datetime(dt.datetime.utcnow()) + utc_time = dt.datetime.utcnow() - dt.timedelta(1) + gps_time = GPSTime.from_datetime(dt.datetime(utc_time.year, utc_time.month, utc_time.day)) + return download_nav(gps_time, cache_dir, ConstellationId.GPS) + +def get_coords(lat, lon, s1, s2, o1=0, o2=0) -> Tuple[int, int]: + lat_add = random.random()*s1 + o1 + lon_add = random.random()*s2 + o2 + + lat = ((lat + lat_add + 90) % 180) - 90 + lon = ((lon + lon_add + 180) % 360) - 180 + return round(lat, 5), round(lon, 5) + +def get_continuous_coords(lat, lon) -> Tuple[int, int]: + # continuously move around the world + return get_coords(lat, lon, 0.01, 0.01) + +def get_random_coords(lat, lon) -> Tuple[int, int]: + # jump around the world + return get_coords(lat, lon, 20, 20, 10, 20) + +def check_availability() -> bool: + cmd = ["LimeSuite/builddir/LimeUtil/LimeUtil", "--find"] + output = sp.check_output(cmd) + + if output.strip() == b"": + return False + + print(f"Device: {output.strip().decode('utf-8')}") + return True + +def main(lat, lon, jump_sim, contin_sim): + if not os.path.exists('LimeGPS'): + print("LimeGPS not found run 'setup.sh' first") + return + + if not os.path.exists('LimeSuite'): + print("LimeSuite not found run 'setup.sh' first") + return + + if not check_availability(): + print("No limeSDR device found!") + return + + rinex_file = download_rinex() + + if lat == 0 and lon == 0: + lat, lon = get_random_coords(47.2020, 15.7403) + + timeout = None + if jump_sim: + timeout = 30 + + while True: + try: + print(f"starting LimeGPS, Location: {lat},{lon}") + cmd = ["LimeGPS/LimeGPS", "-e", rinex_file, "-l", f"{lat},{lon},100"] + sp.check_output(cmd, stderr=sp.PIPE, timeout=timeout) + except KeyboardInterrupt: + print("stopping LimeGPS") + return + except sp.TimeoutExpired: + print("LimeGPS timeout reached!") + except Exception as e: + out_stderr = e.stderr.decode('utf-8')# pylint:disable=no-member + if "Device is busy." in out_stderr: + print("GPS simulation is already running, Device is busy!") + return + + print(f"LimeGPS crashed: {str(e)}") + print(f"stderr:\n{e.stderr.decode('utf-8')}")# pylint:disable=no-member + + if contin_sim: + lat, lon = get_continuous_coords(lat, lon) + else: + lat, lon = get_random_coords(lat, lon) + +if __name__ == "__main__": + parser = argparse.ArgumentParser(description="Simulate static [or random jumping] GPS signal.") + parser.add_argument("lat", type=float, nargs='?', default=0) + parser.add_argument("lon", type=float, nargs='?', default=0) + parser.add_argument("--jump", action="store_true", help="signal that jumps around the world") + parser.add_argument("--contin", action="store_true", help="continuously/slowly moving around the world") + args = parser.parse_args() + main(args.lat, args.lon, args.jump, args.contin) diff --git a/tools/gpstest/test_gps.py b/tools/gpstest/test_gps.py index f5e19372f7..b5d0cdd254 100644 --- a/tools/gpstest/test_gps.py +++ b/tools/gpstest/test_gps.py @@ -2,8 +2,8 @@ import time import unittest import struct -import numpy as np +from common.params import Params import cereal.messaging as messaging import selfdrive.sensord.pigeond as pd from system.hardware import TICI @@ -22,7 +22,20 @@ def read_events(service, duration_sec): return events -def verify_ubloxgnss_data(socket: messaging.SubSocket): +def create_backup(pigeon): + # controlled GNSS stop + pigeon.send(b"\xB5\x62\x06\x04\x04\x00\x00\x00\x08\x00\x16\x74") + + # store almanac in flash + pigeon.send(b"\xB5\x62\x09\x14\x04\x00\x00\x00\x00\x00\x21\xEC") + try: + if not pigeon.wait_for_ack(ack=pd.UBLOX_SOS_ACK, nack=pd.UBLOX_SOS_NACK): + assert False, "Could not store almanac" + except TimeoutError: + pass + + +def verify_ubloxgnss_data(socket: messaging.SubSocket, max_time: int): start_time = 0 end_time = 0 events = messaging.drain_sock(socket) @@ -42,7 +55,7 @@ def verify_ubloxgnss_data(socket: messaging.SubSocket): assert end_time != 0, "no ublox measurements received!" ttfm = (end_time - start_time)/1e9 - assert ttfm < 35, f"Time to first measurement > 35s, {ttfm}" + assert ttfm < max_time, f"Time to first measurement > {max_time}s, {ttfm}" # check for satellite count in measurements sat_count = [] @@ -52,42 +65,31 @@ def verify_ubloxgnss_data(socket: messaging.SubSocket): sat_count.append(event.ubloxGnss.measurementReport.numMeas) num_sat = int(sum(sat_count)/len(sat_count)) - assert num_sat > 8, f"Not enough satellites {num_sat} (TestBox setup!)" + assert num_sat > 5, f"Not enough satellites {num_sat} (TestBox setup!)" -def verify_gps_location(socket: messaging.SubSocket): - buf_lon = [0]*10 - buf_lat = [0]*10 - buf_i = 0 +def verify_gps_location(socket: messaging.SubSocket, max_time: int): events = messaging.drain_sock(socket) assert len(events) != 0, "no gpsLocationExternal measurements" start_time = events[0].logMonoTime end_time = 0 for event in events: - buf_lon[buf_i % 10] = event.gpsLocationExternal.longitude - buf_lat[buf_i % 10] = event.gpsLocationExternal.latitude - buf_i += 1 - - if buf_i < 9: - continue + gps_valid = event.gpsLocationExternal.flags % 2 - if any([lat == 0 or lon == 0 for lat,lon in zip(buf_lat, buf_lon)]): - continue - - if np.std(buf_lon) < 1e-5 and np.std(buf_lat) < 1e-5: + if gps_valid: end_time = event.logMonoTime break assert end_time != 0, "GPS location never converged!" ttfl = (end_time - start_time)/1e9 - assert ttfl < 40, f"Time to first location > 40s, {ttfl}" + assert ttfl < max_time, f"Time to first location > {max_time}s, {ttfl}" hacc = events[-1].gpsLocationExternal.accuracy vacc = events[-1].gpsLocationExternal.verticalAccuracy - assert hacc < 15, f"Horizontal accuracy too high, {hacc}" - assert vacc < 43, f"Vertical accuracy too high, {vacc}" + assert hacc < 20, f"Horizontal accuracy too high, {hacc}" + assert vacc < 45, f"Vertical accuracy too high, {vacc}" def verify_time_to_first_fix(pigeon): @@ -111,11 +113,16 @@ class TestGPS(unittest.TestCase): if not TICI: raise unittest.SkipTest + ublox_available = Params().get_bool("UbloxAvailable") + if not ublox_available: + raise unittest.SkipTest + + def tearDown(self): pd.set_power(False) @with_processes(['ubloxd']) - def test_ublox_reset(self): + def test_a_ublox_reset(self): pigeon, pm = pd.create_pigeon() pd.init_baudrate(pigeon) @@ -127,14 +134,58 @@ class TestGPS(unittest.TestCase): gle = messaging.sub_sock("gpsLocationExternal", timeout=0.1) # receive some messages (restart after cold start takes up to 30seconds) - pd.run_receiving(pigeon, pm, 40) + pd.run_receiving(pigeon, pm, 60) + + # store almanac for next test + create_backup(pigeon) - verify_ubloxgnss_data(ugs) - verify_gps_location(gle) + verify_ubloxgnss_data(ugs, 60) + verify_gps_location(gle, 60) # skip for now, this might hang for a while #verify_time_to_first_fix(pigeon) + @with_processes(['ubloxd']) + def test_b_ublox_almanac(self): + pigeon, pm = pd.create_pigeon() + pd.init_baudrate(pigeon) + + # device cold start + pigeon.send(b"\xb5\x62\x06\x04\x04\x00\xff\xff\x00\x00\x0c\x5d") + time.sleep(1) # wait for cold start + pd.init_baudrate(pigeon) + + # clear configuration + pigeon.send_with_ack(b"\xb5\x62\x06\x09\x0d\x00\x00\x00\x1f\x1f\x00\x00\x00\x00\x00\x00\x00\x00\x17\x71\x5b") + + # restoring almanac backup + pigeon.send(b"\xB5\x62\x09\x14\x00\x00\x1D\x60") + status = pigeon.wait_for_backup_restore_status() + assert status == 2, "Could not restore almanac backup" + + pd.initialize_pigeon(pigeon) + + ugs = messaging.sub_sock("ubloxGnss", timeout=0.1) + gle = messaging.sub_sock("gpsLocationExternal", timeout=0.1) + + pd.run_receiving(pigeon, pm, 15) + verify_ubloxgnss_data(ugs, 15) + verify_gps_location(gle, 20) + + + @with_processes(['ubloxd']) + def test_c_ublox_startup(self): + pigeon, pm = pd.create_pigeon() + pd.init_baudrate(pigeon) + pd.initialize_pigeon(pigeon) + + ugs = messaging.sub_sock("ubloxGnss", timeout=0.1) + gle = messaging.sub_sock("gpsLocationExternal", timeout=0.1) + pd.run_receiving(pigeon, pm, 10) + verify_ubloxgnss_data(ugs, 10) + verify_gps_location(gle, 10) + + if __name__ == "__main__": unittest.main() \ No newline at end of file diff --git a/tools/gpstest/test_gps_qcom.py b/tools/gpstest/test_gps_qcom.py new file mode 100644 index 0000000000..0909316c5e --- /dev/null +++ b/tools/gpstest/test_gps_qcom.py @@ -0,0 +1,109 @@ +#!/usr/bin/env python3 +import time +import unittest +import subprocess as sp + +from common.params import Params +from system.hardware import TICI +import cereal.messaging as messaging +from selfdrive.manager.process_config import managed_processes + + +def exec_mmcli(cmd): + cmd = "mmcli -m 0 " + cmd + p = sp.Popen(cmd, shell=True, stdout=sp.PIPE, stderr=sp.PIPE) + return p.communicate() + + +def wait_for_location(socket, timeout): + while True: + events = messaging.drain_sock(socket) + for event in events: + if event.gpsLocation.flags % 2: + return False + + timeout -= 1 + if timeout <= 0: + return True + + time.sleep(0.1) + continue + + +class TestGPS(unittest.TestCase): + @classmethod + def setUpClass(cls): + if not TICI: + raise unittest.SkipTest + + ublox_available = Params().get_bool("UbloxAvailable") + if ublox_available: + raise unittest.SkipTest + + @unittest.skip("Skip cold start test due to time") + def test_quectel_cold_start(self): + # delete assistance data to enforce cold start for GNSS + # testing shows that this takes up to 20min + + # invalidate supl setting, cannot be reset + _, err = exec_mmcli("--location-set-supl-server=unittest:1") + + _, err = exec_mmcli("--command='AT+QGPSDEL=0'") + assert len(err) == 0, f"GPSDEL failed: {err}" + + managed_processes['rawgpsd'].start() + start_time = time.monotonic() + glo = messaging.sub_sock("gpsLocation", timeout=0.1) + + timeout = 10*60*25 # 25 minute + timedout = wait_for_location(glo, timeout) + managed_processes['rawgpsd'].stop() + + assert timedout is False, "Waiting for location timed out (25min)!" + + duration = time.monotonic() - start_time + assert duration < 50, f"Received GPS location {duration}!" + + + def test_a_quectel_cold_start_AGPS(self): + _, err = exec_mmcli("--command='AT+QGPSDEL=0'") + assert len(err) == 0, f"GPSDEL failed: {err}" + + # setup AGPS + exec_mmcli("--location-set-supl-server=supl.google.com:7276") + + managed_processes['rawgpsd'].start() + start_time = time.monotonic() + glo = messaging.sub_sock("gpsLocation", timeout=0.1) + + timeout = 10*60*3 # 3 minute + timedout = wait_for_location(glo, timeout) + managed_processes['rawgpsd'].stop() + + assert timedout is False, "Waiting for location timed out (3min)!" + + duration = time.monotonic() - start_time + assert duration < 60, f"Received GPS location {duration}!" + + + def test_b_quectel_startup(self): + + # setup AGPS + exec_mmcli("--location-set-supl-server=supl.google.com:7276") + + managed_processes['rawgpsd'].start() + start_time = time.monotonic() + glo = messaging.sub_sock("gpsLocation", timeout=0.1) + + timeout = 10*60*3 # 3 minute + timedout = wait_for_location(glo, timeout) + managed_processes['rawgpsd'].stop() + + assert timedout is False, "Waiting for location timed out (3min)!" + + duration = time.monotonic() - start_time + assert duration < 60, f"Received GPS location {duration}!" + + +if __name__ == "__main__": + unittest.main() From b80f2efdf29fb5095ea2fa258ec7695730467515 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Wed, 26 Oct 2022 14:53:01 -0700 Subject: [PATCH 24/59] No fcw when standstill (#26252) --- selfdrive/controls/lib/longitudinal_planner.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/controls/lib/longitudinal_planner.py b/selfdrive/controls/lib/longitudinal_planner.py index 018136e6f2..457065d3b5 100755 --- a/selfdrive/controls/lib/longitudinal_planner.py +++ b/selfdrive/controls/lib/longitudinal_planner.py @@ -133,7 +133,7 @@ class LongitudinalPlanner: # TODO counter is only needed because radar is glitchy, remove once radar is gone # TODO write fcw in e2e_long mode - self.fcw = self.mpc.mode == 'acc' and self.mpc.crash_cnt > 5 + self.fcw = self.mpc.mode == 'acc' and self.mpc.crash_cnt > 5 and not sm['carState'].standstill if self.fcw: cloudlog.info("FCW triggered") From 9e3e49a81f265eefbee32e7d96dbbae3f4b393f1 Mon Sep 17 00:00:00 2001 From: Kurt Nistelberger Date: Wed, 26 Oct 2022 15:11:45 -0700 Subject: [PATCH 25/59] readd camerad tests --- Jenkinsfile | 2 -- 1 file changed, 2 deletions(-) diff --git a/Jenkinsfile b/Jenkinsfile index 85b4880463..b9b9eda667 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -137,7 +137,6 @@ pipeline { } } - /* stage('camerad') { agent { docker { image 'ghcr.io/commaai/alpine-ssh'; args '--user=root' } } steps { @@ -148,7 +147,6 @@ pipeline { ]) } } - */ stage('replay') { agent { docker { image 'ghcr.io/commaai/alpine-ssh'; args '--user=root' } } From 6b6162d2c822c717cd62312f51113180c21b5664 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Thu, 27 Oct 2022 10:47:32 +0800 Subject: [PATCH 26/59] UI: support switching streams in CameraView (#26248) --- selfdrive/ui/qt/widgets/cameraview.cc | 35 ++++++++++++++++++--------- selfdrive/ui/qt/widgets/cameraview.h | 7 ++++-- 2 files changed, 28 insertions(+), 14 deletions(-) diff --git a/selfdrive/ui/qt/widgets/cameraview.cc b/selfdrive/ui/qt/widgets/cameraview.cc index 200257235d..4f46497776 100644 --- a/selfdrive/ui/qt/widgets/cameraview.cc +++ b/selfdrive/ui/qt/widgets/cameraview.cc @@ -96,8 +96,8 @@ mat4 get_fit_view_transform(float widget_aspect_ratio, float frame_aspect_ratio) CameraWidget::CameraWidget(std::string stream_name, VisionStreamType type, bool zoom, QWidget* parent) : stream_name(stream_name), stream_type(type), zoomed_view(zoom), QOpenGLWidget(parent) { setAttribute(Qt::WA_OpaquePaintEvent); - connect(this, &CameraWidget::vipcThreadConnected, this, &CameraWidget::vipcConnected, Qt::BlockingQueuedConnection); - connect(this, &CameraWidget::vipcThreadFrameReceived, this, &CameraWidget::vipcFrameReceived); + QObject::connect(this, &CameraWidget::vipcThreadConnected, this, &CameraWidget::vipcConnected, Qt::BlockingQueuedConnection); + QObject::connect(this, &CameraWidget::vipcThreadFrameReceived, this, &CameraWidget::vipcFrameReceived, Qt::QueuedConnection); } CameraWidget::~CameraWidget() { @@ -162,13 +162,13 @@ void CameraWidget::initializeGL() { } void CameraWidget::showEvent(QShowEvent *event) { - frames.clear(); if (!vipc_thread) { vipc_thread = new QThread(); connect(vipc_thread, &QThread::started, [=]() { vipcThread(); }); connect(vipc_thread, &QThread::finished, vipc_thread, &QObject::deleteLater); vipc_thread->start(); } + clearFrames(); } void CameraWidget::hideEvent(QHideEvent *event) { @@ -178,6 +178,7 @@ void CameraWidget::hideEvent(QHideEvent *event) { vipc_thread->wait(); vipc_thread = nullptr; } + clearFrames(); } void CameraWidget::updateFrameMat() { @@ -233,6 +234,7 @@ void CameraWidget::paintGL() { glClearColor(bg.redF(), bg.greenF(), bg.blueF(), bg.alphaF()); glClear(GL_STENCIL_BUFFER_BIT | GL_COLOR_BUFFER_BIT); + std::lock_guard lk(frame_lock); if (frames.empty()) return; int frame_idx = frames.size() - 1; @@ -249,14 +251,14 @@ void CameraWidget::paintGL() { qDebug() << "Skipped frame" << frames[frame_idx].first; } prev_frame_id = frames[frame_idx].first; + VisionBuf *frame = frames[frame_idx].second; + assert(frame != nullptr); glViewport(0, 0, width(), height()); glBindVertexArray(frame_vao); glUseProgram(program->programId()); glPixelStorei(GL_UNPACK_ALIGNMENT, 1); - VisionBuf *frame = frames[frame_idx].second; - #ifdef QCOM2 glActiveTexture(GL_TEXTURE0); glEGLImageTargetTexture2DOES(GL_TEXTURE_EXTERNAL_OES, egl_images[frame->idx]); @@ -288,7 +290,6 @@ void CameraWidget::paintGL() { void CameraWidget::vipcConnected(VisionIpcClient *vipc_client) { makeCurrent(); - frames.clear(); stream_width = vipc_client->buffers[0].width; stream_height = vipc_client->buffers[0].height; stream_stride = vipc_client->buffers[0].stride; @@ -339,11 +340,7 @@ void CameraWidget::vipcConnected(VisionIpcClient *vipc_client) { updateFrameMat(); } -void CameraWidget::vipcFrameReceived(VisionBuf *buf, uint32_t frame_id) { - frames.push_back(std::make_pair(frame_id, buf)); - while (frames.size() > FRAME_BUFFER_SIZE) { - frames.pop_front(); - } +void CameraWidget::vipcFrameReceived() { update(); } @@ -354,11 +351,13 @@ void CameraWidget::vipcThread() { while (!QThread::currentThread()->isInterruptionRequested()) { if (!vipc_client || cur_stream_type != stream_type) { + clearFrames(); cur_stream_type = stream_type; vipc_client.reset(new VisionIpcClient(stream_name, cur_stream_type, false)); } if (!vipc_client->connected) { + clearFrames(); if (!vipc_client->connect(false)) { QThread::msleep(100); continue; @@ -367,7 +366,14 @@ void CameraWidget::vipcThread() { } if (VisionBuf *buf = vipc_client->recv(&meta_main, 1000)) { - emit vipcThreadFrameReceived(buf, meta_main.frame_id); + { + std::lock_guard lk(frame_lock); + frames.push_back(std::make_pair(meta_main.frame_id, buf)); + while (frames.size() > FRAME_BUFFER_SIZE) { + frames.pop_front(); + } + } + emit vipcThreadFrameReceived(); } } @@ -378,3 +384,8 @@ void CameraWidget::vipcThread() { egl_images.clear(); #endif } + +void CameraWidget::clearFrames() { + std::lock_guard lk(frame_lock); + frames.clear(); +} diff --git a/selfdrive/ui/qt/widgets/cameraview.h b/selfdrive/ui/qt/widgets/cameraview.h index 9bcad935c0..ef828f8ff6 100644 --- a/selfdrive/ui/qt/widgets/cameraview.h +++ b/selfdrive/ui/qt/widgets/cameraview.h @@ -1,6 +1,7 @@ #pragma once #include +#include #include #include @@ -37,7 +38,7 @@ public: signals: void clicked(); void vipcThreadConnected(VisionIpcClient *); - void vipcThreadFrameReceived(VisionBuf *, quint32); + void vipcThreadFrameReceived(); protected: void paintGL() override; @@ -49,6 +50,7 @@ protected: virtual void updateFrameMat(); void updateCalibration(const mat3 &calib); void vipcThread(); + void clearFrames(); bool zoomed_view; GLuint frame_vao, frame_vbo, frame_ibo; @@ -76,11 +78,12 @@ protected: mat3 calibration = DEFAULT_CALIBRATION; mat3 intrinsic_matrix = fcam_intrinsic_matrix; + std::mutex frame_lock; std::deque> frames; uint32_t draw_frame_id = 0; uint32_t prev_frame_id = 0; protected slots: void vipcConnected(VisionIpcClient *vipc_client); - void vipcFrameReceived(VisionBuf *vipc_client, uint32_t frame_id); + void vipcFrameReceived(); }; From 69b0aa94fa7364265af05936e3e85e94a3c13861 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Wed, 26 Oct 2022 20:17:28 -0700 Subject: [PATCH 27/59] Toyota: add missing RAV4 2022 engine FW (#26249) Update values.py --- selfdrive/car/toyota/values.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 819b85d759..07c33d0173 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -1367,6 +1367,7 @@ FW_VERSIONS = { b'\x01896634AA1000\x00\x00\x00\x00', b'\x01896634A88000\x00\x00\x00\x00', b'\x01896634A89000\x00\x00\x00\x00', + b'\x01896634A89100\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 0xf): [ b'\x018821F0R01100\x00\x00\x00\x00', From 5b455f1d318939470b99ab81d2e20d247db2715d Mon Sep 17 00:00:00 2001 From: Kurt Nistelberger Date: Wed, 26 Oct 2022 20:22:46 -0700 Subject: [PATCH 28/59] finalize gps tests (#26255) * finalize gps test before adding to ci Co-authored-by: Kurt Nistelberger --- tools/gpstest/run_unittest.sh | 4 ++-- tools/gpstest/test_gps.py | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/tools/gpstest/run_unittest.sh b/tools/gpstest/run_unittest.sh index d284fa74e5..9f93fdfc9a 100755 --- a/tools/gpstest/run_unittest.sh +++ b/tools/gpstest/run_unittest.sh @@ -3,8 +3,8 @@ # NOTE: can only run inside limeGPS test box! # run limeGPS with random static location -timeout 300 ./simulate_gps_signal.py & -gps_PID=$? +timeout 300 ./simulate_gps_signal.py 32.7518 -117.1962 & +gps_PID=$(ps -aux | grep -m 1 "timeout 300" | cut -d ' ' -f 7) echo "starting limeGPS..." sleep 10 diff --git a/tools/gpstest/test_gps.py b/tools/gpstest/test_gps.py index b5d0cdd254..8bc5dc89a8 100644 --- a/tools/gpstest/test_gps.py +++ b/tools/gpstest/test_gps.py @@ -65,7 +65,7 @@ def verify_ubloxgnss_data(socket: messaging.SubSocket, max_time: int): sat_count.append(event.ubloxGnss.measurementReport.numMeas) num_sat = int(sum(sat_count)/len(sat_count)) - assert num_sat > 5, f"Not enough satellites {num_sat} (TestBox setup!)" + assert num_sat >= 5, f"Not enough satellites {num_sat} (TestBox setup!)" def verify_gps_location(socket: messaging.SubSocket, max_time: int): @@ -188,4 +188,4 @@ class TestGPS(unittest.TestCase): if __name__ == "__main__": - unittest.main() \ No newline at end of file + unittest.main() From 5e717c12f11151ca064c6829b75616c0776d0059 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Thu, 27 Oct 2022 13:14:26 +0800 Subject: [PATCH 29/59] Cabana:: remove a fixed TODO (#26257) remove a fixed TODO --- tools/cabana/videowidget.cc | 1 - 1 file changed, 1 deletion(-) diff --git a/tools/cabana/videowidget.cc b/tools/cabana/videowidget.cc index 7180d5ac0f..9a28f71bb9 100644 --- a/tools/cabana/videowidget.cc +++ b/tools/cabana/videowidget.cc @@ -17,7 +17,6 @@ VideoWidget::VideoWidget(QWidget *parent) : QWidget(parent) { QVBoxLayout *main_layout = new QVBoxLayout(this); main_layout->setContentsMargins(0, 0, 0, 0); - // TODO: figure out why the CameraWidget crashed occasionally. cam_widget = new CameraWidget("camerad", VISION_STREAM_ROAD, false, this); cam_widget->setFixedSize(parent->width(), parent->width() / 1.596); main_layout->addWidget(cam_widget); From 7c1bb03497f28ad7e014d7df7262f4cfcd2fc738 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Fri, 28 Oct 2022 03:57:22 +0800 Subject: [PATCH 30/59] Cabana: set fixed height for statusbar (#26264) --- tools/cabana/mainwin.cc | 2 ++ 1 file changed, 2 insertions(+) diff --git a/tools/cabana/mainwin.cc b/tools/cabana/mainwin.cc index 30c7e5e0a2..f127e5f52b 100644 --- a/tools/cabana/mainwin.cc +++ b/tools/cabana/mainwin.cc @@ -23,6 +23,7 @@ MainWindow::MainWindow() : QWidget() { main_layout->addLayout(h_layout); QSplitter *splitter = new QSplitter(Qt::Horizontal, this); + splitter->setSizePolicy(QSizePolicy::Preferred, QSizePolicy::Expanding); messages_widget = new MessagesWidget(this); splitter->addWidget(messages_widget); @@ -58,6 +59,7 @@ MainWindow::MainWindow() : QWidget() { // status bar status_bar = new QStatusBar(this); + status_bar->setFixedHeight(20); status_bar->setContentsMargins(0, 0, 0, 0); status_bar->setSizeGripEnabled(true); progress_bar = new QProgressBar(); From f04ca9ff3dc1af71a66c2d1d75364938e898ed10 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Fri, 28 Oct 2022 03:58:25 +0800 Subject: [PATCH 31/59] Cabana: fix dbc opened twice on startup (#26265) --- tools/cabana/messageswidget.cc | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/tools/cabana/messageswidget.cc b/tools/cabana/messageswidget.cc index 9b831ad18c..4975061cc5 100644 --- a/tools/cabana/messageswidget.cc +++ b/tools/cabana/messageswidget.cc @@ -85,10 +85,12 @@ MessagesWidget::MessagesWidget(QWidget *parent) : QWidget(parent) { } void MessagesWidget::loadDBCFromName(const QString &name) { - dbc()->open(name); - dbc_combo->setCurrentText(name); - // refresh model - model->updateState(); + if (name != dbc()->name()) { + dbc()->open(name); + dbc_combo->setCurrentText(name); + // re-sort model to refresh column 'Name' + model->updateState(true); + } } void MessagesWidget::loadDBCFromPaste() { From d67965901895432375584d95103ee1afc14f5554 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Fri, 28 Oct 2022 04:59:52 +0800 Subject: [PATCH 32/59] Cabana: fix marker z-index (#26254) --- tools/cabana/chartswidget.cc | 3 +++ 1 file changed, 3 insertions(+) diff --git a/tools/cabana/chartswidget.cc b/tools/cabana/chartswidget.cc index ea44a4033c..c7846de069 100644 --- a/tools/cabana/chartswidget.cc +++ b/tools/cabana/chartswidget.cc @@ -247,10 +247,13 @@ ChartView::ChartView(const QString &id, const Signal *sig, QWidget *parent) chart->layout()->setContentsMargins(0, 0, 0, 0); track_line = new QGraphicsLineItem(chart); + track_line->setZValue(chart->zValue() + 10); track_line->setPen(QPen(Qt::gray, 1, Qt::DashLine)); value_text = new QGraphicsSimpleTextItem(chart); + value_text->setZValue(chart->zValue() + 10); value_text->setBrush(Qt::gray); line_marker = new QGraphicsLineItem(chart); + line_marker->setZValue(chart->zValue() + 10); line_marker->setPen(QPen(Qt::black, 2)); setChart(chart); From fbafde6f1c46b50c219c3ec3121b94ee0848a7be Mon Sep 17 00:00:00 2001 From: Cameron Clough Date: Thu, 27 Oct 2022 14:04:02 -0700 Subject: [PATCH 33/59] Ford FW batch (#26251) * add Ford Explorer 2022 fw VIN: 1FM5K8GC7NGA85105 8e1bab39e558e773|2022-09-16--02-38-57 * add Ford Escape Titanium PHEV 2021 fw VIN: 1FMCU0LZXMUA80767 f8eaaccd2a90aef8|2022-09-30--15-42-38--0 * add Ford Escape 2020 fw VIN: 1FMCU9DZ9LUA82589 26b2cace68e36212|2022-10-05--18-55-54--0 --- selfdrive/car/ford/values.py | 18 +++++++++++++++--- 1 file changed, 15 insertions(+), 3 deletions(-) diff --git a/selfdrive/car/ford/values.py b/selfdrive/car/ford/values.py index 7b3140fbbf..5114f8d065 100644 --- a/selfdrive/car/ford/values.py +++ b/selfdrive/car/ford/values.py @@ -61,10 +61,10 @@ class FordCarInfo(CarInfo): CAR_INFO: Dict[str, Union[CarInfo, List[CarInfo]]] = { CAR.ESCAPE_MK4: [ - FordCarInfo("Ford Escape 2020"), - FordCarInfo("Ford Kuga EU", "Driver Assistance Pack"), + FordCarInfo("Ford Escape 2020-21"), + FordCarInfo("Ford Kuga 2020-21", "Driver Assistance Pack"), ], - CAR.EXPLORER_MK6: FordCarInfo("Ford Explorer 2020-21"), + CAR.EXPLORER_MK6: FordCarInfo("Ford Explorer 2020-22"), CAR.FOCUS_MK4: FordCarInfo("Ford Focus EU 2019", "Driver Assistance Pack"), } @@ -87,31 +87,41 @@ FW_QUERY_CONFIG = FwQueryConfig( FW_VERSIONS = { CAR.ESCAPE_MK4: { (Ecu.eps, 0x730, None): [ + b'LX6C-14D003-AF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'LX6C-14D003-AH\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.abs, 0x760, None): [ b'LX6C-2D053-NS\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LX6C-2D053-NY\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LX6C-2D053-SA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x764, None): [ b'LB5T-14D049-AB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdCamera, 0x706, None): [ b'LJ6T-14F397-AD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LJ6T-14F397-AE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.engine, 0x7E0, None): [ + b'LX6A-14C204-BJV\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'LX6A-14C204-ESG\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'MX6A-14C204-BEF\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.shiftByWire, 0x732, None): [ + b'LX6P-14G395-AB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LX6P-14G395-AD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], }, CAR.EXPLORER_MK6: { (Ecu.eps, 0x730, None): [ b'L1MC-14D003-AK\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'L1MC-14D003-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'M1MC-14D003-AB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.abs, 0x760, None): [ b'L1MC-2D053-BB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'L1MC-2D053-BF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'L1MC-2D053-KB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x764, None): [ b'LB5T-14D049-AB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', @@ -123,10 +133,12 @@ FW_VERSIONS = { (Ecu.engine, 0x7E0, None): [ b'LB5A-14C204-EAC\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'MB5A-14C204-MD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'NB5A-14C204-HB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.shiftByWire, 0x732, None): [ b'L1MP-14G395-AD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'L1MP-14G395-AE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'L1MP-14G395-JB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], }, CAR.FOCUS_MK4: { From 995c74a994345de3d22c84cd1404aaf4cf8b7e82 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 27 Oct 2022 14:36:47 -0700 Subject: [PATCH 34/59] process replay: test Bolt EUV (camera-ACC platform) (#26270) ADD BOLT TO PROCESS REPLAY --- selfdrive/test/process_replay/ref_commit | 2 +- selfdrive/test/process_replay/test_processes.py | 4 +++- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index ba0f30e5c3..a3ca4163d5 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -8f2919ba4d8509432e93ff0a44f951254c1ff3fe \ No newline at end of file +fbafde6f1c46b50c219c3ec3121b94ee0848a7be \ No newline at end of file diff --git a/selfdrive/test/process_replay/test_processes.py b/selfdrive/test/process_replay/test_processes.py index cecabd8a3a..5c754d9312 100755 --- a/selfdrive/test/process_replay/test_processes.py +++ b/selfdrive/test/process_replay/test_processes.py @@ -24,10 +24,11 @@ source_segments = [ ("TOYOTA3", "f7d7e3538cda1a2a|2021-08-16--08-55-34--6"), # TOYOTA.COROLLA_TSS2 ("HONDA", "eb140f119469d9ab|2021-06-12--10-46-24--27"), # HONDA.CIVIC (NIDEC) ("HONDA2", "7d2244f34d1bbcda|2021-06-25--12-25-37--26"), # HONDA.ACCORD (BOSCH) - ("CHRYSLER", "4deb27de11bee626|2021-02-20--11-28-55--8"), # CHRYSLER.PACIFICA + ("CHRYSLER", "4deb27de11bee626|2021-02-20--11-28-55--8"), # CHRYSLER.PACIFICA_2018_HYBRID ("RAM", "2f4452b03ccb98f0|2022-09-07--13-55-08--10"), # CHRYSLER.RAM_1500 ("SUBARU", "341dccd5359e3c97|2022-09-12--10-35-33--3"), # SUBARU.OUTBACK ("GM", "0c58b6a25109da2b|2021-02-23--16-35-50--11"), # GM.VOLT + ("GM2", "376bf99325883932|2022-10-27--13-41-22--1"), # GM.BOLT_EUV ("NISSAN", "35336926920f3571|2021-02-12--18-38-48--46"), # NISSAN.XTRAIL ("VOLKSWAGEN", "de9592456ad7d144|2021-06-29--11-00-15--6"), # VOLKSWAGEN.GOLF ("MAZDA", "bd6a637565e91581|2021-10-30--15-14-53--4"), # MAZDA.CX9_2021 @@ -50,6 +51,7 @@ segments = [ ("RAM", "regen20490083AE7|2022-09-27--15-53-15--0"), ("SUBARU", "regen1E72BBDCED5|2022-09-27--15-55-31--0"), ("GM", "regen45B05A80EF6|2022-09-27--15-57-22--0"), + ("GM2", "376bf99325883932|2022-10-27--13-41-22--1"), ("NISSAN", "regenC19D899B46D|2022-09-27--15-59-13--0"), ("VOLKSWAGEN", "regenD8F7AC4BD0D|2022-09-27--16-41-45--0"), ("MAZDA", "regenFC3F9ECBB64|2022-09-27--16-03-09--0"), From ba570b963f18d96ac181882b1f4e1678b992f665 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Fri, 28 Oct 2022 05:48:40 +0800 Subject: [PATCH 35/59] Cabana: change the chart theme in setting (#26220) * change the chart theme in setting * change title colors * cleanup --- tools/cabana/chartswidget.cc | 27 ++++++++++++++++++++------- tools/cabana/chartswidget.h | 5 ++++- tools/cabana/settings.cc | 8 ++++++++ tools/cabana/settings.h | 3 +++ 4 files changed, 35 insertions(+), 8 deletions(-) diff --git a/tools/cabana/chartswidget.cc b/tools/cabana/chartswidget.cc index c7846de069..3f1dd890c3 100644 --- a/tools/cabana/chartswidget.cc +++ b/tools/cabana/chartswidget.cc @@ -200,33 +200,31 @@ ChartWidget::ChartWidget(const QString &id, const Signal *sig, QWidget *parent) main_layout->setSpacing(0); main_layout->setContentsMargins(0, 0, 0, 0); - QWidget *header = new QWidget(this); - header->setStyleSheet("background-color:white"); + header = new QWidget(this); QGridLayout *header_layout = new QGridLayout(header); header_layout->setContentsMargins(11, 11, 11, 0); msg_name_label = new QLabel(this); msg_name_label->setTextFormat(Qt::RichText); header_layout->addWidget(msg_name_label, 0, 0, Qt::AlignLeft); sig_name_label = new QLabel(this); - sig_name_label->setStyleSheet("font-weight:bold"); header_layout->addWidget(sig_name_label, 0, 1, Qt::AlignCenter); //, 0, Qt::AlignCenter); - QPushButton *remove_btn = new QPushButton("✖", this); + remove_btn = new QPushButton("✖", this); remove_btn->setFixedSize(20, 20); remove_btn->setToolTip(tr("Remove chart")); header_layout->addWidget(remove_btn, 0, 2, Qt::AlignRight); main_layout->addWidget(header); chart_view = new ChartView(id, sig, this); - chart_view->setFixedHeight(settings.chart_height); main_layout->addWidget(chart_view); main_layout->addStretch(); setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Fixed); updateTitle(); + updateFromSettings(); QObject::connect(remove_btn, &QPushButton::clicked, [=]() { emit remove(id, sig); }); - QObject::connect(&settings, &Settings::changed, [this]() { chart_view->setFixedHeight(settings.chart_height); }); + QObject::connect(&settings, &Settings::changed, this, &ChartWidget::updateFromSettings); } void ChartWidget::updateTitle() { @@ -234,12 +232,22 @@ void ChartWidget::updateTitle() { sig_name_label->setText(signal->name.c_str()); } +void ChartWidget::updateFromSettings() { + header->setStyleSheet(settings.chart_theme == 0 ? "background-color:white" : "background-color:#23242c"); + QString color_style = settings.chart_theme == 0 ? "color:black" : "color:white"; + sig_name_label->setStyleSheet("font-weight:bold;" + color_style); + msg_name_label->setStyleSheet(color_style); + remove_btn->setStyleSheet(color_style); + chart_view->updateFromSettings(); +} + // ChartView ChartView::ChartView(const QString &id, const Signal *sig, QWidget *parent) : id(id), signal(sig), QChartView(nullptr, parent) { QLineSeries *series = new QLineSeries(); QChart *chart = new QChart(); + chart->setBackgroundRoundness(0); chart->addSeries(series); chart->createDefaultAxes(); chart->legend()->hide(); @@ -254,7 +262,6 @@ ChartView::ChartView(const QString &id, const Signal *sig, QWidget *parent) value_text->setBrush(Qt::gray); line_marker = new QGraphicsLineItem(chart); line_marker->setZValue(chart->zValue() + 10); - line_marker->setPen(QPen(Qt::black, 2)); setChart(chart); @@ -277,6 +284,12 @@ ChartView::ChartView(const QString &id, const Signal *sig, QWidget *parent) }); } +void ChartView::updateFromSettings() { + setFixedHeight(settings.chart_height); + chart()->setTheme(settings.chart_theme == 0 ? QChart::ChartThemeLight : QChart::QChart::ChartThemeDark); + line_marker->setPen(QPen(settings.chart_theme == 0 ? Qt::black : Qt::white, 2)); +} + void ChartView::setRange(double min, double max, bool force_update) { auto axis_x = dynamic_cast(chart()->axisX()); if (force_update || (min != axis_x->min() || max != axis_x->max())) { diff --git a/tools/cabana/chartswidget.h b/tools/cabana/chartswidget.h index a7c6f4bbd3..897ed62c2f 100644 --- a/tools/cabana/chartswidget.h +++ b/tools/cabana/chartswidget.h @@ -23,6 +23,7 @@ public: void updateSeries(const std::pair &range); void setRange(double min, double max, bool force_update = false); void updateLineMarker(double current_sec); + void updateFromSettings(); signals: void zoomIn(double min, double max); @@ -34,7 +35,6 @@ private: void enterEvent(QEvent *event) override; void leaveEvent(QEvent *event) override; void adjustChartMargins(); - void updateAxisY(); QGraphicsLineItem *track_line; @@ -51,6 +51,7 @@ Q_OBJECT public: ChartWidget(const QString &id, const Signal *sig, QWidget *parent); void updateTitle(); + void updateFromSettings(); signals: void remove(const QString &msg_id, const Signal *sig); @@ -58,8 +59,10 @@ signals: public: QString id; const Signal *signal; + QWidget *header; QLabel *msg_name_label; QLabel *sig_name_label; + QPushButton *remove_btn; ChartView *chart_view = nullptr; }; diff --git a/tools/cabana/settings.cc b/tools/cabana/settings.cc index 6e9d7f17cc..93bc05f20b 100644 --- a/tools/cabana/settings.cc +++ b/tools/cabana/settings.cc @@ -17,6 +17,7 @@ void Settings::save() { s.setValue("log_size", can_msg_log_size); s.setValue("cached_segment", cached_segment_limit); s.setValue("chart_height", chart_height); + s.setValue("chart_theme", chart_theme); s.setValue("max_chart_x_range", max_chart_x_range); emit changed(); } @@ -27,6 +28,7 @@ void Settings::load() { can_msg_log_size = s.value("log_size", 100).toInt(); cached_segment_limit = s.value("cached_segment", 3).toInt(); chart_height = s.value("chart_height", 200).toInt(); + chart_theme = s.value("chart_theme", 0).toInt(); max_chart_x_range = s.value("max_chart_x_range", 3 * 60).toInt(); } @@ -67,6 +69,11 @@ SettingsDlg::SettingsDlg(QWidget *parent) : QDialog(parent) { chart_height->setValue(settings.chart_height); form_layout->addRow(tr("Chart's height"), chart_height); + chart_theme = new QComboBox(); + chart_theme->addItems({"Light", "Dark"}); + chart_theme->setCurrentIndex(settings.chart_theme == 1 ? 1 : 0); + form_layout->addRow(tr("Chart theme"), chart_theme); + main_layout->addLayout(form_layout); auto buttonBox = new QDialogButtonBox(QDialogButtonBox::Ok | QDialogButtonBox::Cancel); @@ -82,6 +89,7 @@ void SettingsDlg::save() { settings.can_msg_log_size = log_size->value(); settings.cached_segment_limit = cached_segment->value(); settings.chart_height = chart_height->value(); + settings.chart_theme = chart_theme->currentIndex(); settings.max_chart_x_range = max_chart_x_range->value() * 60; settings.save(); accept(); diff --git a/tools/cabana/settings.h b/tools/cabana/settings.h index fa97c49140..88eeebc722 100644 --- a/tools/cabana/settings.h +++ b/tools/cabana/settings.h @@ -1,5 +1,6 @@ #pragma once +#include #include #include @@ -15,6 +16,7 @@ public: int can_msg_log_size = 100; int cached_segment_limit = 3; int chart_height = 200; + int chart_theme = 0; int max_chart_x_range = 3 * 60; // 3 minutes signals: @@ -31,6 +33,7 @@ public: QSpinBox *log_size ; QSpinBox *cached_segment; QSpinBox *chart_height; + QComboBox *chart_theme; QSpinBox *max_chart_x_range; }; From b158c016cbd58a84e57124f49c657dbba8beb19e Mon Sep 17 00:00:00 2001 From: Vivek Aithal Date: Thu, 27 Oct 2022 16:34:11 -0700 Subject: [PATCH 36/59] [torqued] Update offline values (#26261) * add qlog mode to torqued * update offline valujes from qlogs * resollve comments * update refs * resolve comments --- selfdrive/car/torque_data/override.yaml | 1 - selfdrive/car/torque_data/params.yaml | 29 ++++++++++++------------ selfdrive/locationd/torqued.py | 23 ++++++++++++++----- selfdrive/test/process_replay/ref_commit | 2 +- 4 files changed, 33 insertions(+), 22 deletions(-) diff --git a/selfdrive/car/torque_data/override.yaml b/selfdrive/car/torque_data/override.yaml index 13a0dae7a7..460b9a9097 100644 --- a/selfdrive/car/torque_data/override.yaml +++ b/selfdrive/car/torque_data/override.yaml @@ -21,7 +21,6 @@ FORD FOCUS 4TH GEN: [.nan, 1.5, .nan] COMMA BODY: [.nan, 1000, .nan] # Totally new cars -KIA EV6 2022: [3.5, 3.0, 0.0] RAM 1500 5TH GEN: [2.0, 2.0, 0.0] RAM HD 5TH GEN: [1.4, 1.4, 0.0] SUBARU OUTBACK 6TH GEN: [2.3, 2.3, 0.11] diff --git a/selfdrive/car/torque_data/params.yaml b/selfdrive/car/torque_data/params.yaml index 60b1662cee..5c828fa669 100644 --- a/selfdrive/car/torque_data/params.yaml +++ b/selfdrive/car/torque_data/params.yaml @@ -39,17 +39,18 @@ HYUNDAI SONATA 2020: [2.9638737459977467, 2.1259108157250735, 0.0781366561692759 HYUNDAI SONATA HYBRID 2021: [2.8990264092395734, 2.061410192222139, 0.0899805488717382] JEEP GRAND CHEROKEE 2019: [1.7321233388827006, 1.289689569171081, 0.15046331002097185] JEEP GRAND CHEROKEE V6 2018: [1.8776598027756923, 1.4057367824262523, 0.11725947414922003] +KIA EV6 2022: [3.2, 3.0, 0.05] KIA K5 2021: [2.405339728085138, 1.460032270828705, 0.11650989850813716] KIA NIRO EV 2020: [2.9215954981365337, 2.1500583840260044, 0.09236802474810267] KIA SORENTO GT LINE 2018: [2.464854685101844, 1.5335274218367956, 0.12056170567599558] KIA STINGER GT2 2018: [2.7499043387418967, 1.849652021986449, 0.12048334239559202] -LEXUS ES 2019: [2.0203086922726112, 2.134803912579666, 0.12757526789308554] -LEXUS ES HYBRID 2019: [2.392442298703042, 1.863360677810788, 0.17690002108856212] +LEXUS ES 2019: [1.935835, 2.134803912579666, 0.093439] +LEXUS ES HYBRID 2019: [2.135678, 1.863360677810788, 0.109627] LEXUS NX 2018: [2.302625600642627, 2.1382378491466625, 0.14986840878892838] LEXUS NX 2020: [2.4331999786982936, 2.1045680431705414, 0.14099899317761067] LEXUS NX HYBRID 2018: [2.4025593501080955, 1.8080446063815507, 0.15349361249519017] LEXUS RX 2016: [1.5876816543130423, 1.0427699298523752, 0.21334066732397142] -LEXUS RX 2020: [1.5228812994274734, 1.431102486563665, 0.2093316728710659] +LEXUS RX 2020: [1.5228812994274734, 1.431102486563665, 0.164117] LEXUS RX HYBRID 2017: [1.6984261557042386, 1.3211501880159107, 0.1820354534928893] LEXUS RX HYBRID 2020: [1.5522309889823778, 1.255230465866663, 0.2220954003055114] MAZDA CX-9 2021: [1.7601682915983443, 1.0889677335154337, 0.17713792194297195] @@ -62,31 +63,31 @@ TOYOTA AVALON 2019: [1.7036141952825095, 1.239619084240008, 0.08459830394899492] TOYOTA AVALON 2022: [2.3154403649717357, 2.7777922854327124, 0.11453999639164605] TOYOTA C-HR 2018: [1.5591084333664578, 1.271271459066948, 0.20259087058453193] TOYOTA C-HR 2021: [1.7678810166088303, 1.3742176337919942, 0.2319674583741509] -TOYOTA CAMRY 2018: [2.1172995371905015, 1.7156177222420887, 0.13519250664782062] -TOYOTA CAMRY 2021: [2.6922769557433055, 2.3476510120007434, 0.1450430192989234] -TOYOTA CAMRY HYBRID 2018: [2.0974120828287774, 1.7996193116697359, 0.13823613467632756] -TOYOTA CAMRY HYBRID 2021: [2.6426668350384457, 2.3901492458927986, 0.16103875108816076] +TOYOTA CAMRY 2018: [2.1172995371905015, 1.7156177222420887, 0.105192506] +TOYOTA CAMRY 2021: [2.446083, 2.3476510120007434, 0.121615] +TOYOTA CAMRY HYBRID 2018: [1.996333, 1.7996193116697359, 0.112565] +TOYOTA CAMRY HYBRID 2021: [2.263582, 2.3901492458927986, 0.115257] TOYOTA COROLLA 2017: [3.117154369115421, 1.8438132575043773, 0.12289685869250652] TOYOTA COROLLA HYBRID TSS2 2019: [1.9079729107361805, 1.8118712531729109, 0.22251440891543514] TOYOTA COROLLA TSS2 2019: [2.0742917676766712, 1.9258612322678952, 0.16888685704519352] TOYOTA HIGHLANDER 2017: [1.8696367437248915, 1.626293990451463, 0.17485372210240796] TOYOTA HIGHLANDER 2020: [2.022340166827233, 1.6183134804881791, 0.14592306380054457] -TOYOTA HIGHLANDER HYBRID 2018: [1.9421825202382728, 1.6433903296845025, 0.16928956792275918] -TOYOTA HIGHLANDER HYBRID 2020: [2.103373061114133, 2.104015182965606, 0.14447040132184993] +TOYOTA HIGHLANDER HYBRID 2018: [1.752033, 1.6433903296845025, 0.144600] +TOYOTA HIGHLANDER HYBRID 2020: [1.901174, 2.104015182965606, 0.14447040132184993] TOYOTA MIRAI 2021: [2.506899832157829, 1.7417213930750164, 0.20182618449440565] -TOYOTA PRIUS 2017: [2.0183401513314294, 1.5023147650693636, 0.20856908464957724] -TOYOTA PRIUS TSS2 2021: [2.327639738920072, 1.9104337425537743, 0.2030762265549664] +TOYOTA PRIUS 2017: [1.746445, 1.5023147650693636, 0.151515] +TOYOTA PRIUS TSS2 2021: [1.972600, 1.9104337425537743, 0.170968] TOYOTA RAV4 2017: [2.085695074355425, 2.2142832316984733, 0.13339165270103975] -TOYOTA RAV4 2019: [2.5038362866776835, 2.0993589721530252, 0.1552425356342368] +TOYOTA RAV4 2019: [2.331293, 2.0993589721530252, 0.129822] TOYOTA RAV4 2019 8965: [2.5084506298290377, 2.4216520504763475, 0.11992835265067918] TOYOTA RAV4 2019 x02: [2.7209621987605024, 2.2148637653781593, 0.10862567142268198] TOYOTA RAV4 HYBRID 2017: [1.9796257271652042, 1.7503987331707576, 0.14628860048885406] TOYOTA RAV4 HYBRID 2019: [2.2271858492309153, 2.074844961405639, 0.14382216826893632] TOYOTA RAV4 HYBRID 2019 8965: [2.1077397198131336, 1.8162215166877735, 0.13891369391200137] TOYOTA RAV4 HYBRID 2019 x02: [2.803624333289342, 2.272367966572498, 0.11364569214387774] -TOYOTA RAV4 HYBRID 2022: [2.241883248393209, 1.9304407208090029, 0.1565442715453653] +TOYOTA RAV4 HYBRID 2022: [2.241883248393209, 1.9304407208090029, 0.112174] TOYOTA RAV4 HYBRID 2022 x02: [3.044930631831037, 2.3979189796380918, 0.14023209146703736] -TOYOTA SIENNA 2018: [1.8660896232147548, 1.3208264576110418, 0.18799149615227198] +TOYOTA SIENNA 2018: [1.689726, 1.3208264576110418, 0.140456] VOLKSWAGEN ARTEON 1ST GEN: [1.45136518053819, 1.3639364049316804, 0.23806361745695032] VOLKSWAGEN ATLAS 1ST GEN: [1.4677006726964945, 1.6733266634075656, 0.12959584092073367] VOLKSWAGEN GOLF 7TH GEN: [1.3750394140491293, 1.5814743077200641, 0.2018321939386586] diff --git a/selfdrive/locationd/torqued.py b/selfdrive/locationd/torqued.py index 66af234590..42dff60087 100755 --- a/selfdrive/locationd/torqued.py +++ b/selfdrive/locationd/torqued.py @@ -16,7 +16,9 @@ from selfdrive.controls.lib.vehicle_model import ACCELERATION_DUE_TO_GRAVITY HISTORY = 5 # secs POINTS_PER_BUCKET = 1500 MIN_POINTS_TOTAL = 4000 +MIN_POINTS_TOTAL_QLOG = 800 FIT_POINTS_TOTAL = 2000 +FIT_POINTS_TOTAL_QLOG = 800 MIN_VEL = 15 # m/s FRICTION_FACTOR = 1.5 # ~85% of data coverage FACTOR_SANITY = 0.3 @@ -26,7 +28,7 @@ MIN_FILTER_DECAY = 50 MAX_FILTER_DECAY = 250 LAT_ACC_THRESHOLD = 1 STEER_BUCKET_BOUNDS = [(-0.5, -0.3), (-0.3, -0.2), (-0.2, -0.1), (-0.1, 0), (0, 0.1), (0.1, 0.2), (0.2, 0.3), (0.3, 0.5)] -MIN_BUCKET_POINTS = [100, 300, 500, 500, 500, 500, 300, 100] +MIN_BUCKET_POINTS = np.array([100, 300, 500, 500, 500, 500, 300, 100]) MAX_RESETS = 5.0 MAX_INVALID_THRESHOLD = 10 MIN_ENGAGE_BUFFER = 2 # secs @@ -58,10 +60,11 @@ class NPQueue: class PointBuckets: - def __init__(self, x_bounds, min_points): + def __init__(self, x_bounds, min_points, min_points_total): self.x_bounds = x_bounds self.buckets = {bounds: NPQueue(maxlen=POINTS_PER_BUCKET, rowsize=3) for bounds in x_bounds} self.buckets_min_points = {bounds: min_point for bounds, min_point in zip(x_bounds, min_points)} + self.min_points_total = min_points_total def bucket_lengths(self): return [len(v) for v in self.buckets.values()] @@ -70,7 +73,7 @@ class PointBuckets: return sum(self.bucket_lengths()) def is_valid(self): - return all(len(v) >= min_pts for v, min_pts in zip(self.buckets.values(), self.buckets_min_points.values())) and (self.__len__() >= MIN_POINTS_TOTAL) + return all(len(v) >= min_pts for v, min_pts in zip(self.buckets.values(), self.buckets_min_points.values())) and (self.__len__() >= self.min_points_total) def add_point(self, x, y): for bound_min, bound_max in self.x_bounds: @@ -90,9 +93,17 @@ class PointBuckets: class TorqueEstimator: - def __init__(self, CP): + def __init__(self, CP, decimated=False): self.hist_len = int(HISTORY / DT_MDL) self.lag = CP.steerActuatorDelay + .2 # from controlsd + if decimated: + self.min_bucket_points = MIN_BUCKET_POINTS / 10 + self.min_points_total = MIN_POINTS_TOTAL_QLOG + self.fit_points = FIT_POINTS_TOTAL_QLOG + else: + self.min_bucket_points = MIN_BUCKET_POINTS + self.min_points_total = MIN_POINTS_TOTAL + self.fit_points = FIT_POINTS_TOTAL self.offline_friction = 0.0 self.offline_latAccelFactor = 0.0 @@ -157,10 +168,10 @@ class TorqueEstimator: self.invalid_values_tracker = 0.0 self.decay = MIN_FILTER_DECAY self.raw_points = defaultdict(lambda: deque(maxlen=self.hist_len)) - self.filtered_points = PointBuckets(x_bounds=STEER_BUCKET_BOUNDS, min_points=MIN_BUCKET_POINTS) + self.filtered_points = PointBuckets(x_bounds=STEER_BUCKET_BOUNDS, min_points=self.min_bucket_points, min_points_total=self.min_points_total) def estimate_params(self): - points = self.filtered_points.get_points(FIT_POINTS_TOTAL) + points = self.filtered_points.get_points(self.fit_points) # total least square solution as both x and y are noisy observations # this is empirically the slope of the hysteresis parallelogram as opposed to the line through the diagonals try: diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index a3ca4163d5..fad9f5e598 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -fbafde6f1c46b50c219c3ec3121b94ee0848a7be \ No newline at end of file +f4ea2499a95e198914fd275a8380178e8ff65a31 \ No newline at end of file From c2326a421993534c49aea1efa78e31a6bfa0625c Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 27 Oct 2022 16:44:22 -0700 Subject: [PATCH 37/59] process replay: support experimental long (#26233) Support experimental long --- selfdrive/test/process_replay/process_replay.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index 9d37be4a56..bc55e33cbf 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -456,6 +456,9 @@ def setup_env(simulation=False, CP=None, cfg=None, controlsState=None): os.environ['SKIP_FW_QUERY'] = "1" os.environ['FINGERPRINT'] = CP.carFingerprint + if CP.openpilotLongitudinalControl: + params.put_bool("ExperimentalLongitudinalEnabled", True) + def python_replay_process(cfg, lr, fingerprint=None): sub_sockets = [s for _, sub in cfg.pub_sub.items() for s in sub] From 26cb6d09e76baaf0862cdf061013247bb62a197c Mon Sep 17 00:00:00 2001 From: ambientocclusion <1399123+ambientocclusion@users.noreply.github.com> Date: Thu, 27 Oct 2022 17:04:09 -0700 Subject: [PATCH 38/59] Multilang: revise some Japanese translations (#25811) Revise some Japanese translations Co-authored-by: Shane Smiskol --- selfdrive/ui/translations/main_ja.ts | 54 ++++++++++++++-------------- 1 file changed, 27 insertions(+), 27 deletions(-) diff --git a/selfdrive/ui/translations/main_ja.ts b/selfdrive/ui/translations/main_ja.ts index 314a6b8338..a11333a54d 100644 --- a/selfdrive/ui/translations/main_ja.ts +++ b/selfdrive/ui/translations/main_ja.ts @@ -56,7 +56,7 @@ leave blank for automatic configuration - 空白のままにして、自動設定にします + 自動で設定するには、空白のままにしてください。 Cellular Metered @@ -136,7 +136,7 @@ PREVIEW - 見る + プレビュー Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off) @@ -156,7 +156,7 @@ Review Training Guide - 入門書を見る + 使い方の確認 REVIEW @@ -168,7 +168,7 @@ Are you sure you want to review the training guide? - 入門書を見てもよろしいですか? + 使い方の確認をしますか? Regulatory @@ -200,11 +200,11 @@ openpilot requires the device to be mounted within 4° left or right and within 5° up or 8° down. openpilot is continuously calibrating, resetting is rarely required. - openpilot は、左または右の4°以内、上の5°または下の8°以内にデバイスを取付ける必要があります。キャリブレーションを引き続きます、リセットはほとんど必要ありません。 + openpilotの本体は、左右4°以内、上5°、下8°以内の角度で取付ける必要があります。継続してキャリブレーションを続けているので、手動でリセットを行う必要はほぼありません。 Your device is pointed %1° %2 and %3° %4. - このデバイスは%2の%1°、%4の%3°に向けます。 + このデバイスは%2 %1°、%4 %3°の向きに設置されています。 down @@ -309,7 +309,7 @@ MapETA eta - 予定到着時間 + 到着予定時間 min @@ -452,15 +452,15 @@ location set Go to https://connect.comma.ai on your phone - モバイルデバイスで「connect.comma.ai」にアクセスして + スマートフォンで「https://connect.comma.ai」にアクセスしてください。 Click "add new device" and scan the QR code on the right - 「新しいデバイスを追加」を押すと、右側のQRコードをスキャンしてください + 「新しいデバイスを追加」を押し、右側のQRコードをスキャンしてください。 Bookmark connect.comma.ai to your home screen to use it like an app - 「connect.comma.ai」をホーム画面に追加して、アプリのように使うことができます + 「connect.comma.ai」をホーム画面に追加して、アプリのように使うことができます。 @@ -608,7 +608,7 @@ location set Toggles - 切り替え + 機能設定 Software @@ -627,7 +627,7 @@ location set Power your device in a car with a harness or proceed at your own risk. - 自己責任でハーネスから電源を供給してください。 + 自己責任で実行を継続するか、ハーネスから電源を供給してください。 Power off @@ -643,7 +643,7 @@ location set Before we get on the road, let’s finish installation and cover some details. - その前に、インストールを完了し、いくつかの詳細を説明します。 + 道路に向かう前に、インストールを完了して使い方を確認しましょう。 Connect to Wi-Fi @@ -655,7 +655,7 @@ location set Continue without Wi-Fi - Wi-Fi に未接続で続行 + Wi-Fi に接続せずに続行 Waiting for internet @@ -663,7 +663,7 @@ location set Choose Software to Install - インストールするソフトウェアを選びます + インストールするソフトウェアを選択してください Dashcam @@ -710,7 +710,7 @@ location set Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer. - デバイスを comma connect (connect.comma.ai)でペアリングし comma prime 特典を申請してください。 + デバイスを comma connect (connect.comma.ai)でペアリングし、comma primeの特典を申請してください。 Pair device @@ -836,7 +836,7 @@ location set UNINSTALL - アンインストール + 実行 Uninstall %1 @@ -859,7 +859,7 @@ location set Warning: This grants SSH access to all public keys in your GitHub settings. Never enter a GitHub username other than your own. A comma employee will NEVER ask you to add their GitHub username. - 警告: これは、GitHub の設定にあるすべての公開鍵への SSH アクセスを許可するものです。自分以外の GitHub のユーザー名を入力しないでください。コンマのスタッフが GitHub のユーザー名を追加するようお願いすることはありません。 + 警告: これは、GitHub の設定にあるすべての公開鍵への SSH アクセスを許可するものです。自分以外の GitHub のユーザー名を入力しないでください。commaのスタッフが GitHub のユーザー名を追加するようお願いすることはありません。 ADD @@ -871,7 +871,7 @@ location set LOADING - ローディング + 読み込み中 REMOVE @@ -924,7 +924,7 @@ location set Use the openpilot system for adaptive cruise control and lane keep driver assistance. Your attention is required at all times to use this feature. Changing this setting takes effect when the car is powered off. - アダプティブクルーズコントロールとレーンキーピングドライバーアシスト(openpilotシステム)。この機能を使用するには、常に注意が必要です。この設定を変更すると、車の電源が切れたときに有効になります。 + openpilotによるアダプティブクルーズコントロールとレーンキーピングドライバーアシストを利用します。この機能を利用する際は、常に前方への注意が必要です。この設定を変更すると、車の電源が切れた時に反映されます。 Enable Lane Departure Warnings @@ -932,11 +932,11 @@ location set Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31 mph (50 km/h). - 時速31マイル(50km)を超えるスピードで走行中、ウインカーを作動させずに検出された車線ライン上に車両が触れた場合、車線に戻るアラートを受信します。 + 時速31マイル(50km)を超えるスピードで走行中、ウインカーを作動させずに検出された車線ライン上に車両が触れた場合、手動で車線内に戻るように警告を行います。 Use Metric System - メートル法を有効化 + メートル法を使用 Display speed in km/h instead of mph. @@ -952,7 +952,7 @@ location set 🌮 End-to-end longitudinal (extremely alpha) 🌮 - 🌮 エンドツーエンドのアクセル制御 (超アルファ版) 🌮 + 🌮 エンドツーエンドのアクセル制御 (超α版) 🌮 Experimental openpilot longitudinal control @@ -976,11 +976,11 @@ location set Disengage On Accelerator Pedal - アクセル踏むと openpilot をキャンセル + アクセルを踏むと openpilot を中断 When enabled, pressing the accelerator pedal will disengage openpilot. - 有効な場合は、アクセルを踏むと openpilot をキャンセルします。 + この機能を有効化すると、openpilotを利用中にアクセルを踏むとopenpilotによる運転サポートを中断します。 Show ETA in 24h Format @@ -1003,11 +1003,11 @@ location set Updater Update Required - 更新が必要です + アップデートが必要です An operating system update is required. Connect your device to Wi-Fi for the fastest update experience. The download size is approximately 1GB. - オペレーティングシステムのアップデートが必要です。Wi-Fi に接続することで、最速のアップデートを体験できます。ダウンロードサイズは約 1GB です。 + オペレーティングシステムのアップデートが必要です。Wi-Fi に接続してアップデートする事をお勧めします。ダウンロードサイズは約 1GB です。 Connect to Wi-Fi From dbc30c053caacc689e1fafb5e92ff0fcac57db1d Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Thu, 27 Oct 2022 17:27:31 -0700 Subject: [PATCH 39/59] UI: fade into wide camera (#26203) * UI: fade into wide camera * handle routes with no wide calib * more cleanup Co-authored-by: Adeeb Shihadeh --- selfdrive/locationd/calibrationd.py | 7 +------ selfdrive/ui/qt/onroad.cc | 8 +++----- selfdrive/ui/qt/widgets/cameraview.cc | 11 ++++++++--- selfdrive/ui/ui.cc | 27 ++++++++++++++++++++++----- selfdrive/ui/ui.h | 4 +++- 5 files changed, 37 insertions(+), 20 deletions(-) diff --git a/selfdrive/locationd/calibrationd.py b/selfdrive/locationd/calibrationd.py index 4e996bc3b9..1c68eb67bd 100755 --- a/selfdrive/locationd/calibrationd.py +++ b/selfdrive/locationd/calibrationd.py @@ -66,7 +66,6 @@ class Calibrator: # Read saved calibration params = Params() calibration_params = params.get("CalibrationParams") - self.wide_camera = params.get_bool('WideCameraOnly') rpy_init = RPY_INIT wide_from_device_euler = WIDE_FROM_DEVICE_EULER_INIT valid_blocks = 0 @@ -166,10 +165,7 @@ class Calibrator: self.old_rpy_weight = min(0.0, self.old_rpy_weight - 1/SMOOTH_CYCLES) straight_and_fast = ((self.v_ego > MIN_SPEED_FILTER) and (trans[0] > MIN_SPEED_FILTER) and (abs(rot[2]) < MAX_YAW_RATE_FILTER)) - if self.wide_camera: - angle_std_threshold = 4*MAX_VEL_ANGLE_STD - else: - angle_std_threshold = MAX_VEL_ANGLE_STD + angle_std_threshold = MAX_VEL_ANGLE_STD certain_if_calib = ((np.arctan2(trans_std[1], trans[0]) < angle_std_threshold) or (self.valid_blocks < INPUTS_NEEDED)) if not (straight_and_fast and certain_if_calib): @@ -185,7 +181,6 @@ class Calibrator: new_wide_from_device_euler = np.array(wide_from_device_euler) else: new_wide_from_device_euler = WIDE_FROM_DEVICE_EULER_INIT - self.rpys[self.block_idx] = (self.idx*self.rpys[self.block_idx] + (BLOCK_SIZE - self.idx) * new_rpy) / float(BLOCK_SIZE) self.wide_from_device_eulers[self.block_idx] = (self.idx*self.wide_from_device_eulers[self.block_idx] + diff --git a/selfdrive/ui/qt/onroad.cc b/selfdrive/ui/qt/onroad.cc index 1f677fc92d..346cb3ab96 100644 --- a/selfdrive/ui/qt/onroad.cc +++ b/selfdrive/ui/qt/onroad.cc @@ -100,10 +100,6 @@ void OnroadWindow::offroadTransition(bool offroad) { #endif alerts->updateAlert({}, bg); - - // update stream type - bool wide_cam = Params().getBool("WideCameraOnly"); - nvg->setStreamType(wide_cam ? VISION_STREAM_WIDE_ROAD : VISION_STREAM_ROAD); } void OnroadWindow::paintEvent(QPaintEvent *event) { @@ -232,8 +228,10 @@ void AnnotatedCameraWidget::updateState(const UIState &s) { setProperty("rightHandDM", sm["driverMonitoringState"].getDriverMonitoringState().getIsRHD()); } + setStreamType(s.scene.wide_cam ? VISION_STREAM_WIDE_ROAD : VISION_STREAM_ROAD); if (s.scene.calibration_valid) { - CameraWidget::updateCalibration(s.scene.view_from_calib); + auto calib = s.scene.wide_cam ? s.scene.view_from_wide_calib : s.scene.view_from_calib; + CameraWidget::updateCalibration(calib); } else { CameraWidget::updateCalibration(DEFAULT_CALIBRATION); } diff --git a/selfdrive/ui/qt/widgets/cameraview.cc b/selfdrive/ui/qt/widgets/cameraview.cc index 4f46497776..13225414d0 100644 --- a/selfdrive/ui/qt/widgets/cameraview.cc +++ b/selfdrive/ui/qt/widgets/cameraview.cc @@ -188,12 +188,17 @@ void CameraWidget::updateFrameMat() { if (stream_type == VISION_STREAM_DRIVER) { frame_mat = get_driver_view_transform(w, h, stream_width, stream_height); } else { - intrinsic_matrix = (stream_type == VISION_STREAM_WIDE_ROAD) ? ecam_intrinsic_matrix : fcam_intrinsic_matrix; - zoom = (stream_type == VISION_STREAM_WIDE_ROAD) ? 2.5 : 1.1; - // Project point at "infinity" to compute x and y offsets // to ensure this ends up in the middle of the screen + // for narrow come and a little lower for wide cam. // TODO: use proper perspective transform? + if (stream_type == VISION_STREAM_WIDE_ROAD) { + intrinsic_matrix = ecam_intrinsic_matrix; + zoom = 2.0; + } else { + intrinsic_matrix = fcam_intrinsic_matrix; + zoom = 1.1; + } const vec3 inf = {{1000., 0., 0.}}; const vec3 Ep = matvecmul3(calibration, inf); const vec3 Kep = matvecmul3(intrinsic_matrix, Ep); diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index 1a6027bf7f..d1d72b4dad 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -23,8 +23,8 @@ static bool calib_frame_to_full_frame(const UIState *s, float in_x, float in_y, const QRectF clip_region{-margin, -margin, s->fb_w + 2 * margin, s->fb_h + 2 * margin}; const vec3 pt = (vec3){{in_x, in_y, in_z}}; - const vec3 Ep = matvecmul3(s->scene.view_from_calib, pt); - const vec3 KEp = matvecmul3(s->wide_camera ? ecam_intrinsic_matrix : fcam_intrinsic_matrix, Ep); + const vec3 Ep = matvecmul3(s->scene.wide_cam ? s->scene.view_from_wide_calib : s->scene.view_from_calib, pt); + const vec3 KEp = matvecmul3(s->scene.wide_cam ? ecam_intrinsic_matrix : fcam_intrinsic_matrix, Ep); // Project. QPointF point = s->car_space_transform.map(QPointF{KEp.v[0] / KEp.v[2], KEp.v[1] / KEp.v[2]}); @@ -121,17 +121,23 @@ static void update_state(UIState *s) { if (sm.updated("liveCalibration")) { auto rpy_list = sm["liveCalibration"].getLiveCalibration().getRpyCalib(); + auto wfde_list = sm["liveCalibration"].getLiveCalibration().getWideFromDeviceEuler(); Eigen::Vector3d rpy; - rpy << rpy_list[0], rpy_list[1], rpy_list[2]; + Eigen::Vector3d wfde; + if (rpy_list.size() == 3) rpy << rpy_list[0], rpy_list[1], rpy_list[2]; + if (wfde_list.size() == 3) wfde << wfde_list[0], wfde_list[1], wfde_list[2]; Eigen::Matrix3d device_from_calib = euler2rot(rpy); + Eigen::Matrix3d wide_from_device = euler2rot(wfde); Eigen::Matrix3d view_from_device; view_from_device << 0,1,0, 0,0,1, 1,0,0; Eigen::Matrix3d view_from_calib = view_from_device * device_from_calib; + Eigen::Matrix3d view_from_wide_calib = view_from_device * wide_from_device * device_from_calib ; for (int i = 0; i < 3; i++) { for (int j = 0; j < 3; j++) { scene.view_from_calib.v[i*3 + j] = view_from_calib(i,j); + scene.view_from_wide_calib.v[i*3 + j] = view_from_wide_calib(i,j); } } scene.calibration_valid = sm["liveCalibration"].getLiveCalibration().getCalStatus() == 1; @@ -167,6 +173,17 @@ static void update_state(UIState *s) { scene.light_sensor = std::max(100.0f - scale * sm["wideRoadCameraState"].getWideRoadCameraState().getExposureValPercent(), 0.0f); } scene.started = sm["deviceState"].getDeviceState().getStarted() && scene.ignition; + + if (sm.updated("carState")) { + float v_ego = sm["carState"].getCarState().getVEgo(); + // TODO: support replays without ecam by using fcam + // Wide or narrow cam dependent on speed + if ((v_ego < 10) || s->wide_cam_only) { + scene.wide_cam = true; + } else if (v_ego > 15) { + scene.wide_cam = false; + } + } } void ui_update_params(UIState *s) { @@ -197,7 +214,7 @@ void UIState::updateStatus() { if (scene.started) { status = STATUS_DISENGAGED; scene.started_frame = sm->frame; - wide_camera = Params().getBool("WideCameraOnly"); + wide_cam_only = Params().getBool("WideCameraOnly"); } started_prev = scene.started; emit offroadTransition(!scene.started); @@ -219,7 +236,7 @@ UIState::UIState(QObject *parent) : QObject(parent) { }); Params params; - wide_camera = params.getBool("WideCameraOnly"); + wide_cam_only = params.getBool("WideCameraOnly"); prime_type = std::atoi(params.get("PrimeType").c_str()); language = QString::fromStdString(params.get("LanguageSetting")); diff --git a/selfdrive/ui/ui.h b/selfdrive/ui/ui.h index f60c26b59a..5a51dda8f8 100644 --- a/selfdrive/ui/ui.h +++ b/selfdrive/ui/ui.h @@ -87,7 +87,9 @@ const QColor bg_colors [] = { typedef struct UIScene { bool calibration_valid = false; + bool wide_cam = true; mat3 view_from_calib = DEFAULT_CALIBRATION; + mat3 view_from_wide_calib = DEFAULT_CALIBRATION; cereal::PandaState::PandaType pandaType; // modelV2 @@ -130,7 +132,7 @@ public: QString language; QTransform car_space_transform; - bool wide_camera; + bool wide_cam_only; signals: void uiUpdate(const UIState &s); From f76a390daf677700fbce49253f93412dd44eee0d Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Thu, 27 Oct 2022 17:31:15 -0700 Subject: [PATCH 40/59] Eliminate toyota close radar glitches causing no resume (#26272) Eliminate toyota close radar glitches --- selfdrive/controls/lib/radar_helpers.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/selfdrive/controls/lib/radar_helpers.py b/selfdrive/controls/lib/radar_helpers.py index bf788190cd..4bb0179267 100644 --- a/selfdrive/controls/lib/radar_helpers.py +++ b/selfdrive/controls/lib/radar_helpers.py @@ -151,7 +151,8 @@ class Cluster(): def potential_low_speed_lead(self, v_ego): # stop for stuff in front of you and low speed, even without model confirmation - return abs(self.yRel) < 1.0 and (v_ego < v_ego_stationary) and self.dRel < 25 + # Radar points closer than 0.75, are almost always glitches on toyota radars + return abs(self.yRel) < 1.0 and (v_ego < v_ego_stationary) and (0.75 < self.dRel < 25) def is_potential_fcw(self, model_prob): return model_prob > .9 From 6698cd48294e94fdb4e09e8943e6505efa29c5d5 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 27 Oct 2022 20:53:15 -0700 Subject: [PATCH 41/59] controlsd: steer in old preEnable state (#26269) * controlsd: steer in old preEnable state * bump panda * bump panda * Update ref_commit Co-authored-by: Shane Smiskol --- panda | 2 +- selfdrive/controls/controlsd.py | 3 +-- selfdrive/test/process_replay/ref_commit | 2 +- 3 files changed, 3 insertions(+), 4 deletions(-) diff --git a/panda b/panda index bd8d2481dd..187fdee385 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit bd8d2481dd071df62263e093b2e332a2a404dc87 +Subproject commit 187fdee385e59a2a19f85760f529e8e381845dff diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 5172cc4044..1adbba4171 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -254,8 +254,7 @@ class Controls: self.events.add(EventName.pedalPressed) if CS.gasPressed: - self.events.add(EventName.pedalPressedPreEnable if self.disengage_on_accelerator else - EventName.gasPressedOverride) + self.events.add(EventName.gasPressedOverride) if not self.CP.notCar: self.events.add_from_msg(self.sm['driverMonitoringState'].events) diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index fad9f5e598..c7d81c3496 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -f4ea2499a95e198914fd275a8380178e8ff65a31 \ No newline at end of file +e56c5a6ac5b87ee6083c9f92921e7198591f7b5d From 8de9bbaa73ea94b966b1161fb630bf3cac72c764 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Sat, 29 Oct 2022 01:55:05 +0800 Subject: [PATCH 42/59] Cabana: improve track line (#26231) * improve track line * show text label on the left if reach the right edge * cleanup * cleanup --- tools/cabana/chartswidget.cc | 42 ++++++++++++++++++++++-------------- tools/cabana/chartswidget.h | 6 ++++-- 2 files changed, 30 insertions(+), 18 deletions(-) diff --git a/tools/cabana/chartswidget.cc b/tools/cabana/chartswidget.cc index 3f1dd890c3..a3cbaf5b30 100644 --- a/tools/cabana/chartswidget.cc +++ b/tools/cabana/chartswidget.cc @@ -147,7 +147,7 @@ void ChartsWidget::addChart(const QString &id, const Signal *sig) { if (it == charts.end()) { auto chart = new ChartWidget(id, sig, this); chart->chart_view->updateSeries(display_range); - QObject::connect(chart, &ChartWidget::remove, [=]() { removeChart(chart); });; + QObject::connect(chart, &ChartWidget::remove, [=]() { removeChart(chart); }); QObject::connect(chart->chart_view, &ChartView::zoomIn, this, &ChartsWidget::zoomIn); QObject::connect(chart->chart_view, &ChartView::zoomReset, this, &ChartsWidget::zoomReset); charts_layout->insertWidget(0, chart); @@ -184,7 +184,6 @@ void ChartsWidget::signalUpdated(const Signal *sig) { } } - bool ChartsWidget::eventFilter(QObject *obj, QEvent *event) { if (obj != this && event->type() == QEvent::Close) { emit dock_btn->clicked(); @@ -256,10 +255,12 @@ ChartView::ChartView(const QString &id, const Signal *sig, QWidget *parent) track_line = new QGraphicsLineItem(chart); track_line->setZValue(chart->zValue() + 10); - track_line->setPen(QPen(Qt::gray, 1, Qt::DashLine)); - value_text = new QGraphicsSimpleTextItem(chart); + track_line->setPen(QPen(Qt::darkGray, 1, Qt::DashLine)); + track_ellipse = new QGraphicsEllipseItem(chart); + track_ellipse->setZValue(chart->zValue() + 10); + track_ellipse->setBrush(Qt::darkGray); + value_text = new QGraphicsTextItem(chart); value_text->setZValue(chart->zValue() + 10); - value_text->setBrush(Qt::gray); line_marker = new QGraphicsLineItem(chart); line_marker->setZValue(chart->zValue() + 10); @@ -364,12 +365,14 @@ void ChartView::updateAxisY() { void ChartView::enterEvent(QEvent *event) { track_line->setVisible(true); value_text->setVisible(true); + track_ellipse->setVisible(true); QChartView::enterEvent(event); } void ChartView::leaveEvent(QEvent *event) { track_line->setVisible(false); value_text->setVisible(false); + track_ellipse->setVisible(false); QChartView::leaveEvent(event); } @@ -397,21 +400,28 @@ void ChartView::mouseReleaseEvent(QMouseEvent *event) { void ChartView::mouseMoveEvent(QMouseEvent *ev) { auto rubber = findChild(); - bool dragging = rubber && rubber->isVisible(); - if (!dragging) { + bool is_zooming = rubber && rubber->isVisible(); + if (!is_zooming) { const auto plot_area = chart()->plotArea(); - float x = std::clamp((float)ev->pos().x(), (float)plot_area.left(), (float)plot_area.right()); - track_line->setLine(x, plot_area.top(), x, plot_area.bottom()); - auto axis_x = dynamic_cast(chart()->axisX()); - double sec = axis_x->min() + ((x - plot_area.x()) / plot_area.width()) * (axis_x->max() - axis_x->min()); - auto value = std::lower_bound(vals.begin(), vals.end(), sec, [](auto &p, double x) { return p.x() < x; }); - value_text->setPos(x + 6, plot_area.bottom() - 25); + double x = std::clamp((double)ev->pos().x(), plot_area.left(), plot_area.right()-1); + double sec = axis_x->min() + (axis_x->max() - axis_x->min()) * (x - plot_area.left()) / plot_area.width(); + auto value = std::upper_bound(vals.begin(), vals.end(), sec, [](double x, auto &p) { return x < p.x(); }); if (value != vals.end()) { - value_text->setText(QString("(%1, %2)").arg(value->x(), 0, 'f', 3).arg(value->y())); - } else { - value_text->setText("(--, --)"); + QPointF pos = chart()->mapToPosition((*value)); + track_line->setLine(pos.x(), plot_area.top(), pos.x(), plot_area.bottom()); + track_ellipse->setRect(pos.x() - 5, pos.y() - 5, 10, 10); + value_text->setHtml(tr("
%1, %2)
") + .arg(value->x(), 0, 'f', 3).arg(value->y())); + int text_x = pos.x() + 8; + if ((text_x + value_text->boundingRect().width()) > plot_area.right()) { + text_x = pos.x() - value_text->boundingRect().width() - 8; + } + value_text->setPos(text_x, pos.y() - 10); } + track_line->setVisible(value != vals.end()); + value_text->setVisible(value != vals.end()); + track_ellipse->setVisible(value != vals.end()); } QChartView::mouseMoveEvent(ev); } diff --git a/tools/cabana/chartswidget.h b/tools/cabana/chartswidget.h index 897ed62c2f..60081dd882 100644 --- a/tools/cabana/chartswidget.h +++ b/tools/cabana/chartswidget.h @@ -3,8 +3,9 @@ #include #include +#include #include -#include +#include #include #include #include @@ -38,7 +39,8 @@ private: void updateAxisY(); QGraphicsLineItem *track_line; - QGraphicsSimpleTextItem *value_text; + QGraphicsEllipseItem *track_ellipse; + QGraphicsTextItem *value_text; QGraphicsLineItem *line_marker; QList vals; QString id; From 8f70a84a417f848793f87d6c79c25f3ce15d5d38 Mon Sep 17 00:00:00 2001 From: Kurt Nistelberger Date: Fri, 28 Oct 2022 23:43:12 +0200 Subject: [PATCH 43/59] QuectelGPS: add supl server (#26259) add supl server Co-authored-by: Kurt Nistelberger --- selfdrive/sensord/rawgps/rawgpsd.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/sensord/rawgps/rawgpsd.py b/selfdrive/sensord/rawgps/rawgpsd.py index fa23a161c4..1c65051665 100755 --- a/selfdrive/sensord/rawgps/rawgpsd.py +++ b/selfdrive/sensord/rawgps/rawgpsd.py @@ -124,6 +124,7 @@ def setup_quectel(diag: ModemDiag): # don't automatically turn on GNSS on powerup at_cmd("AT+QGPSCFG=\"autogps\",0") + at_cmd("AT+QGPSSUPLURL=\"supl.google.com:7275\"") at_cmd("AT+QGPSCFG=\"outport\",\"usbnmea\"") at_cmd("AT+QGPS=1") From 5ae213142459a64aac8a1654d1087346b17b87c1 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 28 Oct 2022 17:26:25 -0700 Subject: [PATCH 44/59] bump opendbc (#26277) --- opendbc | 2 +- selfdrive/car/hyundai/carstate.py | 1 - 2 files changed, 1 insertion(+), 2 deletions(-) diff --git a/opendbc b/opendbc index a95b0ae8a5..526e21da66 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit a95b0ae8a5244a9d6311bf72aa2a7d63d41b4a9f +Subproject commit 526e21da666aeeabcf2369c66903a5675fdf933b diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py index ec2b3059a3..2e4cb0d25a 100644 --- a/selfdrive/car/hyundai/carstate.py +++ b/selfdrive/car/hyundai/carstate.py @@ -507,7 +507,6 @@ class CarState(CarStateBase): ("ZEROS_5", "CRUISE_INFO"), ("DISTANCE_SETTING", "CRUISE_INFO"), ("SET_SPEED", "CRUISE_INFO"), - ("NEW_SIGNAL_4", "CRUISE_INFO"), ] checks = [ From 602b90f518e9bc51dccdb75413ff86481dff277d Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Sat, 29 Oct 2022 10:05:11 +0800 Subject: [PATCH 45/59] UI: reduce frame drops. (#26266) * reduce frame dropping * This mode will not draw the same frame twice * cleanup comment * use previous texture if update is not triggered by vipc thread and without new frame --- selfdrive/ui/qt/widgets/cameraview.cc | 32 ++++++++++----------------- selfdrive/ui/qt/widgets/cameraview.h | 1 - 2 files changed, 12 insertions(+), 21 deletions(-) diff --git a/selfdrive/ui/qt/widgets/cameraview.cc b/selfdrive/ui/qt/widgets/cameraview.cc index 13225414d0..d7591633c9 100644 --- a/selfdrive/ui/qt/widgets/cameraview.cc +++ b/selfdrive/ui/qt/widgets/cameraview.cc @@ -240,24 +240,13 @@ void CameraWidget::paintGL() { glClear(GL_STENCIL_BUFFER_BIT | GL_COLOR_BUFFER_BIT); std::lock_guard lk(frame_lock); - if (frames.empty()) return; - int frame_idx = frames.size() - 1; - - // Always draw latest frame until sync logic is more stable - // for (frame_idx = 0; frame_idx < frames.size() - 1; frame_idx++) { - // if (frames[frame_idx].first == draw_frame_id) break; - // } - - // Log duplicate/dropped frames - if (frames[frame_idx].first == prev_frame_id) { - qDebug() << "Drawing same frame twice" << frames[frame_idx].first; - } else if (frames[frame_idx].first != prev_frame_id + 1) { - qDebug() << "Skipped frame" << frames[frame_idx].first; + // use previous texture if update() is called without new frame. + VisionBuf *frame = nullptr; + if (!frames.empty()) { + frame = frames.front().second; + frames.pop_front(); } - prev_frame_id = frames[frame_idx].first; - VisionBuf *frame = frames[frame_idx].second; - assert(frame != nullptr); glViewport(0, 0, width(), height()); glBindVertexArray(frame_vao); @@ -266,19 +255,21 @@ void CameraWidget::paintGL() { #ifdef QCOM2 glActiveTexture(GL_TEXTURE0); - glEGLImageTargetTexture2DOES(GL_TEXTURE_EXTERNAL_OES, egl_images[frame->idx]); - assert(glGetError() == GL_NO_ERROR); + if (frame) { + glEGLImageTargetTexture2DOES(GL_TEXTURE_EXTERNAL_OES, egl_images[frame->idx]); + assert(glGetError() == GL_NO_ERROR); + } #else glPixelStorei(GL_UNPACK_ROW_LENGTH, stream_stride); glActiveTexture(GL_TEXTURE0); glBindTexture(GL_TEXTURE_2D, textures[0]); - glTexSubImage2D(GL_TEXTURE_2D, 0, 0, 0, stream_width, stream_height, GL_RED, GL_UNSIGNED_BYTE, frame->y); + if (frame) glTexSubImage2D(GL_TEXTURE_2D, 0, 0, 0, stream_width, stream_height, GL_RED, GL_UNSIGNED_BYTE, frame->y); assert(glGetError() == GL_NO_ERROR); glPixelStorei(GL_UNPACK_ROW_LENGTH, stream_stride/2); glActiveTexture(GL_TEXTURE0 + 1); glBindTexture(GL_TEXTURE_2D, textures[1]); - glTexSubImage2D(GL_TEXTURE_2D, 0, 0, 0, stream_width/2, stream_height/2, GL_RG, GL_UNSIGNED_BYTE, frame->uv); + if (frame) glTexSubImage2D(GL_TEXTURE_2D, 0, 0, 0, stream_width/2, stream_height/2, GL_RG, GL_UNSIGNED_BYTE, frame->uv); assert(glGetError() == GL_NO_ERROR); #endif @@ -375,6 +366,7 @@ void CameraWidget::vipcThread() { std::lock_guard lk(frame_lock); frames.push_back(std::make_pair(meta_main.frame_id, buf)); while (frames.size() > FRAME_BUFFER_SIZE) { + qDebug() << "Skipped frame" << frames.front().first; frames.pop_front(); } } diff --git a/selfdrive/ui/qt/widgets/cameraview.h b/selfdrive/ui/qt/widgets/cameraview.h index ef828f8ff6..aff3abc836 100644 --- a/selfdrive/ui/qt/widgets/cameraview.h +++ b/selfdrive/ui/qt/widgets/cameraview.h @@ -81,7 +81,6 @@ protected: std::mutex frame_lock; std::deque> frames; uint32_t draw_frame_id = 0; - uint32_t prev_frame_id = 0; protected slots: void vipcConnected(VisionIpcClient *vipc_client); From a622e523b2251472aa59b80eee60cae9fcb1e024 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Sat, 29 Oct 2022 12:44:51 +0800 Subject: [PATCH 46/59] Cabana: add tab context menu for 'close other tabs' (#26279) close other tabs --- tools/cabana/detailwidget.cc | 41 ++++++++++++++++++++++++++++++------ tools/cabana/detailwidget.h | 2 +- 2 files changed, 35 insertions(+), 8 deletions(-) diff --git a/tools/cabana/detailwidget.cc b/tools/cabana/detailwidget.cc index 7290e4e6ff..8839cdd509 100644 --- a/tools/cabana/detailwidget.cc +++ b/tools/cabana/detailwidget.cc @@ -2,6 +2,7 @@ #include #include +#include #include #include @@ -22,6 +23,7 @@ DetailWidget::DetailWidget(QWidget *parent) : QWidget(parent) { tabbar->setDrawBase(false); tabbar->setUsesScrollButtons(true); tabbar->setAutoHide(true); + tabbar->setContextMenuPolicy(Qt::CustomContextMenu); main_layout->addWidget(tabbar); // message title @@ -79,22 +81,47 @@ DetailWidget::DetailWidget(QWidget *parent) : QWidget(parent) { QObject::connect(binary_view, &BinaryView::addSignal, this, &DetailWidget::addSignal); QObject::connect(can, &CANMessages::updated, this, &DetailWidget::updateState); QObject::connect(dbc(), &DBCManager::DBCFileChanged, [this]() { dbcMsgChanged(); }); - QObject::connect(tabbar, &QTabBar::currentChanged, [this](int index) { setMessage(messages[index]); }); + QObject::connect(tabbar, &QTabBar::customContextMenuRequested, this, &DetailWidget::showTabBarContextMenu); + QObject::connect(tabbar, &QTabBar::currentChanged, [this](int index) { + if (index != -1 && tabbar->tabText(index) != msg_id) { + setMessage(tabbar->tabText(index)); + } + }); QObject::connect(tabbar, &QTabBar::tabCloseRequested, [=](int index) { - messages.removeAt(index); + if (tabbar->currentIndex() == index) { + tabbar->setCurrentIndex(index == tabbar->count() - 1 ? index - 1 : index + 1); + } tabbar->removeTab(index); - setMessage(messages.isEmpty() ? "" : messages[0]); }); } +void DetailWidget::showTabBarContextMenu(const QPoint &pt) { + int index = tabbar->tabAt(pt); + if (index >= 0) { + QMenu menu(this); + menu.addAction(tr("Close Other Tabs")); + if (menu.exec(tabbar->mapToGlobal(pt))) { + for (int i = tabbar->count() - 1; i >= 0; --i) { + if (i != index) + tabbar->removeTab(i); + } + } + } +} + void DetailWidget::setMessage(const QString &message_id) { if (message_id.isEmpty()) return; - int index = messages.indexOf(message_id); + qWarning() << "setmessage" << message_id; + int index = -1; + for (int i = 0; i < tabbar->count(); ++i) { + if (tabbar->tabText(i) == message_id) { + index = i; + break; + } + } if (index == -1) { - messages.push_back(message_id); - tabbar->addTab(message_id); - index = tabbar->count() - 1; + index = tabbar->addTab(message_id); auto msg = dbc()->msg(message_id); tabbar->setTabToolTip(index, msg ? msg->name.c_str() : "untitled"); } diff --git a/tools/cabana/detailwidget.h b/tools/cabana/detailwidget.h index 5924cdd43f..4ec74eca7e 100644 --- a/tools/cabana/detailwidget.h +++ b/tools/cabana/detailwidget.h @@ -39,6 +39,7 @@ signals: void removeChart(const Signal *sig); private: + void showTabBarContextMenu(const QPoint &pt); void addSignal(int start_bit, int to); void resizeSignal(const Signal *sig, int from, int to); void saveSignal(const Signal *sig, const Signal &new_sig); @@ -53,7 +54,6 @@ private: QPushButton *edit_btn; QWidget *signals_container; QTabBar *tabbar; - QStringList messages; HistoryLog *history_log; BinaryView *binary_view; ScrollArea *scroll; From 5aa0d211f075681e18395d0fd7dd73d8cc44573c Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Sun, 30 Oct 2022 03:01:08 +0800 Subject: [PATCH 47/59] Cabana: double click the title bar to move binview to a separate column (#26280) * double click to move binview to seperate column * cleanup * double click frame * continue * rename signal * add tooltip * fix layout * don't show last cell's bottom line * increase spliter handle size * cleanup * set resize mode to ResizeToContents * add a split button * cleanup layout&fix space * cleanup * remove hardcoded size * cleanup --- tools/cabana/binaryview.cc | 12 +++++---- tools/cabana/binaryview.h | 1 + tools/cabana/detailwidget.cc | 52 ++++++++++++++++++++++++++++-------- tools/cabana/detailwidget.h | 17 ++++++++++++ tools/cabana/mainwin.cc | 14 +++++----- tools/cabana/mainwin.h | 4 ++- 6 files changed, 75 insertions(+), 25 deletions(-) diff --git a/tools/cabana/binaryview.cc b/tools/cabana/binaryview.cc index 26fecd8c38..91353e9726 100644 --- a/tools/cabana/binaryview.cc +++ b/tools/cabana/binaryview.cc @@ -20,13 +20,15 @@ BinaryView::BinaryView(QWidget *parent) : QTableView(parent) { setItemDelegate(delegate); horizontalHeader()->setSectionResizeMode(QHeaderView::Stretch); horizontalHeader()->hide(); - verticalHeader()->setSectionResizeMode(QHeaderView::Stretch); + verticalHeader()->setSectionResizeMode(QHeaderView::ResizeToContents); setHorizontalScrollBarPolicy(Qt::ScrollBarAlwaysOff); setMouseTracking(true); + setSizePolicy(QSizePolicy::Preferred, QSizePolicy::Minimum); +} - QObject::connect(model, &QAbstractItemModel::modelReset, [this]() { - setFixedHeight((CELL_HEIGHT + 1) * std::min(model->rowCount(), 8) + 2); - }); +QSize BinaryView::sizeHint() const { + QSize sz = QTableView::sizeHint(); + return {sz.width(), model->rowCount() <= 8 ? ((CELL_HEIGHT + 1) * model->rowCount() + 2) : sz.height()}; } void BinaryView::highlight(const Signal *sig) { @@ -108,9 +110,9 @@ void BinaryView::leaveEvent(QEvent *event) { void BinaryView::setMessage(const QString &message_id) { msg_id = message_id; model->setMessage(message_id); - resizeRowsToContents(); clearSelection(); updateState(); + updateGeometry(); } void BinaryView::updateState() { diff --git a/tools/cabana/binaryview.h b/tools/cabana/binaryview.h index 0f58e9ed20..060a2eef7f 100644 --- a/tools/cabana/binaryview.h +++ b/tools/cabana/binaryview.h @@ -61,6 +61,7 @@ public: void highlight(const Signal *sig); const Signal *hoveredSignal() const { return hovered_sig; } QSet getOverlappingSignals() const; + QSize sizeHint() const override; signals: void signalHovered(const Signal *sig); diff --git a/tools/cabana/detailwidget.cc b/tools/cabana/detailwidget.cc index 8839cdd509..69b420483d 100644 --- a/tools/cabana/detailwidget.cc +++ b/tools/cabana/detailwidget.cc @@ -13,10 +13,18 @@ // DetailWidget DetailWidget::DetailWidget(QWidget *parent) : QWidget(parent) { - QVBoxLayout *main_layout = new QVBoxLayout(this); + main_layout = new QHBoxLayout(this); main_layout->setContentsMargins(0, 0, 0, 0); - main_layout->setSpacing(0); + right_column = new QVBoxLayout(); + main_layout->addLayout(right_column); + + binary_view_container = new QWidget(this); + binary_view_container->setMinimumWidth(500); + binary_view_container->setSizePolicy(QSizePolicy::Minimum, QSizePolicy::Preferred); + QVBoxLayout *bin_layout = new QVBoxLayout(binary_view_container); + bin_layout->setContentsMargins(0, 0, 0, 0); + bin_layout->setSpacing(0); // tabbar tabbar = new QTabBar(this); tabbar->setTabsClosable(true); @@ -24,14 +32,19 @@ DetailWidget::DetailWidget(QWidget *parent) : QWidget(parent) { tabbar->setUsesScrollButtons(true); tabbar->setAutoHide(true); tabbar->setContextMenuPolicy(Qt::CustomContextMenu); - main_layout->addWidget(tabbar); + bin_layout->addWidget(tabbar); - // message title - QFrame *title_frame = new QFrame(); - main_layout->addWidget(title_frame); - QVBoxLayout *frame_layout = new QVBoxLayout(title_frame); + TitleFrame *title_frame = new TitleFrame(this); title_frame->setFrameShape(QFrame::StyledPanel); + title_frame->setSizePolicy(QSizePolicy::Preferred, QSizePolicy::Fixed); + QVBoxLayout *frame_layout = new QVBoxLayout(title_frame); + + // message title QHBoxLayout *title_layout = new QHBoxLayout(); + split_btn = new QPushButton("⬅", this); + split_btn->setFixedSize(20, 20); + split_btn->setToolTip(tr("Split to two columns")); + title_layout->addWidget(split_btn); title_layout->addWidget(new QLabel("time:")); time_label = new QLabel(this); time_label->setStyleSheet("font-weight:bold"); @@ -56,10 +69,12 @@ DetailWidget::DetailWidget(QWidget *parent) : QWidget(parent) { warning_hlayout->addWidget(warning_label, 1, Qt::AlignLeft); warning_widget->hide(); frame_layout->addWidget(warning_widget); + bin_layout->addWidget(title_frame); // binary view binary_view = new BinaryView(this); - main_layout->addWidget(binary_view, 0, Qt::AlignTop); + bin_layout->addWidget(binary_view); + right_column->addWidget(binary_view_container); // signals signals_container = new QWidget(this); @@ -70,12 +85,14 @@ DetailWidget::DetailWidget(QWidget *parent) : QWidget(parent) { scroll->setWidget(signals_container); scroll->setWidgetResizable(true); scroll->setHorizontalScrollBarPolicy(Qt::ScrollBarAlwaysOff); - main_layout->addWidget(scroll); + right_column->addWidget(scroll); // history log history_log = new HistoryLog(this); - main_layout->addWidget(history_log); + right_column->addWidget(history_log); + QObject::connect(split_btn, &QPushButton::clicked, this, &DetailWidget::moveBinaryView); + QObject::connect(title_frame, &TitleFrame::doubleClicked, this, &DetailWidget::moveBinaryView); QObject::connect(edit_btn, &QPushButton::clicked, this, &DetailWidget::editMsg); QObject::connect(binary_view, &BinaryView::resizeSignal, this, &DetailWidget::resizeSignal); QObject::connect(binary_view, &BinaryView::addSignal, this, &DetailWidget::addSignal); @@ -112,7 +129,6 @@ void DetailWidget::showTabBarContextMenu(const QPoint &pt) { void DetailWidget::setMessage(const QString &message_id) { if (message_id.isEmpty()) return; - qWarning() << "setmessage" << message_id; int index = -1; for (int i = 0; i < tabbar->count(); ++i) { if (tabbar->tabText(i) == message_id) { @@ -182,6 +198,20 @@ void DetailWidget::updateState() { history_log->updateState(); } +void DetailWidget::moveBinaryView() { + if (binview_in_left_col) { + right_column->insertWidget(0, binary_view_container); + emit binaryViewMoved(true); + } else { + main_layout->insertWidget(0, binary_view_container); + emit binaryViewMoved(false); + } + split_btn->setText(binview_in_left_col ? "⬅" : "➡"); + split_btn->setToolTip(binview_in_left_col ? tr("Split to two columns") : tr("Move back")); + binary_view->updateGeometry(); + binview_in_left_col = !binview_in_left_col; +} + void DetailWidget::showForm() { SignalEdit *sender = qobject_cast(QObject::sender()); for (auto f : signals_container->findChildren()) { diff --git a/tools/cabana/detailwidget.h b/tools/cabana/detailwidget.h index 4ec74eca7e..3f042bf2b8 100644 --- a/tools/cabana/detailwidget.h +++ b/tools/cabana/detailwidget.h @@ -2,11 +2,21 @@ #include #include +#include #include "tools/cabana/binaryview.h" #include "tools/cabana/historylog.h" #include "tools/cabana/signaledit.h" +class TitleFrame : public QFrame { + Q_OBJECT +public: + TitleFrame(QWidget *parent) : QFrame(parent) {} + void mouseDoubleClickEvent(QMouseEvent *e) { emit doubleClicked(); } +signals: + void doubleClicked(); +}; + class EditMessageDialog : public QDialog { Q_OBJECT @@ -37,6 +47,7 @@ public: signals: void showChart(const QString &msg_id, const Signal *sig); void removeChart(const Signal *sig); + void binaryViewMoved(bool in); private: void showTabBarContextMenu(const QPoint &pt); @@ -47,6 +58,7 @@ private: void editMsg(); void showForm(); void updateState(); + void moveBinaryView(); QString msg_id; QLabel *name_label, *time_label, *warning_label; @@ -54,6 +66,11 @@ private: QPushButton *edit_btn; QWidget *signals_container; QTabBar *tabbar; + QHBoxLayout *main_layout; + QVBoxLayout *right_column; + bool binview_in_left_col = false; + QWidget *binary_view_container; + QPushButton *split_btn; HistoryLog *history_log; BinaryView *binary_view; ScrollArea *scroll; diff --git a/tools/cabana/mainwin.cc b/tools/cabana/mainwin.cc index f127e5f52b..71ec873551 100644 --- a/tools/cabana/mainwin.cc +++ b/tools/cabana/mainwin.cc @@ -3,14 +3,13 @@ #include #include #include -#include #include #include "tools/replay/util.h" static MainWindow *main_win = nullptr; void qLogMessageHandler(QtMsgType type, const QMessageLogContext &context, const QString &msg) { - if (main_win) main_win->showStatusMessage(msg); + if (main_win) emit main_win->showMessage(msg, 0); } MainWindow::MainWindow() : QWidget() { @@ -22,15 +21,14 @@ MainWindow::MainWindow() : QWidget() { h_layout->setContentsMargins(0, 0, 0, 0); main_layout->addLayout(h_layout); - QSplitter *splitter = new QSplitter(Qt::Horizontal, this); - splitter->setSizePolicy(QSizePolicy::Preferred, QSizePolicy::Expanding); + splitter = new QSplitter(Qt::Horizontal, this); + splitter->setHandleWidth(11); messages_widget = new MessagesWidget(this); splitter->addWidget(messages_widget); detail_widget = new DetailWidget(this); splitter->addWidget(detail_widget); - splitter->setSizes({100, 500}); h_layout->addWidget(splitter); // right widgets @@ -74,16 +72,17 @@ MainWindow::MainWindow() : QWidget() { qRegisterMetaType("ReplyMsgType"); installMessageHandler([this](ReplyMsgType type, const std::string msg) { // use queued connection to recv the log messages from replay. - emit logMessageFromReplay(QString::fromStdString(msg), 3000); + emit showMessage(QString::fromStdString(msg), 3000); }); installDownloadProgressHandler([this](uint64_t cur, uint64_t total, bool success) { emit updateProgressBar(cur, total, success); }); - QObject::connect(this, &MainWindow::logMessageFromReplay, status_bar, &QStatusBar::showMessage); + QObject::connect(this, &MainWindow::showMessage, status_bar, &QStatusBar::showMessage); QObject::connect(this, &MainWindow::updateProgressBar, this, &MainWindow::updateDownloadProgress); QObject::connect(messages_widget, &MessagesWidget::msgSelectionChanged, detail_widget, &DetailWidget::setMessage); QObject::connect(detail_widget, &DetailWidget::showChart, charts_widget, &ChartsWidget::addChart); + QObject::connect(detail_widget, &DetailWidget::binaryViewMoved, [this](bool in) { splitter->setSizes({in ? 100 : 0, 500}); }); QObject::connect(charts_widget, &ChartsWidget::dock, this, &MainWindow::dockCharts); QObject::connect(charts_widget, &ChartsWidget::rangeChanged, video_widget, &VideoWidget::rangeChanged); QObject::connect(settings_btn, &QPushButton::clicked, this, &MainWindow::setOption); @@ -103,7 +102,6 @@ void MainWindow::updateDownloadProgress(uint64_t cur, uint64_t total, bool succe } } - void MainWindow::dockCharts(bool dock) { if (dock && floating_window) { floating_window->removeEventFilter(charts_widget); diff --git a/tools/cabana/mainwin.h b/tools/cabana/mainwin.h index 63f704dcc8..b77744ba9c 100644 --- a/tools/cabana/mainwin.h +++ b/tools/cabana/mainwin.h @@ -1,6 +1,7 @@ #pragma once #include +#include #include #include "tools/cabana/chartswidget.h" @@ -17,7 +18,7 @@ public: void showStatusMessage(const QString &msg, int timeout = 0) { status_bar->showMessage(msg, timeout); } signals: - void logMessageFromReplay(const QString &msg, int timeout); + void showMessage(const QString &msg, int timeout); void updateProgressBar(uint64_t cur, uint64_t total, bool success); protected: @@ -29,6 +30,7 @@ protected: MessagesWidget *messages_widget; DetailWidget *detail_widget; ChartsWidget *charts_widget; + QSplitter *splitter; QWidget *floating_window = nullptr; QVBoxLayout *r_layout; QProgressBar *progress_bar; From 9377448888c181674fdc1b1aa8c3bc485156d3d2 Mon Sep 17 00:00:00 2001 From: Rohit Bernard <43088347+RohitBernard@users.noreply.github.com> Date: Sat, 29 Oct 2022 13:20:37 -0700 Subject: [PATCH 48/59] sim: Converting RGB frames to NV12 format in OpenCL (#26169) * convert carla rgb frames to nv12 * code cleanup * move kernel Co-authored-by: Adeeb Shihadeh --- tools/sim/bridge.py | 5 +- .../rgb_to_yuv.cl => tools/sim/rgb_to_nv12.cl | 46 ++++++++----------- 2 files changed, 21 insertions(+), 30 deletions(-) rename system/camerad/transforms/rgb_to_yuv.cl => tools/sim/rgb_to_nv12.cl (75%) diff --git a/tools/sim/bridge.py b/tools/sim/bridge.py index a105ed751e..f72927ba9a 100755 --- a/tools/sim/bridge.py +++ b/tools/sim/bridge.py @@ -82,11 +82,10 @@ class Camerad: self.queue = cl.CommandQueue(self.ctx) cl_arg = f" -DHEIGHT={H} -DWIDTH={W} -DRGB_STRIDE={W * 3} -DUV_WIDTH={W // 2} -DUV_HEIGHT={H // 2} -DRGB_SIZE={W * H} -DCL_DEBUG " - # TODO: move rgb_to_yuv.cl to local dir once the frame stream camera is removed - kernel_fn = os.path.join(BASEDIR, "system", "camerad", "transforms", "rgb_to_yuv.cl") + kernel_fn = os.path.join(BASEDIR, "tools/sim/rgb_to_nv12.cl") with open(kernel_fn) as f: prg = cl.Program(self.ctx, f.read()).build(cl_arg) - self.krnl = prg.rgb_to_yuv + self.krnl = prg.rgb_to_nv12 self.Wdiv4 = W // 4 if (W % 4 == 0) else (W + (4 - W % 4)) // 4 self.Hdiv4 = H // 4 if (H % 4 == 0) else (H + (4 - H % 4)) // 4 diff --git a/system/camerad/transforms/rgb_to_yuv.cl b/tools/sim/rgb_to_nv12.cl similarity index 75% rename from system/camerad/transforms/rgb_to_yuv.cl rename to tools/sim/rgb_to_nv12.cl index 60dbdb4d5e..54816d5d7d 100644 --- a/system/camerad/transforms/rgb_to_yuv.cl +++ b/tools/sim/rgb_to_nv12.cl @@ -29,23 +29,21 @@ inline void convert_4_ys(__global uchar * out_yuv, int yi, const uchar8 rgbs1, c vstore4(yy, 0, out_yuv + yi); } -inline void convert_uv(__global uchar * out_yuv, int ui, int vi, +inline void convert_uv(__global uchar * out_yuv, int uvi, const uchar8 rgbs1, const uchar8 rgbs2) { // U & V: average of 2x2 pixels square const short ab = AVERAGE(rgbs1.s0, rgbs1.s3, rgbs2.s0, rgbs2.s3); const short ag = AVERAGE(rgbs1.s1, rgbs1.s4, rgbs2.s1, rgbs2.s4); const short ar = AVERAGE(rgbs1.s2, rgbs1.s5, rgbs2.s2, rgbs2.s5); #ifdef CL_DEBUG - if(ui >= RGB_SIZE + RGB_SIZE / 4) - printf("U overflow, %d >= %d\n", ui, RGB_SIZE + RGB_SIZE / 4); - if(vi >= RGB_SIZE + RGB_SIZE / 2) - printf("V overflow, %d >= %d\n", vi, RGB_SIZE + RGB_SIZE / 2); + if(uvi >= RGB_SIZE + RGB_SIZE / 2) + printf("UV overflow, %d >= %d\n", uvi, RGB_SIZE + RGB_SIZE / 2); #endif - out_yuv[ui] = RGB_TO_U(ar, ag, ab); - out_yuv[vi] = RGB_TO_V(ar, ag, ab); + out_yuv[uvi] = RGB_TO_U(ar, ag, ab); + out_yuv[uvi+1] = RGB_TO_V(ar, ag, ab); } -inline void convert_2_uvs(__global uchar * out_yuv, int ui, int vi, +inline void convert_2_uvs(__global uchar * out_yuv, int uvi, const uchar8 rgbs1, const uchar8 rgbs2, const uchar8 rgbs3, const uchar8 rgbs4) { // U & V: average of 2x2 pixels square const short ab1 = AVERAGE(rgbs1.s0, rgbs1.s3, rgbs2.s0, rgbs2.s3); @@ -54,25 +52,20 @@ inline void convert_2_uvs(__global uchar * out_yuv, int ui, int vi, const short ab2 = AVERAGE(rgbs1.s6, rgbs3.s1, rgbs2.s6, rgbs4.s1); const short ag2 = AVERAGE(rgbs1.s7, rgbs3.s2, rgbs2.s7, rgbs4.s2); const short ar2 = AVERAGE(rgbs3.s0, rgbs3.s3, rgbs4.s0, rgbs4.s3); - uchar2 u2 = (uchar2)( + uchar4 uv = (uchar4)( RGB_TO_U(ar1, ag1, ab1), - RGB_TO_U(ar2, ag2, ab2) - ); - uchar2 v2 = (uchar2)( RGB_TO_V(ar1, ag1, ab1), + RGB_TO_U(ar2, ag2, ab2), RGB_TO_V(ar2, ag2, ab2) ); #ifdef CL_DEBUG1 - if(ui > RGB_SIZE + RGB_SIZE / 4 - 2) - printf("U 2 overflow, %d >= %d\n", ui, RGB_SIZE + RGB_SIZE / 4 - 2); - if(vi > RGB_SIZE + RGB_SIZE / 2 - 2) - printf("V 2 overflow, %d >= %d\n", vi, RGB_SIZE + RGB_SIZE / 2 - 2); + if(uvi > RGB_SIZE + RGB_SIZE / 2 - 4) + printf("UV2 overflow, %d >= %d\n", uvi, RGB_SIZE + RGB_SIZE / 2 - 2); #endif - vstore2(u2, 0, out_yuv + ui); - vstore2(v2, 0, out_yuv + vi); + vstore4(uv, 0, out_yuv + uvi); } -__kernel void rgb_to_yuv(__global uchar const * const rgb, +__kernel void rgb_to_nv12(__global uchar const * const rgb, __global uchar * out_yuv) { const int dx = get_global_id(0); @@ -81,8 +74,7 @@ __kernel void rgb_to_yuv(__global uchar const * const rgb, const int row = mul24(dy, 4); // Current row in rgb image const int bgri_start = mad24(row, RGB_STRIDE, mul24(col, 3)); // Start offset of rgb data being converted const int yi_start = mad24(row, WIDTH, col); // Start offset in the target yuv buffer - int ui = mad24(row / 2, UV_WIDTH, RGB_SIZE + col / 2); - int vi = mad24(row / 2 , UV_WIDTH, RGB_SIZE + UV_WIDTH * UV_HEIGHT + col / 2); + int uvi = mad24(row / 2, WIDTH, RGB_SIZE + col); int num_col = min(WIDTH - col, 4); int num_row = min(HEIGHT - row, 4); if(num_row == 4) { @@ -99,15 +91,15 @@ __kernel void rgb_to_yuv(__global uchar const * const rgb, convert_4_ys(out_yuv, yi_start + WIDTH, rgbs1_0, rgbs1_1); convert_4_ys(out_yuv, yi_start + WIDTH * 2, rgbs2_0, rgbs2_1); convert_4_ys(out_yuv, yi_start + WIDTH * 3, rgbs3_0, rgbs3_1); - convert_2_uvs(out_yuv, ui, vi, rgbs0_0, rgbs1_0, rgbs0_1, rgbs1_1); - convert_2_uvs(out_yuv, ui + UV_WIDTH, vi + UV_WIDTH, rgbs2_0, rgbs3_0, rgbs2_1, rgbs3_1); + convert_2_uvs(out_yuv, uvi, rgbs0_0, rgbs1_0, rgbs0_1, rgbs1_1); + convert_2_uvs(out_yuv, uvi + WIDTH, rgbs2_0, rgbs3_0, rgbs2_1, rgbs3_1); } else if(num_col == 2) { convert_2_ys(out_yuv, yi_start, rgbs0_0); convert_2_ys(out_yuv, yi_start + WIDTH, rgbs1_0); convert_2_ys(out_yuv, yi_start + WIDTH * 2, rgbs2_0); convert_2_ys(out_yuv, yi_start + WIDTH * 3, rgbs3_0); - convert_uv(out_yuv, ui, vi, rgbs0_0, rgbs1_0); - convert_uv(out_yuv, ui + UV_WIDTH, vi + UV_WIDTH, rgbs2_0, rgbs3_0); + convert_uv(out_yuv, uvi, rgbs0_0, rgbs1_0); + convert_uv(out_yuv, uvi + WIDTH, rgbs2_0, rgbs3_0); } } else { const uchar8 rgbs0_0 = vload8(0, rgb + bgri_start); @@ -117,11 +109,11 @@ __kernel void rgb_to_yuv(__global uchar const * const rgb, if(num_col == 4) { convert_4_ys(out_yuv, yi_start, rgbs0_0, rgbs0_1); convert_4_ys(out_yuv, yi_start + WIDTH, rgbs1_0, rgbs1_1); - convert_2_uvs(out_yuv, ui, vi, rgbs0_0, rgbs1_0, rgbs0_1, rgbs1_1); + convert_2_uvs(out_yuv, uvi, rgbs0_0, rgbs1_0, rgbs0_1, rgbs1_1); } else if(num_col == 2) { convert_2_ys(out_yuv, yi_start, rgbs0_0); convert_2_ys(out_yuv, yi_start + WIDTH, rgbs1_0); - convert_uv(out_yuv, ui, vi, rgbs0_0, rgbs1_0); + convert_uv(out_yuv, uvi, rgbs0_0, rgbs1_0); } } } From 5de54c35a9017454982c1deda973a8519968d854 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sat, 29 Oct 2022 13:28:14 -0700 Subject: [PATCH 49/59] cabana: fix settings titles --- tools/cabana/settings.cc | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/tools/cabana/settings.cc b/tools/cabana/settings.cc index 93bc05f20b..17299ebca4 100644 --- a/tools/cabana/settings.cc +++ b/tools/cabana/settings.cc @@ -55,19 +55,19 @@ SettingsDlg::SettingsDlg(QWidget *parent) : QDialog(parent) { cached_segment->setRange(3, 60); cached_segment->setSingleStep(1); cached_segment->setValue(settings.cached_segment_limit); - form_layout->addRow(tr("Cached segments limit(minute)"), cached_segment); + form_layout->addRow(tr("Cached segments limit"), cached_segment); max_chart_x_range = new QSpinBox(this); max_chart_x_range->setRange(1, 60); max_chart_x_range->setSingleStep(1); max_chart_x_range->setValue(settings.max_chart_x_range / 60); - form_layout->addRow(tr("Chart's max X-axis range(minute)"), max_chart_x_range); + form_layout->addRow(tr("Chart range (minutes)"), max_chart_x_range); chart_height = new QSpinBox(this); chart_height->setRange(100, 500); chart_height->setSingleStep(10); chart_height->setValue(settings.chart_height); - form_layout->addRow(tr("Chart's height"), chart_height); + form_layout->addRow(tr("Chart height"), chart_height); chart_theme = new QComboBox(); chart_theme->addItems({"Light", "Dark"}); From 80b088c332808439ea9cfe23557fae5a86fb075c Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Sun, 30 Oct 2022 22:31:12 +0800 Subject: [PATCH 50/59] Cabana: add save DBC dialog (#26282) * export DBC to text edit * added saveAs & Copy To Clipboard * cleanup * cleanup include * add test case * rename variable * fix precision --- .github/workflows/selfdrive_tests.yaml | 1 + tools/cabana/.gitignore | 2 +- tools/cabana/SConscript | 6 ++- tools/cabana/dbcmanager.cc | 21 +++++++- tools/cabana/dbcmanager.h | 4 +- tools/cabana/messageswidget.cc | 67 ++++++++++++++++++++++---- tools/cabana/messageswidget.h | 11 +++++ tools/cabana/tests/test_cabana | 4 ++ tools/cabana/tests/test_cabana.cc | 35 ++++++++++++++ tools/cabana/tests/test_runner.cc | 10 ++++ 10 files changed, 146 insertions(+), 15 deletions(-) create mode 100755 tools/cabana/tests/test_cabana create mode 100644 tools/cabana/tests/test_cabana.cc create mode 100644 tools/cabana/tests/test_runner.cc diff --git a/.github/workflows/selfdrive_tests.yaml b/.github/workflows/selfdrive_tests.yaml index e921cd3d00..598f2c592b 100644 --- a/.github/workflows/selfdrive_tests.yaml +++ b/.github/workflows/selfdrive_tests.yaml @@ -232,6 +232,7 @@ jobs: ./selfdrive/loggerd/tests/test_logger &&\ ./system/proclogd/tests/test_proclog && \ ./tools/replay/tests/test_replay && \ + ./tools/cabana/tests/test_cabana && \ ./system/camerad/test/ae_gray_test && \ coverage xml" - name: "Upload coverage to Codecov" diff --git a/tools/cabana/.gitignore b/tools/cabana/.gitignore index d7a552eabb..73879ab05d 100644 --- a/tools/cabana/.gitignore +++ b/tools/cabana/.gitignore @@ -4,4 +4,4 @@ moc_* _cabana settings car_fingerprint_to_dbc.json - +tests/_test_cabana diff --git a/tools/cabana/SConscript b/tools/cabana/SConscript index 4e4e11dbd8..b7321e1f8d 100644 --- a/tools/cabana/SConscript +++ b/tools/cabana/SConscript @@ -18,5 +18,9 @@ cabana_env = qt_env.Clone() prev_moc_path = cabana_env['QT_MOCHPREFIX'] cabana_env['QT_MOCHPREFIX'] = os.path.dirname(prev_moc_path) + '/cabana/moc_' cabana_env.Execute('./generate_dbc_json.py --out car_fingerprint_to_dbc.json') -cabana_env.Program('_cabana', ['cabana.cc', 'mainwin.cc', 'binaryview.cc', 'chartswidget.cc', 'historylog.cc', 'videowidget.cc', 'signaledit.cc', 'dbcmanager.cc', +cabana_lib = cabana_env.Library("cabana_lib", ['mainwin.cc', 'binaryview.cc', 'chartswidget.cc', 'historylog.cc', 'videowidget.cc', 'signaledit.cc', 'dbcmanager.cc', 'canmessages.cc', 'messageswidget.cc', 'settings.cc', 'detailwidget.cc'], LIBS=cabana_libs, FRAMEWORKS=base_frameworks) +cabana_env.Program('_cabana', ['cabana.cc', cabana_lib], LIBS=cabana_libs, FRAMEWORKS=base_frameworks) + +if GetOption('test'): + cabana_env.Program('tests/_test_cabana', ['tests/test_runner.cc', 'tests/test_cabana.cc', cabana_lib], LIBS=[cabana_libs]) diff --git a/tools/cabana/dbcmanager.cc b/tools/cabana/dbcmanager.cc index c3fbab0349..479b14afec 100644 --- a/tools/cabana/dbcmanager.cc +++ b/tools/cabana/dbcmanager.cc @@ -28,8 +28,25 @@ void DBCManager::open(const QString &name, const QString &content) { emit DBCFileChanged(); } -void save(const QString &dbc_file_name) { - // TODO: save DBC to file +QString DBCManager::generateDBC() { + if (!dbc) return {}; + + QString dbc_string; + for (auto &m : dbc->msgs) { + dbc_string += QString("BO_ %1 %2: %3 XXX\n").arg(m.address).arg(m.name.c_str()).arg(m.size); + for (auto &sig : m.sigs) { + dbc_string += QString(" SG_ %1 : %2|%3@%4%5 (%6,%7) [0|0] \"\" XXX\n") + .arg(sig.name.c_str()) + .arg(sig.start_bit) + .arg(sig.size) + .arg(sig.is_little_endian ? '1' : '0') + .arg(sig.is_signed ? '-' : '+') + .arg(sig.factor, 0, 'g', 20) + .arg(sig.offset); + } + dbc_string += "\n"; + } + return dbc_string; } void DBCManager::updateMsg(const QString &id, const QString &name, uint32_t size) { diff --git a/tools/cabana/dbcmanager.h b/tools/cabana/dbcmanager.h index 9e64c4ed53..913445d44e 100644 --- a/tools/cabana/dbcmanager.h +++ b/tools/cabana/dbcmanager.h @@ -13,8 +13,7 @@ public: void open(const QString &dbc_file_name); void open(const QString &name, const QString &content); - void save(const QString &dbc_file_name); - + QString generateDBC(); void addSignal(const QString &id, const Signal &sig); void updateSignal(const QString &id, const QString &sig_name, const Signal &sig); void removeSignal(const QString &id, const QString &sig_name); @@ -24,6 +23,7 @@ public: inline QString name() const { return dbc_name; } void updateMsg(const QString &id, const QString &name, uint32_t size); + inline const DBC *getDBC() const { return dbc; } inline const Msg *msg(const QString &id) const { return msg(addressFromId(id)); } inline const Msg *msg(uint32_t address) const { auto it = msg_map.find(address); diff --git a/tools/cabana/messageswidget.cc b/tools/cabana/messageswidget.cc index 4975061cc5..4d97bba589 100644 --- a/tools/cabana/messageswidget.cc +++ b/tools/cabana/messageswidget.cc @@ -3,6 +3,8 @@ #include #include #include +#include +#include #include #include #include @@ -69,9 +71,7 @@ MessagesWidget::MessagesWidget(QWidget *parent) : QWidget(parent) { QObject::connect(can, &CANMessages::updated, [this]() { model->updateState(); }); QObject::connect(dbc_combo, SIGNAL(activated(const QString &)), SLOT(loadDBCFromName(const QString &))); QObject::connect(load_from_paste, &QPushButton::clicked, this, &MessagesWidget::loadDBCFromPaste); - QObject::connect(save_btn, &QPushButton::clicked, [=]() { - // TODO: save DBC to file - }); + QObject::connect(save_btn, &QPushButton::clicked, this, &MessagesWidget::saveDBC); QObject::connect(table_widget->selectionModel(), &QItemSelectionModel::currentChanged, [=](const QModelIndex ¤t, const QModelIndex &previous) { if (current.isValid()) { emit msgSelectionChanged(current.data(Qt::UserRole).toString()); @@ -79,7 +79,7 @@ MessagesWidget::MessagesWidget(QWidget *parent) : QWidget(parent) { }); QFile json_file("./car_fingerprint_to_dbc.json"); - if(json_file.open(QIODevice::ReadOnly)) { + if (json_file.open(QIODevice::ReadOnly)) { fingerprint_to_dbc = QJsonDocument::fromJson(json_file.readAll()); } } @@ -103,14 +103,20 @@ void MessagesWidget::loadDBCFromPaste() { void MessagesWidget::loadDBCFromFingerprint() { auto fingerprint = can->carFingerprint(); - if (!fingerprint.isEmpty() && dbc()->name().isEmpty()) { + if (!fingerprint.isEmpty() && dbc()->name().isEmpty()) { auto dbc_name = fingerprint_to_dbc[fingerprint]; - if (dbc_name != QJsonValue::Undefined) { + if (dbc_name != QJsonValue::Undefined) { loadDBCFromName(dbc_name.toString()); } } } +void MessagesWidget::saveDBC() { + SaveDBCDialog dlg(this); + dlg.dbc_edit->setText(dbc()->generateDBC()); + dlg.exec(); +} + // MessageListModel QVariant MessageListModel::headerData(int section, Qt::Orientation orientation, int role) const { @@ -224,6 +230,8 @@ void MessageListModel::sort(int column, Qt::SortOrder order) { } } +// LoadDBCDialog + LoadDBCDialog::LoadDBCDialog(QWidget *parent) : QDialog(parent) { QVBoxLayout *main_layout = new QVBoxLayout(this); dbc_edit = new QTextEdit(this); @@ -233,7 +241,48 @@ LoadDBCDialog::LoadDBCDialog(QWidget *parent) : QDialog(parent) { auto buttonBox = new QDialogButtonBox(QDialogButtonBox::Ok | QDialogButtonBox::Cancel); main_layout->addWidget(buttonBox); - setFixedWidth(640); - connect(buttonBox, &QDialogButtonBox::accepted, this, &QDialog::accept); - connect(buttonBox, &QDialogButtonBox::rejected, this, &QDialog::reject); + setMinimumSize({640, 480}); + QObject::connect(buttonBox, &QDialogButtonBox::accepted, this, &QDialog::accept); + QObject::connect(buttonBox, &QDialogButtonBox::rejected, this, &QDialog::reject); +} + +// SaveDBCDialog + +SaveDBCDialog::SaveDBCDialog(QWidget *parent) : QDialog(parent) { + setWindowTitle(tr("Save DBC")); + QVBoxLayout *main_layout = new QVBoxLayout(this); + dbc_edit = new QTextEdit(this); + dbc_edit->setAcceptRichText(false); + main_layout->addWidget(dbc_edit); + + QPushButton *copy_to_clipboard = new QPushButton(tr("Copy To Clipboard"), this); + QPushButton *save_as = new QPushButton(tr("Save As"), this); + + QHBoxLayout *btn_layout = new QHBoxLayout(); + btn_layout->addStretch(); + btn_layout->addWidget(copy_to_clipboard); + btn_layout->addWidget(save_as); + main_layout->addLayout(btn_layout); + setMinimumSize({640, 480}); + + QObject::connect(copy_to_clipboard, &QPushButton::clicked, this, &SaveDBCDialog::copytoClipboard); + QObject::connect(save_as, &QPushButton::clicked, this, &SaveDBCDialog::saveAs); +} + +void SaveDBCDialog::copytoClipboard() { + dbc_edit->selectAll(); + dbc_edit->copy(); + QDialog::accept(); +} + +void SaveDBCDialog::saveAs() { + QString file_name = QFileDialog::getSaveFileName(this, tr("Save File"), + QDir::homePath() + "/untitled.dbc", tr("DBC (*.dbc)")); + if (!file_name.isEmpty()) { + QFile file(file_name); + if (file.open(QIODevice::WriteOnly)) { + file.write(dbc_edit->toPlainText().toUtf8()); + } + QDialog::accept(); + } } diff --git a/tools/cabana/messageswidget.h b/tools/cabana/messageswidget.h index fcd4939dac..a3d4d860b2 100644 --- a/tools/cabana/messageswidget.h +++ b/tools/cabana/messageswidget.h @@ -17,6 +17,16 @@ public: QTextEdit *dbc_edit; }; +class SaveDBCDialog : public QDialog { + Q_OBJECT + +public: + SaveDBCDialog(QWidget *parent); + void copytoClipboard(); + void saveAs(); + QTextEdit *dbc_edit; +}; + class MessageListModel : public QAbstractTableModel { Q_OBJECT @@ -52,6 +62,7 @@ public slots: void loadDBCFromName(const QString &name); void loadDBCFromFingerprint(); void loadDBCFromPaste(); + void saveDBC(); signals: void msgSelectionChanged(const QString &message_id); diff --git a/tools/cabana/tests/test_cabana b/tools/cabana/tests/test_cabana new file mode 100755 index 0000000000..bac242fbdd --- /dev/null +++ b/tools/cabana/tests/test_cabana @@ -0,0 +1,4 @@ +#!/bin/sh +cd "$(dirname "$0")" +export LD_LIBRARY_PATH="../../../opendbc/can:$LD_LIBRARY_PATH" +exec ./_test_cabana "$1" diff --git a/tools/cabana/tests/test_cabana.cc b/tools/cabana/tests/test_cabana.cc new file mode 100644 index 0000000000..d0aa2cbb4f --- /dev/null +++ b/tools/cabana/tests/test_cabana.cc @@ -0,0 +1,35 @@ + +#include "catch2/catch.hpp" +#include "tools/cabana/dbcmanager.h" + +TEST_CASE("DBCManager::generateDBC") { + DBCManager dbc_origin(nullptr); + dbc_origin.open("toyota_new_mc_pt_generated"); + QString dbc_string = dbc_origin.generateDBC(); + + DBCManager dbc_from_generated(nullptr); + dbc_from_generated.open("", dbc_string); + + auto dbc = dbc_origin.getDBC(); + auto new_dbc = dbc_from_generated.getDBC(); + REQUIRE(dbc->msgs.size() == new_dbc->msgs.size()); + for (int i = 0; i < dbc->msgs.size(); ++i) { + REQUIRE(dbc->msgs[i].name == new_dbc->msgs[i].name); + REQUIRE(dbc->msgs[i].address == new_dbc->msgs[i].address); + REQUIRE(dbc->msgs[i].size == new_dbc->msgs[i].size); + REQUIRE(dbc->msgs[i].sigs.size() == new_dbc->msgs[i].sigs.size()); + auto &sig = dbc->msgs[i].sigs; + auto &new_sig = new_dbc->msgs[i].sigs; + for (int j = 0; j < sig.size(); ++j) { + REQUIRE(sig[j].name == new_sig[j].name); + REQUIRE(sig[j].start_bit == new_sig[j].start_bit); + REQUIRE(sig[j].msb == new_sig[j].msb); + REQUIRE(sig[j].lsb == new_sig[j].lsb); + REQUIRE(sig[j].size == new_sig[j].size); + REQUIRE(sig[j].is_signed == new_sig[j].is_signed); + REQUIRE(sig[j].factor == new_sig[j].factor); + REQUIRE(sig[j].offset == new_sig[j].offset); + REQUIRE(sig[j].is_little_endian == new_sig[j].is_little_endian); + } + } +} diff --git a/tools/cabana/tests/test_runner.cc b/tools/cabana/tests/test_runner.cc new file mode 100644 index 0000000000..b20ac86c64 --- /dev/null +++ b/tools/cabana/tests/test_runner.cc @@ -0,0 +1,10 @@ +#define CATCH_CONFIG_RUNNER +#include "catch2/catch.hpp" +#include + +int main(int argc, char **argv) { + // unit tests for Qt + QCoreApplication app(argc, argv); + const int res = Catch::Session().run(argc, argv); + return (res < 0xff ? res : 0xff); +} From 9c7e3759441f0dff1200f7946e77f06c6a101c26 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Sun, 30 Oct 2022 22:31:43 +0800 Subject: [PATCH 51/59] Cabana: sync button state with chart (#26285) sync button state with charts --- tools/cabana/chartswidget.cc | 14 ++++++++++++-- tools/cabana/chartswidget.h | 5 ++++- tools/cabana/detailwidget.cc | 14 ++++++++++++-- tools/cabana/detailwidget.h | 7 ++++--- tools/cabana/mainwin.cc | 5 ++--- tools/cabana/signaledit.cc | 18 ++++++++++++------ tools/cabana/signaledit.h | 7 +++++-- 7 files changed, 51 insertions(+), 19 deletions(-) diff --git a/tools/cabana/chartswidget.cc b/tools/cabana/chartswidget.cc index a3cbaf5b30..21fd71b8ea 100644 --- a/tools/cabana/chartswidget.cc +++ b/tools/cabana/chartswidget.cc @@ -142,9 +142,11 @@ void ChartsWidget::updateTitleBar() { dock_btn->setToolTip(docking ? tr("Undock charts") : tr("Dock charts")); } -void ChartsWidget::addChart(const QString &id, const Signal *sig) { +void ChartsWidget::showChart(const QString &id, const Signal *sig, bool show) { auto it = std::find_if(charts.begin(), charts.end(), [=](auto c) { return c->id == id && c->signal == sig; }); - if (it == charts.end()) { + if (it != charts.end()) { + if (!show) removeChart((*it)); + } else if (show) { auto chart = new ChartWidget(id, sig, this); chart->chart_view->updateSeries(display_range); QObject::connect(chart, &ChartWidget::remove, [=]() { removeChart(chart); }); @@ -152,14 +154,21 @@ void ChartsWidget::addChart(const QString &id, const Signal *sig) { QObject::connect(chart->chart_view, &ChartView::zoomReset, this, &ChartsWidget::zoomReset); charts_layout->insertWidget(0, chart); charts.push_back(chart); + emit chartOpened(chart->id, chart->signal); } updateTitleBar(); } +bool ChartsWidget::isChartOpened(const QString &id, const Signal *sig) { + auto it = std::find_if(charts.begin(), charts.end(), [=](auto c) { return c->id == id && c->signal == sig; }); + return it != charts.end(); +} + void ChartsWidget::removeChart(ChartWidget *chart) { charts.removeOne(chart); chart->deleteLater(); updateTitleBar(); + emit chartClosed(chart->id, chart->signal); } void ChartsWidget::removeAll(const Signal *sig) { @@ -168,6 +177,7 @@ void ChartsWidget::removeAll(const Signal *sig) { auto c = it.next(); if (sig == nullptr || c->signal == sig) { c->deleteLater(); + emit chartClosed(c->id, c->signal); it.remove(); } } diff --git a/tools/cabana/chartswidget.h b/tools/cabana/chartswidget.h index 60081dd882..602d50ca0a 100644 --- a/tools/cabana/chartswidget.h +++ b/tools/cabana/chartswidget.h @@ -73,12 +73,15 @@ class ChartsWidget : public QWidget { public: ChartsWidget(QWidget *parent = nullptr); - void addChart(const QString &id, const Signal *sig); + void showChart(const QString &id, const Signal *sig, bool show); void removeChart(ChartWidget *chart); + bool isChartOpened(const QString &id, const Signal *sig); signals: void dock(bool floating); void rangeChanged(double min, double max, bool is_zommed); + void chartOpened(const QString &id, const Signal *sig); + void chartClosed(const QString &id, const Signal *sig); private: void eventsMerged(); diff --git a/tools/cabana/detailwidget.cc b/tools/cabana/detailwidget.cc index 69b420483d..59e5b5f296 100644 --- a/tools/cabana/detailwidget.cc +++ b/tools/cabana/detailwidget.cc @@ -12,7 +12,7 @@ // DetailWidget -DetailWidget::DetailWidget(QWidget *parent) : QWidget(parent) { +DetailWidget::DetailWidget(ChartsWidget *charts, QWidget *parent) : charts(charts), QWidget(parent) { main_layout = new QHBoxLayout(this); main_layout->setContentsMargins(0, 0, 0, 0); @@ -110,6 +110,8 @@ DetailWidget::DetailWidget(QWidget *parent) : QWidget(parent) { } tabbar->removeTab(index); }); + QObject::connect(charts, &ChartsWidget::chartOpened, [this](const QString &id, const Signal *sig) { updateChartState(id, sig, true); }); + QObject::connect(charts, &ChartsWidget::chartClosed, [this](const QString &id, const Signal *sig) { updateChartState(id, sig, false); }); } void DetailWidget::showTabBarContextMenu(const QPoint &pt) { @@ -157,13 +159,14 @@ void DetailWidget::dbcMsgChanged(int show_form_idx) { if (auto msg = dbc()->msg(msg_id)) { for (int i = 0; i < msg->sigs.size(); ++i) { auto form = new SignalEdit(i, msg_id, &(msg->sigs[i])); + form->setChartOpened(charts->isChartOpened(msg_id, &(msg->sigs[i]))); signals_container->layout()->addWidget(form); - QObject::connect(form, &SignalEdit::showChart, [this, sig = &msg->sigs[i]]() { emit showChart(msg_id, sig); }); QObject::connect(form, &SignalEdit::showFormClicked, this, &DetailWidget::showForm); QObject::connect(form, &SignalEdit::remove, this, &DetailWidget::removeSignal); QObject::connect(form, &SignalEdit::save, this, &DetailWidget::saveSignal); QObject::connect(form, &SignalEdit::highlight, binary_view, &BinaryView::highlight); QObject::connect(binary_view, &BinaryView::signalHovered, form, &SignalEdit::signalHovered); + QObject::connect(form, &SignalEdit::showChart, [this, sig = &msg->sigs[i]](bool show) { charts->showChart(msg_id, sig, show); }); if (i == show_form_idx) { QTimer::singleShot(0, [=]() { emit form->showFormClicked(); }); } @@ -222,6 +225,13 @@ void DetailWidget::showForm() { } } +void DetailWidget::updateChartState(const QString &id, const Signal *sig, bool opened) { + if (id == msg_id) { + for (auto f : signals_container->findChildren()) + if (f->sig == sig) f->setChartOpened(opened); + } +} + void DetailWidget::editMsg() { auto msg = dbc()->msg(msg_id); QString name = msg ? msg->name.c_str() : "untitled"; diff --git a/tools/cabana/detailwidget.h b/tools/cabana/detailwidget.h index 3f042bf2b8..656aacb106 100644 --- a/tools/cabana/detailwidget.h +++ b/tools/cabana/detailwidget.h @@ -5,6 +5,7 @@ #include #include "tools/cabana/binaryview.h" +#include "tools/cabana/chartswidget.h" #include "tools/cabana/historylog.h" #include "tools/cabana/signaledit.h" @@ -40,16 +41,15 @@ class DetailWidget : public QWidget { Q_OBJECT public: - DetailWidget(QWidget *parent); + DetailWidget(ChartsWidget *charts, QWidget *parent); void setMessage(const QString &message_id); void dbcMsgChanged(int show_form_idx = -1); signals: - void showChart(const QString &msg_id, const Signal *sig); - void removeChart(const Signal *sig); void binaryViewMoved(bool in); private: + void updateChartState(const QString &id, const Signal *sig, bool opened); void showTabBarContextMenu(const QPoint &pt); void addSignal(int start_bit, int to); void resizeSignal(const Signal *sig, int from, int to); @@ -74,4 +74,5 @@ private: HistoryLog *history_log; BinaryView *binary_view; ScrollArea *scroll; + ChartsWidget *charts; }; diff --git a/tools/cabana/mainwin.cc b/tools/cabana/mainwin.cc index 71ec873551..c2baca4d22 100644 --- a/tools/cabana/mainwin.cc +++ b/tools/cabana/mainwin.cc @@ -26,7 +26,8 @@ MainWindow::MainWindow() : QWidget() { messages_widget = new MessagesWidget(this); splitter->addWidget(messages_widget); - detail_widget = new DetailWidget(this); + charts_widget = new ChartsWidget(this); + detail_widget = new DetailWidget(charts_widget, this); splitter->addWidget(detail_widget); h_layout->addWidget(splitter); @@ -50,7 +51,6 @@ MainWindow::MainWindow() : QWidget() { video_widget = new VideoWidget(this); r_layout->addWidget(video_widget, 0, Qt::AlignTop); - charts_widget = new ChartsWidget(this); r_layout->addWidget(charts_widget); h_layout->addWidget(right_container); @@ -81,7 +81,6 @@ MainWindow::MainWindow() : QWidget() { QObject::connect(this, &MainWindow::showMessage, status_bar, &QStatusBar::showMessage); QObject::connect(this, &MainWindow::updateProgressBar, this, &MainWindow::updateDownloadProgress); QObject::connect(messages_widget, &MessagesWidget::msgSelectionChanged, detail_widget, &DetailWidget::setMessage); - QObject::connect(detail_widget, &DetailWidget::showChart, charts_widget, &ChartsWidget::addChart); QObject::connect(detail_widget, &DetailWidget::binaryViewMoved, [this](bool in) { splitter->setSizes({in ? 100 : 0, 500}); }); QObject::connect(charts_widget, &ChartsWidget::dock, this, &MainWindow::dockCharts); QObject::connect(charts_widget, &ChartsWidget::rangeChanged, video_widget, &VideoWidget::rangeChanged); diff --git a/tools/cabana/signaledit.cc b/tools/cabana/signaledit.cc index 1bb5e9e533..ef0a85eba3 100644 --- a/tools/cabana/signaledit.cc +++ b/tools/cabana/signaledit.cc @@ -82,15 +82,14 @@ SignalEdit::SignalEdit(int index, const QString &msg_id, const Signal *sig, QWid title_layout->addWidget(title, 1); QPushButton *seek_btn = new QPushButton("⌕"); - seek_btn->setStyleSheet("font-weight:bold;font-size:20px"); + seek_btn->setStyleSheet("QPushButton{font-weight:bold;font-size:18px}"); seek_btn->setToolTip(tr("Find signal values")); - seek_btn->setFixedSize(20, 20); + seek_btn->setFixedSize(25, 25); title_layout->addWidget(seek_btn); - QPushButton *plot_btn = new QPushButton("📈"); - plot_btn->setToolTip(tr("Show Plot")); - plot_btn->setFixedSize(20, 20); - QObject::connect(plot_btn, &QPushButton::clicked, this, &SignalEdit::showChart); + plot_btn = new QPushButton(this); + plot_btn->setStyleSheet("QPushButton {font-size:18px}"); + plot_btn->setFixedSize(25, 25); title_layout->addWidget(plot_btn); main_layout->addLayout(title_layout); @@ -120,6 +119,7 @@ SignalEdit::SignalEdit(int index, const QString &msg_id, const Signal *sig, QWid QObject::connect(remove_btn, &QPushButton::clicked, [this]() { emit remove(this->sig); }); QObject::connect(title, &ElidedLabel::clicked, this, &SignalEdit::showFormClicked); QObject::connect(save_btn, &QPushButton::clicked, this, &SignalEdit::saveSignal); + QObject::connect(plot_btn, &QPushButton::clicked, [this]() { emit showChart(!chart_opened); }); QObject::connect(seek_btn, &QPushButton::clicked, [this, msg_id]() { SignalFindDlg dlg(msg_id, this->sig, this); dlg.exec(); @@ -145,6 +145,12 @@ void SignalEdit::saveSignal() { emit save(this->sig, s); } +void SignalEdit::setChartOpened(bool opened) { + plot_btn->setText(opened ? "☒" : "📈"); + plot_btn->setToolTip(opened ? tr("Close Plot") :tr("Show Plot")); + chart_opened = opened; +} + void SignalEdit::setFormVisible(bool visible) { form_container->setVisible(visible); icon->setText(visible ? "▼" : ">"); diff --git a/tools/cabana/signaledit.h b/tools/cabana/signaledit.h index 71719852f1..e3d38d5b25 100644 --- a/tools/cabana/signaledit.h +++ b/tools/cabana/signaledit.h @@ -26,13 +26,15 @@ class SignalEdit : public QWidget { public: SignalEdit(int index, const QString &msg_id, const Signal *sig, QWidget *parent = nullptr); + void setChartOpened(bool opened); void setFormVisible(bool show); void signalHovered(const Signal *sig); inline bool isFormVisible() const { return form_container->isVisible(); } + const Signal *sig = nullptr; signals: void highlight(const Signal *sig); - void showChart(); + void showChart(bool show); void showFormClicked(); void remove(const Signal *sig); void save(const Signal *sig, const Signal &new_sig); @@ -48,7 +50,8 @@ protected: QLabel *icon; int form_idx = 0; QString msg_id; - const Signal *sig = nullptr; + bool chart_opened = false; + QPushButton *plot_btn; }; class SignalFindDlg : public QDialog { From 6fed76695cbab39ffbaca2cd5e656e4c5a5badca Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Sun, 30 Oct 2022 23:53:02 +0800 Subject: [PATCH 52/59] Cabana: fix possible crash when removing tabs (#26283) fix dead loop --- tools/cabana/detailwidget.cc | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/tools/cabana/detailwidget.cc b/tools/cabana/detailwidget.cc index 59e5b5f296..57a3910303 100644 --- a/tools/cabana/detailwidget.cc +++ b/tools/cabana/detailwidget.cc @@ -104,12 +104,7 @@ DetailWidget::DetailWidget(ChartsWidget *charts, QWidget *parent) : charts(chart setMessage(tabbar->tabText(index)); } }); - QObject::connect(tabbar, &QTabBar::tabCloseRequested, [=](int index) { - if (tabbar->currentIndex() == index) { - tabbar->setCurrentIndex(index == tabbar->count() - 1 ? index - 1 : index + 1); - } - tabbar->removeTab(index); - }); + QObject::connect(tabbar, &QTabBar::tabCloseRequested, tabbar, &QTabBar::removeTab); QObject::connect(charts, &ChartsWidget::chartOpened, [this](const QString &id, const Signal *sig) { updateChartState(id, sig, true); }); QObject::connect(charts, &ChartsWidget::chartClosed, [this](const QString &id, const Signal *sig) { updateChartState(id, sig, false); }); } @@ -120,9 +115,14 @@ void DetailWidget::showTabBarContextMenu(const QPoint &pt) { QMenu menu(this); menu.addAction(tr("Close Other Tabs")); if (menu.exec(tabbar->mapToGlobal(pt))) { - for (int i = tabbar->count() - 1; i >= 0; --i) { - if (i != index) - tabbar->removeTab(i); + tabbar->setCurrentIndex(index); + // remove all tabs before the one to keep + for (int i = 0; i < index; ++i) { + tabbar->removeTab(0); + } + // remove all tabs after the one to keep + while (tabbar->count() > 1) { + tabbar->removeTab(1); } } } From eecd6982059211491cb019dca5453dcde9cc1038 Mon Sep 17 00:00:00 2001 From: Kurt Nistelberger Date: Sun, 30 Oct 2022 17:39:40 -0700 Subject: [PATCH 53/59] remove black connecting background --- selfdrive/ui/qt/offroad/networking.cc | 1 - 1 file changed, 1 deletion(-) diff --git a/selfdrive/ui/qt/offroad/networking.cc b/selfdrive/ui/qt/offroad/networking.cc index 13697adfb5..5b87d47976 100644 --- a/selfdrive/ui/qt/offroad/networking.cc +++ b/selfdrive/ui/qt/offroad/networking.cc @@ -256,7 +256,6 @@ WifiUI::WifiUI(QWidget *parent, WifiManager* wifi) : QWidget(parent), wifi(wifi) padding: 27px; padding-left: 43px; padding-right: 43px; - background-color: black; } #ssidLabel { font-size: 55px; From 0c03fb1be4f47facef1bcda9ad3cb97b98636286 Mon Sep 17 00:00:00 2001 From: Kurt Nistelberger Date: Sun, 30 Oct 2022 17:43:15 -0700 Subject: [PATCH 54/59] Revert "remove black connecting background" This reverts commit eecd6982059211491cb019dca5453dcde9cc1038. --- selfdrive/ui/qt/offroad/networking.cc | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/ui/qt/offroad/networking.cc b/selfdrive/ui/qt/offroad/networking.cc index 5b87d47976..13697adfb5 100644 --- a/selfdrive/ui/qt/offroad/networking.cc +++ b/selfdrive/ui/qt/offroad/networking.cc @@ -256,6 +256,7 @@ WifiUI::WifiUI(QWidget *parent, WifiManager* wifi) : QWidget(parent), wifi(wifi) padding: 27px; padding-left: 43px; padding-right: 43px; + background-color: black; } #ssidLabel { font-size: 55px; From c3388d216c33111ae8bd16452016cf8908679c28 Mon Sep 17 00:00:00 2001 From: YassineYousfi Date: Sun, 30 Oct 2022 23:55:48 -0700 Subject: [PATCH 55/59] Model trained with headlight augmentation (#26284) * d8501d20-bb59-4193-aa82-82b2737dedd6/449 ddfe2a22-fb0e-4ff0-a97f-0157b95eb44d/700 * update ref --- selfdrive/modeld/models/supercombo.onnx | 2 +- selfdrive/test/process_replay/model_replay_ref_commit | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/modeld/models/supercombo.onnx b/selfdrive/modeld/models/supercombo.onnx index 49a1c3a3b8..243223eabd 100644 --- a/selfdrive/modeld/models/supercombo.onnx +++ b/selfdrive/modeld/models/supercombo.onnx @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:a41d42f92913e6cc3909e505b1220b16d31f7cfca5f8a4e82109577b4151b645 +oid sha256:dcfad22cecf37275d01a339d96174800c109e9a70f853fdef3e4ef62ed3f4bbe size 45922983 diff --git a/selfdrive/test/process_replay/model_replay_ref_commit b/selfdrive/test/process_replay/model_replay_ref_commit index 5843a1e174..d13ced3a53 100644 --- a/selfdrive/test/process_replay/model_replay_ref_commit +++ b/selfdrive/test/process_replay/model_replay_ref_commit @@ -1 +1 @@ -d2f1711fd58d4f2c25b81bd332270da60ff9636d +49ea844254883ac61caa2ac425f453799aeb28a6 From b727f6cff4968a53dd489e9825b785d97eda66ef Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 31 Oct 2022 08:37:05 -0700 Subject: [PATCH 56/59] EV6 long tuning (#26166) * some matching and jerk limit * update that * one jerk limit * little more * more jerk * bump opendbc * update refs --- opendbc | 2 +- selfdrive/car/hyundai/carcontroller.py | 4 ++- selfdrive/car/hyundai/carstate.py | 38 ++++++++++---------- selfdrive/car/hyundai/hyundaicanfd.py | 44 +++++++++++++----------- selfdrive/car/hyundai/interface.py | 6 ++-- selfdrive/test/process_replay/ref_commit | 2 +- 6 files changed, 50 insertions(+), 46 deletions(-) diff --git a/opendbc b/opendbc index 526e21da66..b3dc569994 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit 526e21da666aeeabcf2369c66903a5675fdf933b +Subproject commit b3dc569994fd10e4de04afd650980c51ddfce5e1 diff --git a/selfdrive/car/hyundai/carcontroller.py b/selfdrive/car/hyundai/carcontroller.py index 913f683e2c..2f944edc0f 100644 --- a/selfdrive/car/hyundai/carcontroller.py +++ b/selfdrive/car/hyundai/carcontroller.py @@ -49,6 +49,7 @@ class CarController: self.angle_limit_counter = 0 self.frame = 0 + self.accel_last = 0 self.apply_steer_last = 0 self.car_fingerprint = CP.carFingerprint self.last_button_frame = 0 @@ -123,8 +124,9 @@ class CarController: if self.CP.openpilotLongitudinalControl: can_sends.extend(hyundaicanfd.create_adrv_messages(self.packer, self.frame)) if self.frame % 2 == 0: - can_sends.append(hyundaicanfd.create_acc_control(self.packer, self.CP, CC.enabled, accel, stopping, CC.cruiseControl.override, + can_sends.append(hyundaicanfd.create_acc_control(self.packer, self.CP, CC.enabled, self.accel_last, accel, stopping, CC.cruiseControl.override, set_speed_in_units)) + self.accel_last = accel else: # button presses if (self.frame - self.last_button_frame) * DT_CTRL > 0.25: diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py index 2e4cb0d25a..3cce581868 100644 --- a/selfdrive/car/hyundai/carstate.py +++ b/selfdrive/car/hyundai/carstate.py @@ -196,10 +196,10 @@ class CarState(CarStateBase): if not self.CP.openpilotLongitudinalControl: speed_factor = CV.KPH_TO_MS if self.is_metric else CV.MPH_TO_MS cp_cruise_info = cp if self.CP.flags & HyundaiFlags.CANFD_HDA2 else cp_cam - ret.cruiseState.speed = cp_cruise_info.vl["CRUISE_INFO"]["SET_SPEED"] * speed_factor - ret.cruiseState.standstill = cp_cruise_info.vl["CRUISE_INFO"]["CRUISE_STANDSTILL"] == 1 - ret.cruiseState.enabled = cp_cruise_info.vl["CRUISE_INFO"]["CRUISE_STATUS"] != 0 - self.cruise_info = copy.copy(cp_cruise_info.vl["CRUISE_INFO"]) + ret.cruiseState.speed = cp_cruise_info.vl["SCC_CONTROL"]["VSetDis"] * speed_factor + ret.cruiseState.standstill = cp_cruise_info.vl["SCC_CONTROL"]["CRUISE_STANDSTILL"] == 1 + ret.cruiseState.enabled = cp_cruise_info.vl["SCC_CONTROL"]["ACCMode"] in (1, 2) + self.cruise_info = copy.copy(cp_cruise_info.vl["SCC_CONTROL"]) cruise_btn_msg = "CRUISE_BUTTONS_ALT" if self.CP.flags & HyundaiFlags.CANFD_ALT_BUTTONS else "CRUISE_BUTTONS" self.prev_cruise_buttons = self.cruise_buttons[-1] @@ -464,12 +464,12 @@ class CarState(CarStateBase): if CP.flags & HyundaiFlags.CANFD_HDA2 and not CP.openpilotLongitudinalControl: signals += [ - ("CRUISE_STATUS", "CRUISE_INFO"), - ("SET_SPEED", "CRUISE_INFO"), - ("CRUISE_STANDSTILL", "CRUISE_INFO"), + ("ACCMode", "SCC_CONTROL"), + ("VSetDis", "SCC_CONTROL"), + ("CRUISE_STANDSTILL", "SCC_CONTROL"), ] checks += [ - ("CRUISE_INFO", 50), + ("SCC_CONTROL", 50), ] if CP.carFingerprint in EV_CAR: @@ -497,20 +497,20 @@ class CarState(CarStateBase): checks = [("CAM_0x2a4", 20)] else: signals = [ - ("COUNTER", "CRUISE_INFO"), - ("NEW_SIGNAL_1", "CRUISE_INFO"), - ("CRUISE_MAIN", "CRUISE_INFO"), - ("CRUISE_STATUS", "CRUISE_INFO"), - ("CRUISE_INACTIVE", "CRUISE_INFO"), - ("ZEROS_9", "CRUISE_INFO"), - ("CRUISE_STANDSTILL", "CRUISE_INFO"), - ("ZEROS_5", "CRUISE_INFO"), - ("DISTANCE_SETTING", "CRUISE_INFO"), - ("SET_SPEED", "CRUISE_INFO"), + ("COUNTER", "SCC_CONTROL"), + ("NEW_SIGNAL_1", "SCC_CONTROL"), + ("MainMode_ACC", "SCC_CONTROL"), + ("ACCMode", "SCC_CONTROL"), + ("CRUISE_INACTIVE", "SCC_CONTROL"), + ("ZEROS_9", "SCC_CONTROL"), + ("CRUISE_STANDSTILL", "SCC_CONTROL"), + ("ZEROS_5", "SCC_CONTROL"), + ("DISTANCE_SETTING", "SCC_CONTROL"), + ("VSetDis", "SCC_CONTROL"), ] checks = [ - ("CRUISE_INFO", 50), + ("SCC_CONTROL", 50), ] return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 6) diff --git a/selfdrive/car/hyundai/hyundaicanfd.py b/selfdrive/car/hyundai/hyundaicanfd.py index e1478e6f18..8b53e7c378 100644 --- a/selfdrive/car/hyundai/hyundaicanfd.py +++ b/selfdrive/car/hyundai/hyundaicanfd.py @@ -1,3 +1,4 @@ +from common.numpy_fast import clip from selfdrive.car.hyundai.values import HyundaiFlags @@ -52,10 +53,9 @@ def create_buttons(packer, CP, cnt, btn): def create_acc_cancel(packer, CP, cruise_info_copy): values = cruise_info_copy values.update({ - "CRUISE_STATUS": 0, - "CRUISE_INACTIVE": 1, + "ACCMode": 4, }) - return packer.make_can_msg("CRUISE_INFO", get_e_can_bus(CP), values) + return packer.make_can_msg("SCC_CONTROL", get_e_can_bus(CP), values) def create_lfahda_cluster(packer, CP, enabled): values = { @@ -65,33 +65,37 @@ def create_lfahda_cluster(packer, CP, enabled): return packer.make_can_msg("LFAHDA_CLUSTER", get_e_can_bus(CP), values) -def create_acc_control(packer, CP, enabled, accel, stopping, gas_override, set_speed): - cruise_status = 0 if not enabled else (4 if gas_override else 2) +def create_acc_control(packer, CP, enabled, accel_last, accel, stopping, gas_override, set_speed): + jerk = 5 + jn = jerk / 50 if not enabled or gas_override: - accel = 0 + a_val, a_raw = 0, 0 + else: + a_raw = accel + a_val = clip(accel, accel_last - jn, accel_last + jn) + if stopping: + a_raw = 0 + values = { - "CRUISE_STATUS": cruise_status, - "CRUISE_INACTIVE": 0 if enabled else 1, - "CRUISE_MAIN": 1, - "CRUISE_STANDSTILL": 0, - "STOP_REQ": 1 if stopping else 0, - "ACCEL_REQ": accel, - "ACCEL_REQ2": accel, - "SET_SPEED": set_speed, - "DISTANCE_SETTING": 4, + "ACCMode": 0 if not enabled else (2 if gas_override else 1), + "MainMode_ACC": 1, + "StopReq": 1 if stopping else 0, + "aReqValue": a_val, + "aReqRaw": a_raw, + "VSetDis": set_speed, + "JerkLowerLimit": jerk if enabled else 1, "ACC_ObjDist": 1, - "ObjValid": 1, + "ObjValid": 0, "OBJ_STATUS": 2, - "SET_ME_2": 0x2, + "SET_ME_2": 0x4, "SET_ME_3": 0x3, "SET_ME_TMP_64": 0x64, - - "NEW_SIGNAL_9": 2, "NEW_SIGNAL_10": 4, + "DISTANCE_SETTING": 4, } - return packer.make_can_msg("CRUISE_INFO", get_e_can_bus(CP), values) + return packer.make_can_msg("SCC_CONTROL", get_e_can_bus(CP), values) diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 6a1d741dec..4b4d51f3f1 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -202,14 +202,10 @@ class CarInterface(CarInterfaceBase): if candidate in CANFD_CAR: ret.longitudinalTuning.kpV = [0.1] ret.longitudinalTuning.kiV = [0.0] - ret.longitudinalActuatorDelayLowerBound = 0.15 - ret.longitudinalActuatorDelayUpperBound = 0.5 ret.experimentalLongitudinalAvailable = bool(ret.flags & HyundaiFlags.CANFD_HDA2) else: ret.longitudinalTuning.kpV = [0.5] ret.longitudinalTuning.kiV = [0.0] - ret.longitudinalActuatorDelayLowerBound = 0.5 - ret.longitudinalActuatorDelayUpperBound = 0.5 ret.experimentalLongitudinalAvailable = candidate not in (LEGACY_SAFETY_MODE_CAR | CAMERA_SCC_CAR) ret.openpilotLongitudinalControl = experimental_long and ret.experimentalLongitudinalAvailable ret.pcmCruise = not ret.openpilotLongitudinalControl @@ -218,6 +214,8 @@ class CarInterface(CarInterfaceBase): ret.startingState = True ret.vEgoStarting = 0.1 ret.startAccel = 2.0 + ret.longitudinalActuatorDelayLowerBound = 0.5 + ret.longitudinalActuatorDelayUpperBound = 0.5 # *** feature detection *** if candidate in CANFD_CAR: diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index c7d81c3496..0e4ac94784 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -e56c5a6ac5b87ee6083c9f92921e7198591f7b5d +fc3a044c567a8702ed1500d745170c365dd6b3d4 \ No newline at end of file From af685851af226041f349212a0344dd00f0c3dd6e Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Tue, 1 Nov 2022 00:50:27 +0800 Subject: [PATCH 57/59] Cabana: update msg name after load dbc from paste (#26294) update msg name after load dbc from paste --- tools/cabana/messageswidget.cc | 1 + 1 file changed, 1 insertion(+) diff --git a/tools/cabana/messageswidget.cc b/tools/cabana/messageswidget.cc index 4d97bba589..205e5347ce 100644 --- a/tools/cabana/messageswidget.cc +++ b/tools/cabana/messageswidget.cc @@ -98,6 +98,7 @@ void MessagesWidget::loadDBCFromPaste() { if (dlg.exec()) { dbc()->open("from paste", dlg.dbc_edit->toPlainText()); dbc_combo->setCurrentText("loaded from paste"); + model->updateState(true); } } From 23f290941aa16742ba9d9477c4d98533aca15322 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Tue, 1 Nov 2022 00:51:41 +0800 Subject: [PATCH 58/59] Cabana: get double precision from std::numeric_limits (#26293) fix precision --- tools/cabana/dbcmanager.cc | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/tools/cabana/dbcmanager.cc b/tools/cabana/dbcmanager.cc index 479b14afec..0ab67dd305 100644 --- a/tools/cabana/dbcmanager.cc +++ b/tools/cabana/dbcmanager.cc @@ -1,5 +1,6 @@ #include "tools/cabana/dbcmanager.h" +#include #include #include @@ -41,8 +42,8 @@ QString DBCManager::generateDBC() { .arg(sig.size) .arg(sig.is_little_endian ? '1' : '0') .arg(sig.is_signed ? '-' : '+') - .arg(sig.factor, 0, 'g', 20) - .arg(sig.offset); + .arg(sig.factor, 0, 'g', std::numeric_limits::digits10) + .arg(sig.offset, 0, 'g', std::numeric_limits::digits10); } dbc_string += "\n"; } From 131263a75b1cbf6bff0e01a1561d87d25faae353 Mon Sep 17 00:00:00 2001 From: FAN HANGYU <111691572+MaloneFan@users.noreply.github.com> Date: Tue, 1 Nov 2022 04:13:57 +0800 Subject: [PATCH 59/59] Honda: add Chinese Odyssey FW versions (#25943) * Update values.py add a carFW of odyssey_chn * move after odyssey * common carparams * just ignore Co-authored-by: Shane Smiskol --- selfdrive/car/honda/interface.py | 18 ++++++------------ selfdrive/car/honda/values.py | 17 +++++++++++++++++ selfdrive/car/tests/routes.py | 2 +- 3 files changed, 24 insertions(+), 13 deletions(-) diff --git a/selfdrive/car/honda/interface.py b/selfdrive/car/honda/interface.py index c884f586a0..e397f02838 100755 --- a/selfdrive/car/honda/interface.py +++ b/selfdrive/car/honda/interface.py @@ -220,23 +220,17 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2], [0.06]] tire_stiffness_factor = 0.677 - elif candidate == CAR.ODYSSEY: - ret.mass = 4471. * CV.LB_TO_KG + STD_CARGO_KG + elif candidate in (CAR.ODYSSEY, CAR.ODYSSEY_CHN): + ret.mass = 1900. + STD_CARGO_KG ret.wheelbase = 3.00 ret.centerToFront = ret.wheelbase * 0.41 ret.steerRatio = 14.35 # as spec - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end - tire_stiffness_factor = 0.82 - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.28], [0.08]] - - elif candidate == CAR.ODYSSEY_CHN: - ret.mass = 1849.2 + STD_CARGO_KG # mean of 4 models in kg - ret.wheelbase = 2.90 - ret.centerToFront = ret.wheelbase * 0.41 # from CAR.ODYSSEY - ret.steerRatio = 14.35 - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 32767], [0, 32767]] # TODO: determine if there is a dead zone at the top end tire_stiffness_factor = 0.82 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.28], [0.08]] + if candidate == CAR.ODYSSEY_CHN: + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 32767], [0, 32767]] # TODO: determine if there is a dead zone at the top end + else: + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end elif candidate in (CAR.PILOT, CAR.PASSPORT): ret.mass = 4204. * CV.LB_TO_KG + STD_CARGO_KG # average weight diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py index e0810e0bbb..2510f2e1ff 100644 --- a/selfdrive/car/honda/values.py +++ b/selfdrive/car/honda/values.py @@ -1031,6 +1031,23 @@ FW_VERSIONS = { b'54008-THR-A020\x00\x00', ], }, + CAR.ODYSSEY_CHN: { + (Ecu.eps, 0x18da30f1, None): [ + b'39990-T6D-H220\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-T6A-J010\x00\x00', + ], + (Ecu.combinationMeter, 0x18da60f1, None): [ + b'78109-T6A-F310\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36161-T6A-P040\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-T6A-P110\x00\x00', + ], + }, CAR.PILOT: { (Ecu.shiftByWire, 0x18da0bf1, None): [ b'54008-TG7-A520\x00\x00', diff --git a/selfdrive/car/tests/routes.py b/selfdrive/car/tests/routes.py index 326d80b822..5c6d214bcc 100644 --- a/selfdrive/car/tests/routes.py +++ b/selfdrive/car/tests/routes.py @@ -25,6 +25,7 @@ non_tested_cars = [ GM.BOLT_EV, HYUNDAI.GENESIS_G90, HYUNDAI.KIA_OPTIMA_H, + HONDA.ODYSSEY_CHN, ] CarTestRoute = namedtuple('CarTestRoute', ['route', 'car_model', 'segment'], defaults=(None,)) @@ -61,7 +62,6 @@ routes = [ CarTestRoute("2c4292a5cd10536c|2021-08-19--21-32-15", HONDA.FREED), CarTestRoute("03be5f2fd5c508d1|2020-04-19--18-44-15", HONDA.HRV), CarTestRoute("917b074700869333|2021-05-24--20-40-20", HONDA.ACURA_ILX), - CarTestRoute("81722949a62ea724|2019-04-06--15-19-25", HONDA.ODYSSEY_CHN), CarTestRoute("08a3deb07573f157|2020-03-06--16-11-19", HONDA.ACCORD), # 1.5T CarTestRoute("1da5847ac2488106|2021-05-24--19-31-50", HONDA.ACCORD), # 2.0T CarTestRoute("085ac1d942c35910|2021-03-25--20-11-15", HONDA.ACCORD), # 2021 with new style HUD msgs