From df48ab9ee28a28173e3e84f6e7c5da585469de28 Mon Sep 17 00:00:00 2001 From: khoi <6994441+khoi@users.noreply.github.com> Date: Tue, 16 Aug 2022 11:46:56 +0700 Subject: [PATCH 001/172] Car docs: add video link for Hyundai Santa Fe 2022 (#25449) * Add video link for Santa Fe 2022 * Update selfdrive/car/hyundai/values.py Co-authored-by: Shane Smiskol --- selfdrive/car/hyundai/values.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 625b2630f..afd17b86a 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -112,7 +112,7 @@ CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = { CAR.KONA_EV_2022: HyundaiCarInfo("Hyundai Kona Electric 2022", "Smart Cruise Control (SCC)", harness=Harness.hyundai_o), CAR.KONA_HEV: HyundaiCarInfo("Hyundai Kona Hybrid 2020", video_link="https://youtu.be/0dwpAHiZgFo", harness=Harness.hyundai_i), CAR.SANTA_FE: HyundaiCarInfo("Hyundai Santa Fe 2019-20", "All", harness=Harness.hyundai_d), - CAR.SANTA_FE_2022: HyundaiCarInfo("Hyundai Santa Fe 2021-22", "All", harness=Harness.hyundai_l), + CAR.SANTA_FE_2022: HyundaiCarInfo("Hyundai Santa Fe 2021-22", "All", video_link="https://youtu.be/VnHzSTygTS4", harness=Harness.hyundai_l), CAR.SANTA_FE_HEV_2022: HyundaiCarInfo("Hyundai Santa Fe Hybrid 2022", "All", harness=Harness.hyundai_l), CAR.SANTA_FE_PHEV_2022: HyundaiCarInfo("Hyundai Santa Fe Plug-in Hybrid 2022", "All", harness=Harness.hyundai_l), CAR.SONATA: HyundaiCarInfo("Hyundai Sonata 2020-22", "All", video_link="https://www.youtube.com/watch?v=ix63r9kE3Fw", harness=Harness.hyundai_a), From 4602e5a8f9e23f173635e9e00a60ab3b73deb254 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 16 Aug 2022 00:32:42 -0700 Subject: [PATCH 002/172] process replay: print correct ref path (#25448) * fix log paths ref printing in process replay * rm that * this is easier to read * fix model_replay --- selfdrive/test/process_replay/model_replay.py | 2 +- .../test/process_replay/test_processes.py | 19 +++++++++---------- 2 files changed, 10 insertions(+), 11 deletions(-) diff --git a/selfdrive/test/process_replay/model_replay.py b/selfdrive/test/process_replay/model_replay.py index 12f3583ee..d2090aa76 100755 --- a/selfdrive/test/process_replay/model_replay.py +++ b/selfdrive/test/process_replay/model_replay.py @@ -176,7 +176,7 @@ if __name__ == "__main__": # TODO this tolerence is absurdly large tolerance = 5e-1 if PC else None results: Any = {TEST_ROUTE: {}} - log_paths: Any = {TEST_ROUTE: {'ref': BASE_URL + log_fn, 'new': log_fn}} + log_paths: Any = {TEST_ROUTE: {"models": {'ref': BASE_URL + log_fn, 'new': log_fn}}} results[TEST_ROUTE]["models"] = compare_logs(cmp_log, log_msgs, tolerance=tolerance, ignore_fields=ignore) diff1, diff2, failed = format_diff(results, log_paths, ref_commit) diff --git a/selfdrive/test/process_replay/test_processes.py b/selfdrive/test/process_replay/test_processes.py index 9e6fee0de..68c1666b5 100755 --- a/selfdrive/test/process_replay/test_processes.py +++ b/selfdrive/test/process_replay/test_processes.py @@ -117,19 +117,19 @@ def format_diff(results, log_paths, ref_commit): for proc, diff in list(result.items()): # long diff diff2 += f"*** process: {proc} ***\n" - diff2 += f"\tref: {log_paths[segment]['ref']}\n\n" - diff2 += f"\tnew: {log_paths[segment]['new']}\n\n" + diff2 += f"\tref: {log_paths[segment][proc]['ref']}\n" + diff2 += f"\tnew: {log_paths[segment][proc]['new']}\n\n" # short diff diff1 += f" {proc}\n" if isinstance(diff, str): - diff1 += f" ref: {log_paths[segment]['ref']}\n" - diff1 += f" new: {log_paths[segment]['new']}\n\n" + diff1 += f" ref: {log_paths[segment][proc]['ref']}\n" + diff1 += f" new: {log_paths[segment][proc]['new']}\n\n" diff1 += f" {diff}\n" failed = True elif len(diff): - diff1 += f" ref: {log_paths[segment]['ref']}\n" - diff1 += f" new: {log_paths[segment]['new']}\n\n" + diff1 += f" ref: {log_paths[segment][proc]['ref']}\n" + diff1 += f" new: {log_paths[segment][proc]['new']}\n\n" cnt: Dict[str, int] = {} for d in diff: @@ -196,8 +196,7 @@ if __name__ == "__main__": untested = (set(interface_names) - set(excluded_interfaces)) - {c.lower() for c in tested_cars} assert len(untested) == 0, f"Cars missing routes: {str(untested)}" - - log_paths: DefaultDict[str, Dict[str, str]] = defaultdict(dict) + log_paths: DefaultDict[str, Dict[str, Dict[str, str]]] = defaultdict(lambda: defaultdict(dict)) with concurrent.futures.ProcessPoolExecutor(max_workers=args.jobs) as pool: if not args.upload_only: download_segments = [seg for car, seg in segments if car in tested_cars] @@ -225,8 +224,8 @@ if __name__ == "__main__": dat = None if args.upload_only else log_data[segment] pool_args.append((segment, cfg, args, cur_log_fn, ref_log_path, dat)) - log_paths[segment]['ref'] = ref_log_path - log_paths[segment]['new'] = cur_log_fn + log_paths[segment][cfg.proc_name + cfg.subtest_name]['ref'] = ref_log_path + log_paths[segment][cfg.proc_name + cfg.subtest_name]['new'] = cur_log_fn results: Any = defaultdict(dict) p2 = pool.map(run_test_process, pool_args) From 721fae7e8e0fdf239c2ef5bf138c8e7ca7f16771 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 16 Aug 2022 00:37:11 -0700 Subject: [PATCH 003/172] Multilang: language policy (#25414) * add draft translation merging policy * Update policy copy * copy * add link * Update selfdrive/ui/translations/README.md --- selfdrive/ui/translations/README.md | 10 +++++++++- 1 file changed, 9 insertions(+), 1 deletion(-) diff --git a/selfdrive/ui/translations/README.md b/selfdrive/ui/translations/README.md index 349b4847a..5d4698614 100644 --- a/selfdrive/ui/translations/README.md +++ b/selfdrive/ui/translations/README.md @@ -11,6 +11,14 @@ Before getting started, make sure you have set up the openpilot Ubuntu development environment by reading the [tools README.md](/tools/README.md). +### Policy + +Most of the languages supported by openpilot come from and are maintained by the community via pull requests. A pull request likely to be merged is one that [fixes a translation or adds missing translations.](https://github.com/commaai/openpilot/blob/lang-policy/selfdrive/ui/translations/README.md#improving-an-existing-language) + +We also generally merge pull requests adding support for a new language if there are community members willing to maintain it. Maintaining a language is ensuring quality and completion of translations before each openpilot release. + +comma may remove or hide language support from releases depending on translation quality and completeness. + ### Adding a New Language openpilot provides a few tools to help contributors manage their translations and to ensure quality. To get started: @@ -39,7 +47,7 @@ Any time you edit source code in the UI, you need to update the translations to ### Testing -openpilot has a few unit tests to make sure all translations are up to date and that all strings are wrapped in a translation marker. They are run in CI, but you can also run them locally. +openpilot has a few unit tests to make sure all translations are up-to-date and that all strings are wrapped in a translation marker. They are run in CI, but you can also run them locally. Tests translation files up to date: From 3fc001c945bb5e9092050bac1e55267dab63b9eb Mon Sep 17 00:00:00 2001 From: Chris Souers Date: Tue, 16 Aug 2022 03:40:47 -0400 Subject: [PATCH 004/172] Honda: cleanup minEnableSpeed (#25447) * Honda interface.py: cleanup `stop_and_go` variable * Update selfdrive/car/honda/interface.py Co-authored-by: Shane Smiskol --- selfdrive/car/honda/interface.py | 21 ++------------------- 1 file changed, 2 insertions(+), 19 deletions(-) diff --git a/selfdrive/car/honda/interface.py b/selfdrive/car/honda/interface.py index a78189b69..b14618271 100755 --- a/selfdrive/car/honda/interface.py +++ b/selfdrive/car/honda/interface.py @@ -86,7 +86,6 @@ class CarInterface(CarInterfaceBase): eps_modified = True if candidate == CAR.CIVIC: - stop_and_go = True ret.mass = CivicParams.MASS ret.wheelbase = CivicParams.WHEELBASE ret.centerToFront = CivicParams.CENTER_TO_FRONT @@ -106,7 +105,6 @@ class CarInterface(CarInterfaceBase): tire_stiffness_factor = 1. elif candidate in (CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CIVIC_2022): - stop_and_go = True ret.mass = CivicParams.MASS ret.wheelbase = CivicParams.WHEELBASE ret.centerToFront = CivicParams.CENTER_TO_FRONT @@ -116,7 +114,6 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] elif candidate in (CAR.ACCORD, CAR.ACCORDH): - stop_and_go = True ret.mass = 3279. * CV.LB_TO_KG + STD_CARGO_KG ret.wheelbase = 2.83 ret.centerToFront = ret.wheelbase * 0.39 @@ -130,7 +127,6 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.18]] elif candidate == CAR.ACURA_ILX: - stop_and_go = False ret.mass = 3095. * CV.LB_TO_KG + STD_CARGO_KG ret.wheelbase = 2.67 ret.centerToFront = ret.wheelbase * 0.37 @@ -140,7 +136,6 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] elif candidate in (CAR.CRV, CAR.CRV_EU): - stop_and_go = False ret.mass = 3572. * CV.LB_TO_KG + STD_CARGO_KG ret.wheelbase = 2.62 ret.centerToFront = ret.wheelbase * 0.41 @@ -151,7 +146,6 @@ class CarInterface(CarInterfaceBase): ret.wheelSpeedFactor = 1.025 elif candidate == CAR.CRV_5G: - stop_and_go = True ret.mass = 3410. * CV.LB_TO_KG + STD_CARGO_KG ret.wheelbase = 2.66 ret.centerToFront = ret.wheelbase * 0.41 @@ -169,7 +163,6 @@ class CarInterface(CarInterfaceBase): ret.wheelSpeedFactor = 1.025 elif candidate == CAR.CRV_HYBRID: - stop_and_go = True ret.mass = 1667. + STD_CARGO_KG # mean of 4 models in kg ret.wheelbase = 2.66 ret.centerToFront = ret.wheelbase * 0.41 @@ -180,7 +173,6 @@ class CarInterface(CarInterfaceBase): ret.wheelSpeedFactor = 1.025 elif candidate == CAR.FIT: - stop_and_go = False ret.mass = 2644. * CV.LB_TO_KG + STD_CARGO_KG ret.wheelbase = 2.53 ret.centerToFront = ret.wheelbase * 0.39 @@ -190,7 +182,6 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2], [0.05]] elif candidate == CAR.FREED: - stop_and_go = False ret.mass = 3086. * CV.LB_TO_KG + STD_CARGO_KG ret.wheelbase = 2.74 # the remaining parameters were copied from FIT @@ -201,7 +192,6 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2], [0.05]] elif candidate == CAR.HRV: - stop_and_go = False ret.mass = 3125 * CV.LB_TO_KG + STD_CARGO_KG ret.wheelbase = 2.61 ret.centerToFront = ret.wheelbase * 0.41 @@ -212,7 +202,6 @@ class CarInterface(CarInterfaceBase): ret.wheelSpeedFactor = 1.025 elif candidate == CAR.ACURA_RDX: - stop_and_go = False ret.mass = 3935. * CV.LB_TO_KG + STD_CARGO_KG ret.wheelbase = 2.68 ret.centerToFront = ret.wheelbase * 0.38 @@ -222,7 +211,6 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] elif candidate == CAR.ACURA_RDX_3G: - stop_and_go = True ret.mass = 4068. * CV.LB_TO_KG + STD_CARGO_KG ret.wheelbase = 2.75 ret.centerToFront = ret.wheelbase * 0.41 @@ -232,7 +220,6 @@ class CarInterface(CarInterfaceBase): tire_stiffness_factor = 0.677 elif candidate == CAR.ODYSSEY: - stop_and_go = False ret.mass = 4471. * CV.LB_TO_KG + STD_CARGO_KG ret.wheelbase = 3.00 ret.centerToFront = ret.wheelbase * 0.41 @@ -242,7 +229,6 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.28], [0.08]] elif candidate == CAR.ODYSSEY_CHN: - stop_and_go = False 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 @@ -252,7 +238,6 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.28], [0.08]] elif candidate in (CAR.PILOT, CAR.PASSPORT): - stop_and_go = False ret.mass = 4204. * CV.LB_TO_KG + STD_CARGO_KG # average weight ret.wheelbase = 2.82 ret.centerToFront = ret.wheelbase * 0.428 @@ -262,7 +247,6 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.38], [0.11]] elif candidate == CAR.RIDGELINE: - stop_and_go = False ret.mass = 4515. * CV.LB_TO_KG + STD_CARGO_KG ret.wheelbase = 3.18 ret.centerToFront = ret.wheelbase * 0.41 @@ -272,7 +256,6 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.38], [0.11]] elif candidate == CAR.INSIGHT: - stop_and_go = True ret.mass = 2987. * CV.LB_TO_KG + STD_CARGO_KG ret.wheelbase = 2.7 ret.centerToFront = ret.wheelbase * 0.39 @@ -282,7 +265,6 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.18]] elif candidate == CAR.HONDA_E: - stop_and_go = True ret.mass = 3338.8 * CV.LB_TO_KG + STD_CARGO_KG ret.wheelbase = 2.5 ret.centerToFront = ret.wheelbase * 0.5 @@ -311,7 +293,8 @@ class CarInterface(CarInterfaceBase): # min speed to enable ACC. if car can do stop and go, then set enabling speed # to a negative value, so it won't matter. Otherwise, add 0.5 mph margin to not # conflict with PCM acc - ret.minEnableSpeed = -1. if (stop_and_go or ret.enableGasInterceptor) else 25.5 * CV.MPH_TO_MS + stop_and_go = candidate in (HONDA_BOSCH | {CAR.CIVIC}) or ret.enableGasInterceptor + ret.minEnableSpeed = -1. if stop_and_go else 25.5 * CV.MPH_TO_MS # TODO: get actual value, for now starting with reasonable value for # civic and scaling by mass and wheelbase From 76a4daefffe0462162b984aae7baba25866903bb Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 16 Aug 2022 13:16:11 -0700 Subject: [PATCH 005/172] pj: update torque control layout --- .../plotjuggler/layouts/max-torque-debug.xml | 6 -- .../plotjuggler/layouts/torque-controller.xml | 60 ++++++++++--------- 2 files changed, 32 insertions(+), 34 deletions(-) diff --git a/tools/plotjuggler/layouts/max-torque-debug.xml b/tools/plotjuggler/layouts/max-torque-debug.xml index 05aa208e2..6903ca8b1 100644 --- a/tools/plotjuggler/layouts/max-torque-debug.xml +++ b/tools/plotjuggler/layouts/max-torque-debug.xml @@ -51,12 +51,6 @@ - - - - - - diff --git a/tools/plotjuggler/layouts/torque-controller.xml b/tools/plotjuggler/layouts/torque-controller.xml index 661bfe094..443255968 100644 --- a/tools/plotjuggler/layouts/torque-controller.xml +++ b/tools/plotjuggler/layouts/torque-controller.xml @@ -1,12 +1,12 @@ - + - + - + @@ -14,7 +14,7 @@ - + @@ -22,33 +22,26 @@ - + - - + + + + + + + + + + + + - - - - - - - - - - - - - - - - - @@ -64,19 +57,29 @@ - + + + return value * 3.6 + /carState/vEgo + + + + return value * 2.23694 + /carState/vEgo + + return (value * v1 ^ 2) - (v2 * 9.81) - /controlsState/curvature + /controlsState/desiredCurvature /carState/vEgo /liveParameters/roll - + return (value * v1 ^ 2) - (v2 * 9.81) - /controlsState/desiredCurvature + /controlsState/curvature /carState/vEgo /liveParameters/roll @@ -86,3 +89,4 @@ + From 0258ef74ff52b9f2d545537c05984de1b75252f8 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 16 Aug 2022 13:18:39 -0700 Subject: [PATCH 006/172] Hyundai: Kona torque tune (#25426) * Hyundai: Kona EV 2022 torque tune * Update selfdrive/car/hyundai/interface.py * update for all --- selfdrive/car/hyundai/interface.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index d3dc1a2c6..9080e5cdb 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -122,6 +122,7 @@ class CarInterface(CarInterfaceBase): tire_stiffness_factor = 0.385 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] + 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 From 0ed8a7f42def893bece557c0acd3d5fb1e11ecde Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 16 Aug 2022 13:41:58 -0700 Subject: [PATCH 007/172] Toyota: add new corolla fw --- selfdrive/car/toyota/values.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index b6181c1fd..b7b261adb 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -687,6 +687,7 @@ FW_VERSIONS = { b'\x01896630ZP2000\x00\x00\x00\x00', b'\x01896630ZQ5000\x00\x00\x00\x00', b'\x01896630ZU9000\x00\x00\x00\x00', + b'\x01896630ZX4000\x00\x00\x00\x00', b'\x018966312L8000\x00\x00\x00\x00', b'\x018966312M0000\x00\x00\x00\x00', b'\x018966312M9000\x00\x00\x00\x00', From c27d7913f2db43ec668dd068199bc568802dd809 Mon Sep 17 00:00:00 2001 From: Jason Young <46612682+jyoung8607@users.noreply.github.com> Date: Tue, 16 Aug 2022 17:32:59 -0400 Subject: [PATCH 008/172] VW PQ: Volkswagen Passat NMS (#24768) * VW PQ: Volkswagen Passat NMS * regen CARS.md * vEgo from Bremse_1 vehicle speed * sync opendbc to master * handle checksums and counters in opendbc * LDW HUD message handling * GRA_Neu_Zaehler -> COUNTER * bump opendbc * stub in till we find platform ACC standstill * bump opendbc * bump opendbc * placeholder lateral accel data * regen CARS.md * counters now directly supported in opendbc * additional door-open signals * add trunk lid state * add doors and trunk lid to signals list * LDW_Status updates and passthrough * bump opendbc for typo fix * update AWV comment * another comment update * regen CARS.md with PQ in dashcam only * don't show NMS footnotes while still in dashcam * polish * add stubbed-out dashcamOnly prep * VW MQB: Cleanup stock ACC button handling * bump opendbc and panda * use controls resume output as trigger * these can wait until taco bell * bump opendbc * pass through of previously fixed value * retry CI * checks already done in carcontroller * don't need these anymore * reduce diff for now * slightly better abstraction * more engine and trans FW * turn signal is instantaneous stalk position * weak sauce :( * better clarity * try torque tune * add test route references * bump opendbc and panda for OP long * don't show steering faults for 3 seconds after start * longitudinal control senders * a little more torque * test hax to torque control * test a little more delay * allow use of manufacturer ramp-up rate * soften wheel-touch threshold * Revert "test hax to torque control" This reverts commit d1af459c29e36264aae406f72b8fcbc9ef22b9e0. * punch it Chewie * better ACC state and mainswitch handling * a little more * tweak max accel gradient * oops * also oops * stuff * srsly * that's not how this works * regen CARS.md * footnotes now properly excluded for dashcam cars * this wasn't a problem * update network location detection * bump submodules for ACC main switch * clean up DBC references and long flag * bump one more time * one more time * follow CANPacker counter refactor * bump opendbc * sync opendbc to master * bump panda to fix Subaru tests * DBC handling cleanup * fix * model-year stretch * cleanup and rate bugfixes * better abstractions * simplify create_lka_hud_control * volkswagencan -> mqbcan * bump panda * fix doc data bug, regen CARS.md * style updates; diff reduction * use common button enable logic * not needed anymore * refactor TSK and HUD enum values * make common button events function * consistency * bump panda * bump panda * dashcam only * don't need process_replay yet * regen CARS.md with Passat NMS in dashcam * can't handle dashcam-orphaned footnotes yet * remove outdated standstill handling * editor tried to be too helpful at some point * don't need to import this anymore * Apply suggestions from code review Co-authored-by: Adeeb Shihadeh * follow parkingBrake refactor Co-authored-by: Adeeb Shihadeh --- panda | 2 +- release/files_common | 1 + selfdrive/car/tests/routes.py | 1 + selfdrive/car/torque_data/override.yaml | 1 + selfdrive/car/volkswagen/carcontroller.py | 21 +- selfdrive/car/volkswagen/carstate.py | 247 +++++++++++++++++- selfdrive/car/volkswagen/interface.py | 43 ++- selfdrive/car/volkswagen/pqcan.py | 84 ++++++ selfdrive/car/volkswagen/values.py | 62 ++++- .../test/process_replay/test_processes.py | 3 +- 10 files changed, 456 insertions(+), 9 deletions(-) create mode 100644 selfdrive/car/volkswagen/pqcan.py diff --git a/panda b/panda index 5e0dde7b4..199bc10db 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 5e0dde7b480a930d3c3a164331c930541e905d71 +Subproject commit 199bc10db3a937fab0c50d9b708f6c76234f5c3a diff --git a/release/files_common b/release/files_common index 8bf99f022..01386b585 100644 --- a/release/files_common +++ b/release/files_common @@ -552,6 +552,7 @@ opendbc/toyota_nodsu_pt_generated.dbc opendbc/toyota_adas.dbc opendbc/toyota_tss2_adas.dbc +opendbc/vw_golf_mk4.dbc opendbc/vw_mqb_2010.dbc opendbc/tesla_can.dbc diff --git a/selfdrive/car/tests/routes.py b/selfdrive/car/tests/routes.py index 0b1726b01..44672bf9d 100644 --- a/selfdrive/car/tests/routes.py +++ b/selfdrive/car/tests/routes.py @@ -168,6 +168,7 @@ routes = [ TestRoute("cae14e88932eb364|2021-03-26--14-43-28", VOLKSWAGEN.GOLF_MK7), TestRoute("58a7d3b707987d65|2021-03-25--17-26-37", VOLKSWAGEN.JETTA_MK7), TestRoute("4d134e099430fba2|2021-03-26--00-26-06", VOLKSWAGEN.PASSAT_MK8), + TestRoute("3cfdec54aa035f3f|2022-07-19--23-45-10", VOLKSWAGEN.PASSAT_NMS), TestRoute("0cd0b7f7e31a3853|2021-11-03--19-30-22", VOLKSWAGEN.POLO_MK6), TestRoute("7d82b2f3a9115f1f|2021-10-21--15-39-42", VOLKSWAGEN.TAOS_MK1), TestRoute("2744c89a8dda9a51|2021-07-24--21-28-06", VOLKSWAGEN.TCROSS_MK1), diff --git a/selfdrive/car/torque_data/override.yaml b/selfdrive/car/torque_data/override.yaml index 0a958a9d0..8dd8c4322 100644 --- a/selfdrive/car/torque_data/override.yaml +++ b/selfdrive/car/torque_data/override.yaml @@ -25,6 +25,7 @@ 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] CHEVROLET BOLT EUV 2022: [2.0, 2.0, 0.05] +VOLKSWAGEN PASSAT NMS: [2.5, 2.5, 0.1] # Dashcam or fallback configured as ideal car mock: [10.0, 10, 0.0] diff --git a/selfdrive/car/volkswagen/carcontroller.py b/selfdrive/car/volkswagen/carcontroller.py index 2c5830f86..f14c11989 100644 --- a/selfdrive/car/volkswagen/carcontroller.py +++ b/selfdrive/car/volkswagen/carcontroller.py @@ -1,8 +1,10 @@ from cereal import car from opendbc.can.packer import CANPacker +from common.numpy_fast import clip +from common.conversions import Conversions as CV from selfdrive.car import apply_std_steer_torque_limits -from selfdrive.car.volkswagen import mqbcan -from selfdrive.car.volkswagen.values import CANBUS, CarControllerParams +from selfdrive.car.volkswagen import mqbcan, pqcan +from selfdrive.car.volkswagen.values import CANBUS, PQ_CARS, CarControllerParams VisualAlert = car.CarControl.HUDControl.VisualAlert @@ -11,7 +13,7 @@ class CarController: def __init__(self, dbc_name, CP, VM): self.CP = CP self.CCP = CarControllerParams(CP) - self.CCS = mqbcan + self.CCS = pqcan if CP.carFingerprint in PQ_CARS else mqbcan self.packer_pt = CANPacker(dbc_name) self.apply_steer_last = 0 @@ -65,6 +67,13 @@ class CarController: self.apply_steer_last = apply_steer can_sends.append(self.CCS.create_steering_control(self.packer_pt, CANBUS.pt, apply_steer, hcaEnabled)) + # **** Acceleration Controls ******************************************** # + + if self.frame % self.CCP.ACC_CONTROL_STEP == 0 and self.CP.openpilotLongitudinalControl: + tsk_status = self.CCS.tsk_status_value(CS.out.cruiseState.available, CS.out.accFaulted, CC.longActive) + accel = clip(actuators.accel, self.CCP.ACCEL_MIN, self.CCP.ACCEL_MAX) if CC.longActive else 0 + can_sends.extend(self.CCS.create_acc_accel_control(self.packer_pt, CANBUS.pt, tsk_status, accel)) + # **** HUD Controls ***************************************************** # if self.frame % self.CCP.LDW_STEP == 0: @@ -74,6 +83,12 @@ class CarController: can_sends.append(self.CCS.create_lka_hud_control(self.packer_pt, CANBUS.pt, CS.ldw_stock_values, CC.enabled, CS.out.steeringPressed, hud_alert, hud_control)) + if self.frame % self.CCP.ACC_HUD_STEP == 0 and self.CP.openpilotLongitudinalControl: + acc_hud_status = self.CCS.acc_hud_status_value(CS.out.cruiseState.available, CS.out.accFaulted, CC.longActive) + set_speed = hud_control.setSpeed * CV.MS_TO_KPH # FIXME: follow the recent displayed-speed updates, also use mph_kmh toggle to fix display rounding problem? + can_sends.append(self.CCS.create_acc_hud_control(self.packer_pt, CANBUS.pt, acc_hud_status, set_speed, + hud_control.leadVisible)) + # **** Stock ACC Button Controls **************************************** # if self.CP.pcmCruise and self.frame % self.CCP.GRA_ACC_STEP == 0: diff --git a/selfdrive/car/volkswagen/carstate.py b/selfdrive/car/volkswagen/carstate.py index 50be6bf9a..facc740a1 100644 --- a/selfdrive/car/volkswagen/carstate.py +++ b/selfdrive/car/volkswagen/carstate.py @@ -3,7 +3,7 @@ from cereal import car from common.conversions import Conversions as CV from selfdrive.car.interfaces import CarStateBase from opendbc.can.parser import CANParser -from selfdrive.car.volkswagen.values import DBC, CANBUS, NetworkLocation, TransmissionType, GearShifter, \ +from selfdrive.car.volkswagen.values import DBC, CANBUS, PQ_CARS, NetworkLocation, TransmissionType, GearShifter, \ CarControllerParams @@ -28,6 +28,9 @@ class CarState(CarStateBase): return button_events def update(self, pt_cp, cam_cp, ext_cp, trans_type): + if self.CP.carFingerprint in PQ_CARS: + return self.update_pq(pt_cp, cam_cp, ext_cp, trans_type) + ret = car.CarState.new_message() # Update vehicle speed and acceleration from ABS wheel speeds. ret.wheelSpeeds = self.get_wheel_speeds( @@ -135,8 +138,111 @@ class CarState(CarStateBase): return ret + def update_pq(self, pt_cp, cam_cp, ext_cp, trans_type): + ret = car.CarState.new_message() + # Update vehicle speed and acceleration from ABS wheel speeds. + ret.wheelSpeeds = self.get_wheel_speeds( + pt_cp.vl["Bremse_3"]["Radgeschw__VL_4_1"], + pt_cp.vl["Bremse_3"]["Radgeschw__VR_4_1"], + pt_cp.vl["Bremse_3"]["Radgeschw__HL_4_1"], + pt_cp.vl["Bremse_3"]["Radgeschw__HR_4_1"], + ) + + # vEgo obtained from Bremse_1 vehicle speed rather than Bremse_3 wheel speeds because Bremse_3 isn't present on NSF + ret.vEgoRaw = pt_cp.vl["Bremse_1"]["Geschwindigkeit_neu__Bremse_1_"] * CV.KPH_TO_MS + ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) + ret.standstill = ret.vEgo < 0.1 + + # Update steering angle, rate, yaw rate, and driver input torque. VW send + # the sign/direction in a separate signal so they must be recombined. + ret.steeringAngleDeg = pt_cp.vl["Lenkhilfe_3"]["LH3_BLW"] * (1, -1)[int(pt_cp.vl["Lenkhilfe_3"]["LH3_BLWSign"])] + ret.steeringRateDeg = pt_cp.vl["Lenkwinkel_1"]["Lenkradwinkel_Geschwindigkeit"] * (1, -1)[int(pt_cp.vl["Lenkwinkel_1"]["Lenkradwinkel_Geschwindigkeit_S"])] + ret.steeringTorque = pt_cp.vl["Lenkhilfe_3"]["LH3_LM"] * (1, -1)[int(pt_cp.vl["Lenkhilfe_3"]["LH3_LMSign"])] + ret.steeringPressed = abs(ret.steeringTorque) > self.CCP.STEER_DRIVER_ALLOWANCE + ret.yawRate = pt_cp.vl["Bremse_5"]["Giergeschwindigkeit"] * (1, -1)[int(pt_cp.vl["Bremse_5"]["Vorzeichen_der_Giergeschwindigk"])] * CV.DEG_TO_RAD + + # Verify EPS readiness to accept steering commands + hca_status = self.CCP.hca_status_values.get(pt_cp.vl["Lenkhilfe_2"]["LH2_Sta_HCA"]) + ret.steerFaultPermanent = hca_status in ("DISABLED", "FAULT") + ret.steerFaultTemporary = hca_status in ("INITIALIZING", "REJECTED") + + # Update gas, brakes, and gearshift. + ret.gas = pt_cp.vl["Motor_3"]["Fahrpedal_Rohsignal"] / 100.0 + ret.gasPressed = ret.gas > 0 + ret.brake = pt_cp.vl["Bremse_5"]["Bremsdruck"] / 250.0 # FIXME: this is pressure in Bar, not sure what OP expects + ret.brakePressed = bool(pt_cp.vl["Motor_2"]["Bremstestschalter"]) + ret.parkingBrake = bool(pt_cp.vl["Kombi_1"]["Bremsinfo"]) + + # Update gear and/or clutch position data. + if trans_type == TransmissionType.automatic: + ret.gearShifter = self.parse_gear_shifter(self.CCP.shifter_values.get(pt_cp.vl["Getriebe_1"]["Waehlhebelposition__Getriebe_1_"], None)) + elif trans_type == TransmissionType.manual: + ret.clutchPressed = not pt_cp.vl["Motor_1"]["Kupplungsschalter"] + reverse_light = bool(pt_cp.vl["Gate_Komf_1"]["GK1_Rueckfahr"]) + if reverse_light: + ret.gearShifter = GearShifter.reverse + else: + ret.gearShifter = GearShifter.drive + + # Update door and trunk/hatch lid open status. + ret.doorOpen = any([pt_cp.vl["Gate_Komf_1"]["GK1_Fa_Tuerkont"], + pt_cp.vl["Gate_Komf_1"]["BSK_BT_geoeffnet"], + pt_cp.vl["Gate_Komf_1"]["BSK_HL_geoeffnet"], + pt_cp.vl["Gate_Komf_1"]["BSK_HR_geoeffnet"], + pt_cp.vl["Gate_Komf_1"]["BSK_HD_Hauptraste"]]) + + # Update seatbelt fastened status. + ret.seatbeltUnlatched = not bool(pt_cp.vl["Airbag_1"]["Gurtschalter_Fahrer"]) + + # Consume blind-spot monitoring info/warning LED states, if available. + # Infostufe: BSM LED on, Warnung: BSM LED flashing + if self.CP.enableBsm: + ret.leftBlindspot = bool(ext_cp.vl["SWA_1"]["SWA_Infostufe_SWA_li"]) or bool(ext_cp.vl["SWA_1"]["SWA_Warnung_SWA_li"]) + ret.rightBlindspot = bool(ext_cp.vl["SWA_1"]["SWA_Infostufe_SWA_re"]) or bool(ext_cp.vl["SWA_1"]["SWA_Warnung_SWA_re"]) + + # Consume factory LDW data relevant for factory SWA (Lane Change Assist) + # and capture it for forwarding to the blind spot radar controller + self.ldw_stock_values = cam_cp.vl["LDW_Status"] if self.CP.networkLocation == NetworkLocation.fwdCamera else {} + + # Stock FCW is considered active if the release bit for brake-jerk warning + # is set. Stock AEB considered active if the partial braking or target + # braking release bits are set. + # Refer to VW Self Study Program 890253: Volkswagen Driver Assistance + # Systems, chapters on Front Assist with Braking and City Emergency + # Braking for the 2016 Passat NMS + # TODO: deferred until we can collect data on pre-MY2016 behavior, AWV message may be shorter with fewer signals + ret.stockFcw = False + ret.stockAeb = False + + # Update ACC radar status. + ret.cruiseState.available = bool(pt_cp.vl["Motor_5"]["GRA_Hauptschalter"]) + ret.cruiseState.enabled = bool(pt_cp.vl["Motor_2"]["GRA_Status"]) + if self.CP.pcmCruise: + ret.accFaulted = ext_cp.vl["ACC_GRA_Anziege"]["ACA_StaACC"] in (6, 7) + # TODO: update opendbc with PQ TSK state for OP long accFaulted + + # Update ACC setpoint. When the setpoint reads as 255, the driver has not + # yet established an ACC setpoint, so treat it as zero. + ret.cruiseState.speed = ext_cp.vl["ACC_GRA_Anziege"]["ACA_V_Wunsch"] * CV.KPH_TO_MS + if ret.cruiseState.speed > 70: # 255 kph in m/s == no current setpoint + ret.cruiseState.speed = 0 + + # Update button states for turn signals and ACC controls, capture all ACC button state/config for passthrough + ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_stalk(300, pt_cp.vl["Gate_Komf_1"]["GK1_Blinker_li"], + pt_cp.vl["Gate_Komf_1"]["GK1_Blinker_re"]) + ret.buttonEvents = self.create_button_events(pt_cp, self.CCP.BUTTONS) + self.gra_stock_values = pt_cp.vl["GRA_Neu"] + + # Additional safety checks performed in CarInterface. + ret.espDisabled = bool(pt_cp.vl["Bremse_1"]["ESP_Passiv_getastet"]) + + return ret + @staticmethod def get_can_parser(CP): + if CP.carFingerprint in PQ_CARS: + return CarState.get_can_parser_pq(CP) + signals = [ # sig_name, sig_address ("LWI_Lenkradwinkel", "LWI_01"), # Absolute steering angle @@ -222,6 +328,9 @@ class CarState(CarStateBase): @staticmethod def get_cam_can_parser(CP): + if CP.carFingerprint in PQ_CARS: + return CarState.get_cam_can_parser_pq(CP) + signals = [] checks = [] @@ -248,6 +357,123 @@ class CarState(CarStateBase): return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, CANBUS.cam) + @staticmethod + def get_can_parser_pq(CP): + signals = [ + # sig_name, sig_address, default + ("LH3_BLW", "Lenkhilfe_3"), # Absolute steering angle + ("LH3_BLWSign", "Lenkhilfe_3"), # Steering angle sign + ("LH3_LM", "Lenkhilfe_3"), # Absolute driver torque input + ("LH3_LMSign", "Lenkhilfe_3"), # Driver torque input sign + ("LH2_Sta_HCA", "Lenkhilfe_2"), # Steering rack HCA status + ("Lenkradwinkel_Geschwindigkeit", "Lenkwinkel_1"), # Absolute steering rate + ("Lenkradwinkel_Geschwindigkeit_S", "Lenkwinkel_1"), # Steering rate sign + ("Geschwindigkeit_neu__Bremse_1_", "Bremse_1"), # Vehicle speed from ABS + ("Radgeschw__VL_4_1", "Bremse_3"), # ABS wheel speed, front left + ("Radgeschw__VR_4_1", "Bremse_3"), # ABS wheel speed, front right + ("Radgeschw__HL_4_1", "Bremse_3"), # ABS wheel speed, rear left + ("Radgeschw__HR_4_1", "Bremse_3"), # ABS wheel speed, rear right + ("Giergeschwindigkeit", "Bremse_5"), # Absolute yaw rate + ("Vorzeichen_der_Giergeschwindigk", "Bremse_5"), # Yaw rate sign + ("Gurtschalter_Fahrer", "Airbag_1"), # Seatbelt status, driver + ("Gurtschalter_Beifahrer", "Airbag_1"), # Seatbelt status, passenger + ("Bremstestschalter", "Motor_2"), # Brake pedal pressed (brake light test switch) + ("Bremslichtschalter", "Motor_2"), # Brakes applied (brake light switch) + ("Bremsdruck", "Bremse_5"), # Brake pressure applied + ("Vorzeichen_Bremsdruck", "Bremse_5"), # Brake pressure applied sign (???) + ("Fahrpedal_Rohsignal", "Motor_3"), # Accelerator pedal value + ("ESP_Passiv_getastet", "Bremse_1"), # Stability control disabled + ("GRA_Hauptschalter", "Motor_5"), # ACC main switch + ("GRA_Status", "Motor_2"), # ACC engagement status + ("GK1_Fa_Tuerkont", "Gate_Komf_1"), # Door open, driver + ("BSK_BT_geoeffnet", "Gate_Komf_1"), # Door open, passenger + ("BSK_HL_geoeffnet", "Gate_Komf_1"), # Door open, rear left + ("BSK_HR_geoeffnet", "Gate_Komf_1"), # Door open, rear right + ("BSK_HD_Hauptraste", "Gate_Komf_1"), # Trunk or hatch open + ("GK1_Blinker_li", "Gate_Komf_1"), # Left turn signal on + ("GK1_Blinker_re", "Gate_Komf_1"), # Right turn signal on + ("Bremsinfo", "Kombi_1"), # Manual handbrake applied + ("GRA_Hauptschalt", "GRA_Neu"), # ACC button, on/off + ("GRA_Typ_Hauptschalt", "GRA_Neu"), # ACC button, momentary vs latching + ("GRA_Kodierinfo", "GRA_Neu"), # ACC button, configuration + ("GRA_Abbrechen", "GRA_Neu"), # ACC button, cancel + ("GRA_Neu_Setzen", "GRA_Neu"), # ACC button, set + ("GRA_Up_lang", "GRA_Neu"), # ACC button, increase or accel, long press + ("GRA_Down_lang", "GRA_Neu"), # ACC button, decrease or decel, long press + ("GRA_Up_kurz", "GRA_Neu"), # ACC button, increase or accel, short press + ("GRA_Down_kurz", "GRA_Neu"), # ACC button, decrease or decel, short press + ("GRA_Recall", "GRA_Neu"), # ACC button, resume + ("GRA_Zeitluecke", "GRA_Neu"), # ACC button, time gap adj + ("COUNTER", "GRA_Neu"), # ACC button, message counter + ("GRA_Sender", "GRA_Neu"), # ACC button, CAN message originator + ] + + checks = [ + # sig_address, frequency + ("Bremse_1", 100), # From J104 ABS/ESP controller + ("Bremse_3", 100), # From J104 ABS/ESP controller + ("Lenkhilfe_3", 100), # From J500 Steering Assist with integrated sensors + ("Lenkwinkel_1", 100), # From J500 Steering Assist with integrated sensors + ("Motor_3", 100), # From J623 Engine control module + ("Airbag_1", 50), # From J234 Airbag control module + ("Bremse_5", 50), # From J104 ABS/ESP controller + ("GRA_Neu", 50), # From J??? steering wheel control buttons + ("Kombi_1", 50), # From J285 Instrument cluster + ("Motor_2", 50), # From J623 Engine control module + ("Motor_5", 50), # From J623 Engine control module + ("Lenkhilfe_2", 20), # From J500 Steering Assist with integrated sensors + ("Gate_Komf_1", 10), # From J533 CAN gateway + ] + + if CP.transmissionType == TransmissionType.automatic: + signals += [("Waehlhebelposition__Getriebe_1_", "Getriebe_1", 0)] # Auto trans gear selector position + checks += [("Getriebe_1", 100)] # From J743 Auto transmission control module + elif CP.transmissionType == TransmissionType.manual: + signals += [("Kupplungsschalter", "Motor_1", 0), # Clutch switch + ("GK1_Rueckfahr", "Gate_Komf_1", 0)] # Reverse light from BCM + checks += [("Motor_1", 100)] # From J623 Engine control module + + if CP.networkLocation == NetworkLocation.fwdCamera: + # Extended CAN devices other than the camera are here on CANBUS.pt + signals += PqExtraSignals.fwd_radar_signals + checks += PqExtraSignals.fwd_radar_checks + if CP.enableBsm: + signals += PqExtraSignals.bsm_radar_signals + checks += PqExtraSignals.bsm_radar_checks + + return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, CANBUS.pt) + + @staticmethod + def get_cam_can_parser_pq(CP): + + signals = [] + checks = [] + + if CP.networkLocation == NetworkLocation.fwdCamera: + signals += [ + # sig_name, sig_address + ("LDW_SW_Warnung_links", "LDW_Status"), # Blind spot in warning mode on left side due to lane departure + ("LDW_SW_Warnung_rechts", "LDW_Status"), # Blind spot in warning mode on right side due to lane departure + ("LDW_Seite_DLCTLC", "LDW_Status"), # Direction of most likely lane departure (left or right) + ("LDW_DLC", "LDW_Status"), # Lane departure, distance to line crossing + ("LDW_TLC", "LDW_Status"), # Lane departure, time to line crossing + ] + checks += [ + # sig_address, frequency + ("LDW_Status", 10) # From R242 Driver assistance camera + ] + + if CP.networkLocation == NetworkLocation.gateway: + # Radars are here on CANBUS.cam + signals += PqExtraSignals.fwd_radar_signals + checks += PqExtraSignals.fwd_radar_checks + if CP.enableBsm: + signals += PqExtraSignals.bsm_radar_signals + checks += PqExtraSignals.bsm_radar_checks + + return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, CANBUS.cam) + + class MqbExtraSignals: # Additional signal and message lists for optional or bus-portable controllers fwd_radar_signals = [ @@ -269,3 +495,22 @@ class MqbExtraSignals: bsm_radar_checks = [ ("SWA_01", 20), # From J1086 Lane Change Assist ] + +class PqExtraSignals: + # Additional signal and message lists for optional or bus-portable controllers + fwd_radar_signals = [ + ("ACA_StaACC", "ACC_GRA_Anziege", 0), # ACC drivetrain coordinator status + ("ACA_V_Wunsch", "ACC_GRA_Anziege", 0), # ACC set speed + ] + fwd_radar_checks = [ + ("ACC_GRA_Anziege", 25), # From J428 ACC radar control module + ] + bsm_radar_signals = [ + ("SWA_Infostufe_SWA_li", "SWA_1", 0), # Blind spot object info, left + ("SWA_Warnung_SWA_li", "SWA_1", 0), # Blind spot object warning, left + ("SWA_Infostufe_SWA_re", "SWA_1", 0), # Blind spot object info, right + ("SWA_Warnung_SWA_re", "SWA_1", 0), # Blind spot object warning, right + ] + bsm_radar_checks = [ + ("SWA_1", 20), # From J1086 Lane Change Assist + ] diff --git a/selfdrive/car/volkswagen/interface.py b/selfdrive/car/volkswagen/interface.py index dfa0a555e..22206635a 100644 --- a/selfdrive/car/volkswagen/interface.py +++ b/selfdrive/car/volkswagen/interface.py @@ -1,8 +1,10 @@ from cereal import car +from panda import Panda +from common.conversions import Conversions as CV from selfdrive.car import STD_CARGO_KG, create_button_enable_events, scale_rot_inertia, scale_tire_stiffness, \ gen_empty_fingerprint, get_safety_config from selfdrive.car.interfaces import CarInterfaceBase -from selfdrive.car.volkswagen.values import CAR, CANBUS, NetworkLocation, TransmissionType, GearShifter +from selfdrive.car.volkswagen.values import CAR, PQ_CARS, CANBUS, NetworkLocation, TransmissionType, GearShifter EventName = car.CarEvent.EventName @@ -25,7 +27,36 @@ class CarInterface(CarInterfaceBase): ret.carName = "volkswagen" ret.radarOffCan = True - if True: # pylint: disable=using-constant-test + if candidate in PQ_CARS: + # Set global PQ35/PQ46/NMS parameters + ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.volkswagenPq)] + ret.enableBsm = 0x3BA in fingerprint[0] # SWA_1 + + if 0x440 in fingerprint[0]: # Getriebe_1 + ret.transmissionType = TransmissionType.automatic + else: + ret.transmissionType = TransmissionType.manual + + if any(msg in fingerprint[1] for msg in (0x1A0, 0xC2)): # Bremse_1, Lenkwinkel_1 + ret.networkLocation = NetworkLocation.gateway + else: + ret.networkLocation = NetworkLocation.fwdCamera + + # The PQ port is in dashcam-only mode due to a fixed six-minute maximum timer on HCA steering. An unsupported + # EPS flash update to work around this timer, and enable steering down to zero, is available from: + # https://github.com/pd0wm/pq-flasher + # It is documented in a four-part blog series: + # https://blog.willemmelching.nl/carhacking/2022/01/02/vw-part1/ + # Panda ALLOW_DEBUG firmware required. + ret.dashcamOnly = True + + if disable_radar and ret.networkLocation == NetworkLocation.gateway: + # Proof-of-concept, prep for E2E only. No radar points available. Follow-to-stop not yet supported, but should + # be simple to add when a suitable test car becomes available. Panda ALLOW_DEBUG firmware required. + ret.openpilotLongitudinalControl = True + ret.safetyConfigs[0].safetyParam |= Panda.FLAG_VOLKSWAGEN_LONG_CONTROL + + else: # Set global MQB parameters ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.volkswagen)] ret.enableBsm = 0x30F in fingerprint[0] # SWA_01 @@ -83,6 +114,14 @@ class CarInterface(CarInterfaceBase): ret.mass = 1551 + STD_CARGO_KG ret.wheelbase = 2.79 + elif candidate == CAR.PASSAT_NMS: + ret.mass = 1503 + STD_CARGO_KG + ret.wheelbase = 2.80 + ret.minEnableSpeed = 20 * CV.KPH_TO_MS # ACC "basic", no FtS + ret.minSteerSpeed = 50 * CV.KPH_TO_MS + ret.steerActuatorDelay = 0.2 + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) + elif candidate == CAR.POLO_MK6: ret.mass = 1230 + STD_CARGO_KG ret.wheelbase = 2.55 diff --git a/selfdrive/car/volkswagen/pqcan.py b/selfdrive/car/volkswagen/pqcan.py new file mode 100644 index 000000000..1e7ed2134 --- /dev/null +++ b/selfdrive/car/volkswagen/pqcan.py @@ -0,0 +1,84 @@ +def create_steering_control(packer, bus, apply_steer, lkas_enabled): + values = { + "LM_Offset": abs(apply_steer), + "LM_OffSign": 1 if apply_steer < 0 else 0, + "HCA_Status": 5 if (lkas_enabled and apply_steer != 0) else 3, + "Vib_Freq": 16, + } + + return packer.make_can_msg("HCA_1", bus, values) + + +def create_lka_hud_control(packer, bus, ldw_stock_values, enabled, steering_pressed, hud_alert, hud_control): + values = ldw_stock_values.copy() + + values.update({ + "LDW_Lampe_gelb": 1 if enabled and steering_pressed else 0, + "LDW_Lampe_gruen": 1 if enabled and not steering_pressed else 0, + "LDW_Lernmodus_links": 3 if hud_control.leftLaneDepart else 1 + hud_control.leftLaneVisible, + "LDW_Lernmodus_rechts": 3 if hud_control.rightLaneDepart else 1 + hud_control.rightLaneVisible, + "LDW_Textbits": hud_alert, + }) + + return packer.make_can_msg("LDW_Status", bus, values) + + +def create_acc_buttons_control(packer, bus, gra_stock_values, idx, cancel=False, resume=False): + values = gra_stock_values.copy() + + values.update({ + "COUNTER": idx, + "GRA_Abbrechen": cancel, + "GRA_Recall": resume, + }) + + return packer.make_can_msg("GRA_Neu", bus, values) + + +def tsk_status_value(main_switch_on, acc_faulted, long_active): + if long_active: + tsk_status = 1 + elif main_switch_on: + tsk_status = 2 + else: + tsk_status = 0 + + return tsk_status + + +def acc_hud_status_value(main_switch_on, acc_faulted, long_active): + if acc_faulted: + hud_status = 6 + elif long_active: + hud_status = 3 + elif main_switch_on: + hud_status = 2 + else: + hud_status = 0 + + return hud_status + + +def create_acc_accel_control(packer, bus, adr_status, accel): + values = { + "ACS_Sta_ADR": adr_status, + "ACS_StSt_Info": adr_status != 1, + "ACS_Typ_ACC": 0, # TODO: this is ACC "basic", find a way to detect FtS support (1) + "ACS_Sollbeschl": accel if adr_status == 1 else 3.01, + "ACS_zul_Regelabw": 0.2 if adr_status == 1 else 1.27, + "ACS_max_AendGrad": 3.0 if adr_status == 1 else 5.08, + } + + return packer.make_can_msg("ACC_System", bus, values) + + +def create_acc_hud_control(packer, bus, acc_status, set_speed, lead_visible): + values = { + "ACA_StaACC": acc_status, + "ACA_Zeitluecke": 2, + "ACA_V_Wunsch": set_speed, + "ACA_gemZeitl": 8 if lead_visible else 0, + } + # TODO: ACA_ID_StaACC, ACA_AnzDisplay, ACA_kmh_mph, ACA_PrioDisp, ACA_Aend_Zeitluecke + + return packer.make_can_msg("ACC_GRA_Anziege", bus, values) diff --git a/selfdrive/car/volkswagen/values.py b/selfdrive/car/volkswagen/values.py index 785a70d2d..58f071901 100755 --- a/selfdrive/car/volkswagen/values.py +++ b/selfdrive/car/volkswagen/values.py @@ -18,6 +18,11 @@ Button = namedtuple('Button', ['event_type', 'can_addr', 'can_msg', 'values']) class CarControllerParams: HCA_STEP = 2 # HCA_01/HCA_1 message frequency 50Hz GRA_ACC_STEP = 3 # GRA_ACC_01/GRA_Neu message frequency 33Hz + ACC_CONTROL_STEP = 2 # ACC_06/ACC_07/ACC_System frequency 50Hz + ACC_HUD_STEP = 4 # ACC_GRA_Anziege frequency 25Hz + + ACCEL_MAX = 2.0 # 2.0 m/s max acceleration + ACCEL_MIN = -3.5 # 3.5 m/s max deceleration def __init__(self, CP): # Documented lateral limits: 3.00 Nm max, rate of change 5.00 Nm/sec. @@ -29,7 +34,35 @@ class CarControllerParams: can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) - if True: # pylint: disable=using-constant-test + if CP.carFingerprint in PQ_CARS: + self.LDW_STEP = 5 # LDW_1 message frequency 20Hz + self.STEER_DRIVER_ALLOWANCE = 80 # Driver intervention threshold 0.8 Nm + self.STEER_DELTA_UP = 6 # Max HCA reached in 1.00s (STEER_MAX / (50Hz * 1.00)) + self.STEER_DELTA_DOWN = 10 # Min HCA reached in 0.60s (STEER_MAX / (50Hz * 0.60)) + + if CP.transmissionType == TransmissionType.automatic: + self.shifter_values = can_define.dv["Getriebe_1"]["Waehlhebelposition__Getriebe_1_"] + self.hca_status_values = can_define.dv["Lenkhilfe_2"]["LH2_Sta_HCA"] + + self.BUTTONS = [ + Button(car.CarState.ButtonEvent.Type.setCruise, "GRA_Neu", "GRA_Neu_Setzen", [1]), + Button(car.CarState.ButtonEvent.Type.resumeCruise, "GRA_Neu", "GRA_Recall", [1]), + Button(car.CarState.ButtonEvent.Type.accelCruise, "GRA_Neu", "GRA_Up_kurz", [1]), + Button(car.CarState.ButtonEvent.Type.decelCruise, "GRA_Neu", "GRA_Down_kurz", [1]), + Button(car.CarState.ButtonEvent.Type.cancel, "GRA_Neu", "GRA_Abbrechen", [1]), + Button(car.CarState.ButtonEvent.Type.gapAdjustCruise, "GRA_Neu", "GRA_Zeitluecke", [1]), + ] + + self.LDW_MESSAGES = { + "none": 0, # Nothing to display + "laneAssistUnavail": 1, # "Lane Assist currently not available." + "laneAssistUnavailSysError": 2, # "Lane Assist system error" + "laneAssistUnavailNoSensorView": 3, # "Lane Assist not available. No sensor view." + "laneAssistTakeOver": 4, # "Lane Assist: Please Take Over Steering" + "laneAssistDeactivTrailer": 5, # "Lane Assist: no function with trailer" + } + + else: self.LDW_STEP = 10 # LDW_02 message frequency 10Hz self.STEER_DRIVER_ALLOWANCE = 80 # Driver intervention threshold 0.8 Nm self.STEER_DELTA_UP = 4 # Max HCA reached in 1.50s (STEER_MAX / (50Hz * 1.50)) @@ -79,6 +112,7 @@ class CAR: GOLF_MK7 = "VOLKSWAGEN GOLF 7TH GEN" # Chassis 5G/AU/BA/BE, Mk7 VW Golf and variants JETTA_MK7 = "VOLKSWAGEN JETTA 7TH GEN" # Chassis BU, Mk7 VW Jetta PASSAT_MK8 = "VOLKSWAGEN PASSAT 8TH GEN" # Chassis 3G, Mk8 VW Passat and variants + PASSAT_NMS = "VOLKSWAGEN PASSAT NMS" # Chassis A3, North America/China/Mideast NMS Passat, incl. facelift POLO_MK6 = "VOLKSWAGEN POLO 6TH GEN" # Chassis AW, Mk6 VW Polo TAOS_MK1 = "VOLKSWAGEN TAOS 1ST GEN" # Chassis B2, Mk1 VW Taos and Tharu TCROSS_MK1 = "VOLKSWAGEN T-CROSS 1ST GEN" # Chassis C1, Mk1 VW T-Cross SWB and LWB variants @@ -99,7 +133,12 @@ class CAR: SKODA_OCTAVIA_MK3 = "SKODA OCTAVIA 3RD GEN" # Chassis NE, Mk3 Skoda Octavia and variants +PQ_CARS = {CAR.PASSAT_NMS} + + DBC: Dict[str, Dict[str, str]] = defaultdict(lambda: dbc_dict("vw_mqb_2010", None)) +for car_type in PQ_CARS: + DBC[car_type] = dbc_dict("vw_golf_mk4", None) class Footnote(Enum): @@ -160,6 +199,7 @@ CAR_INFO: Dict[str, Union[VWCarInfo, List[VWCarInfo]]] = { VWCarInfo("Volkswagen Passat Alltrack 2015-22", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533), VWCarInfo("Volkswagen Passat GTE 2015-22", footnotes=[Footnote.VW_HARNESS, Footnote.VW_VARIANT], harness=Harness.j533), ], + CAR.PASSAT_NMS: VWCarInfo("Volkswagen Passat NMS 2017-22", harness=Harness.j533), CAR.POLO_MK6: [ VWCarInfo("Volkswagen Polo 2020-22", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533), VWCarInfo("Volkswagen Polo GTI 2020-22", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533), @@ -514,6 +554,26 @@ FW_VERSIONS = { b'\xf1\x875Q0907572R \xf1\x890771', ], }, + CAR.PASSAT_NMS: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8706K906016C \xf1\x899609', + b'\xf1\x8706K906016G \xf1\x891124', + b'\xf1\x8706K906071BJ\xf1\x894891', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x8709G927158AB\xf1\x893318', + b'\xf1\x8709G927158BD\xf1\x893121', + b'\xf1\x8709G927158FQ\xf1\x893745', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x87561959655 \xf1\x890210\xf1\x82\02212121111113000102011--121012--101312', + b'\xf1\x87561959655C \xf1\x890508\xf1\x82\02215141111121100314919--153015--304831', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x87561907567A \xf1\x890132', + b'\xf1\x877N0907572C \xf1\x890211\xf1\x82\00152', + ], + }, CAR.POLO_MK6: { (Ecu.engine, 0x7e0, None): [ b'\xf1\x8704C906025H \xf1\x895177', diff --git a/selfdrive/test/process_replay/test_processes.py b/selfdrive/test/process_replay/test_processes.py index 68c1666b5..f5aaec362 100755 --- a/selfdrive/test/process_replay/test_processes.py +++ b/selfdrive/test/process_replay/test_processes.py @@ -32,8 +32,9 @@ original_segments = [ ("VOLKSWAGEN", "de9592456ad7d144|2021-06-29--11-00-15--6"), # VOLKSWAGEN.GOLF ("MAZDA", "bd6a637565e91581|2021-10-30--15-14-53--2"), # MAZDA.CX9_2021 - # Enable when port is tested and dascamOnly is no longer set + # Enable when port is tested and dashcamOnly is no longer set #("TESLA", "bb50caf5f0945ab1|2021-06-19--17-20-18--3"), # TESLA.AP2_MODELS + #("VOLKSWAGEN2", "3cfdec54aa035f3f|2022-07-19--23-45-10--2"), # VOLKSWAGEN.PASSAT_NMS ] segments = [ From f35468e88c228ae9d3138213525ffdd5beb3edcd Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 16 Aug 2022 14:48:26 -0700 Subject: [PATCH 009/172] Update RELEASES.md --- RELEASES.md | 3 +++ 1 file changed, 3 insertions(+) diff --git a/RELEASES.md b/RELEASES.md index bcd6aa7aa..364d2a494 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,5 +1,8 @@ Version 0.8.16 (2022-XX-XX) ======================== +* New driving model + * Reduced turn cutting +* Auto-detect right hand drive setting with driver monitoring model * Chevrolet Bolt EUV 2022-23 support thanks to JasonJShuler! * Hyundai Ioniq 5 2022 support thanks to sunnyhaibin! * Hyundai Kona Electric 2022 support thanks to sunnyhaibin! From aa32ea0f64e4035ac929e09ee85d268c3185221c Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 16 Aug 2022 16:37:58 -0700 Subject: [PATCH 010/172] loggerd: log all disk space usage in initData (#25455) * bootlog: log all disk space usage * not just agnos * move to initData * cleanup --- cereal | 2 +- selfdrive/loggerd/bootlog.cc | 22 +++++++++------------- selfdrive/loggerd/logger.cc | 27 +++++++++++++++++++++------ 3 files changed, 31 insertions(+), 20 deletions(-) diff --git a/cereal b/cereal index 5ab197001..2d648b0dc 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 5ab19700178f01c14f362735532ee2662ab755fc +Subproject commit 2d648b0dc4654fc7088ffb81fd301352707de749 diff --git a/selfdrive/loggerd/bootlog.cc b/selfdrive/loggerd/bootlog.cc index 882b749fe..90ba487ff 100644 --- a/selfdrive/loggerd/bootlog.cc +++ b/selfdrive/loggerd/bootlog.cc @@ -7,12 +7,6 @@ static kj::Array build_boot_log() { - std::vector bootlog_commands; - if (Hardware::AGNOS()) { - bootlog_commands.push_back("journalctl"); - bootlog_commands.push_back("sudo nvme smart-log --output-format=json /dev/nvme0"); - } - MessageBuilder msg; auto boot = msg.initEvent().initBoot(); @@ -31,17 +25,19 @@ static kj::Array build_boot_log() { } // Gather output of commands - i = 0; + std::vector bootlog_commands = { + "[ -e /dev/nvme0 ] && sudo nvme smart-log --output-format=json /dev/nvme0", + "[ -x \"$(command -v journalctl)\" ] && journalctl", + }; + auto commands = boot.initCommands().initEntries(bootlog_commands.size()); - for (auto &command : bootlog_commands) { - auto lentry = commands[i]; + for (int j = 0; j < bootlog_commands.size(); j++) { + auto lentry = commands[j]; - lentry.setKey(command); + lentry.setKey(bootlog_commands[j]); - const std::string result = util::check_output(command); + const std::string result = util::check_output(bootlog_commands[j]); lentry.setValue(capnp::Data::Reader((const kj::byte*)result.data(), result.size())); - - i++; } boot.setLaunchLog(util::read_file("/tmp/launch_log")); diff --git a/selfdrive/loggerd/logger.cc b/selfdrive/loggerd/logger.cc index 8038f1926..da3710cc7 100644 --- a/selfdrive/loggerd/logger.cc +++ b/selfdrive/loggerd/logger.cc @@ -24,9 +24,11 @@ kj::Array logger_build_init_data() { MessageBuilder msg; auto init = msg.initEvent().initInitData(); - init.setDeviceType(Hardware::get_device_type()); init.setVersion(COMMA_VERSION); + init.setDirty(!getenv("CLEAN")); + init.setDeviceType(Hardware::get_device_type()); + // log kernel args std::ifstream cmdline_stream("/proc/cmdline"); std::vector kernel_args; std::string buf; @@ -42,8 +44,6 @@ kj::Array logger_build_init_data() { init.setKernelVersion(util::read_file("/proc/version")); init.setOsVersion(util::read_file("/VERSION")); - init.setDirty(!getenv("CLEAN")); - // log params auto params = Params(); std::map params_map = params.readAll(); @@ -55,16 +55,31 @@ kj::Array logger_build_init_data() { init.setDongleId(params_map["DongleId"]); auto lparams = init.initParams().initEntries(params_map.size()); - int i = 0; + int j = 0; for (auto& [key, value] : params_map) { - auto lentry = lparams[i]; + auto lentry = lparams[j]; lentry.setKey(key); if ( !(params.getKeyType(key) & DONT_LOG) ) { lentry.setValue(capnp::Data::Reader((const kj::byte*)value.data(), value.size())); } - i++; + j++; + } + + // log commands + std::vector log_commands = { + "df -h", // usage for all filesystems + }; + + auto commands = init.initCommands().initEntries(log_commands.size()); + for (int i = 0; i < log_commands.size(); i++) { + auto lentry = commands[i]; + lentry.setKey(log_commands[i]); + + const std::string result = util::check_output(log_commands[i]); + lentry.setValue(capnp::Data::Reader((const kj::byte*)result.data(), result.size())); } + return capnp::messageToFlatArray(msg); } From bacd2d5aee139865e1520c7d608883196edf2c42 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 16 Aug 2022 18:39:20 -0700 Subject: [PATCH 011/172] Kona: remove pid tuning --- selfdrive/car/hyundai/interface.py | 3 --- 1 file changed, 3 deletions(-) diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 9080e5cdb..6b62477a0 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -115,13 +115,10 @@ class CarInterface(CarInterfaceBase): 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.lateralTuning.pid.kf = 0.00005 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 - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] 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 From b3dc7bb3cb75661993c068b993712a3a9f5238a2 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 16 Aug 2022 18:40:30 -0700 Subject: [PATCH 012/172] regen: initialize once (#25458) regen: init once --- selfdrive/test/process_replay/regen.py | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/selfdrive/test/process_replay/regen.py b/selfdrive/test/process_replay/regen.py index 39f75ce42..16d7ea851 100755 --- a/selfdrive/test/process_replay/regen.py +++ b/selfdrive/test/process_replay/regen.py @@ -201,14 +201,14 @@ def regen_segment(lr, frs=None, outdir=FAKEDATA, disable_tqdm=False): params = Params() os.environ["LOG_ROOT"] = outdir - for msg in lr: - if msg.which() == 'carParams': - setup_env(CP=msg.carParams) - elif msg.which() == 'liveCalibration': - params.put("CalibrationParams", msg.as_builder().to_bytes()) + # Get and setup initial state + CP = [m for m in lr if m.which() == 'carParams'][0].carParams + liveCalibration = [m for m in lr if m.which() == 'liveCalibration'][0] - vs, cam_procs = replay_cameras(lr, frs, disable_tqdm=disable_tqdm) + setup_env(CP=CP) + params.put("CalibrationParams", liveCalibration.as_builder().to_bytes()) + vs, cam_procs = replay_cameras(lr, frs, disable_tqdm=disable_tqdm) fake_daemons = { 'sensord': [ multiprocessing.Process(target=replay_sensor_events, args=('sensorEvents', lr)), From 1388c80a8f6b2e502ec771afba80d37df4da70ba Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 16 Aug 2022 18:41:45 -0700 Subject: [PATCH 013/172] Toyota: remove Camry Hybrid footnote (#25457) * Toyota: remove TSS2 camry footnote * Apply suggestions from code review * update docs Co-authored-by: Shane Smiskol --- docs/CARS.md | 2 +- selfdrive/car/toyota/values.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/CARS.md b/docs/CARS.md index ff539f052..fd82a5aa8 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -165,7 +165,7 @@ A supported vehicle is one that just works when you install a comma device. Ever |Toyota|C-HR Hybrid 2017-19|All|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| |Toyota|Camry 2018-20|All|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)[4](#footnotes)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| |Toyota|Camry 2021-22|All|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)[4](#footnotes)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Toyota|Camry Hybrid 2018-20|All|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)[4](#footnotes)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| +|Toyota|Camry Hybrid 2018-20|All|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| |Toyota|Camry Hybrid 2021-22|All|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| |Toyota|Corolla 2017-19|All|[![star](assets/icon-star-half.svg)](##)[3](#footnotes)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| |Toyota|Corolla 2020-22|All|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index b7b261adb..b4e82ec3e 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -114,7 +114,7 @@ CAR_INFO: Dict[str, Union[ToyotaCarInfo, List[ToyotaCarInfo]]] = { CAR.AVALON_TSS2: ToyotaCarInfo("Toyota Avalon 2022"), CAR.AVALONH_TSS2: ToyotaCarInfo("Toyota Avalon Hybrid 2022"), CAR.CAMRY: ToyotaCarInfo("Toyota Camry 2018-20", video_link="https://www.youtube.com/watch?v=fkcjviZY9CM", footnotes=[Footnote.CAMRY]), - CAR.CAMRYH: ToyotaCarInfo("Toyota Camry Hybrid 2018-20", video_link="https://www.youtube.com/watch?v=Q2DYY0AWKgk", footnotes=[Footnote.CAMRY]), + CAR.CAMRYH: ToyotaCarInfo("Toyota Camry Hybrid 2018-20", video_link="https://www.youtube.com/watch?v=Q2DYY0AWKgk"), CAR.CAMRY_TSS2: ToyotaCarInfo("Toyota Camry 2021-22", footnotes=[Footnote.CAMRY]), CAR.CAMRYH_TSS2: ToyotaCarInfo("Toyota Camry Hybrid 2021-22"), CAR.CHR: ToyotaCarInfo("Toyota C-HR 2017-21"), From d7095d0d4368f0168433455f16236151a91ef83c Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 16 Aug 2022 19:39:11 -0700 Subject: [PATCH 014/172] process replay: show errors when updating refs (#25460) * Update test_processes.py * Apply suggestions from code review --- selfdrive/test/process_replay/test_processes.py | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/selfdrive/test/process_replay/test_processes.py b/selfdrive/test/process_replay/test_processes.py index f5aaec362..608d0c4af 100755 --- a/selfdrive/test/process_replay/test_processes.py +++ b/selfdrive/test/process_replay/test_processes.py @@ -248,8 +248,12 @@ if __name__ == "__main__": print("TEST SUCCEEDED") else: - with open(REF_COMMIT_FN, "w") as f: - f.write(cur_commit) - print(f"\n\nUpdated reference logs for commit: {cur_commit}") + if failed: + print(diff1) + print("FAILED TO UPDATE REFS") + else: + with open(REF_COMMIT_FN, "w") as f: + f.write(cur_commit) + print(f"\n\nUpdated reference logs for commit: {cur_commit}") sys.exit(int(failed)) From 63fb3e591e3d4c6a992ff3e9e7509a08b0f76659 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 16 Aug 2022 20:57:06 -0700 Subject: [PATCH 015/172] Kia: add missing Niro EV 2020 FW versions (#25446) Add missing FW versions from 9b052af2986bbe3c --- selfdrive/car/hyundai/values.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index afd17b86a..c61efcdac 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -1010,6 +1010,7 @@ FW_VERSIONS = { b'\xf1\x00DEev SCC F-CUP 1.00 1.02 96400-Q4000 ', b'\xf1\x00DEev SCC F-CUP 1.00 1.02 96400-Q4100 ', b'\xf1\x00DEev SCC F-CUP 1.00 1.03 96400-Q4100 ', + b'\xf1\x00DEev SCC FHCUP 1.00 1.03 96400-Q4000 ', b'\xf1\x8799110Q4000\xf1\x00DEev SCC F-CUP 1.00 1.00 99110-Q4000 ', b'\xf1\x8799110Q4100\xf1\x00DEev SCC F-CUP 1.00 1.00 99110-Q4100 ', b'\xf1\x8799110Q4500\xf1\x00DEev SCC F-CUP 1.00 1.00 99110-Q4500 ', @@ -1029,6 +1030,7 @@ FW_VERSIONS = { b'\xf1\x00DEE MFC AT USA LHD 1.00 1.03 95740-Q4000 180821', b'\xf1\x00DEE MFC AT USA LHD 1.00 1.01 99211-Q4500 210428', b'\xf1\x00DEE MFC AT EUR LHD 1.00 1.03 95740-Q4000 180821', + b'\xf1\x00DEE MFC AT KOR LHD 1.00 1.03 95740-Q4000 180821', ], }, CAR.KIA_NIRO_HEV: { From 87ca42e993f1cc96cc313e33b3c538143e0a737c Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 16 Aug 2022 22:02:03 -0700 Subject: [PATCH 016/172] process replay: initialize controlsState with original route (#25461) * push * do process replay * commit * update refs * clean up * clean up controlsd * clean up controlsd * Add assert * debubuggier param name * can be peristent * Revert "can be peristent" This reverts commit 6e6d3f6423c26a202623cef728e038259e9e46cd. * Update selfdrive/test/process_replay/process_replay.py --- common/params.cc | 1 + selfdrive/controls/controlsd.py | 16 +++++++++---- .../test/process_replay/process_replay.py | 24 ++++++++++++++++--- selfdrive/test/process_replay/ref_commit | 2 +- selfdrive/test/process_replay/regen.py | 3 ++- .../test/process_replay/test_processes.py | 12 ++++------ 6 files changed, 41 insertions(+), 17 deletions(-) diff --git a/common/params.cc b/common/params.cc index 11b24fe9c..f89e7ff00 100644 --- a/common/params.cc +++ b/common/params.cc @@ -151,6 +151,7 @@ std::unordered_map keys = { {"RecordFront", PERSISTENT}, {"RecordFrontLock", PERSISTENT}, // for the internal fleet {"ReleaseNotes", PERSISTENT}, + {"ReplayControlsState", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_ON}, {"ShouldDoUpdate", CLEAR_ON_MANAGER_START}, {"SnoozeUpdate", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_OFF}, {"SshEnabled", PERSISTENT}, diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 3b2307f04..80d9bccb0 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -203,6 +203,16 @@ class Controls: self.rk = Ratekeeper(100, print_delay_threshold=None) self.prof = Profiler(False) # off by default + def set_initial_state(self): + if REPLAY: + controls_state = Params().get("ReplayControlsState") + if controls_state is not None: + controls_state = log.ControlsState.from_bytes(controls_state) + self.v_cruise_kph = controls_state.vCruise + + if self.sm['pandaStates'][0].controlsAllowed: + self.state = State.enabled + def update_events(self, CS): """Compute carEvents from carState""" @@ -417,11 +427,9 @@ class Controls: if all_valid or timed_out or SIMULATION: if not self.read_only: self.CI.init(self.CP, self.can_sock, self.pm.sock['sendcan']) - self.initialized = True - - if REPLAY and self.sm['pandaStates'][0].controlsAllowed: - self.state = State.enabled + self.initialized = True + self.set_initial_state() Params().put_bool("ControlsReady", True) # Check for CAN timeout diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index 32a3c2f3b..8b9c77625 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -385,7 +385,7 @@ def replay_process(cfg, lr, fingerprint=None): return cpp_replay_process(cfg, lr, fingerprint) -def setup_env(simulation=False, CP=None, cfg=None): +def setup_env(simulation=False, CP=None, cfg=None, controlsState=None): params = Params() params.clear_all() params.put_bool("OpenpilotEnabledToggle", True) @@ -414,6 +414,12 @@ def setup_env(simulation=False, CP=None, cfg=None): elif "SIMULATION" in os.environ: del os.environ["SIMULATION"] + # Initialize controlsd with a controlsState packet + if controlsState is not None: + params.put("ReplayControlsState", controlsState.as_builder().to_bytes()) + else: + params.delete("ReplayControlsState") + # Regen or python process if CP is not None: if CP.alternativeExperience == ALTERNATIVE_EXPERIENCE.DISABLE_DISENGAGE_ON_GAS: @@ -440,13 +446,25 @@ def python_replay_process(cfg, lr, fingerprint=None): all_msgs = sorted(lr, key=lambda msg: msg.logMonoTime) pub_msgs = [msg for msg in all_msgs if msg.which() in list(cfg.pub_sub.keys())] + controlsState = None + initialized = False + for msg in lr: + if msg.which() == 'controlsState': + controlsState = msg.controlsState + if initialized: + break + elif msg.which() == 'carEvents': + initialized = car.CarEvent.EventName.controlsInitializing not in [e.name for e in msg.carEvents] + + assert controlsState is not None and initialized, "controlsState never initialized" + if fingerprint is not None: os.environ['SKIP_FW_QUERY'] = "1" os.environ['FINGERPRINT'] = fingerprint - setup_env(cfg=cfg) + setup_env(cfg=cfg, controlsState=controlsState) else: CP = [m for m in lr if m.which() == 'carParams'][0].carParams - setup_env(CP=CP, cfg=cfg) + setup_env(CP=CP, cfg=cfg, controlsState=controlsState) assert(type(managed_processes[cfg.proc_name]) is PythonProcess) managed_processes[cfg.proc_name].prepare() diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 8aa80d6b7..400d27f1a 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -118d78e2040103c00b4bfcc875fcdcd6a15e2211 +375f581030fe8efeb9dacd63875b3f046d3b420f \ No newline at end of file diff --git a/selfdrive/test/process_replay/regen.py b/selfdrive/test/process_replay/regen.py index 16d7ea851..4e1cbfd30 100755 --- a/selfdrive/test/process_replay/regen.py +++ b/selfdrive/test/process_replay/regen.py @@ -203,9 +203,10 @@ def regen_segment(lr, frs=None, outdir=FAKEDATA, disable_tqdm=False): # Get and setup initial state CP = [m for m in lr if m.which() == 'carParams'][0].carParams + controlsState = [m for m in lr if m.which() == 'controlsState'][0].controlsState liveCalibration = [m for m in lr if m.which() == 'liveCalibration'][0] - setup_env(CP=CP) + setup_env(CP=CP, controlsState=controlsState) params.put("CalibrationParams", liveCalibration.as_builder().to_bytes()) vs, cam_procs = replay_cameras(lr, frs, disable_tqdm=disable_tqdm) diff --git a/selfdrive/test/process_replay/test_processes.py b/selfdrive/test/process_replay/test_processes.py index 608d0c4af..2a005cf4c 100755 --- a/selfdrive/test/process_replay/test_processes.py +++ b/selfdrive/test/process_replay/test_processes.py @@ -49,7 +49,7 @@ segments = [ ("CHRYSLER", "regen38346FB33D0|2022-07-14--18-05-26--0"), ("RAM", "2f4452b03ccb98f0|2022-07-07--08-01-56--3"), ("SUBARU", "regen54A1E2BE5AA|2022-07-14--18-07-50--0"), - ("GM", "regen01D09D915B5|2022-07-06--14-36-20--0"), + ("GM", "regen76027B408B7|2022-08-16--19-56-58--0"), ("NISSAN", "regenCA0B0DC946E|2022-07-14--18-10-17--0"), ("VOLKSWAGEN", "regen007098CA0EF|2022-07-06--15-01-26--0"), ("MAZDA", "regen61BA413D53B|2022-07-06--14-39-42--0"), @@ -248,12 +248,8 @@ if __name__ == "__main__": print("TEST SUCCEEDED") else: - if failed: - print(diff1) - print("FAILED TO UPDATE REFS") - else: - with open(REF_COMMIT_FN, "w") as f: - f.write(cur_commit) - print(f"\n\nUpdated reference logs for commit: {cur_commit}") + with open(REF_COMMIT_FN, "w") as f: + f.write(cur_commit) + print(f"\n\nUpdated reference logs for commit: {cur_commit}") sys.exit(int(failed)) From e0e0aad144f1e47486faa8c06d54d29c3dd94c79 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 17 Aug 2022 15:20:18 -0700 Subject: [PATCH 017/172] Chrysler: ensure control bit is high before torque cmd (#25465) * Chrysler: ensure control bit is high before torque cmd * move that & update refs * check control bit too --- selfdrive/car/chrysler/carcontroller.py | 39 ++++++++++++------------ selfdrive/test/process_replay/ref_commit | 2 +- 2 files changed, 21 insertions(+), 20 deletions(-) diff --git a/selfdrive/car/chrysler/carcontroller.py b/selfdrive/car/chrysler/carcontroller.py index 22abf1b67..5a2d90c64 100644 --- a/selfdrive/car/chrysler/carcontroller.py +++ b/selfdrive/car/chrysler/carcontroller.py @@ -22,23 +22,8 @@ class CarController: def update(self, CC, CS): can_sends = [] - # TODO: can we make this more sane? why is it different for all the cars? - lkas_control_bit = self.lkas_control_bit_prev - if CS.out.vEgo > self.CP.minSteerSpeed: - lkas_control_bit = True - elif self.CP.carFingerprint in (CAR.PACIFICA_2019_HYBRID, CAR.PACIFICA_2020, CAR.JEEP_CHEROKEE_2019): - if CS.out.vEgo < (self.CP.minSteerSpeed - 3.0): - lkas_control_bit = False - elif self.CP.carFingerprint in RAM_CARS: - if CS.out.vEgo < (self.CP.minSteerSpeed - 0.5): - lkas_control_bit = False - - # EPS faults if LKAS re-enables too quickly - lkas_control_bit = lkas_control_bit and (self.frame - self.last_lkas_falling_edge > 200) lkas_active = CC.latActive and self.lkas_control_bit_prev - # *** control msgs *** - # cruise buttons if (self.frame - self.last_button_frame)*DT_CTRL > 0.05: das_bus = 2 if self.CP.carFingerprint in RAM_CARS else 0 @@ -61,19 +46,35 @@ class CarController: # steering if self.frame % 2 == 0: + + # TODO: can we make this more sane? why is it different for all the cars? + lkas_control_bit = self.lkas_control_bit_prev + if CS.out.vEgo > self.CP.minSteerSpeed: + lkas_control_bit = True + elif self.CP.carFingerprint in (CAR.PACIFICA_2019_HYBRID, CAR.PACIFICA_2020, CAR.JEEP_CHEROKEE_2019): + if CS.out.vEgo < (self.CP.minSteerSpeed - 3.0): + lkas_control_bit = False + elif self.CP.carFingerprint in RAM_CARS: + if CS.out.vEgo < (self.CP.minSteerSpeed - 0.5): + lkas_control_bit = False + + # EPS faults if LKAS re-enables too quickly + lkas_control_bit = lkas_control_bit and (self.frame - self.last_lkas_falling_edge > 200) + + if not lkas_control_bit and self.lkas_control_bit_prev: + self.last_lkas_falling_edge = self.frame + self.lkas_control_bit_prev = lkas_control_bit + # steer torque new_steer = int(round(CC.actuators.steer * self.params.STEER_MAX)) apply_steer = apply_toyota_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorqueEps, self.params) - if not lkas_active: + if not lkas_active or not lkas_control_bit: apply_steer = 0 self.apply_steer_last = apply_steer can_sends.append(create_lkas_command(self.packer, self.CP, int(apply_steer), lkas_control_bit)) self.frame += 1 - if not lkas_control_bit and self.lkas_control_bit_prev: - self.last_lkas_falling_edge = self.frame - self.lkas_control_bit_prev = lkas_control_bit new_actuators = CC.actuators.copy() new_actuators.steer = self.apply_steer_last / self.params.STEER_MAX diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 400d27f1a..57d80369f 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -375f581030fe8efeb9dacd63875b3f046d3b420f \ No newline at end of file +29e406826b1d7b0cc7e05153b623fbedcd8fd9e9 \ No newline at end of file From baef4c1fb2b9dd20bfa172eb49961c4171076b1f Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 17 Aug 2022 15:30:20 -0700 Subject: [PATCH 018/172] expand fingerprint dict size for multipanda setups --- selfdrive/car/__init__.py | 2 +- selfdrive/car/tests/test_car_interfaces.py | 8 +++----- 2 files changed, 4 insertions(+), 6 deletions(-) diff --git a/selfdrive/car/__init__.py b/selfdrive/car/__init__.py index c77e40daa..f2d198338 100644 --- a/selfdrive/car/__init__.py +++ b/selfdrive/car/__init__.py @@ -38,7 +38,7 @@ def create_button_enable_events(buttonEvents: capnp.lib.capnp._DynamicListBuilde def gen_empty_fingerprint(): - return {i: {} for i in range(0, 4)} + return {i: {} for i in range(0, 8)} # FIXME: hardcoding honda civic 2016 touring params so they can be used to diff --git a/selfdrive/car/tests/test_car_interfaces.py b/selfdrive/car/tests/test_car_interfaces.py index 412874c81..aabf652c8 100755 --- a/selfdrive/car/tests/test_car_interfaces.py +++ b/selfdrive/car/tests/test_car_interfaces.py @@ -5,6 +5,7 @@ import importlib from parameterized import parameterized from cereal import car +from selfdrive.car import gen_empty_fingerprint from selfdrive.car.fingerprints import all_known_cars from selfdrive.car.car_helpers import interfaces from selfdrive.car.fingerprints import _FINGERPRINTS as FINGERPRINTS @@ -19,11 +20,8 @@ class TestCarInterfaces(unittest.TestCase): fingerprint = {} CarInterface, CarController, CarState = interfaces[car_name] - fingerprints = { - 0: fingerprint, - 1: fingerprint, - 2: fingerprint, - } + fingerprints = gen_empty_fingerprint() + fingerprints.update({k: fingerprint for k in fingerprints.keys()}) car_fw = [] From 5ed587ebeff24bacf70c44879616c51756730bba Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Wed, 17 Aug 2022 18:03:33 -0700 Subject: [PATCH 019/172] controls: block resume if cruise not previously engaged (#25402) * see if this works at all * can revert this * think adding a no entry conditionally is nicer * then we can revert this * 0 makes more sense * Revert "0 makes more sense" This reverts commit efc89e8a2389ef58fbc0cec0a2872d24db524867. * gm CC uses > 70 * bump cereal * comment * test on Honda * whoops * works * add exception with todo * moved button enable events to controlsd * get rid of that get rid of that * different values for now * car interfaces add enable event, controlsd can block it * Regen and update refs * delete if not set * One place one place * regen routes are uninitialized first few frames * Trim start of segment so it's like original segment * stash * regen * not working * clean up * more cleanup * revert * bump ceral * actually check resume button * whoops * pcmCruise cars don't use setSpeed, so we're good * engage correctly in sim * Update ref_commit * Update refs --- cereal | 2 +- selfdrive/controls/controlsd.py | 32 ++++++++++++++--------- selfdrive/controls/lib/drive_helpers.py | 1 + selfdrive/controls/lib/events.py | 4 +++ selfdrive/test/process_replay/ref_commit | 2 +- tools/sim/tests/test_carla_integration.py | 2 +- 6 files changed, 27 insertions(+), 16 deletions(-) diff --git a/cereal b/cereal index 2d648b0dc..f60f0ef20 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 2d648b0dc4654fc7088ffb81fd301352707de749 +Subproject commit f60f0ef200afa9c7da932454b592ad5b0fb58493 diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 80d9bccb0..1f394d487 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -16,7 +16,7 @@ from system.version import get_short_branch from selfdrive.boardd.boardd import can_list_to_can_capnp from selfdrive.car.car_helpers import get_car, get_startup_event, get_one_can from selfdrive.controls.lib.lane_planner import CAMERA_OFFSET -from selfdrive.controls.lib.drive_helpers import update_v_cruise, initialize_v_cruise +from selfdrive.controls.lib.drive_helpers import V_CRUISE_INITIAL, update_v_cruise, initialize_v_cruise from selfdrive.controls.lib.drive_helpers import get_lag_adjusted_curvature from selfdrive.controls.lib.latcontrol import LatControl from selfdrive.controls.lib.longcontrol import LongControl @@ -50,6 +50,7 @@ LaneChangeState = log.LateralPlan.LaneChangeState LaneChangeDirection = log.LateralPlan.LaneChangeDirection EventName = car.CarEvent.EventName ButtonEvent = car.CarState.ButtonEvent +ButtonType = car.CarState.ButtonEvent.Type SafetyModel = car.CarParams.SafetyModel IGNORED_SAFETY_MODES = (SafetyModel.silent, SafetyModel.noOutput) @@ -162,8 +163,8 @@ class Controls: self.active = False self.can_rcv_error = False self.soft_disable_timer = 0 - self.v_cruise_kph = 255 - self.v_cruise_cluster_kph = 255 + self.v_cruise_kph = V_CRUISE_INITIAL + self.v_cruise_cluster_kph = V_CRUISE_INITIAL self.v_cruise_kph_last = 0 self.mismatch_counter = 0 self.cruise_mismatch_counter = 0 @@ -228,6 +229,11 @@ class Controls: self.events.add(EventName.controlsInitializing) return + # Block resume if cruise never previously enabled + resume_pressed = any(be.type in (ButtonType.accelCruise, ButtonType.resumeCruise) for be in CS.buttonEvents) + if not self.CP.pcmCruise and self.v_cruise_kph == V_CRUISE_INITIAL and resume_pressed: + self.events.add(EventName.resumeBlocked) + # Disable on rising edge of accelerator or brake. Also disable on brake when speed > 0 if (CS.gasPressed and not self.CS_prev.gasPressed and self.disengage_on_accelerator) or \ (CS.brakePressed and (not self.CS_prev.brakePressed or not CS.standstill)): @@ -460,18 +466,18 @@ class Controls: self.v_cruise_kph_last = self.v_cruise_kph - # if stock cruise is completely disabled, then we can use our own set speed logic - if not self.CP.pcmCruise: - self.v_cruise_kph = update_v_cruise(self.v_cruise_kph, CS.vEgo, CS.gasPressed, CS.buttonEvents, - self.button_timers, self.enabled, self.is_metric) - self.v_cruise_cluster_kph = self.v_cruise_kph - else: - if CS.cruiseState.available: + if CS.cruiseState.available: + # if stock cruise is completely disabled, then we can use our own set speed logic + if not self.CP.pcmCruise: + self.v_cruise_kph = update_v_cruise(self.v_cruise_kph, CS.vEgo, CS.gasPressed, CS.buttonEvents, + self.button_timers, self.enabled, self.is_metric) + self.v_cruise_cluster_kph = self.v_cruise_kph + else: self.v_cruise_kph = CS.cruiseState.speed * CV.MS_TO_KPH self.v_cruise_cluster_kph = CS.cruiseState.speedCluster * CV.MS_TO_KPH - else: - self.v_cruise_kph = 0 - self.v_cruise_cluster_kph = 0 + else: + self.v_cruise_kph = V_CRUISE_INITIAL + self.v_cruise_cluster_kph = V_CRUISE_INITIAL # decrement the soft disable timer at every step, as it's reset on # entrance in SOFT_DISABLING state diff --git a/selfdrive/controls/lib/drive_helpers.py b/selfdrive/controls/lib/drive_helpers.py index d79f94bbf..ffa837383 100644 --- a/selfdrive/controls/lib/drive_helpers.py +++ b/selfdrive/controls/lib/drive_helpers.py @@ -11,6 +11,7 @@ from selfdrive.modeld.constants import T_IDXS V_CRUISE_MAX = 145 # kph V_CRUISE_MIN = 8 # kph V_CRUISE_ENABLE_MIN = 40 # kph +V_CRUISE_INITIAL = 255 # kph LAT_MPC_N = 16 LON_MPC_N = 32 diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index de666fd50..5139ead84 100644 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -635,6 +635,10 @@ EVENTS: Dict[int, Dict[str, Union[Alert, AlertCallbackType]]] = { ET.NO_ENTRY: wrong_car_mode_alert, }, + EventName.resumeBlocked: { + ET.NO_ENTRY: NoEntryAlert("Press Set to Engage"), + }, + EventName.wrongCruiseMode: { ET.USER_DISABLE: EngagementAlert(AudibleAlert.disengage), ET.NO_ENTRY: NoEntryAlert("Adaptive Cruise Disabled"), diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 57d80369f..da083eeee 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -29e406826b1d7b0cc7e05153b623fbedcd8fd9e9 \ No newline at end of file +35899d5137e298220e91063f3078109227cc8715 \ No newline at end of file diff --git a/tools/sim/tests/test_carla_integration.py b/tools/sim/tests/test_carla_integration.py index 43db783f4..f46739196 100755 --- a/tools/sim/tests/test_carla_integration.py +++ b/tools/sim/tests/test_carla_integration.py @@ -77,7 +77,7 @@ class TestCarlaIntegration(unittest.TestCase): while time.monotonic() < start_time + max_time_per_step: sm.update() - q.put("cruise_up") # Try engaging + q.put("cruise_down") # Try engaging if sm.all_alive() and sm['controlsState'].active: control_active += 1 From 96f8d3acd569a65b2989ce28299291e680d5222b Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 17 Aug 2022 20:00:15 -0700 Subject: [PATCH 020/172] rawgps in CI (#25473) --- release/files_tici | 2 ++ selfdrive/manager/process_config.py | 4 ++-- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/release/files_tici b/release/files_tici index f8c0a2795..8e3249cdf 100644 --- a/release/files_tici +++ b/release/files_tici @@ -11,5 +11,7 @@ system/camerad/cameras/camera_qcom2.cc system/camerad/cameras/camera_qcom2.h system/camerad/cameras/real_debayer.cl +selfdrive/sensord/rawgps/* + selfdrive/ui/qt/spinner_larch64 selfdrive/ui/qt/text_larch64 diff --git a/selfdrive/manager/process_config.py b/selfdrive/manager/process_config.py index dec51966a..927de563c 100644 --- a/selfdrive/manager/process_config.py +++ b/selfdrive/manager/process_config.py @@ -2,7 +2,7 @@ import os from cereal import car from common.params import Params -from system.hardware import PC +from system.hardware import PC, TICI from selfdrive.manager.process import PythonProcess, NativeProcess, DaemonProcess WEBCAM = os.getenv("USE_WEBCAM") is not None @@ -57,7 +57,7 @@ procs = [ PythonProcess("webjoystick", "tools.joystick.web", onroad=False, callback=notcar), # Experimental - PythonProcess("rawgpsd", "selfdrive.sensord.rawgps.rawgpsd", enabled=os.path.isfile("/persist/comma/use-quectel-rawgps")), + PythonProcess("rawgpsd", "selfdrive.sensord.rawgps.rawgpsd", enabled=(TICI and os.path.isfile("/persist/comma/use-quectel-rawgps"))), ] managed_processes = {p.name: p for p in procs} From 1de8ad891bcf8c0b73b24f7e3eab17f3448e7473 Mon Sep 17 00:00:00 2001 From: eFini Date: Thu, 18 Aug 2022 11:21:38 +0800 Subject: [PATCH 021/172] Fix is_rhd param name in map.cc (#25464) --- selfdrive/ui/qt/maps/map.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/ui/qt/maps/map.cc b/selfdrive/ui/qt/maps/map.cc index f81c3dd8f..046814d51 100644 --- a/selfdrive/ui/qt/maps/map.cc +++ b/selfdrive/ui/qt/maps/map.cc @@ -361,7 +361,7 @@ void MapWindow::offroadTransition(bool offroad) { } MapInstructions::MapInstructions(QWidget * parent) : QWidget(parent) { - is_rhd = Params().getBool("IsRHD"); + is_rhd = Params().getBool("IsRhdDetected"); QHBoxLayout *main_layout = new QHBoxLayout(this); main_layout->setContentsMargins(11, 50, 11, 11); { From 7087a154f57ced0919c2f27d6eb5ca4e89d853ac Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 17 Aug 2022 20:29:56 -0700 Subject: [PATCH 022/172] Ford: add Q3 and Q4 harnesses (#25474) --- selfdrive/car/docs_definitions.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/selfdrive/car/docs_definitions.py b/selfdrive/car/docs_definitions.py index 65dbe4c62..d882cd120 100644 --- a/selfdrive/car/docs_definitions.py +++ b/selfdrive/car/docs_definitions.py @@ -217,6 +217,8 @@ class Harness(Enum): nissan_a = "Nissan A" nissan_b = "Nissan B" mazda = "Mazda" + ford_q3 = "Ford Q3" + ford_q4 = "Ford Q4" none = "None" From c870d0cbdeacc3ab6c3e460fdc484c1961a5b2a0 Mon Sep 17 00:00:00 2001 From: Squiggle Squaggle Date: Wed, 17 Aug 2022 22:49:38 -0500 Subject: [PATCH 023/172] Hyundai: add missing FW for 2022 Elantra SEL (#25472) * added missing FW for 2022 Elantra SEL I connected the Comma 3 with Hyundai K Harness and the vehicle was unknown. I worked my way through fingerprint 2.0 and compared the FW I had with this file and added the missing firmware to the Elantra_2021 section. I then went for a drive and it worked as intended. A number of the fwVersion were already there and so I've only added the ones that were missing. * removed erroneous entries removed entries that were not labeled Hyundai that I had added. --- selfdrive/car/hyundai/values.py | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index c61efcdac..d22abc9e2 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -1139,11 +1139,13 @@ FW_VERSIONS = { b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.00 99210-AB000 200819', b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.03 99210-AA000 200819', b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.01 99210-AB000 210205', + b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.06 99210-AA000 220111', ], (Ecu.esp, 0x7d1, None): [ b'\xf1\x00CN ESC \t 101 \x10\x03 58910-AB800', b'\xf1\x8758910-AA800\xf1\x00CN ESC \t 104 \x08\x03 58910-AA800', b'\xf1\x8758910-AB800\xf1\x00CN ESC \t 101 \x10\x03 58910-AB800', + b'\xf1\x8758910-AA800\xf1\x00CN ESC \t 105 \x10\x03 58910-AA800', ], (Ecu.transmission, 0x7e1, None): [ b'\xf1\x00HT6WA280BLHT6VA640A1CCN0N20NS5\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', @@ -1158,7 +1160,7 @@ FW_VERSIONS = { b'\xf1\x82CNCWD0AMFCXCSFFA', b'\xf1\x82CNCWD0AMFCXCSFFB', b'\xf1\x82CNCVD0AMFCXCSFFB', - b'\xf1\x870\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\xf1\x82CNDWD0AMFCXCSG8A', + b'\xf1\x870\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\xf1\x81HM6M2_0a0_G80', ], }, CAR.ELANTRA_HEV_2021: { From 8ed87b12bc177c78ea3ca311d5a9e5675bea8436 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Wed, 17 Aug 2022 20:57:50 -0700 Subject: [PATCH 024/172] Hyundai: add missing Palisade transmission FW (#25476) Add missing transmission fp for Palisade --- 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 d22abc9e2..a27c6f685 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -810,6 +810,7 @@ FW_VERSIONS = { b"\xf1\x87LBLUFN622950KF36\xa8\x88\x88\x88\x87w\x87xh\x99\x96\x89\x88\x99\x98\x89\x88\x99\x98\x89\x87o\xf6\xff\x98\x88o\xffx'\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX2G38NB3\xd1\xc3\xf8\xa8", b'\xf1\x87LDMVBN950669KF37\x97www\x96fffy\x99\xa7\x99\xa9\x99\xaa\x99g\x88\x96x\xb8\x8f\xf9\xffTD/\xff\xa7\xcb\xf1\x81U922\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U922\x00\x00\x00\x00\x00\x00SLX4G38NB5\xb9\x94\xe8\x89', b'\xf1\x87LDLVAA4478824HH1\x87wwwvfvg\x89\x99\xa8\x99w\x88\x87x\x89\x99\xa8\x99\xa6o\xfa\xfffU/\xffu\x92\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00TON4G38NB2[v\\\xb6', + b'\xf1\x87LDMVBN871852KF37\xb9\x99\x99\x99\xa8\x88\x88\x88y\x99\xa7\x99x\x99\xa7\x89\x88\x88\x98\x88\x89o\xf7\xff\xaa\x88o\xff\x0e\xed\xf1\x81U922\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U922\x00\x00\x00\x00\x00\x00SLX4G38NB5\xb9\x94\xe8\x89', ], }, CAR.VELOSTER: { From 7679f4fa90d936850113cd345b23313bf25fde6e Mon Sep 17 00:00:00 2001 From: Robbe Derks Date: Wed, 17 Aug 2022 21:23:03 -0700 Subject: [PATCH 025/172] Panda fan controller (#25475) bump panda and add fan power to pandaState --- cereal | 2 +- panda | 2 +- selfdrive/boardd/boardd.cc | 1 + 3 files changed, 3 insertions(+), 2 deletions(-) diff --git a/cereal b/cereal index f60f0ef20..ecff0a284 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit f60f0ef200afa9c7da932454b592ad5b0fb58493 +Subproject commit ecff0a284a2aa9879c4d04ea797356e4ef024dc4 diff --git a/panda b/panda index 199bc10db..ba8772123 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 199bc10db3a937fab0c50d9b708f6c76234f5c3a +Subproject commit ba8772123f13123c797234660c56adb70795cebb diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index 240935175..afbc592b9 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -372,6 +372,7 @@ std::optional send_panda_states(PubMaster *pm, const std::vector ps.setAlternativeExperience(health.alternative_experience_pkt); ps.setHarnessStatus(cereal::PandaState::HarnessStatus(health.car_harness_status_pkt)); ps.setInterruptLoad(health.interrupt_load); + ps.setFanPower(health.fan_power); // Convert faults bitset to capnp list std::bitset fault_bits(health.faults_pkt); From a21780dbeac42de6e4ab153ed29cd48b41d7f521 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 18 Aug 2022 09:02:33 -0700 Subject: [PATCH 026/172] Subaru: Legacy 2020-22 support (#25313) * Subaru: Legacy 2020 support * clean that up * force for now * update years * test route --- RELEASES.md | 1 + docs/CARS.md | 3 +- selfdrive/car/subaru/carstate.py | 6 ++-- selfdrive/car/subaru/interface.py | 2 +- selfdrive/car/subaru/values.py | 34 ++++++++++++++--------- selfdrive/car/tests/routes.py | 1 + selfdrive/car/torque_data/substitute.yaml | 2 ++ 7 files changed, 32 insertions(+), 17 deletions(-) diff --git a/RELEASES.md b/RELEASES.md index 364d2a494..ced165fb0 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -6,6 +6,7 @@ Version 0.8.16 (2022-XX-XX) * Chevrolet Bolt EUV 2022-23 support thanks to JasonJShuler! * Hyundai Ioniq 5 2022 support thanks to sunnyhaibin! * Hyundai Kona Electric 2022 support thanks to sunnyhaibin! +* Subaru Legacy 2020-22 support thanks to martinl! * Subaru Outback 2020-22 support Version 0.8.15 (2022-07-20) diff --git a/docs/CARS.md b/docs/CARS.md index fd82a5aa8..5757dd6d2 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -19,7 +19,7 @@ A supported vehicle is one that just works when you install a comma device. Ever - [![star](assets/icon-star-empty.svg)](##) - Limited ability to make tighter turns. -# 201 Supported Cars +# 202 Supported Cars |Make|Model|Supported Package|openpilot ACC|Stop and Go|Steer to 0|Steering Torque| |---|---|---|:---:|:---:|:---:|:---:| @@ -143,6 +143,7 @@ A supported vehicle is one that just works when you install a comma device. Ever |Subaru|Forester 2019-21|All|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| |Subaru|Impreza 2017-19|EyeSight Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)| |Subaru|Impreza 2020-22|EyeSight Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| +|Subaru|Legacy 2020-22|All|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| |Subaru|Outback 2020-22|All|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| |Subaru|XV 2018-19|EyeSight Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)| |Subaru|XV 2020-21|EyeSight Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| diff --git a/selfdrive/car/subaru/carstate.py b/selfdrive/car/subaru/carstate.py index de5e62cb7..7fc5456d9 100644 --- a/selfdrive/car/subaru/carstate.py +++ b/selfdrive/car/subaru/carstate.py @@ -4,7 +4,7 @@ from opendbc.can.can_define import CANDefine from common.conversions import Conversions as CV from selfdrive.car.interfaces import CarStateBase from opendbc.can.parser import CANParser -from selfdrive.car.subaru.values import DBC, STEER_THRESHOLD, CAR, GLOBAL_GEN2, PREGLOBAL_CARS +from selfdrive.car.subaru.values import DBC, CAR, GLOBAL_GEN2, PREGLOBAL_CARS class CarState(CarStateBase): @@ -50,7 +50,9 @@ class CarState(CarStateBase): ret.steeringAngleDeg = cp.vl["Steering_Torque"]["Steering_Angle"] ret.steeringTorque = cp.vl["Steering_Torque"]["Steer_Torque_Sensor"] ret.steeringTorqueEps = cp.vl["Steering_Torque"]["Steer_Torque_Output"] - ret.steeringPressed = abs(ret.steeringTorque) > STEER_THRESHOLD[self.car_fingerprint] + + steer_threshold = 75 if self.CP.carFingerprint in PREGLOBAL_CARS else 80 + ret.steeringPressed = abs(ret.steeringTorque) > steer_threshold cp_cruise = cp_body if self.car_fingerprint in GLOBAL_GEN2 else cp ret.cruiseState.enabled = cp_cruise.vl["CruiseControl"]["Cruise_Activated"] != 0 diff --git a/selfdrive/car/subaru/interface.py b/selfdrive/car/subaru/interface.py index 049da10a1..a464734a3 100644 --- a/selfdrive/car/subaru/interface.py +++ b/selfdrive/car/subaru/interface.py @@ -71,7 +71,7 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0., 14., 23.], [0., 14., 23.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.01, 0.065, 0.2], [0.001, 0.015, 0.025]] - elif candidate == CAR.OUTBACK: + elif candidate in (CAR.OUTBACK, CAR.LEGACY): ret.mass = 1568. + STD_CARGO_KG ret.wheelbase = 2.67 ret.centerToFront = ret.wheelbase * 0.5 diff --git a/selfdrive/car/subaru/values.py b/selfdrive/car/subaru/values.py index 691a4c915..7d8365a11 100644 --- a/selfdrive/car/subaru/values.py +++ b/selfdrive/car/subaru/values.py @@ -35,6 +35,7 @@ class CAR: IMPREZA_2020 = "SUBARU IMPREZA SPORT 2020" FORESTER = "SUBARU FORESTER 2019" OUTBACK = "SUBARU OUTBACK 6TH GEN" + LEGACY = "SUBARU LEGACY 7TH GEN" # Pre-global FORESTER_PREGLOBAL = "SUBARU FORESTER 2017 - 2018" @@ -52,6 +53,7 @@ class SubaruCarInfo(CarInfo): CAR_INFO: Dict[str, Union[SubaruCarInfo, List[SubaruCarInfo]]] = { CAR.ASCENT: SubaruCarInfo("Subaru Ascent 2019-21", "All"), CAR.OUTBACK: SubaruCarInfo("Subaru Outback 2020-22", "All", harness=Harness.subaru_b), + CAR.LEGACY: SubaruCarInfo("Subaru Legacy 2020-22", "All", harness=Harness.subaru_b), CAR.IMPREZA: [ SubaruCarInfo("Subaru Impreza 2017-19"), SubaruCarInfo("Subaru Crosstrek 2018-19", video_link="https://youtu.be/Agww7oE1k-s?t=26"), @@ -101,6 +103,23 @@ FW_VERSIONS = { b'\x01\xfe\xf7\x00\x00', ], }, + CAR.LEGACY: { + (Ecu.esp, 0x7b0, None): [ + b'\xa1\\ x04\x01', + ], + (Ecu.eps, 0x746, None): [ + b'\x9b\xc0\x11\x00', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x00\x00e\x80\x00\x1f@ \x19\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xde\"a0\x07', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xa5\xf6\x05@\x00', + ], + }, CAR.IMPREZA: { (Ecu.esp, 0x7b0, None): [ b'\x7a\x94\x3f\x90\x00', @@ -448,29 +467,18 @@ FW_VERSIONS = { }, } -STEER_THRESHOLD = { - CAR.ASCENT: 80, - CAR.IMPREZA: 80, - CAR.IMPREZA_2020: 80, - CAR.FORESTER: 80, - CAR.OUTBACK: 80, - CAR.FORESTER_PREGLOBAL: 75, - CAR.LEGACY_PREGLOBAL: 75, - CAR.OUTBACK_PREGLOBAL: 75, - CAR.OUTBACK_PREGLOBAL_2018: 75, -} - DBC = { CAR.ASCENT: dbc_dict('subaru_global_2017_generated', None), CAR.IMPREZA: dbc_dict('subaru_global_2017_generated', None), CAR.IMPREZA_2020: dbc_dict('subaru_global_2017_generated', None), CAR.FORESTER: dbc_dict('subaru_global_2017_generated', None), CAR.OUTBACK: dbc_dict('subaru_global_2017_generated', None), + CAR.LEGACY: dbc_dict('subaru_global_2017_generated', None), CAR.FORESTER_PREGLOBAL: dbc_dict('subaru_forester_2017_generated', None), CAR.LEGACY_PREGLOBAL: dbc_dict('subaru_outback_2015_generated', None), CAR.OUTBACK_PREGLOBAL: dbc_dict('subaru_outback_2015_generated', None), CAR.OUTBACK_PREGLOBAL_2018: dbc_dict('subaru_outback_2019_generated', None), } -GLOBAL_GEN2 = (CAR.OUTBACK, ) +GLOBAL_GEN2 = (CAR.OUTBACK, CAR.LEGACY) PREGLOBAL_CARS = (CAR.FORESTER_PREGLOBAL, CAR.LEGACY_PREGLOBAL, CAR.OUTBACK_PREGLOBAL, CAR.OUTBACK_PREGLOBAL_2018) diff --git a/selfdrive/car/tests/routes.py b/selfdrive/car/tests/routes.py index 44672bf9d..5c767ae1a 100644 --- a/selfdrive/car/tests/routes.py +++ b/selfdrive/car/tests/routes.py @@ -193,6 +193,7 @@ routes = [ TestRoute("791340bc01ed993d|2019-03-10--16-28-08", SUBARU.IMPREZA), TestRoute("8bf7e79a3ce64055|2021-05-24--09-36-27", SUBARU.IMPREZA_2020), TestRoute("1bbe6bf2d62f58a8|2022-07-14--17-11-43", SUBARU.OUTBACK, segment=3), + TestRoute("c56e69bbc74b8fad|2022-08-18--09-43-51", SUBARU.LEGACY, segment=3), # Pre-global, dashcam TestRoute("95441c38ae8c130e|2020-06-08--12-10-17", SUBARU.FORESTER_PREGLOBAL), TestRoute("df5ca7660000fba8|2020-06-16--17-37-19", SUBARU.LEGACY_PREGLOBAL), diff --git a/selfdrive/car/torque_data/substitute.yaml b/selfdrive/car/torque_data/substitute.yaml index 279e28ff5..de64a5544 100644 --- a/selfdrive/car/torque_data/substitute.yaml +++ b/selfdrive/car/torque_data/substitute.yaml @@ -69,6 +69,8 @@ VOLKSWAGEN POLO 6TH GEN: VOLKSWAGEN GOLF 7TH GEN SEAT LEON 3RD GEN: VOLKSWAGEN GOLF 7TH GEN SEAT ATECA 1ST GEN: VOLKSWAGEN GOLF 7TH GEN +SUBARU LEGACY 7TH GEN: SUBARU OUTBACK 6TH GEN + # Old subarus don't have much data guessing it's like low torque impreza SUBARU OUTBACK 2018 - 2019: SUBARU IMPREZA LIMITED 2019 SUBARU OUTBACK 2015 - 2017: SUBARU IMPREZA LIMITED 2019 From 5f8858266c4127ddd2df851c66678982667fc06b Mon Sep 17 00:00:00 2001 From: Alex Vazquez Date: Thu, 18 Aug 2022 14:35:07 -0400 Subject: [PATCH 027/172] Hyundai: add missing Santa Fe 2022 FW (#25479) * Update values.py Adding 2022 Santa Fe Limited drive train and sensors - 2.5T with Dual Clutch Transmission which is different than the SE/VRT/SEL models. * Update selfdrive/car/hyundai/values.py * Add back other FW Co-authored-by: Shane Smiskol --- selfdrive/car/hyundai/values.py | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index a27c6f685..17745a4d7 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -613,6 +613,7 @@ FW_VERSIONS = { b'\xf1\x00TM__ SCC F-CUP 1.00 1.00 99110-S1500 ', b'\xf1\x8799110S1500\xf1\x00TM__ SCC F-CUP 1.00 1.00 99110-S1500 ', b'\xf1\x8799110S1500\xf1\x00TM__ SCC FHCUP 1.00 1.00 99110-S1500 ', + b'\xf1\x00TM__ SCC FHCUP 1.00 1.00 99110-S1500 ', ], (Ecu.esp, 0x7d1, None): [ b'\xf1\x00TM ESC \x02 101 \x08\x04 58910-S2GA0', @@ -621,6 +622,7 @@ FW_VERSIONS = { b'\xf1\x8758910-S2GA0\xf1\x00TM ESC \x02 101 \x08\x04 58910-S2GA0', b'\xf1\x8758910-S1DA0\xf1\x00TM ESC \x1e 102 \x08\x08 58910-S1DA0', b'\xf1\x8758910-S2GA0\xf1\x00TM ESC \x04 102!\x04\x05 58910-S2GA0', + b'\xf1\x00TM ESC \x04 102!\x04\x05 58910-S2GA0', ], (Ecu.engine, 0x7e0, None): [ b'\xf1\x82TACVN5GMI3XXXH0A', @@ -629,6 +631,7 @@ FW_VERSIONS = { b'\xf1\x82TMCFD5MMCXXXXG0A', b'\xf1\x870\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\xf1\x82TMDWN5TMD3TXXJ1A', b'\xf1\x81HM6M2_0a0_G00', + b'\xf1\x870\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\xf1\x81HM6M1_0a0_J10', ], (Ecu.eps, 0x7d4, None): [ b'\xf1\x00TM MDPS C 1.00 1.02 56370-S2AA0 0B19', @@ -648,6 +651,8 @@ FW_VERSIONS = { b'\xf1\x87KMMYBU034207SB72x\x89\x88\x98h\x88\x98\x89\x87fhvvfWf33_\xff\x87\xff\x8f\xfa\x81\xe5\xf1\x89HT6TAF00A1\xf1\x82STM0M25GS1\x00\x00\x00\x00\x00\x00', b'\xf1\x87954A02N250\x00\x00\x00\x00\x00\xf1\x81T02730A1 \xf1\x00T02601BL T02730A1 VTMPT25XXX730NS2\xa6', b'\xf1\x00HT6TA290BLHT6TAF00A1STM0M25GS1\x00\x00\x00\x00\x00\x006\xd8\x97\x15', + b'\xf1\x00T02601BL T02900A1 VTMPT25XXX900NS8\xb7\xaa\xfe\xfc', + b'\xf1\x87954A02N250\x00\x00\x00\x00\x00\xf1\x81T02900A1 \xf1\x00T02601BL T02900A1 VTMPT25XXX900NS8\xb7\xaa\xfe\xfc', ], }, CAR.SANTA_FE_HEV_2022: { From 747bcb013dabdb1f220dc97a37270b42cb4eae03 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 18 Aug 2022 15:12:18 -0700 Subject: [PATCH 028/172] Car docs: show more information about cars (#25415) * back to actual information * remove some star code * round speeds * Try out showing lateral acceleration * remove that * Fix speed units * Add harness and try rounding to nearest half before scapping it fix ^2 ^2 * Add back steering torque star * Fix static analysis * auto-generate header * fix static analysis. set to Harness.none by default * rm --- docs/CARS.md | 423 ++++++++++++++---------------- selfdrive/car/CARS_template.md | 14 +- selfdrive/car/body/values.py | 4 +- selfdrive/car/docs.py | 28 +- selfdrive/car/docs_definitions.py | 148 ++++------- selfdrive/car/tests/test_docs.py | 2 +- selfdrive/car/toyota/values.py | 4 +- 7 files changed, 270 insertions(+), 353 deletions(-) diff --git a/docs/CARS.md b/docs/CARS.md index 5757dd6d2..efd9b3c52 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -4,227 +4,212 @@ A supported vehicle is one that just works when you install a comma device. Every car performs differently with openpilot, but all supported cars should provide a better experience than any stock system. -## How We Rate The Cars - -### Stop and Go -- [![star](assets/icon-star-full.svg)](##) - openpilot operates down to 0 mph. -- [![star](assets/icon-star-empty.svg)](##) - openpilot operates only above a minimum speed. See your car's manual for the minimum speed. - -### Steer to 0 -- [![star](assets/icon-star-full.svg)](##) - openpilot can control the steering wheel down to 0 mph. -- [![star](assets/icon-star-empty.svg)](##) - No steering control below certain speeds. See your car's manual for the minimum speed. - -### Steering Torque -- [![star](assets/icon-star-full.svg)](##) - Car has enough steering torque to comfortably take most highway turns. -- [![star](assets/icon-star-empty.svg)](##) - Limited ability to make tighter turns. - - # 202 Supported Cars -|Make|Model|Supported Package|openpilot ACC|Stop and Go|Steer to 0|Steering Torque| -|---|---|---|:---:|:---:|:---:|:---:| -|Acura|ILX 2016-19|AcuraWatch Plus|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)| -|Acura|RDX 2016-18|AcuraWatch Plus|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)| -|Acura|RDX 2019-22|All|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)| -|Audi|A3 2014-19|ACC + Lane Assist|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Audi|A3 Sportback e-tron 2017-18|ACC + Lane Assist|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Audi|Q2 2018|ACC + Lane Assist|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Audi|Q3 2020-21|ACC + Lane Assist|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Audi|RS3 2018|ACC + Lane Assist|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Audi|S3 2015-17|ACC + Lane Assist|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Cadillac|Escalade ESV 2016[1](#footnotes)|Adaptive Cruise Control (ACC) & LKAS|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Chevrolet|Bolt EUV 2022-23|Premier/Premier Redline Trim|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Chevrolet|Volt 2017-18[1](#footnotes)|Adaptive Cruise Control|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Chrysler|Pacifica 2017-18|Adaptive Cruise Control|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Chrysler|Pacifica 2019-20|Adaptive Cruise Control|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Chrysler|Pacifica 2021|All|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Chrysler|Pacifica Hybrid 2017-18|Adaptive Cruise Control|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Chrysler|Pacifica Hybrid 2019-22|Adaptive Cruise Control|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|comma|body|All|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Genesis|G70 2018-19|All|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Genesis|G70 2020|All|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Genesis|G80 2017-19|All|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Genesis|G90 2017-18|All|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|GMC|Acadia 2018[1](#footnotes)|Adaptive Cruise Control|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Honda|Accord 2018-22|All|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)| -|Honda|Accord Hybrid 2018-22|All|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)| -|Honda|Civic 2016-18|Honda Sensing|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)| -|Honda|Civic 2019-21|All|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)[2](#footnotes)|[![star](assets/icon-star-empty.svg)](##)| -|Honda|Civic 2022|All|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Honda|Civic Hatchback 2017-21|Honda Sensing|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)| -|Honda|Civic Hatchback 2022|All|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Honda|CR-V 2015-16|Touring Trim|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)| -|Honda|CR-V 2017-22|Honda Sensing|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)| -|Honda|CR-V Hybrid 2017-19|Honda Sensing|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)| -|Honda|e 2020|All|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)| -|Honda|Fit 2018-20|Honda Sensing|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)| -|Honda|Freed 2020|Honda Sensing|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)| -|Honda|HR-V 2019-22|Honda Sensing|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)| -|Honda|Insight 2019-22|All|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)| -|Honda|Inspire 2018|All|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)| -|Honda|Odyssey 2018-20|Honda Sensing|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)| -|Honda|Passport 2019-21|All|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)| -|Honda|Pilot 2016-22|Honda Sensing|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)| -|Honda|Ridgeline 2017-22|Honda Sensing|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)| -|Hyundai|Elantra 2017-19|Smart Cruise Control (SCC) & LKAS|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Hyundai|Elantra 2021-22|Smart Cruise Control (SCC) & LKAS|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Hyundai|Elantra Hybrid 2021-22|Smart Cruise Control (SCC)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Hyundai|Genesis 2015-16|Smart Cruise Control (SCC) & LKAS|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Hyundai|Ioniq 5 2022|Highway Driving Assist II|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Hyundai|Ioniq Electric 2019|Smart Cruise Control (SCC) & LKAS|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Hyundai|Ioniq Electric 2020|Smart Cruise Control (SCC) & LKAS|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Hyundai|Ioniq Hybrid 2017-19|Smart Cruise Control (SCC) & LKAS|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Hyundai|Ioniq Hybrid 2020-22|Smart Cruise Control (SCC) & LFA|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Hyundai|Ioniq Plug-in Hybrid 2019|Smart Cruise Control (SCC) & LKAS|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Hyundai|Ioniq Plug-in Hybrid 2020-21|Smart Cruise Control (SCC)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Hyundai|Kona 2020|Smart Cruise Control (SCC)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Hyundai|Kona Electric 2018-21|Smart Cruise Control (SCC) & LKAS|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Hyundai|Kona Electric 2022|Smart Cruise Control (SCC)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Hyundai|Kona Hybrid 2020|Smart Cruise Control (SCC) & LKAS|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Hyundai|Palisade 2020-22|All|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Hyundai|Santa Fe 2019-20|All|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Hyundai|Santa Fe 2021-22|All|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Hyundai|Santa Fe Hybrid 2022|All|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Hyundai|Santa Fe Plug-in Hybrid 2022|All|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Hyundai|Sonata 2018-19|Smart Cruise Control (SCC) & LKAS|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Hyundai|Sonata 2020-22|All|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Hyundai|Sonata Hybrid 2020-22|All|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Hyundai|Tucson 2021|Smart Cruise Control (SCC)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Hyundai|Tucson Diesel 2019|Smart Cruise Control (SCC)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Hyundai|Veloster 2019-20|Smart Cruise Control (SCC)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Jeep|Grand Cherokee 2016-18|Adaptive Cruise Control|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Jeep|Grand Cherokee 2019-21|Adaptive Cruise Control|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Kia|Ceed 2019|Smart Cruise Control (SCC) & LKAS|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Kia|EV6 2022|Highway Driving Assist II|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Kia|Forte 2018|Smart Cruise Control (SCC) & LKAS|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Kia|Forte 2019-21|All|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Kia|K5 2021-22|Smart Cruise Control (SCC)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Kia|Niro Electric 2019|All|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Kia|Niro Electric 2020|All|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Kia|Niro Electric 2021|All|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Kia|Niro Electric 2022|All|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Kia|Niro Hybrid 2021|Smart Cruise Control (SCC) & LKAS|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Kia|Niro Hybrid 2022|Smart Cruise Control (SCC) & LKAS|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Kia|Niro Plug-in Hybrid 2018-19|Smart Cruise Control (SCC) & LKAS|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Kia|Optima 2017|Smart Cruise Control (SCC) & LKAS|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Kia|Optima 2019|Smart Cruise Control (SCC) & LKAS|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Kia|Seltos 2021|Smart Cruise Control (SCC)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Kia|Sorento 2018|Smart Cruise Control (SCC) & LKAS|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Kia|Sorento 2019|Smart Cruise Control (SCC) & LKAS|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Kia|Stinger 2018-20|Smart Cruise Control (SCC) & LKAS|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Kia|Telluride 2020|All|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Lexus|CT Hybrid 2017-18|Lexus Safety System+|[![star](assets/icon-star-half.svg)](##)[3](#footnotes)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Lexus|ES 2019-22|All|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Lexus|ES Hybrid 2017-18|Lexus Safety System+|[![star](assets/icon-star-half.svg)](##)[3](#footnotes)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Lexus|ES Hybrid 2019-22|All|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Lexus|IS 2017-19|All|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Lexus|NX 2018-19|All|[![star](assets/icon-star-half.svg)](##)[3](#footnotes)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Lexus|NX 2020-21|All|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Lexus|NX Hybrid 2018-19|All|[![star](assets/icon-star-half.svg)](##)[3](#footnotes)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Lexus|NX Hybrid 2020-21|All|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Lexus|RC 2017-20|All|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Lexus|RX 2016-19|All|[![star](assets/icon-star-half.svg)](##)[3](#footnotes)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Lexus|RX 2020-22|All|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Lexus|RX Hybrid 2016-19|All|[![star](assets/icon-star-half.svg)](##)[3](#footnotes)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Lexus|RX Hybrid 2020-21|All|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Lexus|UX Hybrid 2019-22|All|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Mazda|CX-5 2022|All|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Mazda|CX-9 2021-22|All|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Nissan|Altima 2019-20|ProPILOT Assist|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Nissan|Leaf 2018-22|ProPILOT Assist|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Nissan|Rogue 2018-20|ProPILOT Assist|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Nissan|X-Trail 2017|ProPILOT Assist|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Ram|1500 2019-22|Adaptive Cruise Control|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|SEAT|Ateca 2018|Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|SEAT|Leon 2014-20|Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Subaru|Ascent 2019-21|All|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Subaru|Crosstrek 2018-19|EyeSight Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)| -|Subaru|Crosstrek 2020-21|EyeSight Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Subaru|Forester 2019-21|All|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Subaru|Impreza 2017-19|EyeSight Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)| -|Subaru|Impreza 2020-22|EyeSight Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Subaru|Legacy 2020-22|All|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Subaru|Outback 2020-22|All|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Subaru|XV 2018-19|EyeSight Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)| -|Subaru|XV 2020-21|EyeSight Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Škoda|Kamiq 2021[5](#footnotes)|Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Škoda|Karoq 2019-21[7](#footnotes)|Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Škoda|Kodiaq 2018-19|Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Škoda|Octavia 2015, 2018-19|Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Škoda|Octavia RS 2016|Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Škoda|Scala 2020|Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Škoda|Superb 2015-18|Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Toyota|Alphard 2019-20|All|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Toyota|Alphard Hybrid 2021|All|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Toyota|Avalon 2016|Toyota Safety Sense P|[![star](assets/icon-star-half.svg)](##)[3](#footnotes)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Toyota|Avalon 2017-18|All|[![star](assets/icon-star-half.svg)](##)[3](#footnotes)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Toyota|Avalon 2019-21|All|[![star](assets/icon-star-half.svg)](##)[3](#footnotes)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Toyota|Avalon 2022|All|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Toyota|Avalon Hybrid 2019-21|All|[![star](assets/icon-star-half.svg)](##)[3](#footnotes)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Toyota|Avalon Hybrid 2022|All|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Toyota|C-HR 2017-21|All|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Toyota|C-HR Hybrid 2017-19|All|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Toyota|Camry 2018-20|All|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)[4](#footnotes)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Toyota|Camry 2021-22|All|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)[4](#footnotes)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Toyota|Camry Hybrid 2018-20|All|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Toyota|Camry Hybrid 2021-22|All|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Toyota|Corolla 2017-19|All|[![star](assets/icon-star-half.svg)](##)[3](#footnotes)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Toyota|Corolla 2020-22|All|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Toyota|Corolla Cross (Non-US only) 2020-21|All|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Toyota|Corolla Cross Hybrid (Non-US only) 2020-22|All|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Toyota|Corolla Hatchback 2019-22|All|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Toyota|Corolla Hybrid 2020-22|All|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Toyota|Highlander 2017-19|All|[![star](assets/icon-star-half.svg)](##)[3](#footnotes)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Toyota|Highlander 2020-22|All|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Toyota|Highlander Hybrid 2017-19|All|[![star](assets/icon-star-half.svg)](##)[3](#footnotes)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Toyota|Highlander Hybrid 2020-22|All|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Toyota|Mirai 2021|All|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Toyota|Prius 2016|Toyota Safety Sense P|[![star](assets/icon-star-half.svg)](##)[3](#footnotes)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Toyota|Prius 2017-20|All|[![star](assets/icon-star-half.svg)](##)[3](#footnotes)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Toyota|Prius 2021-22|All|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Toyota|Prius Prime 2017-20|All|[![star](assets/icon-star-half.svg)](##)[3](#footnotes)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Toyota|Prius Prime 2021-22|All|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Toyota|Prius v 2017|Toyota Safety Sense P|[![star](assets/icon-star-half.svg)](##)[3](#footnotes)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Toyota|RAV4 2016|Toyota Safety Sense P|[![star](assets/icon-star-half.svg)](##)[3](#footnotes)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Toyota|RAV4 2017-18|All|[![star](assets/icon-star-half.svg)](##)[3](#footnotes)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Toyota|RAV4 2019-21|All|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Toyota|RAV4 2022|All|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Toyota|RAV4 Hybrid 2016|Toyota Safety Sense P|[![star](assets/icon-star-half.svg)](##)[3](#footnotes)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Toyota|RAV4 Hybrid 2017-18|All|[![star](assets/icon-star-half.svg)](##)[3](#footnotes)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Toyota|RAV4 Hybrid 2019-21|All|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Toyota|RAV4 Hybrid 2022|All|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Toyota|Sienna 2018-20|All|[![star](assets/icon-star-half.svg)](##)[3](#footnotes)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Volkswagen|Arteon 2018-22[7,8](#footnotes)|Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Volkswagen|Arteon eHybrid 2020-22[7,8](#footnotes)|Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Volkswagen|Arteon R 2020-22[7,8](#footnotes)|Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Volkswagen|Atlas 2018-22[7](#footnotes)|Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Volkswagen|Atlas Cross Sport 2021-22[7](#footnotes)|Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Volkswagen|California 2021[7](#footnotes)|Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Volkswagen|Caravelle 2020[7](#footnotes)|Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Volkswagen|CC 2018-22[7,8](#footnotes)|Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Volkswagen|e-Golf 2014-20|Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Volkswagen|Golf 2015-20[8](#footnotes)|Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Volkswagen|Golf Alltrack 2015-19|Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Volkswagen|Golf GTD 2015-20|Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Volkswagen|Golf GTE 2015-20|Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Volkswagen|Golf GTI 2015-21|Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Volkswagen|Golf R 2015-19[8](#footnotes)|Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Volkswagen|Golf SportsVan 2015-20|Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Volkswagen|Jetta 2018-22[7](#footnotes)|Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Volkswagen|Jetta GLI 2021-22[7](#footnotes)|Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Volkswagen|Passat 2015-22[6,7,8](#footnotes)|Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Volkswagen|Passat Alltrack 2015-22[7](#footnotes)|Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Volkswagen|Passat GTE 2015-22[7,8](#footnotes)|Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Volkswagen|Polo 2020-22[7](#footnotes)|Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Volkswagen|Polo GTI 2020-22[7](#footnotes)|Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Volkswagen|T-Cross 2021[7](#footnotes)|Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Volkswagen|T-Roc 2021[7](#footnotes)|Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Volkswagen|Taos 2022[7](#footnotes)|Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Volkswagen|Teramont 2018-22[7](#footnotes)|Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Volkswagen|Teramont Cross Sport 2021-22[7](#footnotes)|Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Volkswagen|Teramont X 2021-22[7](#footnotes)|Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Volkswagen|Tiguan 2019-22[7](#footnotes)|Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| -|Volkswagen|Touran 2017|Driver Assistance|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)| +|Make|Model|Supported Package|ACC|No ACC accel below|No ALC below|Steering Torque|Harness| +|---|---|---|:---:|:---:|:---:|:---:|:---:| +|Acura|ILX 2016-19|AcuraWatch Plus|openpilot|25 mph|25 mph|[![star](assets/icon-star-empty.svg)](##)|Honda Nidec| +|Acura|RDX 2016-18|AcuraWatch Plus|openpilot|25 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|Honda Nidec| +|Acura|RDX 2019-22|All|Stock|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|Honda Bosch A| +|Audi|A3 2014-19|ACC + Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| +|Audi|A3 Sportback e-tron 2017-18|ACC + Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| +|Audi|Q2 2018|ACC + Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| +|Audi|Q3 2020-21|ACC + Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| +|Audi|RS3 2018|ACC + Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| +|Audi|S3 2015-17|ACC + Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| +|Cadillac|Escalade ESV 2016[1](#footnotes)|Adaptive Cruise Control (ACC) & LKAS|openpilot|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|OBD-II| +|Chevrolet|Bolt EUV 2022-23|Premier/Premier Redline Trim|Stock|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|GM| +|Chevrolet|Volt 2017-18[1](#footnotes)|Adaptive Cruise Control|openpilot|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|OBD-II| +|Chrysler|Pacifica 2017-18|Adaptive Cruise Control|Stock|0 mph|9 mph|[![star](assets/icon-star-full.svg)](##)|FCA| +|Chrysler|Pacifica 2019-20|Adaptive Cruise Control|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|FCA| +|Chrysler|Pacifica 2021|All|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|FCA| +|Chrysler|Pacifica Hybrid 2017-18|Adaptive Cruise Control|Stock|0 mph|9 mph|[![star](assets/icon-star-full.svg)](##)|FCA| +|Chrysler|Pacifica Hybrid 2019-22|Adaptive Cruise Control|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|FCA| +|comma|body|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|None| +|Genesis|G70 2018-19|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai F| +|Genesis|G70 2020|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai F| +|Genesis|G80 2017-19|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai H| +|Genesis|G90 2017-18|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai C| +|GMC|Acadia 2018[1](#footnotes)|Adaptive Cruise Control|openpilot|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|OBD-II| +|Honda|Accord 2018-22|All|Stock|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|Honda Bosch A| +|Honda|Accord Hybrid 2018-22|All|Stock|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|Honda Bosch A| +|Honda|Civic 2016-18|Honda Sensing|openpilot|0 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|Honda Nidec| +|Honda|Civic 2019-21|All|Stock|0 mph|2 mph[2](#footnotes)|[![star](assets/icon-star-empty.svg)](##)|Honda Bosch A| +|Honda|Civic 2022|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Honda Bosch B| +|Honda|Civic Hatchback 2017-21|Honda Sensing|Stock|0 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|Honda Bosch A| +|Honda|Civic Hatchback 2022|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Honda Bosch B| +|Honda|CR-V 2015-16|Touring Trim|openpilot|25 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|Honda Nidec| +|Honda|CR-V 2017-22|Honda Sensing|Stock|0 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|Honda Bosch A| +|Honda|CR-V Hybrid 2017-19|Honda Sensing|Stock|0 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|Honda Bosch A| +|Honda|e 2020|All|Stock|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|Honda Bosch A| +|Honda|Fit 2018-20|Honda Sensing|openpilot|25 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|Honda Nidec| +|Honda|Freed 2020|Honda Sensing|openpilot|25 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|Honda Nidec| +|Honda|HR-V 2019-22|Honda Sensing|openpilot|25 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|Honda Nidec| +|Honda|Insight 2019-22|All|Stock|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|Honda Bosch A| +|Honda|Inspire 2018|All|Stock|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|Honda Bosch A| +|Honda|Odyssey 2018-20|Honda Sensing|openpilot|25 mph|0 mph|[![star](assets/icon-star-empty.svg)](##)|Honda Nidec| +|Honda|Passport 2019-21|All|openpilot|25 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|Honda Nidec| +|Honda|Pilot 2016-22|Honda Sensing|openpilot|25 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|Honda Nidec| +|Honda|Ridgeline 2017-22|Honda Sensing|openpilot|25 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|Honda Nidec| +|Hyundai|Elantra 2017-19|Smart Cruise Control (SCC) & LKAS|Stock|19 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai B| +|Hyundai|Elantra 2021-22|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai K| +|Hyundai|Elantra Hybrid 2021-22|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai K| +|Hyundai|Genesis 2015-16|Smart Cruise Control (SCC) & LKAS|Stock|19 mph|37 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai J| +|Hyundai|Ioniq 5 2022|Highway Driving Assist II|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai Q| +|Hyundai|Ioniq Electric 2019|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai C| +|Hyundai|Ioniq Electric 2020|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai H| +|Hyundai|Ioniq Hybrid 2017-19|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai C| +|Hyundai|Ioniq Hybrid 2020-22|Smart Cruise Control (SCC) & LFA|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai H| +|Hyundai|Ioniq Plug-in Hybrid 2019|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai C| +|Hyundai|Ioniq Plug-in Hybrid 2020-21|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai H| +|Hyundai|Kona 2020|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai B| +|Hyundai|Kona Electric 2018-21|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai G| +|Hyundai|Kona Electric 2022|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai O| +|Hyundai|Kona Hybrid 2020|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai I| +|Hyundai|Palisade 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai H| +|Hyundai|Santa Fe 2019-20|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai D| +|Hyundai|Santa Fe 2021-22|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai L| +|Hyundai|Santa Fe Hybrid 2022|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai L| +|Hyundai|Santa Fe Plug-in Hybrid 2022|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai L| +|Hyundai|Sonata 2018-19|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai E| +|Hyundai|Sonata 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai A| +|Hyundai|Sonata Hybrid 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai A| +|Hyundai|Tucson 2021|Smart Cruise Control (SCC)|Stock|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai L| +|Hyundai|Tucson Diesel 2019|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai L| +|Hyundai|Veloster 2019-20|Smart Cruise Control (SCC)|Stock|5 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai E| +|Jeep|Grand Cherokee 2016-18|Adaptive Cruise Control|Stock|0 mph|9 mph|[![star](assets/icon-star-full.svg)](##)|FCA| +|Jeep|Grand Cherokee 2019-21|Adaptive Cruise Control|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|FCA| +|Kia|Ceed 2019|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai E| +|Kia|EV6 2022|Highway Driving Assist II|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai P| +|Kia|Forte 2018|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai B| +|Kia|Forte 2019-21|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai G| +|Kia|K5 2021-22|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai A| +|Kia|Niro Electric 2019|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai H| +|Kia|Niro Electric 2020|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai F| +|Kia|Niro Electric 2021|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai C| +|Kia|Niro Electric 2022|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai H| +|Kia|Niro Hybrid 2021|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai F| +|Kia|Niro Hybrid 2022|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai H| +|Kia|Niro Plug-in Hybrid 2018-19|Smart Cruise Control (SCC) & LKAS|openpilot|10 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai C| +|Kia|Optima 2017|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai B| +|Kia|Optima 2019|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai G| +|Kia|Seltos 2021|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai A| +|Kia|Sorento 2018|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai C| +|Kia|Sorento 2019|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai E| +|Kia|Stinger 2018-20|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai C| +|Kia|Telluride 2020|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai H| +|Lexus|CT Hybrid 2017-18|Lexus Safety System+|Stock[3](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Lexus|ES 2019-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Lexus|ES Hybrid 2017-18|Lexus Safety System+|Stock[3](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Lexus|ES Hybrid 2019-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Lexus|IS 2017-19|All|Stock|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Lexus|NX 2018-19|All|Stock[3](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Lexus|NX 2020-21|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Lexus|NX Hybrid 2018-19|All|Stock[3](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Lexus|NX Hybrid 2020-21|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Lexus|RC 2017-20|All|Stock|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Lexus|RX 2016-19|All|Stock[3](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Lexus|RX 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Lexus|RX Hybrid 2016-19|All|Stock[3](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Lexus|RX Hybrid 2020-21|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Lexus|UX Hybrid 2019-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Mazda|CX-5 2022|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Mazda| +|Mazda|CX-9 2021-22|All|Stock|0 mph|28 mph|[![star](assets/icon-star-full.svg)](##)|Mazda| +|Nissan|Altima 2019-20|ProPILOT Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Nissan B| +|Nissan|Leaf 2018-22|ProPILOT Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Nissan A| +|Nissan|Rogue 2018-20|ProPILOT Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Nissan A| +|Nissan|X-Trail 2017|ProPILOT Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Nissan A| +|Ram|1500 2019-22|Adaptive Cruise Control|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|Ram| +|SEAT|Ateca 2018|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| +|SEAT|Leon 2014-20|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| +|Subaru|Ascent 2019-21|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Subaru A| +|Subaru|Crosstrek 2018-19|EyeSight Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-empty.svg)](##)|Subaru A| +|Subaru|Crosstrek 2020-21|EyeSight Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Subaru A| +|Subaru|Forester 2019-21|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Subaru A| +|Subaru|Impreza 2017-19|EyeSight Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-empty.svg)](##)|Subaru A| +|Subaru|Impreza 2020-22|EyeSight Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Subaru A| +|Subaru|Legacy 2020-22|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Subaru B| +|Subaru|Outback 2020-22|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Subaru B| +|Subaru|XV 2018-19|EyeSight Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-empty.svg)](##)|Subaru A| +|Subaru|XV 2020-21|EyeSight Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Subaru A| +|Škoda|Kamiq 2021[5](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| +|Škoda|Karoq 2019-21[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| +|Škoda|Kodiaq 2018-19|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| +|Škoda|Octavia 2015, 2018-19|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| +|Škoda|Octavia RS 2016|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| +|Škoda|Scala 2020|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| +|Škoda|Superb 2015-18|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| +|Toyota|Alphard 2019-20|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|Alphard Hybrid 2021|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|Avalon 2016|Toyota Safety Sense P|Stock[3](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|Avalon 2017-18|All|Stock[3](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|Avalon 2019-21|All|Stock[3](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|Avalon 2022|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|Avalon Hybrid 2019-21|All|Stock[3](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|Avalon Hybrid 2022|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|C-HR 2017-21|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|C-HR Hybrid 2017-19|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|Camry 2018-20|All|Stock|0 mph[4](#footnotes)|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|Camry 2021-22|All|openpilot|0 mph[4](#footnotes)|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|Camry Hybrid 2018-20|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|Camry Hybrid 2021-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|Corolla 2017-19|All|Stock[3](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|Corolla 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|Corolla Cross (Non-US only) 2020-21|All|openpilot|17 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|Corolla Cross Hybrid (Non-US only) 2020-22|All|openpilot|17 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|Corolla Hatchback 2019-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|Corolla Hybrid 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|Highlander 2017-19|All|Stock[3](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|Highlander 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|Highlander Hybrid 2017-19|All|Stock[3](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|Highlander Hybrid 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|Mirai 2021|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|Prius 2016|Toyota Safety Sense P|Stock[3](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|Prius 2017-20|All|Stock[3](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|Prius 2021-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|Prius Prime 2017-20|All|Stock[3](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|Prius Prime 2021-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|Prius v 2017|Toyota Safety Sense P|Stock[3](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|RAV4 2016|Toyota Safety Sense P|Stock[3](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|RAV4 2017-18|All|Stock[3](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|RAV4 2019-21|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|RAV4 2022|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|RAV4 Hybrid 2016|Toyota Safety Sense P|Stock[3](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|RAV4 Hybrid 2017-18|All|Stock[3](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|RAV4 Hybrid 2019-21|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|RAV4 Hybrid 2022|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|Sienna 2018-20|All|Stock[3](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Volkswagen|Arteon 2018-22[7,8](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Arteon eHybrid 2020-22[7,8](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Arteon R 2020-22[7,8](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Atlas 2018-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Atlas Cross Sport 2021-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|California 2021[7](#footnotes)|Driver Assistance|Stock|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Caravelle 2020[7](#footnotes)|Driver Assistance|Stock|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|CC 2018-22[7,8](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|e-Golf 2014-20|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| +|Volkswagen|Golf 2015-20[8](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| +|Volkswagen|Golf Alltrack 2015-19|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| +|Volkswagen|Golf GTD 2015-20|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| +|Volkswagen|Golf GTE 2015-20|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| +|Volkswagen|Golf GTI 2015-21|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| +|Volkswagen|Golf R 2015-19[8](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| +|Volkswagen|Golf SportsVan 2015-20|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| +|Volkswagen|Jetta 2018-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Jetta GLI 2021-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Passat 2015-22[6,7,8](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Passat Alltrack 2015-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Passat GTE 2015-22[7,8](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Polo 2020-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Polo GTI 2020-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|T-Cross 2021[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|T-Roc 2021[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Taos 2022[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Teramont 2018-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Teramont Cross Sport 2021-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Teramont X 2021-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Tiguan 2019-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Touran 2017|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| 1Requires a community built ASCM harness. NOTE: disconnecting the ASCM disables Automatic Emergency Braking (AEB).
diff --git a/selfdrive/car/CARS_template.md b/selfdrive/car/CARS_template.md index e448c19d3..d306ca5d9 100644 --- a/selfdrive/car/CARS_template.md +++ b/selfdrive/car/CARS_template.md @@ -7,22 +7,10 @@ A supported vehicle is one that just works when you install a comma device. Every car performs differently with openpilot, but all supported cars should provide a better experience than any stock system. -## How We Rate The Cars - -{% for star_row in STAR_DESCRIPTIONS.values() %} -{% for name, stars in star_row.items() %} -### {{name}} -{% for star, description in stars %} -- {{star_icon.format(star)}} - {{description}} -{% endfor %} - -{% endfor %} -{% endfor %} - # {{all_car_info | length}} Supported Cars |{{Column | map(attribute='value') | join('|')}}| -|---|---|---|:---:|:---:|:---:|:---:| +|---|---|---|{% for _ in range((Column | length) - 3) %}{{':---:|'}}{% endfor +%} {% for car_info in all_car_info %} |{% for column in Column %}{{car_info.get_column(column, star_icon, footnote_tag)}}|{% endfor %} diff --git a/selfdrive/car/body/values.py b/selfdrive/car/body/values.py index 0caf93b61..61b72d5ad 100644 --- a/selfdrive/car/body/values.py +++ b/selfdrive/car/body/values.py @@ -2,7 +2,7 @@ from typing import Dict from cereal import car from selfdrive.car import dbc_dict -from selfdrive.car.docs_definitions import CarInfo, Harness +from selfdrive.car.docs_definitions import CarInfo Ecu = car.CarParams.Ecu SPEED_FROM_RPM = 0.008587 @@ -18,7 +18,7 @@ class CAR: BODY = "COMMA BODY" CAR_INFO: Dict[str, CarInfo] = { - CAR.BODY: CarInfo("comma body", package="All", harness=Harness.none), + CAR.BODY: CarInfo("comma body", package="All"), } FW_VERSIONS = { diff --git a/selfdrive/car/docs.py b/selfdrive/car/docs.py index 5793596a4..795668381 100755 --- a/selfdrive/car/docs.py +++ b/selfdrive/car/docs.py @@ -8,16 +8,15 @@ from natsort import natsorted from typing import Dict, List from common.basedir import BASEDIR -from selfdrive.car.docs_definitions import STAR_DESCRIPTIONS, StarColumns, TierColumns, CarInfo, Column, Star +from selfdrive.car.docs_definitions import CarInfo, Column from selfdrive.car.car_helpers import interfaces, get_interface_attr from selfdrive.car.hyundai.radar_interface import RADAR_START_ADDR as HKG_RADAR_START_ADDR -def get_all_footnotes(only_tier_cols: bool = False) -> Dict[Enum, int]: +def get_all_footnotes() -> Dict[Enum, int]: all_footnotes = [] - hide_cols = set(StarColumns) - set(TierColumns) if only_tier_cols else [] for footnotes in get_interface_attr("Footnote", ignore_none=True).values(): - all_footnotes.extend([fn for fn in footnotes if fn.value.column not in hide_cols]) + all_footnotes.extend(footnotes) return {fn: idx + 1 for idx, fn in enumerate(all_footnotes)} @@ -25,9 +24,9 @@ CARS_MD_OUT = os.path.join(BASEDIR, "docs", "CARS.md") CARS_MD_TEMPLATE = os.path.join(BASEDIR, "selfdrive", "car", "CARS_template.md") -def get_all_car_info(only_tier_cols: bool = False) -> List[CarInfo]: +def get_all_car_info() -> List[CarInfo]: all_car_info: List[CarInfo] = [] - footnotes = get_all_footnotes(only_tier_cols) + footnotes = get_all_footnotes() for model, car_info in get_interface_attr("CAR_INFO", combine_brands=True).items(): # Hyundai exception: those with radar have openpilot longitudinal fingerprint = {0: {}, 1: {HKG_RADAR_START_ADDR: 8}, 2: {}, 3: {}} @@ -57,21 +56,13 @@ def group_by_make(all_car_info: List[CarInfo]) -> Dict[str, List[CarInfo]]: return dict(sorted_car_info) -def generate_cars_md(all_car_info: List[CarInfo], template_fn: str, only_tier_cols: bool) -> str: +def generate_cars_md(all_car_info: List[CarInfo], template_fn: str) -> str: with open(template_fn, "r") as f: template = jinja2.Template(f.read(), trim_blocks=True, lstrip_blocks=True) - cols = list(Column) - if only_tier_cols: - hide_cols = set(StarColumns) - set(TierColumns) - cols = [c for c in cols if c not in hide_cols] - for car in all_car_info: - for c in hide_cols: - del car.row[c] - - footnotes = [fn.value.text for fn in get_all_footnotes(only_tier_cols)] + footnotes = [fn.value.text for fn in get_all_footnotes()] cars_md: str = template.render(all_car_info=all_car_info, group_by_make=group_by_make, - footnotes=footnotes, Star=Star, Column=cols, STAR_DESCRIPTIONS=STAR_DESCRIPTIONS) + footnotes=footnotes, Column=Column) return cars_md @@ -79,11 +70,10 @@ if __name__ == "__main__": parser = argparse.ArgumentParser(description="Auto generates supported cars documentation", formatter_class=argparse.ArgumentDefaultsHelpFormatter) - parser.add_argument("--tier-columns", action="store_true", help="Include only columns that count in the tier") parser.add_argument("--template", default=CARS_MD_TEMPLATE, help="Override default template filename") parser.add_argument("--out", default=CARS_MD_OUT, help="Override default generated filename") args = parser.parse_args() with open(args.out, 'w') as f: - f.write(generate_cars_md(get_all_car_info(args.tier_columns), args.template, args.tier_columns)) + f.write(generate_cars_md(get_all_car_info(), args.template)) print(f"Generated and written to {args.out}") diff --git a/selfdrive/car/docs_definitions.py b/selfdrive/car/docs_definitions.py index d882cd120..52d6388d7 100644 --- a/selfdrive/car/docs_definitions.py +++ b/selfdrive/car/docs_definitions.py @@ -2,7 +2,7 @@ import re from collections import namedtuple from dataclasses import dataclass, field from enum import Enum -from typing import Dict, List, Optional, Tuple, Union, no_type_check +from typing import Dict, List, Optional, Tuple, Union from cereal import car from common.conversions import Conversions as CV @@ -15,20 +15,15 @@ NO_AUTO_RESUME_STOCK_LONG = {"toyota", "gm"} NO_AUTO_RESUME = NO_AUTO_RESUME_STOCK_LONG | {"nissan", "subaru"} -class Tier(Enum): - GOLD = 0 - SILVER = 1 - BRONZE = 2 - - class Column(Enum): MAKE = "Make" MODEL = "Model" PACKAGE = "Supported Package" - LONGITUDINAL = "openpilot ACC" - FSR_LONGITUDINAL = "Stop and Go" - FSR_STEERING = "Steer to 0" + LONGITUDINAL = "ACC" + FSR_LONGITUDINAL = "No ACC accel below" + FSR_STEERING = "No ALC below" STEERING_TORQUE = "Steering Torque" + HARNESS = "Harness" class Star(Enum): @@ -37,9 +32,46 @@ class Star(Enum): EMPTY = "empty" -StarColumns = list(Column)[3:] -TierColumns = (Column.FSR_LONGITUDINAL, Column.FSR_STEERING, Column.STEERING_TORQUE) -CarFootnote = namedtuple("CarFootnote", ["text", "column", "star"], defaults=[None]) +class Harness(Enum): + nidec = "Honda Nidec" + bosch_a = "Honda Bosch A" + bosch_b = "Honda Bosch B" + toyota = "Toyota" + subaru_a = "Subaru A" + subaru_b = "Subaru B" + fca = "FCA" + ram = "Ram" + vw = "VW" + j533 = "J533" + hyundai_a = "Hyundai A" + hyundai_b = "Hyundai B" + hyundai_c = "Hyundai C" + hyundai_d = "Hyundai D" + hyundai_e = "Hyundai E" + hyundai_f = "Hyundai F" + hyundai_g = "Hyundai G" + hyundai_h = "Hyundai H" + hyundai_i = "Hyundai I" + hyundai_j = "Hyundai J" + hyundai_k = "Hyundai K" + hyundai_l = "Hyundai L" + hyundai_m = "Hyundai M" + hyundai_n = "Hyundai N" + hyundai_o = "Hyundai O" + hyundai_p = "Hyundai P" + hyundai_q = "Hyundai Q" + custom = "Developer" + obd_ii = "OBD-II" + gm = "GM" + nissan_a = "Nissan A" + nissan_b = "Nissan B" + mazda = "Mazda" + ford_q3 = "Ford Q3" + ford_q4 = "Ford Q4" + none = "None" + + +CarFootnote = namedtuple("CarFootnote", ["text", "column"], defaults=[None]) def get_footnotes(footnotes: List[Enum], column: Column) -> List[Enum]: @@ -83,7 +115,7 @@ class CarInfo: footnotes: List[Enum] = field(default_factory=list) min_steer_speed: Optional[float] = None min_enable_speed: Optional[float] = None - harness: Optional[Enum] = None + harness: Enum = Harness.none def init(self, CP: car.CarParams, all_footnotes: Dict[Enum, int]): # TODO: set all the min steer speeds in carParams and remove this @@ -103,11 +135,11 @@ class CarInfo: Column.MAKE: self.make, Column.MODEL: self.model, Column.PACKAGE: self.package, - # StarColumns - Column.LONGITUDINAL: Star.FULL if CP.openpilotLongitudinalControl and not CP.radarOffCan else Star.EMPTY, - Column.FSR_LONGITUDINAL: Star.FULL if self.min_enable_speed <= 0. else Star.EMPTY, - Column.FSR_STEERING: Star.FULL if self.min_steer_speed <= 0. else Star.EMPTY, + Column.LONGITUDINAL: "openpilot" if CP.openpilotLongitudinalControl and not CP.radarOffCan else "Stock", + Column.FSR_LONGITUDINAL: f"{max(self.min_enable_speed * CV.MS_TO_MPH, 0):.0f} mph", + Column.FSR_STEERING: f"{max(self.min_steer_speed * CV.MS_TO_MPH, 0):.0f} mph", Column.STEERING_TORQUE: Star.EMPTY, + Column.HARNESS: self.harness.value, } # Set steering torque star from max lateral acceleration @@ -115,26 +147,7 @@ class CarInfo: if CP.maxLateralAccel >= GOOD_TORQUE_THRESHOLD: self.row[Column.STEERING_TORQUE] = Star.FULL - if CP.notCar: - for col in StarColumns: - self.row[col] = Star.FULL - self.all_footnotes = all_footnotes - for column in StarColumns: - # Demote if footnote specifies a star - for fn in get_footnotes(self.footnotes, column): - if fn.value.star is not None: - self.row[column] = fn.value.star - - # openpilot ACC star doesn't count for tiers - full_stars = [s for col, s in self.row.items() if col in TierColumns].count(Star.FULL) - if full_stars == len(TierColumns): - self.tier = Tier.GOLD - elif full_stars == len(TierColumns) - 1: - self.tier = Tier.SILVER - else: - self.tier = Tier.BRONZE - self.year_list = get_year_list(self.years) self.detail_sentence = self.get_detail_sentence(CP) @@ -167,10 +180,9 @@ class CarInfo: else: raise Exception(f"This notCar does not have a detail sentence: {CP.carFingerprint}") - @no_type_check def get_column(self, column: Column, star_icon: str, footnote_tag: str) -> str: item: Union[str, Star] = self.row[column] - if column in StarColumns: + if isinstance(item, Star): item = star_icon.format(item.value) elif column == Column.MODEL and len(self.years): item += f" {self.years}" @@ -182,61 +194,3 @@ class CarInfo: return item - -class Harness(Enum): - nidec = "Honda Nidec" - bosch_a = "Honda Bosch A" - bosch_b = "Honda Bosch B" - toyota = "Toyota" - subaru_a = "Subaru A" - subaru_b = "Subaru B" - fca = "FCA" - ram = "Ram" - vw = "VW" - j533 = "J533" - hyundai_a = "Hyundai A" - hyundai_b = "Hyundai B" - hyundai_c = "Hyundai C" - hyundai_d = "Hyundai D" - hyundai_e = "Hyundai E" - hyundai_f = "Hyundai F" - hyundai_g = "Hyundai G" - hyundai_h = "Hyundai H" - hyundai_i = "Hyundai I" - hyundai_j = "Hyundai J" - hyundai_k = "Hyundai K" - hyundai_l = "Hyundai L" - hyundai_m = "Hyundai M" - hyundai_n = "Hyundai N" - hyundai_o = "Hyundai O" - hyundai_p = "Hyundai P" - hyundai_q = "Hyundai Q" - custom = "Developer" - obd_ii = "OBD-II" - gm = "GM" - nissan_a = "Nissan A" - nissan_b = "Nissan B" - mazda = "Mazda" - ford_q3 = "Ford Q3" - ford_q4 = "Ford Q4" - none = "None" - - -STAR_DESCRIPTIONS = { - "Gas & Brakes": { # icon and row name - Column.FSR_LONGITUDINAL.value: [ - [Star.FULL.value, "openpilot operates down to 0 mph."], - [Star.EMPTY.value, "openpilot operates only above a minimum speed. See your car's manual for the minimum speed."], - ], - }, - "Steering": { - Column.FSR_STEERING.value: [ - [Star.FULL.value, "openpilot can control the steering wheel down to 0 mph."], - [Star.EMPTY.value, "No steering control below certain speeds. See your car's manual for the minimum speed."], - ], - Column.STEERING_TORQUE.value: [ - [Star.FULL.value, "Car has enough steering torque to comfortably take most highway turns."], - [Star.EMPTY.value, "Limited ability to make tighter turns."], - ], - }, -} diff --git a/selfdrive/car/tests/test_docs.py b/selfdrive/car/tests/test_docs.py index 84c6b6e52..af58bb5e5 100755 --- a/selfdrive/car/tests/test_docs.py +++ b/selfdrive/car/tests/test_docs.py @@ -13,7 +13,7 @@ class TestCarDocs(unittest.TestCase): self.all_cars = get_all_car_info() def test_generator(self): - generated_cars_md = generate_cars_md(self.all_cars, CARS_MD_TEMPLATE, False) + generated_cars_md = generate_cars_md(self.all_cars, CARS_MD_TEMPLATE) with open(CARS_MD_OUT, "r") as f: current_cars_md = f.read() diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index b4e82ec3e..891514606 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -6,7 +6,7 @@ from typing import Dict, List, Union from cereal import car from common.conversions import Conversions as CV from selfdrive.car import dbc_dict -from selfdrive.car.docs_definitions import CarFootnote, CarInfo, Column, Harness, Star +from selfdrive.car.docs_definitions import CarFootnote, CarInfo, Column, Harness Ecu = car.CarParams.Ecu MIN_ACC_SPEED = 19. * CV.MPH_TO_MS @@ -89,7 +89,7 @@ class Footnote(Enum): DSU = CarFootnote( "When the Driver Support Unit (DSU) is disconnected, openpilot Adaptive Cruise Control (ACC) will replace " + "stock Adaptive Cruise Control (ACC). NOTE: disconnecting the DSU disables Automatic Emergency Braking (AEB).", - Column.LONGITUDINAL, star=Star.HALF) + Column.LONGITUDINAL) CAMRY = CarFootnote( "openpilot operates above 28mph for Camry 4CYL L, 4CYL LE and 4CYL SE which don't have Full-Speed Range Dynamic Radar Cruise Control.", Column.FSR_LONGITUDINAL) From 6a3a9944c25da54880460a579f3d4616ed4b7fa4 Mon Sep 17 00:00:00 2001 From: Erich Moraga <33645296+ErichMoraga@users.noreply.github.com> Date: Thu, 18 Aug 2022 17:18:50 -0500 Subject: [PATCH 029/172] ssh docs: corrections and readability improvements (#25482) * Corrections and readability improvements * Apply suggestions from code review Co-authored-by: Shane Smiskol --- tools/ssh/README.md | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/tools/ssh/README.md b/tools/ssh/README.md index 29d334932..67b5271a4 100644 --- a/tools/ssh/README.md +++ b/tools/ssh/README.md @@ -7,11 +7,11 @@ In order to SSH into your device, you'll need a GitHub account with SSH keys. Se * Enable SSH in your device's settings * Enter your GitHub username in the device's settings * Connect to your device - * Username: `comma` (comma three) + * Username: `comma` * Port: `22` or `8022` -Here's an example command for connecting to your device using its tethered connection: -`ssh root@192.168.43.1` +Here's an example command for connecting to your device using its tethered connection:
+`ssh comma@192.168.43.1` For doing development work on device, it's recommended to use [SSH agent forwarding](https://docs.github.com/en/developers/overview/using-ssh-agent-forwarding). @@ -34,7 +34,8 @@ Requires [comma SIM with comma prime](https://comma.ai/shop) activated with comm ## Recommended .ssh/config -With the below ssh configuration, you can type `ssh comma-{dongleid}` to connect to your device through `ssh.comma.ai`. For example, `ssh comma-ffffffffffffffff`. +With the below SSH configuration, you can type `ssh comma-{dongleid}` to connect to your device through `ssh.comma.ai`.
+For example: `ssh comma-ffffffffffffffff` ``` Host comma-* From d907021d58b14f49480308f01935c975daa590a6 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 18 Aug 2022 15:36:50 -0700 Subject: [PATCH 030/172] disable panda deep sleep for now --- selfdrive/boardd/boardd.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index afbc592b9..23bf8f292 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -197,7 +197,7 @@ Panda *usb_connect(std::string serial="", uint32_t index=0) { if (getenv("BOARDD_LOOPBACK")) { panda->set_loopback(true); } - panda->enable_deepsleep(); + //panda->enable_deepsleep(); // power on charging, only the first time. Panda can also change mode and it causes a brief disconneciton #ifndef __x86_64__ From 17992f29c82cbf2f5f7eacf6edf839f97c0e5816 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 18 Aug 2022 16:40:16 -0700 Subject: [PATCH 031/172] bump opendbc --- opendbc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/opendbc b/opendbc index c6665ed11..3f722780c 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit c6665ed11b8d8c998e46f8dbee30e70a7d451e5e +Subproject commit 3f722780c3af70a1c244ea762d61edd8c002ed9c From 858eea91634a866cef2e2943fa3654bf3e46d522 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 18 Aug 2022 17:52:09 -0700 Subject: [PATCH 032/172] Hyundai: add HDA1 signals (#25484) * Hyundai: add HDA1 signals * bump * bump to master --- opendbc | 2 +- release/files_common | 2 +- selfdrive/car/hyundai/values.py | 4 ++-- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/opendbc b/opendbc index 3f722780c..1619c9a40 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit 3f722780c3af70a1c244ea762d61edd8c002ed9c +Subproject commit 1619c9a40f46d1976a1d4a55f7cf1e3367eea170 diff --git a/release/files_common b/release/files_common index 01386b585..ac2a3ce62 100644 --- a/release/files_common +++ b/release/files_common @@ -532,7 +532,7 @@ opendbc/honda_insight_ex_2019_can_generated.dbc opendbc/acura_ilx_2016_nidec.dbc opendbc/honda_civic_ex_2022_can_generated.dbc -opendbc/kia_ev6.dbc +opendbc/hyundai_canfd.dbc opendbc/hyundai_kia_generic.dbc opendbc/hyundai_kia_mando_front_radar.dbc diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 17745a4d7..9db6c3697 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -1362,7 +1362,7 @@ DBC = { CAR.PALISADE: dbc_dict('hyundai_kia_generic', 'hyundai_kia_mando_front_radar'), CAR.VELOSTER: dbc_dict('hyundai_kia_generic', None), CAR.KIA_CEED: dbc_dict('hyundai_kia_generic', None), - CAR.KIA_EV6: dbc_dict('kia_ev6', None), + CAR.KIA_EV6: dbc_dict('hyundai_canfd', None), CAR.SONATA_HYBRID: dbc_dict('hyundai_kia_generic', 'hyundai_kia_mando_front_radar'), - CAR.IONIQ_5: dbc_dict('kia_ev6', None), + CAR.IONIQ_5: dbc_dict('hyundai_canfd', None), } From e5bb55ccd69fa42777fcd4d836adc777feff9cb1 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 18 Aug 2022 22:23:39 -0700 Subject: [PATCH 033/172] Toyota: remove STEERING_LKA frequency check (#25490) * remove STEERING_LKA frequency check * bump to master * Update ref_commit --- opendbc | 2 +- selfdrive/car/toyota/carstate.py | 4 +--- selfdrive/test/process_replay/ref_commit | 2 +- 3 files changed, 3 insertions(+), 5 deletions(-) diff --git a/opendbc b/opendbc index 1619c9a40..7e095a90a 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit 1619c9a40f46d1976a1d4a55f7cf1e3367eea170 +Subproject commit 7e095a90af3d36e6db9128a80f6f3b0cca01efa2 diff --git a/selfdrive/car/toyota/carstate.py b/selfdrive/car/toyota/carstate.py index 281d01026..537915919 100644 --- a/selfdrive/car/toyota/carstate.py +++ b/selfdrive/car/toyota/carstate.py @@ -228,10 +228,8 @@ class CarState(CarStateBase): ("PRECOLLISION_ACTIVE", "PRE_COLLISION"), ] - # use steering message to check if panda is connected to frc checks = [ - ("STEERING_LKA", 42), - ("PRE_COLLISION", 0), # TODO: figure out why freq is inconsistent + ("PRE_COLLISION", 0), # TODO: figure out why freq is inconsistent ] if CP.carFingerprint in (TSS2_CAR - RADAR_ACC_CAR): diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index da083eeee..b9e99cd61 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -35899d5137e298220e91063f3078109227cc8715 \ No newline at end of file +93a136f91739847afe1e1a4a1e98bc7c0adb5ec8 From 844d4d2eceee487aaaf27601522cb9b9bb351614 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 18 Aug 2022 23:32:11 -0700 Subject: [PATCH 034/172] Multilang: add plural translation test (#25491) Add test for correct format specifier for plural translations --- selfdrive/ui/tests/test_translations.py | 12 ++++++++++-- 1 file changed, 10 insertions(+), 2 deletions(-) diff --git a/selfdrive/ui/tests/test_translations.py b/selfdrive/ui/tests/test_translations.py index 7da4ec0d6..fead288df 100755 --- a/selfdrive/ui/tests/test_translations.py +++ b/selfdrive/ui/tests/test_translations.py @@ -1,6 +1,7 @@ #!/usr/bin/env python3 import json import os +import re import shutil import unittest import xml.etree.ElementTree as ET @@ -66,6 +67,11 @@ class TestTranslations(unittest.TestCase): f"{file} ({name}) translation file has obsolete translations. Run selfdrive/ui/update_translations.py --vanish to remove them") def test_plural_translations(self): + """ + Tests: + - that any numerus (plural) translations marked "finished" have all plural forms non-empty + - that the correct format specifier is used (%n) + """ for name, file in self.translation_files.items(): with self.subTest(name=name, file=file): tr_xml = ET.parse(os.path.join(TRANSLATIONS_DIR, f"{file}.ts")) @@ -74,13 +80,15 @@ class TestTranslations(unittest.TestCase): for message in context.iterfind("message"): if message.get("numerus") == "yes": translation = message.find("translation") - numerusform = translation.findall("numerusform") + numerusform = [t.text for t in translation.findall("numerusform")] # Do not assert finished translations if translation.get("type") == "unfinished": continue - self.assertNotIn(None, [x.text for x in numerusform], "Ensure all plural translation forms are completed.") + self.assertNotIn(None, numerusform, "Ensure all plural translation forms are completed.") + self.assertTrue(all([re.search("%[0-9]+", t) is None for t in numerusform]), + "Plural translations must use %n, not %1, %2, etc.: {}".format(numerusform)) if __name__ == "__main__": From 16fe10e1281d68d8e560a9489b973bd34417d469 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 18 Aug 2022 23:34:48 -0700 Subject: [PATCH 035/172] joystick: revert max axes value (#25483) revert this to 255 --- tools/joystick/joystickd.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tools/joystick/joystickd.py b/tools/joystick/joystickd.py index 6226038d5..35ecca351 100755 --- a/tools/joystick/joystickd.py +++ b/tools/joystick/joystickd.py @@ -41,7 +41,7 @@ class Joystick: def __init__(self): # TODO: find a way to get this from API, perhaps "inputs" doesn't support it self.min_axis_value = {'ABS_Y': 0., 'ABS_RZ': 0.} - self.max_axis_value = {'ABS_Y': 1023., 'ABS_RZ': 255.} + self.max_axis_value = {'ABS_Y': 255., 'ABS_RZ': 255.} self.cancel_button = 'BTN_TRIGGER' self.axes_values = {'ABS_Y': 0., 'ABS_RZ': 0.} # gb, steer self.axes_order = ['ABS_Y', 'ABS_RZ'] From e3d3fd02300ef7109f5fdf0717395eca3757195e Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 18 Aug 2022 23:40:24 -0700 Subject: [PATCH 036/172] Common button enable/cancel event creation (#25445) * handle button presses in create_common_events * remove from imports * Handle * Fix Honda (it hardcodes pcmCruise) * Update selfdrive/car/volkswagen/interface.py * Update selfdrive/car/volkswagen/interface.py --- selfdrive/car/gm/interface.py | 5 +---- selfdrive/car/honda/interface.py | 5 +---- selfdrive/car/hyundai/interface.py | 19 +++++++++---------- selfdrive/car/interfaces.py | 5 ++++- selfdrive/car/volkswagen/interface.py | 4 +--- 5 files changed, 16 insertions(+), 22 deletions(-) diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py index f3f1e587c..18709a2a8 100755 --- a/selfdrive/car/gm/interface.py +++ b/selfdrive/car/gm/interface.py @@ -4,7 +4,7 @@ from math import fabs from panda import Panda from common.conversions import Conversions as CV -from selfdrive.car import STD_CARGO_KG, create_button_enable_events, create_button_event, scale_rot_inertia, scale_tire_stiffness, gen_empty_fingerprint, get_safety_config +from selfdrive.car import STD_CARGO_KG, create_button_event, scale_rot_inertia, scale_tire_stiffness, gen_empty_fingerprint, get_safety_config from selfdrive.car.gm.values import CAR, CruiseButtons, CarControllerParams, EV_CAR, CAMERA_ACC_CAR from selfdrive.car.interfaces import CarInterfaceBase @@ -195,9 +195,6 @@ class CarInterface(CarInterfaceBase): if ret.vEgo < self.CP.minSteerSpeed: events.add(car.CarEvent.EventName.belowSteerSpeed) - # handle button presses - events.events.extend(create_button_enable_events(ret.buttonEvents, pcm_cruise=self.CP.pcmCruise)) - ret.events = events.to_msg() return ret diff --git a/selfdrive/car/honda/interface.py b/selfdrive/car/honda/interface.py index b14618271..a235ba6cd 100755 --- a/selfdrive/car/honda/interface.py +++ b/selfdrive/car/honda/interface.py @@ -4,7 +4,7 @@ from panda import Panda from common.conversions import Conversions as CV from common.numpy_fast import interp from selfdrive.car.honda.values import CarControllerParams, CruiseButtons, HondaFlags, CAR, HONDA_BOSCH, HONDA_NIDEC_ALT_SCM_MESSAGES, HONDA_BOSCH_ALT_BRAKE_SIGNAL, HONDA_BOSCH_RADARLESS -from selfdrive.car import STD_CARGO_KG, CivicParams, create_button_enable_events, create_button_event, scale_rot_inertia, scale_tire_stiffness, gen_empty_fingerprint, get_safety_config +from selfdrive.car import STD_CARGO_KG, CivicParams, create_button_event, scale_rot_inertia, scale_tire_stiffness, gen_empty_fingerprint, get_safety_config from selfdrive.car.interfaces import CarInterfaceBase from selfdrive.car.disable_ecu import disable_ecu @@ -352,9 +352,6 @@ class CarInterface(CarInterfaceBase): if self.CS.CP.minEnableSpeed > 0 and ret.vEgo < 0.001: events.add(EventName.manualRestart) - # handle button presses - events.events.extend(create_button_enable_events(ret.buttonEvents, self.CP.pcmCruise)) - ret.events = events.to_msg() return ret diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 6b62477a0..6986b973e 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -4,7 +4,7 @@ from panda import Panda from common.conversions import Conversions as CV from selfdrive.car.hyundai.values import CAR, DBC, CANFD_CAR, CAMERA_SCC_CAR, EV_CAR, HYBRID_CAR, LEGACY_SAFETY_MODE_CAR, Buttons, CarControllerParams from selfdrive.car.hyundai.radar_interface import RADAR_START_ADDR -from selfdrive.car import STD_CARGO_KG, create_button_enable_events, create_button_event, scale_rot_inertia, scale_tire_stiffness, gen_empty_fingerprint, get_safety_config +from selfdrive.car import STD_CARGO_KG, create_button_event, scale_rot_inertia, scale_tire_stiffness, gen_empty_fingerprint, get_safety_config from selfdrive.car.interfaces import CarInterfaceBase from selfdrive.car.disable_ecu import disable_ecu @@ -326,6 +326,14 @@ class CarInterface(CarInterfaceBase): def _update(self, c): ret = self.CS.update(self.cp, self.cp_cam) + if self.CS.CP.openpilotLongitudinalControl and self.CS.cruise_buttons[-1] != self.CS.prev_cruise_buttons: + buttonEvents = [create_button_event(self.CS.cruise_buttons[-1], self.CS.prev_cruise_buttons, BUTTONS_DICT)] + # Handle CF_Clu_CruiseSwState changing buttons mid-press + if self.CS.cruise_buttons[-1] != 0 and self.CS.prev_cruise_buttons != 0: + buttonEvents.append(create_button_event(0, self.CS.prev_cruise_buttons, BUTTONS_DICT)) + + ret.buttonEvents = buttonEvents + # On some newer model years, the CANCEL button acts as a pause/resume button based on the PCM state # To avoid re-engaging when openpilot cancels, check user engagement intention via buttons # Main button also can trigger an engagement on these cars @@ -335,15 +343,6 @@ class CarInterface(CarInterfaceBase): if self.CS.brake_error: events.add(EventName.brakeUnavailable) - if self.CS.CP.openpilotLongitudinalControl and self.CS.cruise_buttons[-1] != self.CS.prev_cruise_buttons: - buttonEvents = [create_button_event(self.CS.cruise_buttons[-1], self.CS.prev_cruise_buttons, BUTTONS_DICT)] - # Handle CF_Clu_CruiseSwState changing buttons mid-press - if self.CS.cruise_buttons[-1] != 0 and self.CS.prev_cruise_buttons != 0: - buttonEvents.append(create_button_event(0, self.CS.prev_cruise_buttons, BUTTONS_DICT)) - - ret.buttonEvents = buttonEvents - events.events.extend(create_button_enable_events(ret.buttonEvents)) - # low speed steer alert hysteresis logic (only for cars with steer cut off above 10 m/s) if ret.vEgo < (self.CP.minSteerSpeed + 2.) and self.CP.minSteerSpeed > 10.: self.low_speed_alert = True diff --git a/selfdrive/car/interfaces.py b/selfdrive/car/interfaces.py index 1e55e72ac..9da6aabd6 100644 --- a/selfdrive/car/interfaces.py +++ b/selfdrive/car/interfaces.py @@ -9,7 +9,7 @@ from common.basedir import BASEDIR from common.conversions import Conversions as CV from common.kalman.simple_kalman import KF1D from common.realtime import DT_CTRL -from selfdrive.car import gen_empty_fingerprint +from selfdrive.car import create_button_enable_events, gen_empty_fingerprint from selfdrive.controls.lib.drive_helpers import V_CRUISE_MAX from selfdrive.controls.lib.events import Events from selfdrive.controls.lib.vehicle_model import VehicleModel @@ -213,6 +213,9 @@ class CarInterfaceBase(ABC): if cs_out.accFaulted: events.add(EventName.accFaulted) + # Handle button presses + events.events.extend(create_button_enable_events(cs_out.buttonEvents, pcm_cruise=self.CP.pcmCruise)) + # Handle permanent and temporary steering faults self.steering_unpressed = 0 if cs_out.steeringPressed else self.steering_unpressed + 1 if cs_out.steerFaultTemporary: diff --git a/selfdrive/car/volkswagen/interface.py b/selfdrive/car/volkswagen/interface.py index 22206635a..7e686b970 100644 --- a/selfdrive/car/volkswagen/interface.py +++ b/selfdrive/car/volkswagen/interface.py @@ -1,12 +1,11 @@ from cereal import car from panda import Panda from common.conversions import Conversions as CV -from selfdrive.car import STD_CARGO_KG, create_button_enable_events, scale_rot_inertia, scale_tire_stiffness, \ +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 from selfdrive.car.volkswagen.values import CAR, PQ_CARS, CANBUS, NetworkLocation, TransmissionType, GearShifter - EventName = car.CarEvent.EventName @@ -225,7 +224,6 @@ class CarInterface(CarInterfaceBase): if c.enabled and ret.vEgo < self.CP.minEnableSpeed: events.add(EventName.speedTooLow) - events.events.extend(create_button_enable_events(ret.buttonEvents, pcm_cruise=self.CP.pcmCruise)) ret.events = events.to_msg() return ret From 03b074426a7de22b9f5dbfb9bb30f8325ac43b4a Mon Sep 17 00:00:00 2001 From: Jason Wen <47793918+sunnyhaibin@users.noreply.github.com> Date: Fri, 19 Aug 2022 03:48:51 -0400 Subject: [PATCH 037/172] Rename KIA_NIRO_HEV to KIA_NIRO_PHEV (#24216) * Add car port: Kia Niro Plug-In Hybrid 2018 * Add additional FW version * Low speed lockout 32 MPH * Add test route * min_steer_speed in CarInfo * Remove min_steer_speed from CarInfo * Add to CARS.md * run generator * update min enable speed and regen * update ci routes * these are the same car * i think we only add a note if it's a new platform * fix HEV -> PHEV * Add test route * dup fw * haha we already support this car in #25187 Co-authored-by: Shane Smiskol --- selfdrive/car/hyundai/interface.py | 4 ++-- selfdrive/car/hyundai/values.py | 14 +++++++------- selfdrive/car/tests/routes.py | 2 +- 3 files changed, 10 insertions(+), 10 deletions(-) diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 6986b973e..23a49a05e 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -169,7 +169,7 @@ class CarInterface(CarInterfaceBase): 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_HEV, CAR.KIA_NIRO_HEV_2021): + 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 @@ -177,7 +177,7 @@ class CarInterface(CarInterfaceBase): tire_stiffness_factor = 0.385 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] - if candidate == CAR.KIA_NIRO_HEV: + if candidate == CAR.KIA_NIRO_PHEV: ret.minSteerSpeed = 32 * CV.MPH_TO_MS elif candidate == CAR.KIA_SELTOS: ret.mass = 1337. + STD_CARGO_KG diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 9db6c3697..e36c9a6ac 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -29,7 +29,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, - CAR.IONIQ_EV_LTD, CAR.SANTA_FE_PHEV_2022, CAR.SONATA_LF, CAR.KIA_FORTE, CAR.KIA_NIRO_HEV, + 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, CAR.KIA_STINGER): self.STEER_MAX = 255 @@ -71,7 +71,7 @@ class CAR: KIA_FORTE = "KIA FORTE E 2018 & GT 2021" KIA_K5_2021 = "KIA K5 2021" KIA_NIRO_EV = "KIA NIRO EV 2020" - KIA_NIRO_HEV = "KIA NIRO HYBRID 2019" + KIA_NIRO_PHEV = "KIA NIRO HYBRID 2019" KIA_NIRO_HEV_2021 = "KIA NIRO HYBRID 2021" KIA_OPTIMA = "KIA OPTIMA SX 2019 & 2016" KIA_OPTIMA_H = "KIA OPTIMA HYBRID 2017 & SPORTS 2019" @@ -141,7 +141,7 @@ CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = { HyundaiCarInfo("Kia Niro Electric 2021", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", harness=Harness.hyundai_c), HyundaiCarInfo("Kia Niro Electric 2022", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", harness=Harness.hyundai_h), ], - CAR.KIA_NIRO_HEV: HyundaiCarInfo("Kia Niro Plug-in Hybrid 2018-19", min_enable_speed=10. * CV.MPH_TO_MS, harness=Harness.hyundai_c), + CAR.KIA_NIRO_PHEV: HyundaiCarInfo("Kia Niro Plug-in Hybrid 2018-19", min_enable_speed=10. * CV.MPH_TO_MS, harness=Harness.hyundai_c), CAR.KIA_NIRO_HEV_2021: [ HyundaiCarInfo("Kia Niro Hybrid 2021", harness=Harness.hyundai_f), # TODO: could be hyundai_d, verify HyundaiCarInfo("Kia Niro Hybrid 2022", harness=Harness.hyundai_h), @@ -1039,7 +1039,7 @@ FW_VERSIONS = { b'\xf1\x00DEE MFC AT KOR LHD 1.00 1.03 95740-Q4000 180821', ], }, - CAR.KIA_NIRO_HEV: { + CAR.KIA_NIRO_PHEV: { (Ecu.engine, 0x7e0, None): [ b'\xf1\x816H6F4051\x00\x00\x00\x00\x00\x00\x00\x00', b'\xf1\x816H6D1051\x00\x00\x00\x00\x00\x00\x00\x00', @@ -1303,7 +1303,7 @@ FEATURES = { # which message has the gear "use_cluster_gears": {CAR.ELANTRA, CAR.ELANTRA_GT_I30, CAR.KONA}, "use_tcu_gears": {CAR.KIA_OPTIMA, CAR.SONATA_LF, CAR.VELOSTER, CAR.TUCSON}, - "use_elect_gears": {CAR.KIA_NIRO_EV, CAR.KIA_NIRO_HEV, 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}, + "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}, @@ -1314,7 +1314,7 @@ CANFD_CAR = {CAR.KIA_EV6, CAR.IONIQ_5} # The camera does SCC on these cars, rather than the radar CAMERA_SCC_CAR = {CAR.KONA_EV_2022, } -HYBRID_CAR = {CAR.IONIQ_PHEV, CAR.ELANTRA_HEV_2021, CAR.KIA_NIRO_HEV, CAR.KIA_NIRO_HEV_2021, CAR.SONATA_HYBRID, CAR.KONA_HEV, CAR.IONIQ, CAR.IONIQ_HEV_2022, CAR.SANTA_FE_HEV_2022, CAR.SANTA_FE_PHEV_2022, CAR.IONIQ_PHEV_2019} # these cars use a different gas signal +HYBRID_CAR = {CAR.IONIQ_PHEV, CAR.ELANTRA_HEV_2021, CAR.KIA_NIRO_PHEV, CAR.KIA_NIRO_HEV_2021, CAR.SONATA_HYBRID, CAR.KONA_HEV, CAR.IONIQ, CAR.IONIQ_HEV_2022, CAR.SANTA_FE_HEV_2022, CAR.SANTA_FE_PHEV_2022, CAR.IONIQ_PHEV_2019} # these cars use a different gas signal EV_CAR = {CAR.IONIQ_EV_2020, CAR.IONIQ_EV_LTD, CAR.KONA_EV, CAR.KIA_NIRO_EV, CAR.KONA_EV_2022} # these cars require a special panda safety mode due to missing counters and checksums in the messages @@ -1341,7 +1341,7 @@ DBC = { CAR.KIA_FORTE: dbc_dict('hyundai_kia_generic', None), CAR.KIA_K5_2021: dbc_dict('hyundai_kia_generic', None), CAR.KIA_NIRO_EV: dbc_dict('hyundai_kia_generic', 'hyundai_kia_mando_front_radar'), - CAR.KIA_NIRO_HEV: dbc_dict('hyundai_kia_generic', 'hyundai_kia_mando_front_radar'), + CAR.KIA_NIRO_PHEV: dbc_dict('hyundai_kia_generic', 'hyundai_kia_mando_front_radar'), CAR.KIA_NIRO_HEV_2021: dbc_dict('hyundai_kia_generic', None), CAR.KIA_OPTIMA: dbc_dict('hyundai_kia_generic', None), CAR.KIA_OPTIMA_H: dbc_dict('hyundai_kia_generic', None), diff --git a/selfdrive/car/tests/routes.py b/selfdrive/car/tests/routes.py index 5c767ae1a..7e2788820 100644 --- a/selfdrive/car/tests/routes.py +++ b/selfdrive/car/tests/routes.py @@ -107,7 +107,7 @@ routes = [ TestRoute("d824e27e8c60172c|2022-05-19--16-15-28", HYUNDAI.KIA_EV6), TestRoute("007d5e4ad9f86d13|2021-09-30--15-09-23", HYUNDAI.KIA_K5_2021), TestRoute("50c6c9b85fd1ff03|2020-10-26--17-56-06", HYUNDAI.KIA_NIRO_EV), - TestRoute("173219cf50acdd7b|2021-07-05--10-27-41", HYUNDAI.KIA_NIRO_HEV), + TestRoute("173219cf50acdd7b|2021-07-05--10-27-41", HYUNDAI.KIA_NIRO_PHEV), TestRoute("34a875f29f69841a|2021-07-29--13-02-09", HYUNDAI.KIA_NIRO_HEV_2021), TestRoute("50a2212c41f65c7b|2021-05-24--16-22-06", HYUNDAI.KIA_FORTE), TestRoute("c5ac319aa9583f83|2021-06-01--18-18-31", HYUNDAI.ELANTRA), From fe509e0354466a301dd403d29b5b2c82aea8aad1 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Fri, 19 Aug 2022 12:04:12 -0700 Subject: [PATCH 038/172] GM pcmCruise: cancel more reliably (#25454) * Cancel more reliably * Apply suggestions from code review * Try sending multiple * Apply suggestions from code review * Apply suggestions from code review * Update selfdrive/car/gm/carcontroller.py * lower rate a bit * try this * Update selfdrive/car/gm/carcontroller.py --- selfdrive/car/gm/carcontroller.py | 4 ++-- selfdrive/car/gm/carstate.py | 3 +++ selfdrive/car/gm/gmcan.py | 7 +++++-- 3 files changed, 10 insertions(+), 4 deletions(-) diff --git a/selfdrive/car/gm/carcontroller.py b/selfdrive/car/gm/carcontroller.py index 10e602797..977d20c5b 100644 --- a/selfdrive/car/gm/carcontroller.py +++ b/selfdrive/car/gm/carcontroller.py @@ -109,10 +109,10 @@ class CarController: else: # Stock longitudinal, integrated at camera - if (self.frame - self.last_button_frame) * DT_CTRL > 0.1: + if (self.frame - self.last_button_frame) * DT_CTRL > 0.04: if CC.cruiseControl.cancel: self.last_button_frame = self.frame - can_sends.append(gmcan.create_buttons(self.packer_pt, CanBus.CAMERA, CruiseButtons.CANCEL)) + can_sends.append(gmcan.create_buttons(self.packer_pt, CanBus.CAMERA, CS.buttons_counter, CruiseButtons.CANCEL)) # Show green icon when LKA torque is applied, and # alarming orange icon when approaching torque limit. diff --git a/selfdrive/car/gm/carstate.py b/selfdrive/car/gm/carstate.py index 0bda7edad..0bba1d29b 100644 --- a/selfdrive/car/gm/carstate.py +++ b/selfdrive/car/gm/carstate.py @@ -16,12 +16,14 @@ class CarState(CarStateBase): can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) self.shifter_values = can_define.dv["ECMPRDNL2"]["PRNDL2"] self.lka_steering_cmd_counter = 0 + self.buttons_counter = 0 def update(self, pt_cp, cam_cp, loopback_cp): ret = car.CarState.new_message() self.prev_cruise_buttons = self.cruise_buttons self.cruise_buttons = pt_cp.vl["ASCMSteeringButton"]["ACCButtons"] + self.buttons_counter = pt_cp.vl["ASCMSteeringButton"]["RollingCounter"] ret.wheelSpeeds = self.get_wheel_speeds( pt_cp.vl["EBCMWheelSpdFront"]["FLWheelSpd"], @@ -109,6 +111,7 @@ class CarState(CarStateBase): ("AcceleratorPedal2", "AcceleratorPedal2"), ("CruiseState", "AcceleratorPedal2"), ("ACCButtons", "ASCMSteeringButton"), + ("RollingCounter", "ASCMSteeringButton"), ("SteeringWheelAngle", "PSCMSteeringAngle"), ("SteeringWheelRate", "PSCMSteeringAngle"), ("FLWheelSpd", "EBCMWheelSpdFront"), diff --git a/selfdrive/car/gm/gmcan.py b/selfdrive/car/gm/gmcan.py index 3a10c4d9d..20e4c4ab6 100644 --- a/selfdrive/car/gm/gmcan.py +++ b/selfdrive/car/gm/gmcan.py @@ -1,7 +1,10 @@ from selfdrive.car import make_can_msg -def create_buttons(packer, bus, button): - values = {"ACCButtons": button} +def create_buttons(packer, bus, idx, button): + values = { + "ACCButtons": button, + "RollingCounter": idx, + } return packer.make_can_msg("ASCMSteeringButton", bus, values) def create_steering_control(packer, bus, apply_steer, idx, lkas_active): From 93b01fd9eaa472ab93930bf8259574bdb7040c95 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 19 Aug 2022 12:54:08 -0700 Subject: [PATCH 039/172] bump panda --- panda | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/panda b/panda index ba8772123..abaa9f896 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit ba8772123f13123c797234660c56adb70795cebb +Subproject commit abaa9f8968df13c8a858413cc9936269702c2d60 From a0af3a998d3a36c9f65ca6d6443f043cbf5be068 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Fri, 19 Aug 2022 13:34:23 -0700 Subject: [PATCH 040/172] Car docs: add more videos (#25494) * Add Civic video * add mazda cx-9 2022 video link --- selfdrive/car/honda/values.py | 2 +- selfdrive/car/mazda/values.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py index ab1cc9a6c..ad4f73c01 100644 --- a/selfdrive/car/honda/values.py +++ b/selfdrive/car/honda/values.py @@ -113,7 +113,7 @@ CAR_INFO: Dict[str, Optional[Union[HondaCarInfo, List[HondaCarInfo]]]] = { HondaCarInfo("Honda Inspire 2018", "All", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch_a), ], CAR.ACCORDH: HondaCarInfo("Honda Accord Hybrid 2018-22", "All", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch_a), - CAR.CIVIC: HondaCarInfo("Honda Civic 2016-18", harness=Harness.nidec), + CAR.CIVIC: HondaCarInfo("Honda Civic 2016-18", harness=Harness.nidec, video_link="https://youtu.be/-IkImTe1NYE"), CAR.CIVIC_BOSCH: [ HondaCarInfo("Honda Civic 2019-21", "All", video_link="https://www.youtube.com/watch?v=4Iz1Mz5LGF8", footnotes=[Footnote.CIVIC_DIESEL], min_steer_speed=2. * CV.MPH_TO_MS, harness=Harness.bosch_a), HondaCarInfo("Honda Civic Hatchback 2017-21", harness=Harness.bosch_a), diff --git a/selfdrive/car/mazda/values.py b/selfdrive/car/mazda/values.py index 7e99cccec..ed246f15d 100644 --- a/selfdrive/car/mazda/values.py +++ b/selfdrive/car/mazda/values.py @@ -40,7 +40,7 @@ CAR_INFO: Dict[str, Union[MazdaCarInfo, List[MazdaCarInfo]]] = { CAR.CX9: MazdaCarInfo("Mazda CX-9 2016-20"), CAR.MAZDA3: MazdaCarInfo("Mazda 3 2017-18"), CAR.MAZDA6: MazdaCarInfo("Mazda 6 2017-20"), - CAR.CX9_2021: MazdaCarInfo("Mazda CX-9 2021-22"), + CAR.CX9_2021: MazdaCarInfo("Mazda CX-9 2021-22", video_link="https://youtu.be/dA3duO4a0O4"), CAR.CX5_2022: MazdaCarInfo("Mazda CX-5 2022"), } From fb19e24d6019a23e8bfb5f767bfa976d373a6e3d Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Fri, 19 Aug 2022 15:48:46 -0700 Subject: [PATCH 041/172] GM Bolt EUV: update supported packages (#25496) * Update values.py * Update selfdrive/car/gm/values.py Co-authored-by: Adeeb Shihadeh * update docs Co-authored-by: Adeeb Shihadeh --- docs/CARS.md | 2 +- selfdrive/car/gm/values.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/CARS.md b/docs/CARS.md index efd9b3c52..fe2c42327 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -18,7 +18,7 @@ A supported vehicle is one that just works when you install a comma device. Ever |Audi|RS3 2018|ACC + Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| |Audi|S3 2015-17|ACC + Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| |Cadillac|Escalade ESV 2016[1](#footnotes)|Adaptive Cruise Control (ACC) & LKAS|openpilot|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|OBD-II| -|Chevrolet|Bolt EUV 2022-23|Premier/Premier Redline Trim|Stock|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|GM| +|Chevrolet|Bolt EUV 2022-23|Premier or Premier Redline Trim without Super Cruise Package|Stock|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|GM| |Chevrolet|Volt 2017-18[1](#footnotes)|Adaptive Cruise Control|openpilot|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|OBD-II| |Chrysler|Pacifica 2017-18|Adaptive Cruise Control|Stock|0 mph|9 mph|[![star](assets/icon-star-full.svg)](##)|FCA| |Chrysler|Pacifica 2019-20|Adaptive Cruise Control|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|FCA| diff --git a/selfdrive/car/gm/values.py b/selfdrive/car/gm/values.py index cb9aff172..1f7b0a5db 100644 --- a/selfdrive/car/gm/values.py +++ b/selfdrive/car/gm/values.py @@ -83,7 +83,7 @@ CAR_INFO: Dict[str, Union[GMCarInfo, List[GMCarInfo]]] = { CAR.ACADIA: GMCarInfo("GMC Acadia 2018", video_link="https://www.youtube.com/watch?v=0ZN6DdsBUZo"), CAR.BUICK_REGAL: GMCarInfo("Buick Regal Essence 2018"), CAR.ESCALADE_ESV: GMCarInfo("Cadillac Escalade ESV 2016", "Adaptive Cruise Control (ACC) & LKAS"), - CAR.BOLT_EUV: GMCarInfo("Chevrolet Bolt EUV 2022-23", "Premier/Premier Redline Trim", video_link="https://youtu.be/xvwzGMUA210", footnotes=[], harness=Harness.gm), + CAR.BOLT_EUV: GMCarInfo("Chevrolet Bolt EUV 2022-23", "Premier or Premier Redline Trim without Super Cruise Package", video_link="https://youtu.be/xvwzGMUA210", footnotes=[], harness=Harness.gm), } From 090e92bb699ac05340dbb325076402d09dd53a9c Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 19 Aug 2022 16:12:16 -0700 Subject: [PATCH 042/172] Hyundai: common CAN-FD gear signal (#25498) * Hyundai: common CAN-FD gear signal * bump opendbc --- opendbc | 2 +- selfdrive/car/hyundai/carstate.py | 7 ++++--- 2 files changed, 5 insertions(+), 4 deletions(-) diff --git a/opendbc b/opendbc index 7e095a90a..3270c931c 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit 7e095a90af3d36e6db9128a80f6f3b0cca01efa2 +Subproject commit 3270c931c07bd3a47839a1a84c109eb2a7d295a6 diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py index 9105f1278..08eccc3fe 100644 --- a/selfdrive/car/hyundai/carstate.py +++ b/selfdrive/car/hyundai/carstate.py @@ -20,7 +20,7 @@ class CarState(CarStateBase): self.main_buttons = deque([Buttons.NONE] * PREV_BUTTON_SAMPLES, maxlen=PREV_BUTTON_SAMPLES) if CP.carFingerprint in CANFD_CAR: - self.shifter_values = can_define.dv["ACCELERATOR"]["GEAR"] + self.shifter_values = can_define.dv["GEAR_SHIFTER"]["GEAR"] elif self.CP.carFingerprint in FEATURES["use_cluster_gears"]: self.shifter_values = can_define.dv["CLU15"]["CF_Clu_Gear"] elif self.CP.carFingerprint in FEATURES["use_tcu_gears"]: @@ -143,7 +143,7 @@ class CarState(CarStateBase): ret.doorOpen = cp.vl["DOORS_SEATBELTS"]["DRIVER_DOOR_OPEN"] == 1 ret.seatbeltUnlatched = cp.vl["DOORS_SEATBELTS"]["DRIVER_SEATBELT_LATCHED"] == 0 - gear = cp.vl["ACCELERATOR"]["GEAR"] + gear = cp.vl["GEAR_SHIFTER"]["GEAR"] ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(gear)) # TODO: figure out positions @@ -381,7 +381,7 @@ class CarState(CarStateBase): ("WHEEL_SPEED_4", "WHEEL_SPEEDS"), ("ACCELERATOR_PEDAL", "ACCELERATOR"), - ("GEAR", "ACCELERATOR"), + ("GEAR", "GEAR_SHIFTER"), ("BRAKE_PRESSED", "BRAKE"), ("STEERING_RATE", "STEERING_SENSORS"), @@ -408,6 +408,7 @@ class CarState(CarStateBase): checks = [ ("WHEEL_SPEEDS", 100), ("ACCELERATOR", 100), + ("GEAR_SHIFTER", 100), ("BRAKE", 100), ("STEERING_SENSORS", 100), ("MDPS", 100), From 1e9fdff6422c4f49702f5de56280241088b2abca Mon Sep 17 00:00:00 2001 From: Jason Shuler Date: Fri, 19 Aug 2022 19:58:06 -0400 Subject: [PATCH 043/172] GM: Chevy Silverado 2020-21 support (#25429) * Silverado support Co-authored-by: Jason Shuler * Update docs * Try 2 m/s/s * Should be good torque values * Add Silverado test route * Add to releases * Send counter * can't send multiple or it faults * Send at 33hz, no counter * try 25hz, don't line up exactly with car's buttons * never tried 10hz with same counter * Update selfdrive/car/gm/gmcan.py * Make same as pcmCruise branch * update year and package (different packages needed per-trim) * Update year in releases * Revert to 21 * We can use this package name again * wrong one! Co-authored-by: Shane Smiskol --- RELEASES.md | 1 + docs/CARS.md | 3 ++- selfdrive/car/gm/interface.py | 9 +++++++++ selfdrive/car/gm/values.py | 8 +++++++- selfdrive/car/tests/routes.py | 1 + selfdrive/car/torque_data/override.yaml | 1 + 6 files changed, 21 insertions(+), 2 deletions(-) diff --git a/RELEASES.md b/RELEASES.md index ced165fb0..cb6bf1552 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -4,6 +4,7 @@ Version 0.8.16 (2022-XX-XX) * Reduced turn cutting * Auto-detect right hand drive setting with driver monitoring model * Chevrolet Bolt EUV 2022-23 support thanks to JasonJShuler! +* Chevrolet Silverado 2020-21 support thanks to JasonJShuler! * Hyundai Ioniq 5 2022 support thanks to sunnyhaibin! * Hyundai Kona Electric 2022 support thanks to sunnyhaibin! * Subaru Legacy 2020-22 support thanks to martinl! diff --git a/docs/CARS.md b/docs/CARS.md index fe2c42327..b244b5c36 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 device. Every car performs differently with openpilot, but all supported cars should provide a better experience than any stock system. -# 202 Supported Cars +# 203 Supported Cars |Make|Model|Supported Package|ACC|No ACC accel below|No ALC below|Steering Torque|Harness| |---|---|---|:---:|:---:|:---:|:---:|:---:| @@ -19,6 +19,7 @@ A supported vehicle is one that just works when you install a comma device. Ever |Audi|S3 2015-17|ACC + Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| |Cadillac|Escalade ESV 2016[1](#footnotes)|Adaptive Cruise Control (ACC) & LKAS|openpilot|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|OBD-II| |Chevrolet|Bolt EUV 2022-23|Premier or Premier Redline Trim without Super Cruise Package|Stock|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|GM| +|Chevrolet|Silverado 1500 2020-21|Safety Package II|Stock|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|GM| |Chevrolet|Volt 2017-18[1](#footnotes)|Adaptive Cruise Control|openpilot|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|OBD-II| |Chrysler|Pacifica 2017-18|Adaptive Cruise Control|Stock|0 mph|9 mph|[![star](assets/icon-star-full.svg)](##)|FCA| |Chrysler|Pacifica 2019-20|Adaptive Cruise Control|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|FCA| diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py index 18709a2a8..09d950ea8 100755 --- a/selfdrive/car/gm/interface.py +++ b/selfdrive/car/gm/interface.py @@ -160,6 +160,15 @@ class CarInterface(CarInterfaceBase): ret.steerActuatorDelay = 0.2 CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) + elif candidate == CAR.SILVERADO: + ret.minEnableSpeed = -1 + ret.mass = 2200. + STD_CARGO_KG + ret.wheelbase = 3.75 + ret.steerRatio = 16.3 + ret.centerToFront = ret.wheelbase * 0.5 + tire_stiffness_factor = 1.0 + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) + # TODO: get actual value, for now starting with reasonable value for # civic and scaling by mass and wheelbase ret.rotationalInertia = scale_rot_inertia(ret.mass, ret.wheelbase) diff --git a/selfdrive/car/gm/values.py b/selfdrive/car/gm/values.py index 1f7b0a5db..df91938d8 100644 --- a/selfdrive/car/gm/values.py +++ b/selfdrive/car/gm/values.py @@ -59,6 +59,7 @@ class CAR: BUICK_REGAL = "BUICK REGAL ESSENCE 2018" ESCALADE_ESV = "CADILLAC ESCALADE ESV 2016" BOLT_EUV = "CHEVROLET BOLT EUV 2022" + SILVERADO = "CHEVROLET SILVERADO 1500 2020" class Footnote(Enum): @@ -84,6 +85,7 @@ CAR_INFO: Dict[str, Union[GMCarInfo, List[GMCarInfo]]] = { CAR.BUICK_REGAL: GMCarInfo("Buick Regal Essence 2018"), CAR.ESCALADE_ESV: GMCarInfo("Cadillac Escalade ESV 2016", "Adaptive Cruise Control (ACC) & LKAS"), CAR.BOLT_EUV: GMCarInfo("Chevrolet Bolt EUV 2022-23", "Premier or Premier Redline Trim without Super Cruise Package", video_link="https://youtu.be/xvwzGMUA210", footnotes=[], harness=Harness.gm), + CAR.SILVERADO: GMCarInfo("Chevrolet Silverado 1500 2020-21", "Safety Package II", footnotes=[], harness=Harness.gm), } @@ -157,6 +159,10 @@ FINGERPRINTS = { { 189: 7, 190: 7, 193: 8, 197: 8, 201: 8, 209: 7, 211: 3, 241: 6, 257: 8, 288: 5, 289: 8, 298: 8, 304: 3, 309: 8, 311: 8, 313: 8, 320: 4, 322: 7, 328: 1, 352: 5, 381: 8, 384: 4, 386: 8, 388: 8, 451: 8, 452: 8, 453: 6, 458: 5, 463: 3, 479: 3, 481: 7, 485: 8, 489: 8, 497: 8, 500: 6, 501: 8, 528: 5, 532: 6, 560: 8, 562: 8, 563: 5, 565: 5, 566: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 789: 5, 800: 6, 810: 8, 840: 5, 842: 5, 844: 8, 848: 4, 869: 4, 880: 6, 977: 8, 1001: 8, 1017: 8, 1020: 8, 1217: 8, 1221: 5, 1233: 8, 1249: 8, 1265: 8, 1280: 4, 1296: 4, 1300: 8, 1930: 7 }], + CAR.SILVERADO: [ + { + 190: 6, 193: 8, 197: 8, 201: 8, 208: 8, 209: 7, 211: 2, 241: 6, 249: 8, 257: 8, 288: 5, 289: 8, 298: 8, 304: 3, 309: 8, 311: 8, 313: 8, 320: 4, 322: 7, 328: 1, 352: 5, 381: 8, 384: 4, 386: 8, 388: 8, 413: 8, 451: 8, 452: 8, 453: 6, 455: 7, 460: 5, 463: 3, 479: 3, 481: 7, 485: 8, 489: 8, 497: 8, 500: 6, 501: 8, 528: 5, 532: 6, 560: 8, 562: 8, 563: 5, 565: 5, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 707: 8, 715: 8, 717: 5, 761: 7, 789: 5, 800: 6, 810: 8, 840: 5, 842: 5, 844: 8, 848: 4, 869: 4, 880: 6, 977: 8, 1001: 8, 1011: 6, 1017: 8, 1020: 8, 1033: 7, 1034: 7, 1217: 8, 1221: 5, 1233: 8, 1249: 8, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1271: 8, 1280: 4, 1296: 4, 1300: 8, 1930: 7 + }], } DBC: Dict[str, Dict[str, str]] = defaultdict(lambda: dbc_dict('gm_global_a_powertrain_generated', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis')) @@ -164,6 +170,6 @@ DBC: Dict[str, Dict[str, str]] = defaultdict(lambda: dbc_dict('gm_global_a_power EV_CAR = {CAR.VOLT, CAR.BOLT_EUV} # We're integrated at the camera with VOACC on these cars (instead of ASCM w/ OBD-II harness) -CAMERA_ACC_CAR = {CAR.BOLT_EUV} +CAMERA_ACC_CAR = {CAR.BOLT_EUV, CAR.SILVERADO} STEER_THRESHOLD = 1.0 diff --git a/selfdrive/car/tests/routes.py b/selfdrive/car/tests/routes.py index 7e2788820..6cae48cd9 100644 --- a/selfdrive/car/tests/routes.py +++ b/selfdrive/car/tests/routes.py @@ -48,6 +48,7 @@ routes = [ TestRoute("46460f0da08e621e|2021-10-26--07-21-46", GM.ESCALADE_ESV), TestRoute("c950e28c26b5b168|2018-05-30--22-03-41", GM.VOLT), TestRoute("f08912a233c1584f|2022-08-11--18-02-41", GM.BOLT_EUV), + TestRoute("38aa7da107d5d252|2022-08-15--16-01-12", GM.SILVERADO), TestRoute("0e7a2ba168465df5|2020-10-18--14-14-22", HONDA.ACURA_RDX_3G), TestRoute("a74b011b32b51b56|2020-07-26--17-09-36", HONDA.CIVIC), diff --git a/selfdrive/car/torque_data/override.yaml b/selfdrive/car/torque_data/override.yaml index 8dd8c4322..532410821 100644 --- a/selfdrive/car/torque_data/override.yaml +++ b/selfdrive/car/torque_data/override.yaml @@ -25,6 +25,7 @@ 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] CHEVROLET BOLT EUV 2022: [2.0, 2.0, 0.05] +CHEVROLET SILVERADO 1500 2020: [1.9, 1.9, 0.112] VOLKSWAGEN PASSAT NMS: [2.5, 2.5, 0.1] # Dashcam or fallback configured as ideal car From 3640922f85323250d852900c18ea532f4f89304b Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Fri, 19 Aug 2022 19:27:16 -0700 Subject: [PATCH 044/172] Show CAN error if message counters are invalid (#25497) * counter check affects can valid * Apply suggestions from code review * bump to master --- opendbc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/opendbc b/opendbc index 3270c931c..b913296c9 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit 3270c931c07bd3a47839a1a84c109eb2a7d295a6 +Subproject commit b913296c9123441b2b271c00239929ed388169b5 From bd5e28909f4576699717f8a2f6751f0d9fdfecc0 Mon Sep 17 00:00:00 2001 From: Jason Wen <47793918+sunnyhaibin@users.noreply.github.com> Date: Fri, 19 Aug 2022 23:14:30 -0400 Subject: [PATCH 045/172] Hyundai: Car Port for Tucson Hybrid 2022 (#25276) * Hyundai: Car Port for Tucson Hybrid 2022 * Update RELEASES.md * Init gear_msg at the top * FW versions from script * Button send attempt * start with some cleanup * Send button fixed bits * Define all bytes and only send PAUSE/RESUME * Use CRUISE_INFO to cancel cruise and resume * 8-bit counter * Cleanup ish * 8 bit counter * Send at 20ms * Disengage bits * Revert bump submodules * Allow tx on 0x1a0 * Fix byte counts * Send LFA and HDA icons based on engageability * Send cruise buttons only on HDA2 cars for now * Add comments * Add FLAG_HYUNDAI_CANFD_HDA2 flag * Update interface.py * Update carstate.py * Update carstate.py * Update carstate.py * Bump submodules * Bump panda * Bump opendbc * Allow tx with CRUISE_INACTIVE * GEAR has 24 bytes only * Generate car docs * Fix CRUISE_INFO copy * Remove unused class * Add CAN-FD busses to unit test * Bump opendbc * Revert "Add CAN-FD busses to unit test" This reverts commit 2f751640408a7f73a9100947cbd95ea13fbb8a48. * Remove duplicate * New tune based on data * Panda safety cleanup * Include bus 0 in rx checks * Missed one * bus 6 check * Remove redundant check * Add comments * Bump opendbc * Sync with DBC * Hide LFA icon when disengaged * Little endian * fix comment * more conditions in carcontroller * update pedal signal * update tuning * cleanup carcontroller * bump panda * fix mismatch * alt buttons * little more cleanup * update refs for EV6 new safety param * bump panda Co-authored-by: Adeeb Shihadeh --- RELEASES.md | 1 + docs/CARS.md | 3 +- panda | 2 +- selfdrive/car/docs.py | 4 +- selfdrive/car/hyundai/carcontroller.py | 29 ++++-- selfdrive/car/hyundai/carstate.py | 96 ++++++++++++++----- selfdrive/car/hyundai/hyundaicanfd.py | 23 ++++- selfdrive/car/hyundai/interface.py | 21 +++- selfdrive/car/hyundai/values.py | 26 ++++- selfdrive/car/tests/routes.py | 1 + selfdrive/car/torque_data/override.yaml | 1 + selfdrive/test/process_replay/ref_commit | 2 +- .../test/process_replay/test_processes.py | 4 +- 13 files changed, 169 insertions(+), 44 deletions(-) diff --git a/RELEASES.md b/RELEASES.md index cb6bf1552..235e90a3d 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -7,6 +7,7 @@ Version 0.8.16 (2022-XX-XX) * Chevrolet Silverado 2020-21 support thanks to JasonJShuler! * Hyundai Ioniq 5 2022 support thanks to sunnyhaibin! * Hyundai Kona Electric 2022 support thanks to sunnyhaibin! +* Hyundai Tucson Hybrid 2022 support thanks to sunnyhaibin! * Subaru Legacy 2020-22 support thanks to martinl! * Subaru Outback 2020-22 support diff --git a/docs/CARS.md b/docs/CARS.md index b244b5c36..2a1f770b7 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 device. Every car performs differently with openpilot, but all supported cars should provide a better experience than any stock system. -# 203 Supported Cars +# 204 Supported Cars |Make|Model|Supported Package|ACC|No ACC accel below|No ALC below|Steering Torque|Harness| |---|---|---|:---:|:---:|:---:|:---:|:---:| @@ -77,6 +77,7 @@ A supported vehicle is one that just works when you install a comma device. Ever |Hyundai|Sonata Hybrid 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai A| |Hyundai|Tucson 2021|Smart Cruise Control (SCC)|Stock|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai L| |Hyundai|Tucson Diesel 2019|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai L| +|Hyundai|Tucson Hybrid 2022|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai N| |Hyundai|Veloster 2019-20|Smart Cruise Control (SCC)|Stock|5 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai E| |Jeep|Grand Cherokee 2016-18|Adaptive Cruise Control|Stock|0 mph|9 mph|[![star](assets/icon-star-full.svg)](##)|FCA| |Jeep|Grand Cherokee 2019-21|Adaptive Cruise Control|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|FCA| diff --git a/panda b/panda index abaa9f896..9d6496ece 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit abaa9f8968df13c8a858413cc9936269702c2d60 +Subproject commit 9d6496ece8465dfe30997b31dfb352e1e51dde6c diff --git a/selfdrive/car/docs.py b/selfdrive/car/docs.py index 795668381..4d79cbfc7 100755 --- a/selfdrive/car/docs.py +++ b/selfdrive/car/docs.py @@ -8,6 +8,7 @@ from natsort import natsorted from typing import Dict, List from common.basedir import BASEDIR +from selfdrive.car import gen_empty_fingerprint from selfdrive.car.docs_definitions import CarInfo, Column from selfdrive.car.car_helpers import interfaces, get_interface_attr from selfdrive.car.hyundai.radar_interface import RADAR_START_ADDR as HKG_RADAR_START_ADDR @@ -29,7 +30,8 @@ def get_all_car_info() -> List[CarInfo]: footnotes = get_all_footnotes() for model, car_info in get_interface_attr("CAR_INFO", combine_brands=True).items(): # Hyundai exception: those with radar have openpilot longitudinal - fingerprint = {0: {}, 1: {HKG_RADAR_START_ADDR: 8}, 2: {}, 3: {}} + fingerprint = gen_empty_fingerprint() + fingerprint[1] = {HKG_RADAR_START_ADDR: 8} CP = interfaces[model][0].get_params(model, fingerprint=fingerprint, disable_radar=True) if CP.dashcamOnly or car_info is None: diff --git a/selfdrive/car/hyundai/carcontroller.py b/selfdrive/car/hyundai/carcontroller.py index 60fb46340..971330a33 100644 --- a/selfdrive/car/hyundai/carcontroller.py +++ b/selfdrive/car/hyundai/carcontroller.py @@ -5,7 +5,7 @@ from common.realtime import DT_CTRL from opendbc.can.packer import CANPacker from selfdrive.car import apply_std_steer_torque_limits from selfdrive.car.hyundai import hyundaicanfd, hyundaican -from selfdrive.car.hyundai.values import Buttons, CarControllerParams, CANFD_CAR, CAR +from selfdrive.car.hyundai.values import HyundaiFlags, Buttons, CarControllerParams, CANFD_CAR, CAR VisualAlert = car.CarControl.HUDControl.VisualAlert LongCtrlState = car.CarControl.Actuators.LongControlState @@ -71,22 +71,33 @@ class CarController: if self.CP.carFingerprint in CANFD_CAR: # steering control - can_sends.append(hyundaicanfd.create_lkas(self.packer, CC.enabled, CC.latActive, apply_steer)) + can_sends.append(hyundaicanfd.create_lkas(self.packer, self.CP, CC.enabled, CC.latActive, apply_steer)) - if self.frame % 5 == 0: + # block LFA on HDA2 + if self.frame % 5 == 0 and (self.CP.flags & HyundaiFlags.CANFD_HDA2): can_sends.append(hyundaicanfd.create_cam_0x2a4(self.packer, CS.cam_0x2a4)) - # cruise cancel + # LFA and HDA icons + if self.frame % 2 == 0 and not (self.CP.flags & HyundaiFlags.CANFD_HDA2): + can_sends.append(hyundaicanfd.create_lfahda_cluster(self.packer, CC.enabled)) + + # button presses if (self.frame - self.last_button_frame) * DT_CTRL > 0.25: + # cruise cancel if CC.cruiseControl.cancel: - for _ in range(20): - can_sends.append(hyundaicanfd.create_buttons(self.packer, CS.buttons_counter+1, Buttons.CANCEL)) - self.last_button_frame = self.frame + if self.CP.flags & HyundaiFlags.CANFD_ALT_BUTTONS: + can_sends.append(hyundaicanfd.create_cruise_info(self.packer, CS.cruise_info_copy, True)) + self.last_button_frame = self.frame + else: + for _ in range(20): + can_sends.append(hyundaicanfd.create_buttons(self.packer, CS.buttons_counter+1, Buttons.CANCEL)) + self.last_button_frame = self.frame # cruise standstill resume elif CC.cruiseControl.resume: - can_sends.append(hyundaicanfd.create_buttons(self.packer, CS.buttons_counter+1, Buttons.RES_ACCEL)) - self.last_button_frame = self.frame + if not (self.CP.flags & HyundaiFlags.CANFD_ALT_BUTTONS): + can_sends.append(hyundaicanfd.create_buttons(self.packer, CS.buttons_counter+1, Buttons.RES_ACCEL)) + self.last_button_frame = self.frame else: # tester present - w/ no response (keeps radar disabled) diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py index 08eccc3fe..eab6e73f1 100644 --- a/selfdrive/car/hyundai/carstate.py +++ b/selfdrive/car/hyundai/carstate.py @@ -5,7 +5,7 @@ from cereal import car from common.conversions import Conversions as CV from opendbc.can.parser import CANParser from opendbc.can.can_define import CANDefine -from selfdrive.car.hyundai.values import DBC, FEATURES, CAMERA_SCC_CAR, CANFD_CAR, EV_CAR, HYBRID_CAR, Buttons, CarControllerParams +from selfdrive.car.hyundai.values import HyundaiFlags, DBC, FEATURES, CAMERA_SCC_CAR, CANFD_CAR, EV_CAR, HYBRID_CAR, Buttons, CarControllerParams from selfdrive.car.interfaces import CarStateBase PREV_BUTTON_SAMPLES = 8 @@ -136,8 +136,11 @@ class CarState(CarStateBase): def update_canfd(self, cp, cp_cam): ret = car.CarState.new_message() - ret.gas = cp.vl["ACCELERATOR"]["ACCELERATOR_PEDAL"] / 255. - ret.gasPressed = ret.gas > 1e-3 + if self.CP.flags & HyundaiFlags.CANFD_HDA2: + ret.gas = cp.vl["ACCELERATOR"]["ACCELERATOR_PEDAL"] / 255. + else: + ret.gas = cp.vl["ACCELERATOR_ALT"]["ACCELERATOR_PEDAL"] / 1023. + ret.gasPressed = ret.gas > 1e-5 ret.brakePressed = cp.vl["BRAKE"]["BRAKE_PRESSED"] == 1 ret.doorOpen = cp.vl["DOORS_SEATBELTS"]["DRIVER_DOOR_OPEN"] == 1 @@ -168,16 +171,19 @@ class CarState(CarStateBase): ret.cruiseState.available = True ret.cruiseState.enabled = cp.vl["SCC1"]["CRUISE_ACTIVE"] == 1 - ret.cruiseState.standstill = cp.vl["CRUISE_INFO"]["CRUISE_STANDSTILL"] == 1 - + cp_cruise_info = cp if self.CP.flags & HyundaiFlags.CANFD_HDA2 else cp_cam speed_factor = CV.MPH_TO_MS if cp.vl["CLUSTER_INFO"]["DISTANCE_UNIT"] == 1 else CV.KPH_TO_MS - ret.cruiseState.speed = cp.vl["CRUISE_INFO"]["SET_SPEED"] * speed_factor + 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 - self.cruise_buttons.extend(cp.vl_all["CRUISE_BUTTONS"]["CRUISE_BUTTONS"]) - self.main_buttons.extend(cp.vl_all["CRUISE_BUTTONS"]["ADAPTIVE_CRUISE_MAIN_BTN"]) - self.buttons_counter = cp.vl["CRUISE_BUTTONS"]["COUNTER"] + cruise_btn_msg = "CRUISE_BUTTONS_ALT" if self.CP.flags & HyundaiFlags.CANFD_ALT_BUTTONS else "CRUISE_BUTTONS" + self.cruise_buttons.extend(cp.vl_all[cruise_btn_msg]["CRUISE_BUTTONS"]) + self.main_buttons.extend(cp.vl_all[cruise_btn_msg]["ADAPTIVE_CRUISE_MAIN_BTN"]) + self.buttons_counter = cp.vl[cruise_btn_msg]["COUNTER"] + self.cruise_info_copy = copy.copy(cp_cruise_info.vl["CRUISE_INFO"]) - self.cam_0x2a4 = copy.copy(cp_cam.vl["CAM_0x2a4"]) + if self.CP.flags & HyundaiFlags.CANFD_HDA2: + self.cam_0x2a4 = copy.copy(cp_cam.vl["CAM_0x2a4"]) return ret @@ -319,9 +325,7 @@ class CarState(CarStateBase): @staticmethod def get_cam_can_parser(CP): if CP.carFingerprint in CANFD_CAR: - signals = [(f"BYTE{i}", "CAM_0x2a4") for i in range(3, 24)] - checks = [("CAM_0x2a4", 20)] - return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 6) + return CarState.get_cam_can_parser_canfd(CP) signals = [ # signal_name, signal_address @@ -374,13 +378,14 @@ class CarState(CarStateBase): @staticmethod def get_can_parser_canfd(CP): + + cruise_btn_msg = "CRUISE_BUTTONS_ALT" if CP.flags & HyundaiFlags.CANFD_ALT_BUTTONS else "CRUISE_BUTTONS" signals = [ ("WHEEL_SPEED_1", "WHEEL_SPEEDS"), ("WHEEL_SPEED_2", "WHEEL_SPEEDS"), ("WHEEL_SPEED_3", "WHEEL_SPEEDS"), ("WHEEL_SPEED_4", "WHEEL_SPEEDS"), - ("ACCELERATOR_PEDAL", "ACCELERATOR"), ("GEAR", "GEAR_SHIFTER"), ("BRAKE_PRESSED", "BRAKE"), @@ -390,11 +395,9 @@ class CarState(CarStateBase): ("STEERING_OUT_TORQUE", "MDPS"), ("CRUISE_ACTIVE", "SCC1"), - ("SET_SPEED", "CRUISE_INFO"), - ("CRUISE_STANDSTILL", "CRUISE_INFO"), - ("COUNTER", "CRUISE_BUTTONS"), - ("CRUISE_BUTTONS", "CRUISE_BUTTONS"), - ("ADAPTIVE_CRUISE_MAIN_BTN", "CRUISE_BUTTONS"), + ("COUNTER", cruise_btn_msg), + ("CRUISE_BUTTONS", cruise_btn_msg), + ("ADAPTIVE_CRUISE_MAIN_BTN", cruise_btn_msg), ("DISTANCE_UNIT", "CLUSTER_INFO"), @@ -407,17 +410,64 @@ class CarState(CarStateBase): checks = [ ("WHEEL_SPEEDS", 100), - ("ACCELERATOR", 100), ("GEAR_SHIFTER", 100), ("BRAKE", 100), ("STEERING_SENSORS", 100), ("MDPS", 100), ("SCC1", 50), - ("CRUISE_INFO", 50), - ("CRUISE_BUTTONS", 50), + (cruise_btn_msg, 50), ("CLUSTER_INFO", 4), ("BLINKERS", 4), ("DOORS_SEATBELTS", 4), ] - return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 5) + if CP.flags & HyundaiFlags.CANFD_HDA2: + signals += [ + ("ACCELERATOR_PEDAL", "ACCELERATOR"), + ("GEAR", "ACCELERATOR"), + ("SET_SPEED", "CRUISE_INFO"), + ("CRUISE_STANDSTILL", "CRUISE_INFO"), + ] + checks += [ + ("CRUISE_INFO", 50), + ("ACCELERATOR", 100), + ] + else: + signals += [ + ("ACCELERATOR_PEDAL", "ACCELERATOR_ALT"), + ] + checks += [ + ("ACCELERATOR_ALT", 100), + ] + + bus = 5 if CP.flags & HyundaiFlags.CANFD_HDA2 else 4 + return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, bus) + + @staticmethod + def get_cam_can_parser_canfd(CP): + if CP.flags & HyundaiFlags.CANFD_HDA2: + signals = [(f"BYTE{i}", "CAM_0x2a4") for i in range(3, 24)] + 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"), + ("NEW_SIGNAL_2", "CRUISE_INFO"), + ("CRUISE_STANDSTILL", "CRUISE_INFO"), + ("NEW_SIGNAL_3", "CRUISE_INFO"), + ("BYTE11", "CRUISE_INFO"), + ("SET_SPEED", "CRUISE_INFO"), + ("NEW_SIGNAL_4", "CRUISE_INFO"), + ] + + signals += [(f"BYTE{i}", "CRUISE_INFO") for i in range(3, 7)] + signals += [(f"BYTE{i}", "CRUISE_INFO") for i in range(13, 31)] + + checks = [ + ("CRUISE_INFO", 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 36207aa11..a53be7627 100644 --- a/selfdrive/car/hyundai/hyundaicanfd.py +++ b/selfdrive/car/hyundai/hyundaicanfd.py @@ -1,4 +1,7 @@ -def create_lkas(packer, enabled, lat_active, apply_steer): +from selfdrive.car.hyundai.values import HyundaiFlags + + +def create_lkas(packer, CP, enabled, lat_active, apply_steer): values = { "LKA_MODE": 2, "LKA_ICON": 2 if enabled else 1, @@ -10,7 +13,9 @@ def create_lkas(packer, enabled, lat_active, apply_steer): "NEW_SIGNAL_1": 0, "NEW_SIGNAL_2": 0, } - return packer.make_can_msg("LKAS", 4, values) + + msg = "LKAS" if CP.flags & HyundaiFlags.CANFD_HDA2 else "LFA" + return packer.make_can_msg(msg, 4, values) def create_cam_0x2a4(packer, camera_values): camera_values.update({ @@ -25,3 +30,17 @@ def create_buttons(packer, cnt, btn): "CRUISE_BUTTONS": btn, } return packer.make_can_msg("CRUISE_BUTTONS", 5, values) + +def create_cruise_info(packer, cruise_info_copy, cancel): + values = cruise_info_copy + if cancel: + values["CRUISE_STATUS"] = 0 + values["CRUISE_INACTIVE"] = 1 + return packer.make_can_msg("CRUISE_INFO", 4, values) + +def create_lfahda_cluster(packer, enabled): + values = { + "HDA_ICON": 1 if enabled else 0, + "LFA_ICON": 2 if enabled else 0, + } + return packer.make_can_msg("LFAHDA_CLUSTER", 4, values) diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 23a49a05e..fbf233498 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -2,7 +2,7 @@ from cereal import car from panda import Panda from common.conversions import Conversions as CV -from selfdrive.car.hyundai.values import CAR, DBC, CANFD_CAR, CAMERA_SCC_CAR, EV_CAR, HYBRID_CAR, LEGACY_SAFETY_MODE_CAR, Buttons, CarControllerParams +from selfdrive.car.hyundai.values import HyundaiFlags, CAR, DBC, CANFD_CAR, CAMERA_SCC_CAR, EV_CAR, HYBRID_CAR, LEGACY_SAFETY_MODE_CAR, Buttons, CarControllerParams from selfdrive.car.hyundai.radar_interface import RADAR_START_ADDR from selfdrive.car import STD_CARGO_KG, create_button_event, scale_rot_inertia, scale_tire_stiffness, gen_empty_fingerprint, get_safety_config from selfdrive.car.interfaces import CarInterfaceBase @@ -160,6 +160,12 @@ class CarInterface(CarInterfaceBase): tire_stiffness_factor = 0.385 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] + elif candidate == CAR.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: @@ -284,7 +290,18 @@ class CarInterface(CarInterfaceBase): if candidate in CANFD_CAR: ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.noOutput), get_safety_config(car.CarParams.SafetyModel.hyundaiCanfd)] + + # detect HDA2 with LKAS message + if 0x50 in fingerprint[6]: + ret.flags |= HyundaiFlags.CANFD_HDA2.value + ret.safetyConfigs[1].safetyParam |= Panda.FLAG_HYUNDAI_CANFD_HDA2 + else: + # non-HDA2 + if 0x1cf not in fingerprint[4]: + ret.flags |= HyundaiFlags.CANFD_ALT_BUTTONS.value 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)] @@ -314,8 +331,6 @@ class CarInterface(CarInterfaceBase): ret.tireStiffnessFront, ret.tireStiffnessRear = scale_tire_stiffness(ret.mass, ret.wheelbase, ret.centerToFront, tire_stiffness_factor=tire_stiffness_factor) - ret.enableBsm = 0x58b in fingerprint[0] - return ret @staticmethod diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index e36c9a6ac..2861e4dc8 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -1,3 +1,4 @@ +from enum import IntFlag from dataclasses import dataclass from typing import Dict, List, Optional, Union @@ -38,6 +39,11 @@ class CarControllerParams: self.STEER_MAX = 384 +class HyundaiFlags(IntFlag): + CANFD_HDA2 = 1 + CANFD_ALT_BUTTONS = 2 + + class CAR: # Hyundai ELANTRA = "HYUNDAI ELANTRA 2017" @@ -66,6 +72,7 @@ class CAR: VELOSTER = "HYUNDAI VELOSTER 2019" SONATA_HYBRID = "HYUNDAI SONATA HYBRID 2021" IONIQ_5 = "HYUNDAI IONIQ 5 2022" + TUCSON_HYBRID_4TH_GEN = "HYUNDAI TUCSON HYBRID 4TH GEN" # Kia KIA_FORTE = "KIA FORTE E 2018 & GT 2021" @@ -128,6 +135,7 @@ CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = { CAR.VELOSTER: HyundaiCarInfo("Hyundai Veloster 2019-20", "Smart Cruise Control (SCC)", min_enable_speed=5. * CV.MPH_TO_MS, harness=Harness.hyundai_e), CAR.SONATA_HYBRID: HyundaiCarInfo("Hyundai Sonata Hybrid 2020-22", "All", harness=Harness.hyundai_a), CAR.IONIQ_5: HyundaiCarInfo("Hyundai Ioniq 5 2022", "Highway Driving Assist II", harness=Harness.hyundai_q), + CAR.TUCSON_HYBRID_4TH_GEN: HyundaiCarInfo("Hyundai Tucson Hybrid 2022", "All", harness=Harness.hyundai_n), # Kia CAR.KIA_FORTE: [ @@ -1292,6 +1300,21 @@ FW_VERSIONS = { b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.02 99211-GI010 211206', ], }, + CAR.TUCSON_HYBRID_4TH_GEN: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-N9240 14Q', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00NX4 MDPS C 1.00 1.01 56300-P0100 2228', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x87391312MND0', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x00PSBG2441 G19_Rev\x00\x00\x00SNX4T16XXHS01NS2lS\xdfa', + b'\xf1\x8795441-3D220\x00\xf1\x81G19_Rev\x00\x00\x00\xf1\x00PSBG2441 G19_Rev\x00\x00\x00SNX4T16XXHS01NS2lS\xdfa', + ], + }, } CHECKSUM = { @@ -1309,7 +1332,7 @@ FEATURES = { "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}, } -CANFD_CAR = {CAR.KIA_EV6, CAR.IONIQ_5} +CANFD_CAR = {CAR.KIA_EV6, CAR.IONIQ_5, CAR.TUCSON_HYBRID_4TH_GEN} # The camera does SCC on these cars, rather than the radar CAMERA_SCC_CAR = {CAR.KONA_EV_2022, } @@ -1364,5 +1387,6 @@ DBC = { CAR.KIA_CEED: dbc_dict('hyundai_kia_generic', None), CAR.KIA_EV6: dbc_dict('hyundai_canfd', None), CAR.SONATA_HYBRID: dbc_dict('hyundai_kia_generic', 'hyundai_kia_mando_front_radar'), + CAR.TUCSON_HYBRID_4TH_GEN: dbc_dict('hyundai_canfd', None), CAR.IONIQ_5: dbc_dict('hyundai_canfd', None), } diff --git a/selfdrive/car/tests/routes.py b/selfdrive/car/tests/routes.py index 6cae48cd9..33467ffcf 100644 --- a/selfdrive/car/tests/routes.py +++ b/selfdrive/car/tests/routes.py @@ -90,6 +90,7 @@ routes = [ TestRoute("5b7c365c50084530|2020-04-15--16-13-24", HYUNDAI.SONATA), TestRoute("b2a38c712dcf90bd|2020-05-18--18-12-48", HYUNDAI.SONATA_LF), TestRoute("fb3fd42f0baaa2f8|2022-03-30--15-25-05", HYUNDAI.TUCSON), + TestRoute("36e10531feea61a4|2022-07-25--13-37-42", HYUNDAI.TUCSON_HYBRID_4TH_GEN), TestRoute("5875672fc1d4bf57|2020-07-23--21-33-28", HYUNDAI.KIA_SORENTO), TestRoute("9c917ba0d42ffe78|2020-04-17--12-43-19", HYUNDAI.PALISADE), TestRoute("22de8111a8c5463c|2022-07-29--13-34-49", HYUNDAI.IONIQ_5), diff --git a/selfdrive/car/torque_data/override.yaml b/selfdrive/car/torque_data/override.yaml index 532410821..14ee7e223 100644 --- a/selfdrive/car/torque_data/override.yaml +++ b/selfdrive/car/torque_data/override.yaml @@ -27,6 +27,7 @@ SUBARU OUTBACK 6TH GEN: [2.3, 2.3, 0.11] CHEVROLET BOLT EUV 2022: [2.0, 2.0, 0.05] CHEVROLET SILVERADO 1500 2020: [1.9, 1.9, 0.112] VOLKSWAGEN PASSAT NMS: [2.5, 2.5, 0.1] +HYUNDAI TUCSON HYBRID 4TH GEN: [2.5, 2.5, 0.0] # Dashcam or fallback configured as ideal car mock: [10.0, 10, 0.0] diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index b9e99cd61..f77f24459 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -93a136f91739847afe1e1a4a1e98bc7c0adb5ec8 +656daeb9de3680258527500ecae4ddff323b2e59 \ 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 2a005cf4c..e8c2e1dc9 100755 --- a/selfdrive/test/process_replay/test_processes.py +++ b/selfdrive/test/process_replay/test_processes.py @@ -18,7 +18,7 @@ from tools.lib.logreader import LogReader original_segments = [ ("BODY", "937ccb7243511b65|2022-05-24--16-03-09--1"), # COMMA.BODY ("HYUNDAI", "02c45f73a2e5c6e9|2021-01-01--19-08-22--1"), # HYUNDAI.SONATA - ("HYUNDAI", "d824e27e8c60172c|2022-07-08--21-21-15--0"), # HYUNDAI.KIA_EV6 + ("HYUNDAI", "d824e27e8c60172c|2022-08-19--17-58-07--2"), # HYUNDAI.KIA_EV6 ("TOYOTA", "0982d79ebb0de295|2021-01-04--17-13-21--13"), # TOYOTA.PRIUS (INDI) ("TOYOTA2", "0982d79ebb0de295|2021-01-03--20-03-36--6"), # TOYOTA.RAV4 (LQR) ("TOYOTA3", "f7d7e3538cda1a2a|2021-08-16--08-55-34--6"), # TOYOTA.COROLLA_TSS2 @@ -40,7 +40,7 @@ original_segments = [ segments = [ ("BODY", "regen660D86654BA|2022-07-06--14-27-15--0"), ("HYUNDAI", "regen114E5FF24D8|2022-07-14--17-08-47--0"), - ("HYUNDAI", "d824e27e8c60172c|2022-07-08--21-21-15--0"), + ("HYUNDAI", "d824e27e8c60172c|2022-08-19--17-58-07--2"), ("TOYOTA", "regenBA97410FBEC|2022-07-06--14-26-49--0"), ("TOYOTA2", "regenDEDB1D9C991|2022-07-06--14-54-08--0"), ("TOYOTA3", "regenDDC1FE60734|2022-07-06--14-32-06--0"), From ddb7f91c9ba7d3aee7fe5da020db9598dc07cf5c Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 19 Aug 2022 23:09:21 -0700 Subject: [PATCH 046/172] remove old boardd stuff --- selfdrive/boardd/tests/boardd_old.py | 245 ---------------------- selfdrive/boardd/tests/replay_many.py | 83 -------- selfdrive/boardd/tests/test_boardd_api.py | 77 ------- 3 files changed, 405 deletions(-) delete mode 100755 selfdrive/boardd/tests/boardd_old.py delete mode 100755 selfdrive/boardd/tests/replay_many.py delete mode 100644 selfdrive/boardd/tests/test_boardd_api.py diff --git a/selfdrive/boardd/tests/boardd_old.py b/selfdrive/boardd/tests/boardd_old.py deleted file mode 100755 index fad29f6f3..000000000 --- a/selfdrive/boardd/tests/boardd_old.py +++ /dev/null @@ -1,245 +0,0 @@ -#!/usr/bin/env python3 -# pylint: skip-file - -# This file is not used by openpilot. Only boardd.cc is used. -# The python version is slower, but has more options for development. - -# TODO: merge the extra functionalities of this file (like MOCK) in boardd.c and -# delete this python version of boardd - -import os -import struct -import time - -import cereal.messaging as messaging -from common.realtime import Ratekeeper -from system.swaglog import cloudlog -from selfdrive.boardd.boardd import can_capnp_to_can_list -from cereal import car - -SafetyModel = car.CarParams.SafetyModel - -# USB is optional -try: - import usb1 - from usb1 import USBErrorIO, USBErrorOverflow # pylint: disable=no-name-in-module -except Exception: - pass - -# *** serialization functions *** -def can_list_to_can_capnp(can_msgs, msgtype='can'): - dat = messaging.new_message(msgtype, len(can_msgs)) - for i, can_msg in enumerate(can_msgs): - if msgtype == 'sendcan': - cc = dat.sendcan[i] - else: - cc = dat.can[i] - cc.address = can_msg[0] - cc.busTime = can_msg[1] - cc.dat = bytes(can_msg[2]) - cc.src = can_msg[3] - return dat - - -# *** can driver *** -def can_health(): - while 1: - try: - dat = handle.controlRead(usb1.TYPE_VENDOR | usb1.RECIPIENT_DEVICE, 0xd2, 0, 0, 0x16) - break - except (USBErrorIO, USBErrorOverflow): - cloudlog.exception("CAN: BAD HEALTH, RETRYING") - v, i = struct.unpack("II", dat[0:8]) - ign_line, ign_can = struct.unpack("BB", dat[20:22]) - return {"voltage": v, "current": i, "ignition_line": bool(ign_line), "ignition_can": bool(ign_can)} - -def __parse_can_buffer(dat): - ret = [] - for j in range(0, len(dat), 0x10): - ddat = dat[j:j+0x10] - f1, f2 = struct.unpack("II", ddat[0:8]) - ret.append((f1 >> 21, f2 >> 16, ddat[8:8 + (f2 & 0xF)], (f2 >> 4) & 0xFF)) - return ret - -def can_send_many(arr): - snds = [] - for addr, _, dat, alt in arr: - if addr < 0x800: # only support 11 bit addr - snd = struct.pack("II", ((addr << 21) | 1), len(dat) | (alt << 4)) + dat - snd = snd.ljust(0x10, b'\x00') - snds.append(snd) - while 1: - try: - handle.bulkWrite(3, b''.join(snds)) - break - except (USBErrorIO, USBErrorOverflow): - cloudlog.exception("CAN: BAD SEND MANY, RETRYING") - -def can_recv(): - dat = b"" - while 1: - try: - dat = handle.bulkRead(1, 0x10*256) - break - except (USBErrorIO, USBErrorOverflow): - cloudlog.exception("CAN: BAD RECV, RETRYING") - return __parse_can_buffer(dat) - -def can_init(): - global handle, context - handle = None - cloudlog.info("attempting can init") - - context = usb1.USBContext() - #context.setDebug(9) - - for device in context.getDeviceList(skip_on_error=True): - if device.getVendorID() == 0xbbaa and device.getProductID() == 0xddcc: - handle = device.open() - handle.claimInterface(0) - handle.controlWrite(0x40, 0xdc, SafetyModel.allOutput, 0, b'') - - if handle is None: - cloudlog.warning("CAN NOT FOUND") - exit(-1) - - cloudlog.info("got handle") - cloudlog.info("can init done") - -def boardd_mock_loop(): - can_init() - handle.controlWrite(0x40, 0xdc, SafetyModel.allOutput, 0, b'') - - logcan = messaging.sub_sock('can') - sendcan = messaging.pub_sock('sendcan') - - while 1: - tsc = messaging.drain_sock(logcan, wait_for_one=True) - snds = map(lambda x: can_capnp_to_can_list(x.can), tsc) - snd = [] - for s in snds: - snd += s - snd = list(filter(lambda x: x[-1] <= 2, snd)) - snd_0 = len(list(filter(lambda x: x[-1] == 0, snd))) - snd_1 = len(list(filter(lambda x: x[-1] == 1, snd))) - snd_2 = len(list(filter(lambda x: x[-1] == 2, snd))) - can_send_many(snd) - - # recv @ 100hz - can_msgs = can_recv() - got_0 = len(list(filter(lambda x: x[-1] == 0+0x80, can_msgs))) - got_1 = len(list(filter(lambda x: x[-1] == 1+0x80, can_msgs))) - got_2 = len(list(filter(lambda x: x[-1] == 2+0x80, can_msgs))) - print("sent %3d (%3d/%3d/%3d) got %3d (%3d/%3d/%3d)" % - (len(snd), snd_0, snd_1, snd_2, len(can_msgs), got_0, got_1, got_2)) - m = can_list_to_can_capnp(can_msgs, msgtype='sendcan') - sendcan.send(m.to_bytes()) - -def boardd_test_loop(): - can_init() - cnt = 0 - while 1: - can_send_many([[0xbb, 0, "\xaa\xaa\xaa\xaa", 0], [0xaa, 0, "\xaa\xaa\xaa\xaa"+struct.pack("!I", cnt), 1]]) - #can_send_many([[0xaa,0,"\xaa\xaa\xaa\xaa",0]]) - #can_send_many([[0xaa,0,"\xaa\xaa\xaa\xaa",1]]) - # recv @ 100hz - can_msgs = can_recv() - print("got %d" % (len(can_msgs))) - time.sleep(0.01) - cnt += 1 - -# *** main loop *** -def boardd_loop(rate=100): - rk = Ratekeeper(rate) - - can_init() - - # *** publishes can and health - logcan = messaging.pub_sock('can') - health_sock = messaging.pub_sock('pandaStates') - - # *** subscribes to can send - sendcan = messaging.sub_sock('sendcan') - - # drain sendcan to delete any stale messages from previous runs - messaging.drain_sock(sendcan) - - while 1: - # health packet @ 2hz - if (rk.frame % (rate // 2)) == 0: - health = can_health() - msg = messaging.new_message('pandaStates', 1) - - # store the health to be logged - msg.pandaState[0].voltage = health['voltage'] - msg.pandaState[0].current = health['current'] - msg.pandaState[0].ignitionLine = health['ignition_line'] - msg.pandaState[0].ignitionCan = health['ignition_can'] - msg.pandaState[0].controlsAllowed = True - - health_sock.send(msg.to_bytes()) - - # recv @ 100hz - can_msgs = can_recv() - - # publish to logger - # TODO: refactor for speed - if len(can_msgs) > 0: - dat = can_list_to_can_capnp(can_msgs).to_bytes() - logcan.send(dat) - - # send can if we have a packet - tsc = messaging.recv_sock(sendcan) - if tsc is not None: - can_send_many(can_capnp_to_can_list(tsc.sendcan)) - - rk.keep_time() - -# *** main loop *** -def boardd_proxy_loop(rate=100, address="192.168.2.251"): - rk = Ratekeeper(rate) - - can_init() - - # *** subscribes can - logcan = messaging.sub_sock('can', addr=address) - # *** publishes to can send - sendcan = messaging.pub_sock('sendcan') - - # drain sendcan to delete any stale messages from previous runs - messaging.drain_sock(sendcan) - - while 1: - # recv @ 100hz - can_msgs = can_recv() - #for m in can_msgs: - # print("R: {0} {1}".format(hex(m[0]), str(m[2]).encode("hex"))) - - # publish to logger - # TODO: refactor for speed - if len(can_msgs) > 0: - dat = can_list_to_can_capnp(can_msgs, "sendcan") - sendcan.send(dat) - - # send can if we have a packet - tsc = messaging.recv_sock(logcan) - if tsc is not None: - cl = can_capnp_to_can_list(tsc.can) - #for m in cl: - # print("S: {0} {1}".format(hex(m[0]), str(m[2]).encode("hex"))) - can_send_many(cl) - - rk.keep_time() - -def main(): - if os.getenv("MOCK") is not None: - boardd_mock_loop() - elif os.getenv("PROXY") is not None: - boardd_proxy_loop() - elif os.getenv("BOARDTEST") is not None: - boardd_test_loop() - else: - boardd_loop() - -if __name__ == "__main__": - main() diff --git a/selfdrive/boardd/tests/replay_many.py b/selfdrive/boardd/tests/replay_many.py deleted file mode 100755 index 78aef0749..000000000 --- a/selfdrive/boardd/tests/replay_many.py +++ /dev/null @@ -1,83 +0,0 @@ -#!/usr/bin/env python3 -import os -import sys -import time -import signal -import traceback -import usb1 -from panda import Panda, PandaDFU -from multiprocessing import Pool - -jungle = "JUNGLE" in os.environ -if jungle: - from panda_jungle import PandaJungle # pylint: disable=import-error - -import cereal.messaging as messaging -from selfdrive.boardd.boardd import can_capnp_to_can_list - -def initializer(): - """Ignore CTRL+C in the worker process. - source: https://stackoverflow.com/a/44869451 """ - signal.signal(signal.SIGINT, signal.SIG_IGN) - -def send_thread(sender_serial): - while True: - try: - if jungle: - sender = PandaJungle(sender_serial) - else: - sender = Panda(sender_serial) - sender.set_safety_mode(Panda.SAFETY_ALLOUTPUT) - - sender.set_can_loopback(False) - can_sock = messaging.sub_sock('can') - - while True: - tsc = messaging.recv_one(can_sock) - snd = can_capnp_to_can_list(tsc.can) - snd = list(filter(lambda x: x[-1] <= 2, snd)) - - try: - sender.can_send_many(snd) - except usb1.USBErrorTimeout: - pass - - # Drain panda message buffer - sender.can_recv() - except Exception: - traceback.print_exc() - time.sleep(1) - -if __name__ == "__main__": - if jungle: - serials = PandaJungle.list() - else: - serials = Panda.list() - num_senders = len(serials) - - if num_senders == 0: - print("No senders found. Exiting") - sys.exit(1) - else: - print("%d senders found. Starting broadcast" % num_senders) - - if "FLASH" in os.environ: - for s in PandaDFU.list(): - PandaDFU(s).recover() - - time.sleep(1) - for s in serials: - Panda(s).recover() - Panda(s).flash() - - pool = Pool(num_senders, initializer=initializer) - pool.map_async(send_thread, serials) - - while True: - try: - time.sleep(10) - except KeyboardInterrupt: - pool.terminate() - pool.join() - raise - diff --git a/selfdrive/boardd/tests/test_boardd_api.py b/selfdrive/boardd/tests/test_boardd_api.py deleted file mode 100644 index f2bcd57a6..000000000 --- a/selfdrive/boardd/tests/test_boardd_api.py +++ /dev/null @@ -1,77 +0,0 @@ -import random -import numpy as np - -import selfdrive.boardd.tests.boardd_old as boardd_old -import selfdrive.boardd.boardd as boardd - -from common.realtime import sec_since_boot -from cereal import log -import unittest - - -def generate_random_can_data_list(): - can_list = [] - cnt = random.randint(1, 64) - for _ in range(cnt): - can_data = np.random.bytes(random.randint(1, 8)) - can_list.append([random.randint(0, 128), random.randint(0, 128), can_data, random.randint(0, 128)]) - return can_list, cnt - - -class TestBoarddApiMethods(unittest.TestCase): - def test_correctness(self): - for i in range(1000): - can_list, _ = generate_random_can_data_list() - - # Sendcan - # Old API - m_old = boardd_old.can_list_to_can_capnp(can_list, 'sendcan').to_bytes() - # new API - m = boardd.can_list_to_can_capnp(can_list, 'sendcan') - - ev_old = log.Event.from_bytes(m_old) - ev = log.Event.from_bytes(m) - - self.assertEqual(ev_old.which(), ev.which()) - self.assertEqual(len(ev.sendcan), len(ev_old.sendcan)) - for i in range(len(ev.sendcan)): - attrs = ['address', 'busTime', 'dat', 'src'] - for attr in attrs: - self.assertEqual(getattr(ev.sendcan[i], attr, 'new'), getattr(ev_old.sendcan[i], attr, 'old')) - - # Can - m_old = boardd_old.can_list_to_can_capnp(can_list, 'can').to_bytes() - # new API - m = boardd.can_list_to_can_capnp(can_list, 'can') - - ev_old = log.Event.from_bytes(m_old) - ev = log.Event.from_bytes(m) - self.assertEqual(ev_old.which(), ev.which()) - self.assertEqual(len(ev.can), len(ev_old.can)) - for i in range(len(ev.can)): - attrs = ['address', 'busTime', 'dat', 'src'] - for attr in attrs: - self.assertEqual(getattr(ev.can[i], attr, 'new'), getattr(ev_old.can[i], attr, 'old')) - - def test_performance(self): - can_list, _ = generate_random_can_data_list() - recursions = 1000 - - n1 = sec_since_boot() - for _ in range(recursions): - boardd_old.can_list_to_can_capnp(can_list, 'sendcan').to_bytes() - n2 = sec_since_boot() - elapsed_old = n2 - n1 - - # print('Old API, elapsed time: {} secs'.format(elapsed_old)) - n1 = sec_since_boot() - for _ in range(recursions): - boardd.can_list_to_can_capnp(can_list) - n2 = sec_since_boot() - elapsed_new = n2 - n1 - # print('New API, elapsed time: {} secs'.format(elapsed_new)) - self.assertTrue(elapsed_new < elapsed_old / 2) - - -if __name__ == '__main__': - unittest.main() From ebea805aa8e45d8a56c1935b5181aa5a1151684f Mon Sep 17 00:00:00 2001 From: Cameron Clough Date: Sat, 20 Aug 2022 07:29:09 +0100 Subject: [PATCH 047/172] Ford: add CADS radar interface (#24296) * Ford: use FORD_CADS radar dbc * Ford: CADS radar interface impl Co-authored-by: ReFil <31960031+ReFil@users.noreply.github.com> * fixup radar interface for FORD_CADS dbc * CADS treat different scan indexes as separate points * Ford: support both Fusion and CADS radars * Ford: rename radars to DELPHI_ESR and DELPHI_MRR Co-authored-by: ReFil <31960031+ReFil@users.noreply.github.com> --- release/files_common | 2 + selfdrive/car/ford/radar_interface.py | 114 +++++++++++++++++++++----- selfdrive/car/ford/values.py | 9 +- 3 files changed, 101 insertions(+), 24 deletions(-) diff --git a/release/files_common b/release/files_common index ac2a3ce62..663d6d355 100644 --- a/release/files_common +++ b/release/files_common @@ -513,6 +513,8 @@ opendbc/gm_global_a_powertrain_generated.dbc opendbc/gm_global_a_object.dbc opendbc/gm_global_a_chassis.dbc +opendbc/FORD_CADS.dbc +opendbc/ford_fusion_2018_adas.dbc opendbc/ford_lincoln_base_pt.dbc opendbc/honda_accord_2018_can_generated.dbc diff --git a/selfdrive/car/ford/radar_interface.py b/selfdrive/car/ford/radar_interface.py index 866602cf0..c94270300 100644 --- a/selfdrive/car/ford/radar_interface.py +++ b/selfdrive/car/ford/radar_interface.py @@ -1,33 +1,63 @@ #!/usr/bin/env python3 +from math import cos, sin from cereal import car -from common.conversions import Conversions as CV from opendbc.can.parser import CANParser -from selfdrive.car.ford.values import CANBUS, DBC +from common.conversions import Conversions as CV +from selfdrive.car.ford.values import CANBUS, DBC, RADAR from selfdrive.car.interfaces import RadarInterfaceBase -RADAR_MSGS = list(range(0x500, 0x540)) +DELPHI_ESR_RADAR_MSGS = list(range(0x500, 0x540)) +DELPHI_MRR_RADAR_START_ADDR = 0x120 +DELPHI_MRR_RADAR_MSG_COUNT = 64 -def _create_radar_can_parser(car_fingerprint): - if DBC[car_fingerprint]['radar'] is None: - return None - msg_n = len(RADAR_MSGS) +def _create_delphi_esr_radar_can_parser(): + msg_n = len(DELPHI_ESR_RADAR_MSGS) signals = list(zip(['X_Rel'] * msg_n + ['Angle'] * msg_n + ['V_Rel'] * msg_n, - RADAR_MSGS * 3)) - checks = list(zip(RADAR_MSGS, [20] * msg_n)) + DELPHI_ESR_RADAR_MSGS * 3)) + checks = list(zip(DELPHI_ESR_RADAR_MSGS, [20] * msg_n)) + + return CANParser(RADAR.DELPHI_ESR, signals, checks, CANBUS.radar) + + +def _create_delphi_mrr_radar_can_parser(): + signals = [] + checks = [] + + for i in range(1, DELPHI_MRR_RADAR_MSG_COUNT + 1): + msg = f"MRR_Detection_{i:03d}" + signals += [ + (f"CAN_DET_VALID_LEVEL_{i:02d}", msg), + (f"CAN_DET_AZIMUTH_{i:02d}", msg), + (f"CAN_DET_RANGE_{i:02d}", msg), + (f"CAN_DET_RANGE_RATE_{i:02d}", msg), + (f"CAN_DET_AMPLITUDE_{i:02d}", msg), + (f"CAN_SCAN_INDEX_2LSB_{i:02d}", msg), + ] + checks += [(msg, 20)] + + return CANParser(RADAR.DELPHI_MRR, signals, checks, CANBUS.radar) - return CANParser(DBC[car_fingerprint]['radar'], signals, checks, CANBUS.radar) class RadarInterface(RadarInterfaceBase): def __init__(self, CP): super().__init__(CP) - self.validCnt = {key: 0 for key in RADAR_MSGS} - self.track_id = 0 - self.rcp = _create_radar_can_parser(CP.carFingerprint) - self.trigger_msg = 0x53f self.updated_messages = set() + self.track_id = 0 + self.radar = DBC[CP.carFingerprint]['radar'] + if self.radar is None: + self.rcp = None + elif self.radar == RADAR.DELPHI_ESR: + self.rcp = _create_delphi_esr_radar_can_parser() + self.trigger_msg = DELPHI_ESR_RADAR_MSGS[-1] + self.valid_cnt = {key: 0 for key in DELPHI_ESR_RADAR_MSGS} + elif self.radar == RADAR.DELPHI_MRR: + self.rcp = _create_delphi_mrr_radar_can_parser() + self.trigger_msg = DELPHI_MRR_RADAR_START_ADDR + DELPHI_MRR_RADAR_MSG_COUNT - 1 + else: + raise ValueError(f"Unsupported radar: {self.radar}") def update(self, can_strings): if self.rcp is None: @@ -45,20 +75,30 @@ class RadarInterface(RadarInterfaceBase): errors.append("canError") ret.errors = errors + if self.radar == RADAR.DELPHI_ESR: + self._update_delphi_esr() + elif self.radar == RADAR.DELPHI_MRR: + self._update_delphi_mrr() + + ret.points = list(self.pts.values()) + self.updated_messages.clear() + return ret + + def _update_delphi_esr(self): for ii in sorted(self.updated_messages): cpt = self.rcp.vl[ii] if cpt['X_Rel'] > 0.00001: - self.validCnt[ii] = 0 # reset counter + self.valid_cnt[ii] = 0 # reset counter if cpt['X_Rel'] > 0.00001: - self.validCnt[ii] += 1 + self.valid_cnt[ii] += 1 else: - self.validCnt[ii] = max(self.validCnt[ii] - 1, 0) - #print ii, self.validCnt[ii], cpt['VALID'], cpt['X_Rel'], cpt['Angle'] + self.valid_cnt[ii] = max(self.valid_cnt[ii] - 1, 0) + #print ii, self.valid_cnt[ii], cpt['VALID'], cpt['X_Rel'], cpt['Angle'] # radar point only valid if there have been enough valid measurements - if self.validCnt[ii] > 0: + if self.valid_cnt[ii] > 0: if ii not in self.pts: self.pts[ii] = car.RadarData.RadarPoint.new_message() self.pts[ii].trackId = self.track_id @@ -73,6 +113,36 @@ class RadarInterface(RadarInterfaceBase): if ii in self.pts: del self.pts[ii] - ret.points = list(self.pts.values()) - self.updated_messages.clear() - return ret + def _update_delphi_mrr(self): + for ii in range(1, DELPHI_MRR_RADAR_MSG_COUNT + 1): + msg = self.rcp.vl[f"MRR_Detection_{ii:03d}"] + + # SCAN_INDEX rotates through 0..3 on each message + # treat these as separate points + scanIndex = msg[f"CAN_SCAN_INDEX_2LSB_{ii:02d}"] + i = (ii - 1) * 4 + scanIndex + + if i not in self.pts: + self.pts[i] = car.RadarData.RadarPoint.new_message() + self.pts[i].trackId = self.track_id + self.pts[i].aRel = float('nan') + self.pts[i].yvRel = float('nan') + self.track_id += 1 + + valid = bool(msg[f"CAN_DET_VALID_LEVEL_{ii:02d}"]) + amplitude = msg[f"CAN_DET_AMPLITUDE_{ii:02d}"] # dBsm [-64|63] + + if valid and 0 < amplitude <= 15: + azimuth = msg[f"CAN_DET_AZIMUTH_{ii:02d}"] # rad [-3.1416|3.13964] + dist = msg[f"CAN_DET_RANGE_{ii:02d}"] # m [0|255.984] + distRate = msg[f"CAN_DET_RANGE_RATE_{ii:02d}"] # m/s [-128|127.984] + + # *** openpilot radar point *** + self.pts[i].dRel = cos(azimuth) * dist # m from front of car + self.pts[i].yRel = -sin(azimuth) * dist # in car frame's y axis, left is positive + self.pts[i].vRel = distRate # m/s + + self.pts[i].measured = True + + else: + del self.pts[i] diff --git a/selfdrive/car/ford/values.py b/selfdrive/car/ford/values.py index 6b8396cf0..825d515da 100644 --- a/selfdrive/car/ford/values.py +++ b/selfdrive/car/ford/values.py @@ -24,6 +24,11 @@ class CarControllerParams: STEER_RATE_LIMIT_DOWN = AngleRateLimit(speed_points=[0., 5., 15.], max_angle_diff_points=[5., 3.5, 0.4]) +class RADAR: + DELPHI_ESR = 'ford_fusion_2018_adas' + DELPHI_MRR = 'FORD_CADS' + + class CANBUS: main = 0 radar = 1 @@ -80,6 +85,6 @@ FW_VERSIONS = { DBC = { - CAR.ESCAPE_MK4: dbc_dict('ford_lincoln_base_pt', None), - CAR.FOCUS_MK4: dbc_dict('ford_lincoln_base_pt', None), + CAR.ESCAPE_MK4: dbc_dict('ford_lincoln_base_pt', RADAR.DELPHI_MRR), + CAR.FOCUS_MK4: dbc_dict('ford_lincoln_base_pt', RADAR.DELPHI_MRR), } From 992ee329e96c80795bab2be98f979c0ae39ee5a2 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 19 Aug 2022 23:41:47 -0700 Subject: [PATCH 048/172] 0.8.16 release notes --- RELEASES.md | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/RELEASES.md b/RELEASES.md index 235e90a3d..169a7af4d 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,8 +1,12 @@ -Version 0.8.16 (2022-XX-XX) +Version 0.8.16 (2022-08-26) ======================== * New driving model * Reduced turn cutting * Auto-detect right hand drive setting with driver monitoring model +* Improved fan controller for comma three +* New translations + * Japanese thanks to cydia2020! + * Brazilian Portuguese thanks to AlexandreSato! * Chevrolet Bolt EUV 2022-23 support thanks to JasonJShuler! * Chevrolet Silverado 2020-21 support thanks to JasonJShuler! * Hyundai Ioniq 5 2022 support thanks to sunnyhaibin! From beae985f989068b6105df1a4698403a3f2329503 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Sat, 20 Aug 2022 14:47:18 -0700 Subject: [PATCH 049/172] test_models: no CAN invalid tolerance (#25501) * don't use end of route segment * no can invalid cnt tolerance * start checking can valid immediately once available * we check counter violations --- selfdrive/car/tests/routes.py | 2 +- selfdrive/car/tests/test_models.py | 12 ++++++++---- 2 files changed, 9 insertions(+), 5 deletions(-) diff --git a/selfdrive/car/tests/routes.py b/selfdrive/car/tests/routes.py index 33467ffcf..532ab7119 100644 --- a/selfdrive/car/tests/routes.py +++ b/selfdrive/car/tests/routes.py @@ -83,7 +83,7 @@ routes = [ TestRoute("4dbd55df87507948|2022-03-01--09-45-38", HYUNDAI.SANTA_FE), TestRoute("bf43d9df2b660eb0|2021-09-23--14-16-37", HYUNDAI.SANTA_FE_2022), TestRoute("37398f32561a23ad|2021-11-18--00-11-35", HYUNDAI.SANTA_FE_HEV_2022), - TestRoute("656ac0d830792fcc|2021-12-28--14-45-56", HYUNDAI.SANTA_FE_PHEV_2022), + TestRoute("656ac0d830792fcc|2021-12-28--14-45-56", HYUNDAI.SANTA_FE_PHEV_2022, segment=1), TestRoute("e0e98335f3ebc58f|2021-03-07--16-38-29", HYUNDAI.KIA_CEED), TestRoute("7653b2bce7bcfdaa|2020-03-04--15-34-32", HYUNDAI.KIA_OPTIMA), TestRoute("c75a59efa0ecd502|2021-03-11--20-52-55", HYUNDAI.KIA_SELTOS), diff --git a/selfdrive/car/tests/test_models.py b/selfdrive/car/tests/test_models.py index 4a1f1a61e..fdf7bca3d 100755 --- a/selfdrive/car/tests/test_models.py +++ b/selfdrive/car/tests/test_models.py @@ -138,19 +138,23 @@ class TestCarModelBase(unittest.TestCase): raise Exception("unkown tuning") def test_car_interface(self): - # TODO: also check for checkusm and counter violations from can parser + # TODO: also check for checksum violations from can parser can_invalid_cnt = 0 + can_valid = False CC = car.CarControl.new_message() for i, msg in enumerate(self.can_msgs): CS = self.CI.update(CC, (msg.as_builder().to_bytes(),)) self.CI.apply(CC) - # wait 2s for low frequency msgs to be seen - if i > 200: + if CS.canValid: + can_valid = True + + # wait max of 2s for low frequency msgs to be seen + if i > 200 or can_valid: can_invalid_cnt += not CS.canValid - self.assertLess(can_invalid_cnt, 50) + self.assertEqual(can_invalid_cnt, 0) def test_radar_interface(self): os.environ['NO_RADAR_SLEEP'] = "1" From f528e9618b0f345039d19c0007539686c433c877 Mon Sep 17 00:00:00 2001 From: Joseph Wagner <68037585+wjoseph0@users.noreply.github.com> Date: Sat, 20 Aug 2022 16:51:50 -0500 Subject: [PATCH 050/172] README.md: update grammar (#25488) * first paragraph * second section * second section pt2 * third section * fifth section * fifth section pt2 * sixth section * Apply suggestions from code review Co-authored-by: Adeeb Shihadeh --- README.md | 26 +++++++++++++------------- 1 file changed, 13 insertions(+), 13 deletions(-) diff --git a/README.md b/README.md index 94837575b..0b6fc2010 100755 --- a/README.md +++ b/README.md @@ -17,7 +17,7 @@ Table of Contents What is openpilot? ------ -[openpilot](http://github.com/commaai/openpilot) is an open source driver assistance system. Currently, openpilot performs the functions of Adaptive Cruise Control (ACC), Automated Lane Centering (ALC), Forward Collision Warning (FCW) and Lane Departure Warning (LDW) for a growing variety of [supported car makes, models and model years](docs/CARS.md). In addition, while openpilot is engaged, a camera based Driver Monitoring (DM) feature alerts distracted and asleep drivers. See more about [the vehicle integration](docs/INTEGRATION.md) and [limitations](docs/LIMITATIONS.md). +[openpilot](http://github.com/commaai/openpilot) is an open source driver assistance system. Currently, openpilot performs the functions of Adaptive Cruise Control (ACC), Automated Lane Centering (ALC), Forward Collision Warning (FCW), and Lane Departure Warning (LDW) for a growing variety of [supported car makes, models, and model years](docs/CARS.md). In addition, while openpilot is engaged, a camera-based Driver Monitoring (DM) feature alerts distracted and asleep drivers. See more about [the vehicle integration](docs/INTEGRATION.md) and [limitations](docs/LIMITATIONS.md). @@ -40,9 +40,9 @@ Running on a dedicated device in a car To use openpilot in a car, you need four things * A supported device to run this software: a [comma three](https://comma.ai/shop/products/three). -* This software. The setup procedure of the comma three allows the user to enter a url for custom software. -The url, openpilot.comma.ai will install the release version of openpilot. To install openpilot master, you can use installer.comma.ai/commaai/master, and replacing commaai with another github username can install a fork. -* One of [the 150+ supported cars](docs/CARS.md). We support Honda, Toyota, Hyundai, Nissan, Kia, Chrysler, Lexus, Acura, Audi, VW, and more. If your car is not supported, but has adaptive cruise control and lane keeping assist, it's likely able to run openpilot. +* This software. The setup procedure of the comma three allows the user to enter a URL for custom software. +The URL, openpilot.comma.ai will install the release version of openpilot. To install openpilot master, you can use installer.comma.ai/commaai/master, and replacing commaai with another GitHub username can install a fork. +* One of [the 150+ supported cars](docs/CARS.md). We support Honda, Toyota, Hyundai, Nissan, Kia, Chrysler, Lexus, Acura, Audi, VW, and more. If your car is not supported but has adaptive cruise control and lane-keeping assist, it's likely able to run openpilot. * A [car harness](https://comma.ai/shop/products/car-harness) to connect to your car. We have detailed instructions for [how to mount the device in a car](https://comma.ai/setup). @@ -52,11 +52,11 @@ Running on PC All of openpilot's services can run as normal on a PC, even without special hardware or a car. To develop or experiment with openpilot you can run openpilot on recorded or simulated data. -With openpilot's tools you can plot logs, replay drives and watch the full-res camera streams. See [the tools README](tools/README.md) for more information. +With openpilot's tools, you can plot logs, replay drives, and watch the full-res camera streams. See [the tools README](tools/README.md) for more information. -You can also run openpilot in simulation [with the CARLA simulator](tools/sim/README.md). This allows openpilot to drive around a virtual car on your Ubuntu machine. The whole setup should only take a few minutes, but does require a decent GPU. +You can also run openpilot in simulation [with the CARLA simulator](tools/sim/README.md). This allows openpilot to drive around a virtual car on your Ubuntu machine. The whole setup should only take a few minutes but does require a decent GPU. -A PC running openpilot can also control your vehicle if it is connected to a [a webcam](https://github.com/commaai/openpilot/tree/master/tools/webcam), a [black panda](https://comma.ai/shop/products/panda), and [a harness](https://comma.ai/shop/products/car-harness). +A PC running openpilot can also control your vehicle if it is connected to a [webcam](https://github.com/commaai/openpilot/tree/master/tools/webcam), a [black panda](https://comma.ai/shop/products/panda), and a [harness](https://comma.ai/shop/products/car-harness). Community and Contributing ------ @@ -78,8 +78,8 @@ By default, openpilot uploads the driving data to our servers. You can also acce openpilot is open source software: the user is free to disable data collection if they wish to do so. -openpilot logs the road facing cameras, CAN, GPS, IMU, magnetometer, thermal sensors, crashes, and operating system logs. -The driver facing camera is only logged if you explicitly opt-in in settings. The microphone is not recorded. +openpilot logs the road-facing cameras, CAN, GPS, IMU, magnetometer, thermal sensors, crashes, and operating system logs. +The driver-facing camera is only logged if you explicitly opt-in in settings. The microphone is not recorded. By using openpilot, you agree to [our Privacy Policy](https://comma.ai/privacy). You understand that use of this software or its related services will generate certain types of user data, which may be logged and stored at the sole discretion of comma. By accepting this agreement, you grant an irrevocable, perpetual, worldwide right to comma for the use of this data. @@ -87,11 +87,11 @@ Safety and Testing ---- * openpilot observes ISO26262 guidelines, see [SAFETY.md](docs/SAFETY.md) for more details. -* openpilot has software in the loop [tests](.github/workflows/selfdrive_tests.yaml) that run on every commit. +* openpilot has software-in-the-loop [tests](.github/workflows/selfdrive_tests.yaml) that run on every commit. * The code enforcing the safety model lives in panda and is written in C, see [code rigor](https://github.com/commaai/panda#code-rigor) for more details. -* panda has software in the loop [safety tests](https://github.com/commaai/panda/tree/master/tests/safety). -* Internally, we have a hardware in the loop Jenkins test suite that builds and unit tests the various processes. -* panda has additional hardware in the loop [tests](https://github.com/commaai/panda/blob/master/Jenkinsfile). +* panda has software-in-the-loop [safety tests](https://github.com/commaai/panda/tree/master/tests/safety). +* Internally, we have a hardware-in-the-loop Jenkins test suite that builds and unit tests the various processes. +* panda has additional hardware-in-the-loop [tests](https://github.com/commaai/panda/blob/master/Jenkinsfile). * We run the latest openpilot in a testing closet containing 10 comma devices continuously replaying routes. Directory Structure From f2f8e7b930ec9c8ca2d264076700933bee7fa7d0 Mon Sep 17 00:00:00 2001 From: Greg Hogan Date: Sat, 20 Aug 2022 23:13:19 -0700 Subject: [PATCH 051/172] setup: perform all pyenv setup in a single place (#23408) * consolidate pyenv setup * cleanup openpilot_env.sh * undo openpilot_env.sh changes * needed on mac * add that back Co-authored-by: Adeeb Shihadeh --- update_requirements.sh | 17 ++++++++++++++++- 1 file changed, 16 insertions(+), 1 deletion(-) diff --git a/update_requirements.sh b/update_requirements.sh index 94b14496f..719a28c35 100755 --- a/update_requirements.sh +++ b/update_requirements.sh @@ -4,11 +4,26 @@ set -e DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null && pwd )" cd $DIR +RC_FILE="${HOME}/.$(basename ${SHELL})rc" +if [ "$(uname)" == "Darwin" ] && [ $SHELL == "/bin/bash" ]; then + RC_FILE="$HOME/.bash_profile" +fi + if ! command -v "pyenv" > /dev/null 2>&1; then echo "pyenv install ..." curl -L https://github.com/pyenv/pyenv-installer/raw/master/bin/pyenv-installer | bash - export PATH=$HOME/.pyenv/bin:$HOME/.pyenv/shims:$PATH + + echo -e "\n. ~/.pyenvrc" >> $RC_FILE + cat < "${HOME}/.pyenvrc" +if [ -z "\$PYENV_ROOT" ]; then + export PATH=\$HOME/.pyenv/bin:\$HOME/.pyenv/shims:\$PATH + export PYENV_ROOT="\$HOME/.pyenv" + eval "\$(pyenv init -)" + eval "\$(pyenv virtualenv-init -)" +fi +EOF fi +source $RC_FILE export MAKEFLAGS="-j$(nproc)" From ed70a9ab1de142dfc3a8afe89a5b3c32b592dda1 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Mon, 22 Aug 2022 05:03:44 +0800 Subject: [PATCH 052/172] v4l_encoder: free buf_out in destructor (#25044) --- selfdrive/loggerd/encoder/v4l_encoder.cc | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/selfdrive/loggerd/encoder/v4l_encoder.cc b/selfdrive/loggerd/encoder/v4l_encoder.cc index b3bd692b1..016e6c570 100644 --- a/selfdrive/loggerd/encoder/v4l_encoder.cc +++ b/selfdrive/loggerd/encoder/v4l_encoder.cc @@ -303,4 +303,10 @@ V4LEncoder::~V4LEncoder() { checked_ioctl(fd, VIDIOC_STREAMOFF, &buf_type); request_buffers(fd, V4L2_BUF_TYPE_VIDEO_CAPTURE_MPLANE, 0); close(fd); + + for (int i = 0; i < BUF_OUT_COUNT; i++) { + if (buf_out[i].free() != 0) { + LOGE("Failed to free buffer"); + } + } } From 62bb70ef2987647e9a9bb93af21f5424c617bafe Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 21 Aug 2022 14:29:52 -0700 Subject: [PATCH 053/172] test onroad: update dmonitoringd cpu usage --- selfdrive/test/test_onroad.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py index 31651706c..93598a1b0 100755 --- a/selfdrive/test/test_onroad.py +++ b/selfdrive/test/test_onroad.py @@ -37,7 +37,7 @@ PROCS = { "selfdrive.thermald.thermald": 3.87, "selfdrive.locationd.calibrationd": 2.0, "./_soundd": 1.0, - "selfdrive.monitoring.dmonitoringd": 1.90, + "selfdrive.monitoring.dmonitoringd": 4.0, "./proclogd": 1.54, "system.logmessaged": 0.2, "./clocksd": 0.02, From 71e76c3d0fa819b8aa9d3580c96b52480febf3d4 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 21 Aug 2022 19:14:36 -0700 Subject: [PATCH 054/172] CI: Actions cleanup + speedup (#25514) * actions cache cleanup * release build cleanup * fetch dpeth --- .github/workflows/badges.yaml | 25 +-- .github/workflows/selfdrive_tests.yaml | 230 +++++-------------------- .github/workflows/setup/action.yaml | 45 +++++ .github/workflows/tools_tests.yaml | 40 ----- 4 files changed, 88 insertions(+), 252 deletions(-) create mode 100644 .github/workflows/setup/action.yaml diff --git a/.github/workflows/badges.yaml b/.github/workflows/badges.yaml index 223c73486..644745920 100644 --- a/.github/workflows/badges.yaml +++ b/.github/workflows/badges.yaml @@ -7,12 +7,7 @@ on: env: BASE_IMAGE: openpilot-base DOCKER_REGISTRY: ghcr.io/commaai - - BUILD: | - docker pull $(grep -iohP '(?<=^from)\s+\S+' Dockerfile.openpilot_base) || true - docker pull $DOCKER_REGISTRY/$BASE_IMAGE:latest || true - docker build --cache-from $DOCKER_REGISTRY/$BASE_IMAGE:latest -t $DOCKER_REGISTRY/$BASE_IMAGE:latest -t $BASE_IMAGE:latest -f Dockerfile.openpilot_base . - RUN: docker run --shm-size 1G -v $PWD:/tmp/openpilot -w /tmp/openpilot -e PYTHONPATH=/tmp/openpilot -e NUM_JOBS -e JOB_ID -e GITHUB_ACTION -e GITHUB_REF -e GITHUB_HEAD_REF -e GITHUB_SHA -e GITHUB_REPOSITORY -e GITHUB_RUN_ID -v /tmp/scons_cache:/tmp/scons_cache -v /tmp/comma_download_cache:/tmp/comma_download_cache -v /tmp/openpilot_cache:/tmp/openpilot_cache $BASE_IMAGE /bin/sh -c + RUN: docker run --shm-size 1G -v $PWD:/tmp/openpilot -w /tmp/openpilot -e PYTHONPATH=/tmp/openpilot -e NUM_JOBS -e JOB_ID -e GITHUB_ACTION -e GITHUB_REF -e GITHUB_HEAD_REF -e GITHUB_SHA -e GITHUB_REPOSITORY -e GITHUB_RUN_ID -v /tmp/scons_cache:/tmp/scons_cache -v /tmp/comma_download_cache:/tmp/comma_download_cache -v /tmp/openpilot_cache:/tmp/openpilot_cache $DOCKER_REGISTRY/$BASE_IMAGE:latest /bin/sh -c jobs: badges: @@ -23,23 +18,7 @@ jobs: - uses: actions/checkout@v3 with: submodules: true - - - name: Cache scons - id: scons-cache - # TODO: Change the version to the released version when https://github.com/actions/cache/pull/489 (or 571) is merged. - uses: actions/cache@03e00da99d75a2204924908e1cca7902cafce66b - env: - CACHE_SKIP_SAVE: true - with: - path: /tmp/scons_cache - key: scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}- - restore-keys: | - scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}- - scons- - - - name: Build Docker image - run: eval "$BUILD" - + - uses: ./.github/workflows/setup - name: Push badges run: | ${{ env.RUN }} "scons -j$(nproc) && python selfdrive/ui/translations/create_badges.py" diff --git a/.github/workflows/selfdrive_tests.yaml b/.github/workflows/selfdrive_tests.yaml index 7397e30f8..8529da8e8 100644 --- a/.github/workflows/selfdrive_tests.yaml +++ b/.github/workflows/selfdrive_tests.yaml @@ -17,7 +17,7 @@ env: docker pull $DOCKER_REGISTRY/$BASE_IMAGE:latest || true docker build --cache-from $DOCKER_REGISTRY/$BASE_IMAGE:latest -t $DOCKER_REGISTRY/$BASE_IMAGE:latest -t $BASE_IMAGE:latest -f Dockerfile.openpilot_base . - RUN: docker run --shm-size 1G -v $PWD:/tmp/openpilot -w /tmp/openpilot -e PYTHONPATH=/tmp/openpilot -e NUM_JOBS -e JOB_ID -e GITHUB_ACTION -e GITHUB_REF -e GITHUB_HEAD_REF -e GITHUB_SHA -e GITHUB_REPOSITORY -e GITHUB_RUN_ID -v /tmp/scons_cache:/tmp/scons_cache -v /tmp/comma_download_cache:/tmp/comma_download_cache -v /tmp/openpilot_cache:/tmp/openpilot_cache $BASE_IMAGE /bin/sh -c + RUN: docker run --shm-size 1G -v $PWD:/tmp/openpilot -w /tmp/openpilot -e FILEREADER_CACHE=1 -e PYTHONPATH=/tmp/openpilot -e NUM_JOBS -e JOB_ID -e GITHUB_ACTION -e GITHUB_REF -e GITHUB_HEAD_REF -e GITHUB_SHA -e GITHUB_REPOSITORY -e GITHUB_RUN_ID -v /tmp/scons_cache:/tmp/scons_cache -v /tmp/comma_download_cache:/tmp/comma_download_cache -v /tmp/openpilot_cache:/tmp/openpilot_cache $BASE_IMAGE /bin/sh -c BUILD_CL: | docker pull $DOCKER_REGISTRY/$CL_BASE_IMAGE:latest || true @@ -27,11 +27,10 @@ env: UNIT_TEST: coverage run --append -m unittest discover jobs: - # TODO: once actions/cache supports read only mode, use the cache for all jobs build_release: name: build release runs-on: ubuntu-20.04 - timeout-minutes: 50 + timeout-minutes: 30 env: STRIPPED_DIR: /tmp/releasepilot steps: @@ -39,44 +38,29 @@ jobs: with: fetch-depth: 0 submodules: true - - name: Pull LFS - run: git lfs pull + - name: Build devel + run: TARGET_DIR=$STRIPPED_DIR release/build_devel.sh + - uses: ./.github/workflows/setup - name: Check submodules if: github.ref == 'refs/heads/master' && github.repository == 'commaai/openpilot' run: release/check-submodules.sh - - name: Cache scons - id: scons-cache - # TODO: Change the version to the released version when https://github.com/actions/cache/pull/489 (or 571) is merged. - uses: actions/cache@03e00da99d75a2204924908e1cca7902cafce66b - env: - CACHE_SKIP_SAVE: true - with: - path: /tmp/scons_cache - key: scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}- - restore-keys: | - scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}- - scons- - - name: Build devel + - name: Build openpilot and run checks + run: | + cd $STRIPPED_DIR + ${{ env.RUN }} "CI=1 python selfdrive/manager/build.py" + - name: Run tests run: | - TARGET_DIR=$STRIPPED_DIR release/build_devel.sh - cp Dockerfile.openpilot_base $STRIPPED_DIR + cd $STRIPPED_DIR + ${{ env.RUN }} "release/check-dirty.sh && \ + python -m unittest discover selfdrive/car" + - name: pre-commit + run: | + cd $GITHUB_WORKSPACE cp .pre-commit-config.yaml $STRIPPED_DIR cp .pylintrc $STRIPPED_DIR cp mypy.ini $STRIPPED_DIR - - name: Build Docker image - run: | - eval "$BUILD" - rm $STRIPPED_DIR/Dockerfile.openpilot_base - - name: Build openpilot and run checks - run: | - cd $STRIPPED_DIR - ${{ env.RUN }} "CI=1 python selfdrive/manager/build.py && \ - pre-commit run --all && \ - rm .pre-commit-config.yaml && \ - rm .pylintrc && \ - rm mypy.ini && \ - release/check-dirty.sh && \ - python -m unittest discover selfdrive/car" + cd $STRIPPED_DIR + ${{ env.RUN }} "pre-commit run --all" build_all: name: build all @@ -86,26 +70,14 @@ jobs: - uses: actions/checkout@v3 with: submodules: true - - name: Cache scons - id: scons-cache - # TODO: Change the version to the released version when https://github.com/actions/cache/pull/489 (or 571) is merged. - uses: actions/cache@03e00da99d75a2204924908e1cca7902cafce66b - env: - CACHE_SKIP_SAVE: ${{ github.ref != 'refs/heads/master' || github.repository != 'commaai/openpilot' }} + - uses: ./.github/workflows/setup with: - path: /tmp/scons_cache - key: scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}-${{ steps.date.outputs.time }} - restore-keys: | - scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}- - scons- - - name: Build Docker image - run: eval "$BUILD" + save-cache: true - name: Build openpilot with all flags run: ${{ env.RUN }} "scons -j$(nproc) --extras --test && release/check-dirty.sh" - name: Cleanup scons cache run: | - ${{ env.RUN }} "scons -j$(nproc) --extras --test && \ - rm -rf /tmp/scons_cache/* && \ + ${{ env.RUN }} "rm -rf /tmp/scons_cache/* && \ scons -j$(nproc) --extras --test --cache-populate" #build_mac: @@ -175,21 +147,9 @@ jobs: - uses: actions/checkout@v3 with: submodules: true - - name: Cache scons - id: scons-cache - # TODO: Change the version to the released version when https://github.com/actions/cache/pull/489 (or 571) is merged. - uses: actions/cache@03e00da99d75a2204924908e1cca7902cafce66b - env: - CACHE_SKIP_SAVE: true - with: - path: /tmp/scons_cache - key: scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}- - restore-keys: | - scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}- - scons- + - uses: ./.github/workflows/setup - name: Build Docker image run: | - eval "$BUILD" docker pull $DOCKER_REGISTRY/$IMAGE_NAME:latest || true docker build --cache-from $DOCKER_REGISTRY/$IMAGE_NAME:latest -t $DOCKER_REGISTRY/$IMAGE_NAME:latest -f tools/webcam/Dockerfile . - name: Build openpilot @@ -244,30 +204,11 @@ jobs: - uses: actions/checkout@v3 with: submodules: true - - name: Cache dependencies - id: dependency-cache - uses: actions/cache@v2 - with: - path: /tmp/comma_download_cache - key: ${{ hashFiles('.github/workflows/selfdrive_tests.yaml', 'selfdrive/test/test_valgrind_replay.py') }} - - name: Cache scons - id: scons-cache - # TODO: Change the version to the released version when https://github.com/actions/cache/pull/489 (or 571) is merged. - uses: actions/cache@03e00da99d75a2204924908e1cca7902cafce66b - env: - CACHE_SKIP_SAVE: true - with: - path: /tmp/scons_cache - key: scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}- - restore-keys: | - scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}- - scons- - - name: Build Docker image - run: eval "$BUILD" + - uses: ./.github/workflows/setup - name: Run valgrind run: | ${{ env.RUN }} "scons -j$(nproc) && \ - FILEREADER_CACHE=1 python selfdrive/test/test_valgrind_replay.py" + python selfdrive/test/test_valgrind_replay.py" - name: Print logs if: always() run: cat selfdrive/test/valgrind_logs.txt @@ -277,28 +218,10 @@ jobs: runs-on: ubuntu-20.04 timeout-minutes: 50 steps: - - name: Get current date - id: date - run: echo "::set-output name=time::$(date +'%s')" - - name: Output timestamp - run: echo $TIMESTAMP - env: - TIMESTAMP: ${{ steps.date.outputs.time }} - uses: actions/checkout@v3 with: submodules: true - - name: Cache scons - id: scons-cache - # TODO: Change the version to the released version when https://github.com/actions/cache/pull/489 (or 571) is merged. - uses: actions/cache@03e00da99d75a2204924908e1cca7902cafce66b - env: - CACHE_SKIP_SAVE: ${{ github.ref != 'refs/heads/master' || github.repository != 'commaai/openpilot' }} - with: - path: /tmp/scons_cache - key: scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}-${{ steps.date.outputs.time }} - restore-keys: scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}- - - name: Build Docker image - run: eval "$BUILD" + - uses: ./.github/workflows/setup - name: Run unit tests run: | ${{ env.RUN }} "export SKIP_LONG_TESTS=1 && \ @@ -339,30 +262,17 @@ jobs: - uses: actions/checkout@v3 with: submodules: true - - name: Cache dependencies + - uses: ./.github/workflows/setup + - name: Cache test routes id: dependency-cache - uses: actions/cache@v2 + uses: actions/cache@v3 with: path: /tmp/comma_download_cache - key: ${{ hashFiles('.github/workflows/selfdrive_tests.yaml', 'selfdrive/test/process_replay/test_processes.py') }} - - name: Cache scons - id: scons-cache - # TODO: Change the version to the released version when https://github.com/actions/cache/pull/489 (or 571) is merged. - uses: actions/cache@03e00da99d75a2204924908e1cca7902cafce66b - env: - CACHE_SKIP_SAVE: true - with: - path: /tmp/scons_cache - key: scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}- - restore-keys: | - scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}- - scons- - - name: Build Docker image - run: eval "$BUILD" + key: proc-replay-${{ hashFiles('.github/workflows/selfdrive_tests.yaml', 'selfdrive/test/process_replay/ref_commit') }} - name: Run replay run: | ${{ env.RUN }} "scons -j$(nproc) && \ - FILEREADER_CACHE=1 CI=1 coverage run selfdrive/test/process_replay/test_processes.py -j$(nproc) && \ + CI=1 coverage run selfdrive/test/process_replay/test_processes.py -j$(nproc) && \ coverage xml" - name: Print diff if: always() @@ -389,35 +299,16 @@ jobs: - uses: actions/checkout@v3 with: submodules: true - - name: Pull LFS - run: git lfs pull - - name: Cache dependencies - id: dependency-cache - uses: actions/cache@v2 - with: - path: /tmp/comma_download_cache - key: ${{ hashFiles('.github/workflows/selfdrive_tests.yaml', 'selfdrive/test/process_replay/model_replay.py') }} - - name: Cache scons - id: scons-cache - # TODO: Change the version to the released version when https://github.com/actions/cache/pull/489 (or 571) is merged. - uses: actions/cache@03e00da99d75a2204924908e1cca7902cafce66b - env: - CACHE_SKIP_SAVE: true - with: - path: /tmp/scons_cache - key: scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}- - restore-keys: | - scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}- - scons- + - uses: ./.github/workflows/setup - name: Build Docker image - # Sim docker is needed to get the intel OPENCL drivers + # Sim docker is needed to get the OpenCL drivers run: eval "$BUILD_CL" - name: Run replay run: | ${{ env.RUN_CL }} "scons -j$(nproc) && \ - ONNXCPU=1 FILEREADER_CACHE=1 CI=1 coverage run \ - selfdrive/test/process_replay/model_replay.py -j$(nproc) && \ - coverage xml" + ONNXCPU=1 CI=1 coverage run \ + selfdrive/test/process_replay/model_replay.py -j$(nproc) && \ + coverage xml" test_longitudinal: name: longitudinal @@ -427,20 +318,7 @@ jobs: - uses: actions/checkout@v3 with: submodules: true - - name: Cache scons - id: scons-cache - # TODO: Change the version to the released version when https://github.com/actions/cache/pull/489 (or 571) is merged. - uses: actions/cache@03e00da99d75a2204924908e1cca7902cafce66b - env: - CACHE_SKIP_SAVE: true - with: - path: /tmp/scons_cache - key: scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}- - restore-keys: | - scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}- - scons- - - name: Build Docker image - run: eval "$BUILD" + - uses: ./.github/workflows/setup - name: Test longitudinal run: | ${{ env.RUN }} "mkdir -p selfdrive/test/out && \ @@ -469,30 +347,17 @@ jobs: - uses: actions/checkout@v3 with: submodules: true - - name: Cache dependencies + - uses: ./.github/workflows/setup + - name: Cache test routes id: dependency-cache - uses: actions/cache@v2 + uses: actions/cache@03e00da99d75a2204924908e1cca7902cafce66b with: path: /tmp/comma_download_cache key: car_models-${{ hashFiles('selfdrive/car/tests/test_models.py', 'selfdrive/car/tests/routes.py') }}-${{ matrix.job }} - - name: Cache scons - id: scons-cache - # TODO: Change the version to the released version when https://github.com/actions/cache/pull/489 (or 571) is merged. - uses: actions/cache@03e00da99d75a2204924908e1cca7902cafce66b - env: - CACHE_SKIP_SAVE: true - with: - path: /tmp/scons_cache - key: scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}- - restore-keys: | - scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}- - scons- - - name: Build Docker image - run: eval "$BUILD" - name: Test car models run: | ${{ env.RUN }} "scons -j$(nproc) --test && \ - FILEREADER_CACHE=1 coverage run -m pytest selfdrive/car/tests/test_models.py && \ + coverage run -m pytest selfdrive/car/tests/test_models.py && \ coverage xml && \ chmod -R 777 /tmp/comma_download_cache" env: @@ -530,20 +395,7 @@ jobs: with: submodules: true ref: ${{ github.event.pull_request.base.ref }} - - name: Cache scons - id: scons-cache - # TODO: Change the version to the released version when https://github.com/actions/cache/pull/489 (or 571) is merged. - uses: actions/cache@03e00da99d75a2204924908e1cca7902cafce66b - env: - CACHE_SKIP_SAVE: true - with: - path: /tmp/scons_cache - key: scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}- - restore-keys: | - scons-${{ hashFiles('.github/workflows/selfdrive_tests.yaml') }}- - scons- - - name: Build Docker image - run: eval "$BUILD" + - uses: ./.github/workflows/setup - name: Get base car info run: | ${{ env.RUN }} "scons -j$(nproc) && python selfdrive/debug/dump_car_info.py --path /tmp/openpilot_cache/base_car_info" diff --git a/.github/workflows/setup/action.yaml b/.github/workflows/setup/action.yaml new file mode 100644 index 000000000..79ec92123 --- /dev/null +++ b/.github/workflows/setup/action.yaml @@ -0,0 +1,45 @@ +name: 'openpilot env setup' + +env: + BASE_IMAGE: openpilot-base + DOCKER_REGISTRY: ghcr.io/commaai + BUILD: | + docker pull $(grep -iohP '(?<=^from)\s+\S+' Dockerfile.openpilot_base) || true + docker pull $DOCKER_REGISTRY/$BASE_IMAGE:latest || true + docker build --cache-from $DOCKER_REGISTRY/$BASE_IMAGE:latest -t $DOCKER_REGISTRY/$BASE_IMAGE:latest -t $BASE_IMAGE:latest -f Dockerfile.openpilot_base . + +inputs: + save-cache: + default: false + required: false + +runs: + using: "composite" + steps: + # do this after checkout to ensure our custom LFS config is used to pull from GitLab + - shell: bash + run: git lfs pull + + # build cache + - id: date + shell: bash + run: echo "::set-output name=date::$(git log -1 --pretty='format:%cd' --date=format:'%Y-%m-%d')" + - shell: bash + run: echo "${{ steps.date.outputs.date }}" + - shell: bash + run: echo "CACHE_SKIP_SAVE=true" >> $GITHUB_ENV + if: github.ref != 'refs/heads/master' || inputs.save-cache == 'false' + - id: scons-cache + # TODO: change the version to the released version + # when https://github.com/actions/cache/pull/489 (or 571) is merged. + uses: actions/cache@03e00da99d75a2204924908e1cca7902cafce66b + with: + path: /tmp/scons_cache + key: scons-${{ steps.date.outputs.date }}-${{ github.sha }} + restore-keys: | + scons-${{ steps.date.outputs.date }}- + scons- + + # build our docker image + - shell: bash + run: eval "$BUILD" diff --git a/.github/workflows/tools_tests.yaml b/.github/workflows/tools_tests.yaml index e93ce2bb3..173e20838 100644 --- a/.github/workflows/tools_tests.yaml +++ b/.github/workflows/tools_tests.yaml @@ -21,46 +21,6 @@ env: GITHUB_REPOSITORY -e GITHUB_RUN_ID -v /tmp/comma_download_cache:/tmp/comma_download_cache $BASE_IMAGE /bin/sh -c jobs: - build_latest_ubuntu: - name: build latest ubuntu - runs-on: ubuntu-20.04 - timeout-minutes: 60 - steps: - - uses: actions/checkout@v3 - with: - submodules: true - - name: Cache pyenv - id: ubuntu-latest-pyenv - uses: actions/cache@v3 - with: - path: | - ~/.pyenv - ~/.local/share/virtualenvs/ - key: ubuntu-latest-python-${{ hashFiles('tools/ubuntu_setup.sh') }}- - - name: Cache scons - id: ubuntu-latest-scons - uses: actions/cache@v3 - with: - path: /tmp/scons_cache - key: ubuntu-latest-scons-${{ hashFiles('.github/workflows/tools_test.yaml') }}- - restore-keys: | - ubuntu-latest-scons-${{ hashFiles('.github/workflows/tools_test.yaml') }}- - ubuntu-latest-scons- - - - name: tools/ubuntu_setup.sh - run: | - source tools/openpilot_env.sh - tools/ubuntu_setup.sh - - name: Build openpilot - run: | - source tools/openpilot_env.sh - pipenv run scons -j$(nproc) --extras --test - - name: Cleanup scons cache - run: | - source tools/openpilot_env.sh - rm -rf /tmp/scons_cache/* - pipenv run scons -j$(nproc) --extras --test --cache-populate - plotjuggler: name: plotjuggler runs-on: ubuntu-20.04 From f65547fbe25501c1f6a1f7d0397a266dffa0e0ff Mon Sep 17 00:00:00 2001 From: Cameron Clough Date: Mon, 22 Aug 2022 16:23:36 -0700 Subject: [PATCH 055/172] sim: fix gps message (#25521) fix gps timestamp field renamed bug introduced in https://github.com/commaai/cereal/pull/341 --- tools/sim/bridge.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tools/sim/bridge.py b/tools/sim/bridge.py index fa4ce2b41..f008b9e71 100755 --- a/tools/sim/bridge.py +++ b/tools/sim/bridge.py @@ -179,7 +179,7 @@ def gps_callback(gps, vehicle_state): ] dat.gpsLocationExternal = { - "timestamp": int(time.time() * 1000), + "unixTimestampMillis": int(time.time() * 1000), "flags": 1, # valid fix "accuracy": 1.0, "verticalAccuracy": 1.0, From 68ba8df69329024e57efdbd00740acc0d298f214 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 22 Aug 2022 17:35:04 -0700 Subject: [PATCH 056/172] GMC: Sierra 2020-21 support (#25523) * Add Sierra * actually this package works * add to releases * credit --- RELEASES.md | 1 + docs/CARS.md | 3 ++- selfdrive/car/gm/values.py | 5 ++++- 3 files changed, 7 insertions(+), 2 deletions(-) diff --git a/RELEASES.md b/RELEASES.md index 169a7af4d..4b33ea8dc 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -9,6 +9,7 @@ Version 0.8.16 (2022-08-26) * Brazilian Portuguese thanks to AlexandreSato! * Chevrolet Bolt EUV 2022-23 support thanks to JasonJShuler! * Chevrolet Silverado 2020-21 support thanks to JasonJShuler! +* GMC Sierra 1500 2020-21 support thanks to JasonJShuler! * Hyundai Ioniq 5 2022 support thanks to sunnyhaibin! * Hyundai Kona Electric 2022 support thanks to sunnyhaibin! * Hyundai Tucson Hybrid 2022 support thanks to sunnyhaibin! diff --git a/docs/CARS.md b/docs/CARS.md index 2a1f770b7..24be43e4f 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 device. Every car performs differently with openpilot, but all supported cars should provide a better experience than any stock system. -# 204 Supported Cars +# 205 Supported Cars |Make|Model|Supported Package|ACC|No ACC accel below|No ALC below|Steering Torque|Harness| |---|---|---|:---:|:---:|:---:|:---:|:---:| @@ -32,6 +32,7 @@ A supported vehicle is one that just works when you install a comma device. Ever |Genesis|G80 2017-19|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai H| |Genesis|G90 2017-18|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai C| |GMC|Acadia 2018[1](#footnotes)|Adaptive Cruise Control|openpilot|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|OBD-II| +|GMC|Sierra 1500 2020-21|Driver Alert Package II|Stock|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|GM| |Honda|Accord 2018-22|All|Stock|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|Honda Bosch A| |Honda|Accord Hybrid 2018-22|All|Stock|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|Honda Bosch A| |Honda|Civic 2016-18|Honda Sensing|openpilot|0 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|Honda Nidec| diff --git a/selfdrive/car/gm/values.py b/selfdrive/car/gm/values.py index df91938d8..14022d23d 100644 --- a/selfdrive/car/gm/values.py +++ b/selfdrive/car/gm/values.py @@ -85,7 +85,10 @@ CAR_INFO: Dict[str, Union[GMCarInfo, List[GMCarInfo]]] = { CAR.BUICK_REGAL: GMCarInfo("Buick Regal Essence 2018"), CAR.ESCALADE_ESV: GMCarInfo("Cadillac Escalade ESV 2016", "Adaptive Cruise Control (ACC) & LKAS"), CAR.BOLT_EUV: GMCarInfo("Chevrolet Bolt EUV 2022-23", "Premier or Premier Redline Trim without Super Cruise Package", video_link="https://youtu.be/xvwzGMUA210", footnotes=[], harness=Harness.gm), - CAR.SILVERADO: GMCarInfo("Chevrolet Silverado 1500 2020-21", "Safety Package II", footnotes=[], harness=Harness.gm), + CAR.SILVERADO: [ + GMCarInfo("Chevrolet Silverado 1500 2020-21", "Safety Package II", footnotes=[], harness=Harness.gm), + GMCarInfo("GMC Sierra 1500 2020-21", "Driver Alert Package II", footnotes=[], harness=Harness.gm), + ], } From 0822f94bb4545bb9427d1525b157edbf46416fe7 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 22 Aug 2022 17:45:41 -0700 Subject: [PATCH 057/172] GM: add Silverado 2021 High Country FP (#25499) * Add FP from 61c6258cac78af08 * add to dict --- selfdrive/car/gm/values.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/car/gm/values.py b/selfdrive/car/gm/values.py index 14022d23d..21ede171e 100644 --- a/selfdrive/car/gm/values.py +++ b/selfdrive/car/gm/values.py @@ -164,7 +164,7 @@ FINGERPRINTS = { }], CAR.SILVERADO: [ { - 190: 6, 193: 8, 197: 8, 201: 8, 208: 8, 209: 7, 211: 2, 241: 6, 249: 8, 257: 8, 288: 5, 289: 8, 298: 8, 304: 3, 309: 8, 311: 8, 313: 8, 320: 4, 322: 7, 328: 1, 352: 5, 381: 8, 384: 4, 386: 8, 388: 8, 413: 8, 451: 8, 452: 8, 453: 6, 455: 7, 460: 5, 463: 3, 479: 3, 481: 7, 485: 8, 489: 8, 497: 8, 500: 6, 501: 8, 528: 5, 532: 6, 560: 8, 562: 8, 563: 5, 565: 5, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 707: 8, 715: 8, 717: 5, 761: 7, 789: 5, 800: 6, 810: 8, 840: 5, 842: 5, 844: 8, 848: 4, 869: 4, 880: 6, 977: 8, 1001: 8, 1011: 6, 1017: 8, 1020: 8, 1033: 7, 1034: 7, 1217: 8, 1221: 5, 1233: 8, 1249: 8, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1271: 8, 1280: 4, 1296: 4, 1300: 8, 1930: 7 + 190: 6, 193: 8, 197: 8, 201: 8, 208: 8, 209: 7, 211: 2, 241: 6, 249: 8, 257: 8, 288: 5, 289: 8, 298: 8, 304: 3, 309: 8, 311: 8, 313: 8, 320: 4, 322: 7, 328: 1, 352: 5, 381: 8, 384: 4, 386: 8, 388: 8, 413: 8, 451: 8, 452: 8, 453: 6, 455: 7, 460: 5, 463: 3, 479: 3, 481: 7, 485: 8, 489: 8, 497: 8, 500: 6, 501: 8, 528: 5, 532: 6, 534: 2, 560: 8, 562: 8, 563: 5, 565: 5, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 707: 8, 715: 8, 717: 5, 761: 7, 789: 5, 800: 6, 801: 8, 810: 8, 840: 5, 842: 5, 844: 8, 848: 4, 869: 4, 880: 6, 977: 8, 1001: 8, 1011: 6, 1017: 8, 1020: 8, 1033: 7, 1034: 7, 1217: 8, 1221: 5, 1233: 8, 1249: 8, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1271: 8, 1280: 4, 1296: 4, 1300: 8, 1930: 7 }], } From e84f397a72e7a7e76ea6c81ae9b627b41dd45e17 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 22 Aug 2022 19:15:32 -0700 Subject: [PATCH 058/172] Update Silverado release note (#25526) --- RELEASES.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/RELEASES.md b/RELEASES.md index 4b33ea8dc..a6ba4558e 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -8,7 +8,7 @@ Version 0.8.16 (2022-08-26) * Japanese thanks to cydia2020! * Brazilian Portuguese thanks to AlexandreSato! * Chevrolet Bolt EUV 2022-23 support thanks to JasonJShuler! -* Chevrolet Silverado 2020-21 support thanks to JasonJShuler! +* Chevrolet Silverado 1500 2020-21 support thanks to JasonJShuler! * GMC Sierra 1500 2020-21 support thanks to JasonJShuler! * Hyundai Ioniq 5 2022 support thanks to sunnyhaibin! * Hyundai Kona Electric 2022 support thanks to sunnyhaibin! From ad8d3de0d9abedc7c9db177b6c4a6b1a0fb03020 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 22 Aug 2022 20:39:54 -0700 Subject: [PATCH 059/172] Translations badges: concatenate into one badge (#25522) * add badge done correctly works Update translation_badge.svg Update translation_badge.svg Update translation_badge.svg Update README.md Update translation_badge.svg Update translation_badge.svg Update translation_badge.svg Update badge Update README.md test this try this finalize remove badges fixup readme add to test fix fix rm * clean up * no formats --- selfdrive/ui/translations/README.md | 7 +------ selfdrive/ui/translations/create_badges.py | 23 ++++++++++++++-------- 2 files changed, 16 insertions(+), 14 deletions(-) diff --git a/selfdrive/ui/translations/README.md b/selfdrive/ui/translations/README.md index 5d4698614..ac3112c61 100644 --- a/selfdrive/ui/translations/README.md +++ b/selfdrive/ui/translations/README.md @@ -1,11 +1,6 @@ # Multilanguage -[![language](https://raw.githubusercontent.com/commaai/openpilot/badges/translation_badge_main_en.svg)](https://github.com/commaai/openpilot/blob/master/selfdrive/ui/translations/main_en.ts) -[![language](https://raw.githubusercontent.com/commaai/openpilot/badges/translation_badge_main_pt.svg)](https://github.com/commaai/openpilot/blob/master/selfdrive/ui/translations/main_pt.ts) -[![language](https://raw.githubusercontent.com/commaai/openpilot/badges/translation_badge_main_zh-CHT.svg)](https://github.com/commaai/openpilot/blob/master/selfdrive/ui/translations/main_zh-CHT.ts) -[![language](https://raw.githubusercontent.com/commaai/openpilot/badges/translation_badge_main_zh-CHS.svg)](https://github.com/commaai/openpilot/blob/master/selfdrive/ui/translations/main_zh-CHS.ts) -[![language](https://raw.githubusercontent.com/commaai/openpilot/badges/translation_badge_main_ko.svg)](https://github.com/commaai/openpilot/blob/master/selfdrive/ui/translations/main_ko.ts) -[![language](https://raw.githubusercontent.com/commaai/openpilot/badges/translation_badge_main_ja.svg)](https://github.com/commaai/openpilot/blob/master/selfdrive/ui/translations/main_ja.ts) +[![languages](https://raw.githubusercontent.com/commaai/openpilot/badges/translation_badge.svg)](#) ## Contributing diff --git a/selfdrive/ui/translations/create_badges.py b/selfdrive/ui/translations/create_badges.py index d9e2d443b..451fbb23e 100755 --- a/selfdrive/ui/translations/create_badges.py +++ b/selfdrive/ui/translations/create_badges.py @@ -8,20 +8,17 @@ from selfdrive.ui.update_translations import LANGUAGES_FILE, TRANSLATIONS_DIR TRANSLATION_TAG = "'] + for idx, (name, file) in enumerate(translation_files.items()): with open(os.path.join(TRANSLATIONS_DIR, f"{file}.ts"), "r") as tr_f: tr_file = tr_f.read() - print(f"[![language](https://raw.githubusercontent.com/commaai/openpilot/badges/{TRANSLATION_BADGE.format(file)})]({TRANSLATION_LINK.format(file)}.ts)") - total_translations = 0 unfinished_translations = 0 for line in tr_file.splitlines(): @@ -35,6 +32,16 @@ if __name__ == "__main__": r = requests.get(f"https://img.shields.io/badge/LANGUAGE {name}-{percent_finished}%25 complete-{color}") assert r.status_code == 200, "Error downloading badge" + content_svg = r.content.decode("utf-8") + + # make tag ids in each badge unique + for tag in ("r", "s"): + content_svg = content_svg.replace(f'id="{tag}"', f'id="{tag}{idx}"') + content_svg = content_svg.replace(f'"url(#{tag})"', f'"url(#{tag}{idx})"') + + badge_svg.extend([f'', content_svg, ""]) + + badge_svg.append("") - with open(os.path.join(BASEDIR, TRANSLATION_BADGE.format(file)), "wb") as badge_f: - badge_f.write(r.content) + with open(os.path.join(BASEDIR, "translation_badge.svg"), "w") as badge_f: + badge_f.write("\n".join(badge_svg)) From 10e414f9905d7d5ff9441b598d2a0285a618775b Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 22 Aug 2022 20:54:02 -0700 Subject: [PATCH 060/172] Fix badge workflow --- .github/workflows/badges.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/badges.yaml b/.github/workflows/badges.yaml index 644745920..16edb45c2 100644 --- a/.github/workflows/badges.yaml +++ b/.github/workflows/badges.yaml @@ -28,6 +28,6 @@ jobs: git config user.email "badge-researcher@comma.ai" git config user.name "Badge Researcher" - git add translation_badge_*.svg + git add translation_badge.svg git commit -m "Add/Update badges" git push -f origin HEAD From b3cfe962cf346e70cce1389fe3c9bf23344a5512 Mon Sep 17 00:00:00 2001 From: Cameron Clough Date: Mon, 22 Aug 2022 21:47:09 -0700 Subject: [PATCH 061/172] user event flagging (#25517) * setup home_btn in sidebar * create UserFlag msg * replay: show and skip to user flags * update translations * bump to cereal master * remove comment Co-authored-by: Adeeb Shihadeh --- cereal | 2 +- selfdrive/ui/qt/sidebar.cc | 11 ++++++-- selfdrive/ui/qt/sidebar.h | 4 +++ selfdrive/ui/translations/main_ja.ts | 34 ++++++++++++------------ selfdrive/ui/translations/main_ko.ts | 34 ++++++++++++------------ selfdrive/ui/translations/main_pt.ts | 34 ++++++++++++------------ selfdrive/ui/translations/main_zh-CHS.ts | 34 ++++++++++++------------ selfdrive/ui/translations/main_zh-CHT.ts | 34 ++++++++++++------------ tools/replay/consoleui.cc | 8 ++++++ tools/replay/replay.cc | 9 ++++++- tools/replay/replay.h | 5 ++-- 11 files changed, 118 insertions(+), 91 deletions(-) diff --git a/cereal b/cereal index ecff0a284..589ef049a 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit ecff0a284a2aa9879c4d04ea797356e4ef024dc4 +Subproject commit 589ef049a7b0bac31f4c8987c0fc539839fae489 diff --git a/selfdrive/ui/qt/sidebar.cc b/selfdrive/ui/qt/sidebar.cc index accab67bf..a84542d29 100644 --- a/selfdrive/ui/qt/sidebar.cc +++ b/selfdrive/ui/qt/sidebar.cc @@ -33,7 +33,7 @@ void Sidebar::drawMetric(QPainter &p, const QPair &label, QCol } Sidebar::Sidebar(QWidget *parent) : QFrame(parent) { - home_img = loadPixmap("../assets/images/button_home.png", {180, 180}); + home_img = loadPixmap("../assets/images/button_home.png", home_btn.size()); settings_img = loadPixmap("../assets/images/button_settings.png", settings_btn.size(), Qt::IgnoreAspectRatio); connect(this, &Sidebar::valueChanged, [=] { update(); }); @@ -43,9 +43,16 @@ Sidebar::Sidebar(QWidget *parent) : QFrame(parent) { setFixedWidth(300); QObject::connect(uiState(), &UIState::uiUpdate, this, &Sidebar::updateState); + + pm = std::make_unique>({"userFlag"}); } void Sidebar::mouseReleaseEvent(QMouseEvent *event) { + if (home_btn.contains(event->pos())) { + MessageBuilder msg; + msg.initEvent().initUserFlag(); + pm->send("userFlag", msg); + } if (settings_btn.contains(event->pos())) { emit openSettings(); } @@ -99,7 +106,7 @@ void Sidebar::paintEvent(QPaintEvent *event) { p.setOpacity(0.65); p.drawPixmap(settings_btn.x(), settings_btn.y(), settings_img); p.setOpacity(1.0); - p.drawPixmap(60, 1080 - 180 - 40, home_img); + p.drawPixmap(home_btn.x(), home_btn.y(), home_img); // network int x = 58; diff --git a/selfdrive/ui/qt/sidebar.h b/selfdrive/ui/qt/sidebar.h index 4c6d8f47e..0140673aa 100644 --- a/selfdrive/ui/qt/sidebar.h +++ b/selfdrive/ui/qt/sidebar.h @@ -43,6 +43,7 @@ protected: {cereal::DeviceState::NetworkType::CELL5_G, tr("5G")} }; + const QRect home_btn = QRect(60, 860, 180, 180); const QRect settings_btn = QRect(50, 35, 200, 117); const QColor good_color = QColor(255, 255, 255); const QColor warning_color = QColor(218, 202, 37); @@ -52,4 +53,7 @@ protected: ItemStatus connect_status, panda_status, temp_status; QString net_type; int net_strength = 0; + +private: + std::unique_ptr pm; }; diff --git a/selfdrive/ui/translations/main_ja.ts b/selfdrive/ui/translations/main_ja.ts index b66bc4b80..79c982f81 100644 --- a/selfdrive/ui/translations/main_ja.ts +++ b/selfdrive/ui/translations/main_ja.ts @@ -876,71 +876,71 @@ location set Sidebar - - + + CONNECT 接続 - + OFFLINE オフライン - - + + ONLINE オンライン - + ERROR エラー - - - + + + TEMP 温度 - + HIGH 高温 - + GOOD 最適 - + OK OK - + VEHICLE 車両 - + NO NO - + PANDA PANDA - + GPS GPS - + SEARCH 検索 diff --git a/selfdrive/ui/translations/main_ko.ts b/selfdrive/ui/translations/main_ko.ts index a67b957e8..ed5f1a965 100644 --- a/selfdrive/ui/translations/main_ko.ts +++ b/selfdrive/ui/translations/main_ko.ts @@ -876,71 +876,71 @@ location set Sidebar - - + + CONNECT 연결 - + OFFLINE 오프라인 - - + + ONLINE 온라인 - + ERROR 오류 - - - + + + TEMP 온도 - + HIGH 높음 - + GOOD 좋음 - + OK 경고 - + VEHICLE 차량 - + NO NO - + PANDA PANDA - + GPS GPS - + SEARCH 검색중 diff --git a/selfdrive/ui/translations/main_pt.ts b/selfdrive/ui/translations/main_pt.ts index 912afa38a..980e7d408 100644 --- a/selfdrive/ui/translations/main_pt.ts +++ b/selfdrive/ui/translations/main_pt.ts @@ -880,71 +880,71 @@ trabalho definido Sidebar - - + + CONNECT CONEXÃO - + OFFLINE DESCONEC - - + + ONLINE CONECTADO - + ERROR ERRO - - - + + + TEMP TEMP - + HIGH ALTA - + GOOD BOA - + OK OK - + VEHICLE VEÍCULO - + NO SEM - + PANDA PANDA - + GPS GPS - + SEARCH PROCURA diff --git a/selfdrive/ui/translations/main_zh-CHS.ts b/selfdrive/ui/translations/main_zh-CHS.ts index 1ed96422b..1fb65623e 100644 --- a/selfdrive/ui/translations/main_zh-CHS.ts +++ b/selfdrive/ui/translations/main_zh-CHS.ts @@ -874,71 +874,71 @@ location set Sidebar - - + + CONNECT CONNECT - + OFFLINE 离线 - - + + ONLINE 在线 - + ERROR 连接出错 - - - + + + TEMP 设备温度 - + HIGH 过热 - + GOOD 良好 - + OK 一般 - + VEHICLE 车辆连接 - + NO - + PANDA PANDA - + GPS GPS - + SEARCH 搜索中 diff --git a/selfdrive/ui/translations/main_zh-CHT.ts b/selfdrive/ui/translations/main_zh-CHT.ts index 4f5c37764..0ba2f67a8 100644 --- a/selfdrive/ui/translations/main_zh-CHT.ts +++ b/selfdrive/ui/translations/main_zh-CHT.ts @@ -876,71 +876,71 @@ location set Sidebar - - + + CONNECT 雲端服務 - + OFFLINE 已離線 - - + + ONLINE 已連線 - + ERROR 錯誤 - - - + + + TEMP 溫度 - + HIGH 偏高 - + GOOD 正常 - + OK 一般 - + VEHICLE 車輛通訊 - + NO 未連線 - + PANDA 車輛通訊 - + GPS GPS - + SEARCH 車輛通訊 diff --git a/tools/replay/consoleui.cc b/tools/replay/consoleui.cc index e4a3146a6..6b419ca9d 100644 --- a/tools/replay/consoleui.cc +++ b/tools/replay/consoleui.cc @@ -18,6 +18,7 @@ const std::initializer_list> keyboard_shortc {"space", "Pause/Resume"}, {"e", "Next Engagement"}, {"d", "Next Disengagement"}, + {"t", "Next User Tag"} }, { {"enter", "Enter seek request"}, @@ -32,6 +33,7 @@ enum Color { Yellow, Green, Red, + Cyan, BrightWhite, Engaged, Disengaged, @@ -70,6 +72,7 @@ ConsoleUI::ConsoleUI(Replay *replay, QObject *parent) : replay(replay), sm({"car init_pair(Color::Debug, 246, COLOR_BLACK); // #949494 init_pair(Color::Yellow, 184, COLOR_BLACK); init_pair(Color::Red, COLOR_RED, COLOR_BLACK); + init_pair(Color::Cyan, COLOR_CYAN, COLOR_BLACK); init_pair(Color::BrightWhite, 15, COLOR_BLACK); init_pair(Color::Disengaged, COLOR_BLUE, COLOR_BLUE); init_pair(Color::Engaged, 28, 28); @@ -205,6 +208,7 @@ void ConsoleUI::displayTimelineDesc() { {Color::Green, " Info ", true}, {Color::Yellow, " Warning ", true}, {Color::Red, " Critical ", true}, + {Color::Cyan, " User Tag ", true}, }; for (auto [color, name, bold] : indicators) { add_str(w[Win::TimelineDesc], "__", color, bold); @@ -263,6 +267,8 @@ void ConsoleUI::updateTimeline() { if (type == TimelineType::Engaged) { mvwchgat(win, 1, start_pos, end_pos - start_pos + 1, A_COLOR, Color::Engaged, NULL); mvwchgat(win, 2, start_pos, end_pos - start_pos + 1, A_COLOR, Color::Engaged, NULL); + } else if (type == TimelineType::UserFlag) { + mvwchgat(win, 3, start_pos, end_pos - start_pos + 1, ACS_S3, Color::Cyan, NULL); } else { auto color_id = Color::Green; if (type != TimelineType::AlertInfo) { @@ -336,6 +342,8 @@ void ConsoleUI::handleKey(char c) { replay->seekToFlag(FindFlag::nextEngagement); } else if (c == 'd') { replay->seekToFlag(FindFlag::nextDisEngagement); + } else if (c == 't') { + replay->seekToFlag(FindFlag::nextUserFlag); } else if (c == 'm') { replay->seekTo(+60, true); } else if (c == 'M') { diff --git a/tools/replay/replay.cc b/tools/replay/replay.cc index c886a7e18..4b983fff8 100644 --- a/tools/replay/replay.cc +++ b/tools/replay/replay.cc @@ -149,6 +149,9 @@ void Replay::buildTimeline() { timeline.push_back({toSeconds(alert_begin), toSeconds(e->mono_time), alert_type}); alert_begin = 0; } + } else if (e->which == cereal::Event::Which::USER_FLAG) { + std::lock_guard lk(timeline_lock); + timeline.push_back({toSeconds(e->mono_time), toSeconds(e->mono_time), TimelineType::UserFlag}); } } } @@ -163,6 +166,10 @@ std::optional Replay::find(FindFlag flag) { } else if (flag == FindFlag::nextDisEngagement && end_ts > cur_ts) { return end_ts; } + } else if (type == TimelineType::UserFlag) { + if (flag == FindFlag::nextUserFlag && start_ts > cur_ts) { + return start_ts; + } } } return std::nullopt; @@ -360,7 +367,7 @@ void Replay::stream() { setCurrentSegment(toSeconds(cur_mono_time_) / 60); // migration for pandaState -> pandaStates to keep UI working for old segments - if (cur_which == cereal::Event::Which::PANDA_STATE_D_E_P_R_E_C_A_T_E_D && + if (cur_which == cereal::Event::Which::PANDA_STATE_D_E_P_R_E_C_A_T_E_D && sockets_[cereal::Event::Which::PANDA_STATES] != nullptr) { MessageBuilder msg; auto ps = msg.initEvent().initPandaStates(1); diff --git a/tools/replay/replay.h b/tools/replay/replay.h index 13269d3ec..86d609683 100644 --- a/tools/replay/replay.h +++ b/tools/replay/replay.h @@ -24,10 +24,11 @@ enum REPLAY_FLAGS { enum class FindFlag { nextEngagement, - nextDisEngagement + nextDisEngagement, + nextUserFlag, }; -enum class TimelineType { None, Engaged, AlertInfo, AlertWarning, AlertCritical }; +enum class TimelineType { None, Engaged, AlertInfo, AlertWarning, AlertCritical, UserFlag }; class Replay : public QObject { Q_OBJECT From 8b154fe27145f529d2459658e25cdd02f3fc9b5c Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 23 Aug 2022 11:18:23 -0700 Subject: [PATCH 062/172] Update translations --- selfdrive/ui/translations/main_ja.ts | 34 ++++++++++++------------ selfdrive/ui/translations/main_ko.ts | 34 ++++++++++++------------ selfdrive/ui/translations/main_pt.ts | 34 ++++++++++++------------ selfdrive/ui/translations/main_zh-CHS.ts | 34 ++++++++++++------------ selfdrive/ui/translations/main_zh-CHT.ts | 34 ++++++++++++------------ 5 files changed, 85 insertions(+), 85 deletions(-) diff --git a/selfdrive/ui/translations/main_ja.ts b/selfdrive/ui/translations/main_ja.ts index 79c982f81..dd9f933dc 100644 --- a/selfdrive/ui/translations/main_ja.ts +++ b/selfdrive/ui/translations/main_ja.ts @@ -876,71 +876,71 @@ location set Sidebar - - + + CONNECT 接続 - + OFFLINE オフライン - - + + ONLINE オンライン - + ERROR エラー - - - + + + TEMP 温度 - + HIGH 高温 - + GOOD 最適 - + OK OK - + VEHICLE 車両 - + NO NO - + PANDA PANDA - + GPS GPS - + SEARCH 検索 diff --git a/selfdrive/ui/translations/main_ko.ts b/selfdrive/ui/translations/main_ko.ts index ed5f1a965..d4abe8619 100644 --- a/selfdrive/ui/translations/main_ko.ts +++ b/selfdrive/ui/translations/main_ko.ts @@ -876,71 +876,71 @@ location set Sidebar - - + + CONNECT 연결 - + OFFLINE 오프라인 - - + + ONLINE 온라인 - + ERROR 오류 - - - + + + TEMP 온도 - + HIGH 높음 - + GOOD 좋음 - + OK 경고 - + VEHICLE 차량 - + NO NO - + PANDA PANDA - + GPS GPS - + SEARCH 검색중 diff --git a/selfdrive/ui/translations/main_pt.ts b/selfdrive/ui/translations/main_pt.ts index 980e7d408..3d5eda118 100644 --- a/selfdrive/ui/translations/main_pt.ts +++ b/selfdrive/ui/translations/main_pt.ts @@ -880,71 +880,71 @@ trabalho definido Sidebar - - + + CONNECT CONEXÃO - + OFFLINE DESCONEC - - + + ONLINE CONECTADO - + ERROR ERRO - - - + + + TEMP TEMP - + HIGH ALTA - + GOOD BOA - + OK OK - + VEHICLE VEÍCULO - + NO SEM - + PANDA PANDA - + GPS GPS - + SEARCH PROCURA diff --git a/selfdrive/ui/translations/main_zh-CHS.ts b/selfdrive/ui/translations/main_zh-CHS.ts index 1fb65623e..a26cddc0c 100644 --- a/selfdrive/ui/translations/main_zh-CHS.ts +++ b/selfdrive/ui/translations/main_zh-CHS.ts @@ -874,71 +874,71 @@ location set Sidebar - - + + CONNECT CONNECT - + OFFLINE 离线 - - + + ONLINE 在线 - + ERROR 连接出错 - - - + + + TEMP 设备温度 - + HIGH 过热 - + GOOD 良好 - + OK 一般 - + VEHICLE 车辆连接 - + NO - + PANDA PANDA - + GPS GPS - + SEARCH 搜索中 diff --git a/selfdrive/ui/translations/main_zh-CHT.ts b/selfdrive/ui/translations/main_zh-CHT.ts index 0ba2f67a8..f4681f85d 100644 --- a/selfdrive/ui/translations/main_zh-CHT.ts +++ b/selfdrive/ui/translations/main_zh-CHT.ts @@ -876,71 +876,71 @@ location set Sidebar - - + + CONNECT 雲端服務 - + OFFLINE 已離線 - - + + ONLINE 已連線 - + ERROR 錯誤 - - - + + + TEMP 溫度 - + HIGH 偏高 - + GOOD 正常 - + OK 一般 - + VEHICLE 車輛通訊 - + NO 未連線 - + PANDA 車輛通訊 - + GPS GPS - + SEARCH 車輛通訊 From 506b719a40d4391a17a7bc081f761ec1215040ef Mon Sep 17 00:00:00 2001 From: AlexandreSato <66435071+AlexandreSato@users.noreply.github.com> Date: Tue, 23 Aug 2022 15:20:34 -0300 Subject: [PATCH 063/172] Toyota: add missing engine and esp FW for Corolla Cross Hybrid (#25532) add missing engine and esp FW for CorollaCross Hybrid DongleId 147613502316e718 --- selfdrive/car/toyota/values.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 891514606..7b4031ca6 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -783,6 +783,7 @@ FW_VERSIONS = { b'\x01896637626000\x00\x00\x00\x00', b'\x01896637648000\x00\x00\x00\x00', b'\x01896637643000\x00\x00\x00\x00', + b'\x02896630A21000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x02896630ZJ5000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x02896630ZN8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x02896630ZQ3000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', @@ -827,6 +828,7 @@ FW_VERSIONS = { b'F152612A10\x00\x00\x00\x00\x00\x00', b'F152612D00\x00\x00\x00\x00\x00\x00', b'F152616011\x00\x00\x00\x00\x00\x00', + b'F152616060\x00\x00\x00\x00\x00\x00', b'F152642540\x00\x00\x00\x00\x00\x00', b'F152676293\x00\x00\x00\x00\x00\x00', b'F152676303\x00\x00\x00\x00\x00\x00', From f41dc62a12cc0f3cb8c5453c0caa0ba21e1bd01e Mon Sep 17 00:00:00 2001 From: Jason Wen <47793918+sunnyhaibin@users.noreply.github.com> Date: Tue, 23 Aug 2022 14:21:07 -0400 Subject: [PATCH 064/172] HKG: Add FW for 2018 Kia Stinger (#25531) * HKG: Add FW for 2008 Kia Stinger * 2018 in disguise Co-authored-by: Shane Smiskol --- selfdrive/car/hyundai/values.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 2861e4dc8..aa1823522 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -703,6 +703,7 @@ FW_VERSIONS = { (Ecu.fwdRadar, 0x7d0, None): [ b'\xf1\x00CK__ SCC F_CUP 1.00 1.01 96400-J5100 ', b'\xf1\x00CK__ SCC F_CUP 1.00 1.03 96400-J5100 ', + b'\xf1\x00CK__ SCC F_CUP 1.00 1.01 96400-J5000 ', ], (Ecu.engine, 0x7e0, None): [ b'\xf1\x81606DE051\x00\x00\x00\x00\x00\x00\x00\x00', @@ -720,6 +721,7 @@ FW_VERSIONS = { (Ecu.fwdCamera, 0x7c4, None): [ b'\xf1\x00CK MFC AT USA LHD 1.00 1.03 95740-J5000 170822', b'\xf1\x00CK MFC AT USA LHD 1.00 1.04 95740-J5000 180504', + b'\xf1\x00CK MFC AT EUR LHD 1.00 1.03 95740-J5000 170822', ], (Ecu.transmission, 0x7e1, None): [ b'\xf1\x87VCJLE17622572DK0vd6D\x99\x98y\x97vwVffUfvfC%CuT&Dx\x87o\xff{\x1c\xf1\x81E21\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 E21\x00\x00\x00\x00\x00\x00\x00SCK0T33NB0\x88\xa2\xe6\xf0', @@ -729,6 +731,7 @@ FW_VERSIONS = { b'\xf1\x87VDHLG17118862DK2\x8awWwgu\x96wVfUVwv\x97xWvfvUTGTx\x87o\xff\xc9\xed\xf1\x81E21\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 E21\x00\x00\x00\x00\x00\x00\x00SCK0T33NB0\x88\xa2\xe6\xf0', b'\xf1\x87VDKLJ18675252DK6\x89vhgwwwwveVU\x88w\x87w\x99vgf\x97vXfgw_\xff\xc2\xfb\xf1\x89E25\x00\x00\x00\x00\x00\x00\x00\xf1\x82TCK0T33NB2', b'\xf1\x87WAJTE17552812CH4vfFffvfVeT5DwvvVVdFeegeg\x88\x88o\xff\x1a]\xf1\x81E21\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 E21\x00\x00\x00\x00\x00\x00\x00TCK2T20NB1\x19\xd2\x00\x94', + b'\xf1\x87VDHLG17274082DK2wfFf\x89x\x98wUT5T\x88v\x97xgeGefTGTVvO\xff\x1c\x14\xf1\x81E19\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 E19\x00\x00\x00\x00\x00\x00\x00SCK0T33UB2\xee[\x97S', ], }, CAR.PALISADE: { From f8e44f2e9b186d5a3f99c9dfcf46dbf887b3861b Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 23 Aug 2022 13:42:14 -0700 Subject: [PATCH 065/172] test_models: pass carFw into car interface (#25535) pass carFw into get_params --- selfdrive/car/tests/test_models.py | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/selfdrive/car/tests/test_models.py b/selfdrive/car/tests/test_models.py index fdf7bca3d..6e88e227c 100755 --- a/selfdrive/car/tests/test_models.py +++ b/selfdrive/car/tests/test_models.py @@ -81,6 +81,7 @@ class TestCarModelBase(unittest.TestCase): except Exception: continue + car_fw = [] can_msgs = [] fingerprint = defaultdict(dict) for msg in lr: @@ -90,6 +91,7 @@ class TestCarModelBase(unittest.TestCase): fingerprint[m.src][m.address] = len(m.dat) can_msgs.append(msg) elif msg.which() == "carParams": + car_fw = msg.carParams.carFw if msg.carParams.openpilotLongitudinalControl: disable_radar = True if cls.car_model is None and not cls.ci: @@ -103,7 +105,7 @@ class TestCarModelBase(unittest.TestCase): cls.can_msgs = sorted(can_msgs, key=lambda msg: msg.logMonoTime) cls.CarInterface, cls.CarController, cls.CarState = interfaces[cls.car_model] - cls.CP = cls.CarInterface.get_params(cls.car_model, fingerprint, [], disable_radar) + cls.CP = cls.CarInterface.get_params(cls.car_model, fingerprint, car_fw, disable_radar) assert cls.CP assert cls.CP.carFingerprint == cls.car_model From a34acc316e8c4fc6d4ea101ef58919686cd0807c Mon Sep 17 00:00:00 2001 From: Rewat S <76684800+taperec@users.noreply.github.com> Date: Wed, 24 Aug 2022 06:29:47 +0700 Subject: [PATCH 066/172] Add Thai translations (#25189) * Add Thai translations * update to add plurals remove * Update translations * Update Thai translation to match English source. * Add to badges * use shorter km/h * Add test for correct format specifier for plural translations * pass new test * Update some sentences to make it clear. Change short form of some words. * Hide from the UI Co-authored-by: Shane Smiskol --- selfdrive/ui/translations/main_th.ts | 1303 ++++++++++++++++++++++++++ 1 file changed, 1303 insertions(+) create mode 100644 selfdrive/ui/translations/main_th.ts diff --git a/selfdrive/ui/translations/main_th.ts b/selfdrive/ui/translations/main_th.ts new file mode 100644 index 000000000..3277f5374 --- /dev/null +++ b/selfdrive/ui/translations/main_th.ts @@ -0,0 +1,1303 @@ + + + + + AbstractAlert + + + Close + ปิด + + + + Snooze Update + เลื่อนการอัปเดต + + + + Reboot and Update + รีบูตและอัปเดต + + + + AdvancedNetworking + + + Back + ย้อนกลับ + + + + Enable Tethering + ปล่อยฮอตสปอต + + + + Tethering Password + รหัสผ่านฮอตสปอต + + + + + EDIT + แก้ไข + + + + Enter new tethering password + ป้อนรหัสผ่านฮอตสปอตใหม่ + + + + IP Address + หมายเลขไอพี + + + + Enable Roaming + เปิดใช้งานโรมมิ่ง + + + + APN Setting + ตั้งค่า APN + + + + Enter APN + ป้อนค่า APN + + + + leave blank for automatic configuration + เว้นว่างเพื่อตั้งค่าอัตโนมัติ + + + + ConfirmationDialog + + + + Ok + ตกลง + + + + Cancel + ยกเลิก + + + + DeclinePage + + + You must accept the Terms and Conditions in order to use openpilot. + คุณต้องยอมรับเงื่อนไขและข้อตกลง เพื่อใช้งาน openpilot + + + + Back + ย้อนกลับ + + + + Decline, uninstall %1 + ปฏิเสธ และถอนการติดตั้ง %1 + + + + DevicePanel + + + Dongle ID + Dongle ID + + + + N/A + ไม่มี + + + + Serial + ซีเรียล + + + + Driver Camera + กล้องฝั่งคนขับ + + + + PREVIEW + แสดงภาพ + + + + Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off) + ดูภาพตัวอย่างกล้องที่หันเข้าหาคนขับเพื่อให้แน่ใจว่าการตรวจสอบคนขับมีทัศนวิสัยที่ดี (รถต้องดับเครื่องยนต์) + + + + Reset Calibration + รีเซ็ตการคาลิเบรท + + + + RESET + รีเซ็ต + + + + Are you sure you want to reset calibration? + คุณแน่ใจหรือไม่ว่าต้องการรีเซ็ตการคาลิเบรท? + + + + Review Training Guide + ทบทวนคู่มือการใช้งาน + + + + REVIEW + ทบทวน + + + + Review the rules, features, and limitations of openpilot + ตรวจสอบกฎ คุณสมบัติ และข้อจำกัดของ openpilot + + + + Are you sure you want to review the training guide? + คุณแน่ใจหรือไม่ว่าต้องการทบทวนคู่มือการใช้งาน? + + + + Regulatory + ระเบียบข้อบังคับ + + + + VIEW + ดู + + + + Change Language + เปลี่ยนภาษา + + + + CHANGE + เปลี่ยน + + + + Select a language + เลือกภาษา + + + + Reboot + รีบูต + + + + Power Off + ปิดเครื่อง + + + + 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 ทำการคาลิเบรทอย่างต่อเนื่อง แทบจะไม่จำเป็นต้องทำการรีเซ็ตการคาลิเบรท + + + + Your device is pointed %1° %2 and %3° %4. + อุปกรณ์ของคุณเอียงไปทาง %2 %1° และ %4 %3° + + + + down + ด้านล่าง + + + + up + ด้านบน + + + + left + ด้านซ้าย + + + + right + ด้านขวา + + + + Are you sure you want to reboot? + คุณแน่ใจหรือไม่ว่าต้องการรีบูต? + + + + Disengage to Reboot + ยกเลิกระบบช่วยขับเพื่อรีบูต + + + + Are you sure you want to power off? + คุณแน่ใจหรือไม่ว่าต้องการปิดเครื่อง? + + + + Disengage to Power Off + ยกเลิกระบบช่วยขับเพื่อปิดเครื่อง + + + + DriveStats + + + Drives + การขับขี่ + + + + Hours + ชั่วโมง + + + + ALL TIME + ทั้งหมด + + + + PAST WEEK + สัปดาห์ที่ผ่านมา + + + + KM + กิโลเมตร + + + + Miles + ไมล์ + + + + DriverViewScene + + + camera starting + กำลังเปิดกล้อง + + + + InputDialog + + + Cancel + ยกเลิก + + + + Need at least %n character(s)! + + ต้องการอย่างน้อย %n ตัวอักษร! + + + + + Installer + + + Installing... + กำลังติดตั้ง... + + + + Receiving objects: + กำลังรับข้อมูล: + + + + Resolving deltas: + การแก้ไขเดลต้า: + + + + Updating files: + กำลังอัปเดตไฟล์: + + + + MapETA + + + eta + eta + + + + min + นาที + + + + hr + ชม. + + + + km + กม. + + + + mi + ไมล์ + + + + MapInstructions + + + km + กม. + + + + m + ม. + + + + mi + ไมล์ + + + + ft + ฟุต + + + + MapPanel + + + Current Destination + ปลายทางปัจจุบัน + + + + CLEAR + ล้างข้อมูล + + + + Recent Destinations + ปลายทางล่าสุด + + + + Try the Navigation Beta + ลองใช้ระบบนำทาง (เบต้า) + + + + Get turn-by-turn directions displayed and more with a comma +prime subscription. Sign up now: https://connect.comma.ai + รับการแสดงเส้นทางแบบเลี้ยวต่อเลี้ยว และอื่นๆ ด้วยการสมัครบริการ +comma prime สมัครเลย: https://connect.comma.ai + + + + No home +location set + ยังไม่ได้กำหนด +ตำแหน่งของบ้าน + + + + No work +location set + ยังไม่ได้กำหนด +ตำแหน่งของที่ทำงาน + + + + no recent destinations + ไม่พบปลายทางล่าสุด + + + + MapWindow + + + Map Loading + กำลังโหลดแผนที่ + + + + Waiting for GPS + กำลังรอสัญญาณ GPS + + + + MultiOptionDialog + + + Select + เลือก + + + + Cancel + ยกเลิก + + + + Networking + + + Advanced + ขั้นสูง + + + + Enter password + ใส่รหัสผ่าน + + + + + for "%1" + สำหรับ "%1" + + + + Wrong password + รหัสผ่านผิด + + + + NvgWindow + + + km/h + กม./ชม. + + + + mph + ไมล์/ชม. + + + + + MAX + สูงสุด + + + + + SPEED + ความเร็ว + + + + + LIMIT + จำกัด + + + + OffroadHome + + + UPDATE + อัปเดต + + + + ALERTS + การแจ้งเตือน + + + + ALERT + การแจ้งเตือน + + + + PairingPopup + + + Pair your device to your comma account + จับคู่อุปกรณ์ของคุณกับบัญชี comma ของคุณ + + + + Go to https://connect.comma.ai on your phone + ไปที่ https://connect.comma.ai ด้วยโทรศัพท์ของคุณ + + + + Click "add new device" and scan the QR code on the right + กดที่ "add new device" และสแกนคิวอาร์โค้ดทางด้านขวา + + + + Bookmark connect.comma.ai to your home screen to use it like an app + จดจำ connect.comma.ai โดยการเพิ่มไปยังหน้าจอโฮม เพื่อใช้งานเหมือนเป็นแอปพลิเคชัน + + + + PrimeAdWidget + + + Upgrade Now + อัพเกรดเดี๋ยวนี้ + + + + Become a comma prime member at connect.comma.ai + สมัครสมาชิก comma prime ได้ที่ connect.comma.ai + + + + PRIME FEATURES: + คุณสมบัติของ PRIME: + + + + Remote access + การเข้าถึงระยะไกล + + + + 1 year of storage + จัดเก็บข้อมูลนาน 1 ปี + + + + Developer perks + สิทธิพิเศษสำหรับนักพัฒนา + + + + PrimeUserWidget + + + ✓ SUBSCRIBED + ✓ สมัครสำเร็จ + + + + comma prime + comma prime + + + + CONNECT.COMMA.AI + CONNECT.COMMA.AI + + + + COMMA POINTS + คะแนน COMMA + + + + QObject + + + Reboot + รีบูต + + + + Exit + ปิด + + + + dashcam + กล้องติดรถยนต์ + + + + openpilot + openpilot + + + + %n minute(s) ago + + %n นาทีที่แล้ว + + + + + %n hour(s) ago + + %n ชั่วโมงที่แล้ว + + + + + %n day(s) ago + + %n วันที่แล้ว + + + + + Reset + + + Reset failed. Reboot to try again. + การรีเซ็ตล้มเหลว รีบูตเพื่อลองอีกครั้ง + + + + Are you sure you want to reset your device? + คุณแน่ใจหรือไม่ว่าต้องการรีเซ็ตอุปกรณ์? + + + + Resetting device... + กำลังรีเซ็ตอุปกรณ์... + + + + System Reset + รีเซ็ตระบบ + + + + System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot. + มีการสั่งรีเซ็ตระบบ กดยืนยันเพื่อลบข้อมูลและการตั้งค่าทั้งหมด กดยกเลิกเพื่อบูตเข้าระบบตามปกติ + + + + Cancel + ยกเลิก + + + + Reboot + รีบูต + + + + Confirm + ยืนยัน + + + + Unable to mount data partition. Press confirm to reset your device. + ไม่สามารถเมานต์พาร์ติชั่นข้อมูล กดยืนยันเพื่อรีเซ็ตอุปกรณ์ของคุณ + + + + RichTextDialog + + + Ok + ตกลง + + + + SettingsWindow + + + × + × + + + + Device + อุปกรณ์ + + + + + Network + เครือข่าย + + + + Toggles + ตัวเลือก + + + + Software + ซอฟต์แวร์ + + + + Navigation + การนำทาง + + + + Setup + + + WARNING: Low Voltage + คำเตือน: แรงดันไฟฟ้าต่ำ + + + + Power your device in a car with a harness or proceed at your own risk. + โปรดต่ออุปกรณ์ของคุณเข้ากับสายควบคุมในรถยนต์ หรือดำเนินการด้วยความเสี่ยงของคุณเอง + + + + Power off + ปิดเครื่อง + + + + + + Continue + ดำเนินการต่อ + + + + Getting Started + เริ่มกันเลย + + + + Before we get on the road, let’s finish installation and cover some details. + ก่อนออกเดินทาง เรามาทำการติดตั้งซอฟต์แวร์ และตรวจสอบการตั้งค่า + + + + Connect to Wi-Fi + เชื่อมต่อ Wi-Fi + + + + + Back + ย้อนกลับ + + + + Continue without Wi-Fi + ดำเนินการต่อโดยไม่ใช้ Wi-Fi + + + + Waiting for internet + กำลังรอสัญญาณอินเตอร์เน็ต + + + + Choose Software to Install + เลือกซอฟต์แวร์ที่จะติดตั้ง + + + + Dashcam + กล้องติดรถยนต์ + + + + Custom Software + ซอฟต์แวร์ที่กำหนดเอง + + + + Enter URL + ป้อน URL + + + + for Custom Software + สำหรับซอฟต์แวร์ที่กำหนดเอง + + + + Downloading... + กำลังดาวน์โหลด... + + + + Download Failed + ดาวน์โหลดล้มเหลว + + + + Ensure the entered URL is valid, and the device’s internet connection is good. + ตรวจสอบให้แน่ใจว่า URL ที่ป้อนนั้นถูกต้อง และอุปกรณ์เชื่อมต่ออินเทอร์เน็ตอยู่ + + + + Reboot device + รีบูตอุปกรณ์ + + + + Start over + เริ่มต้นใหม่ + + + + SetupWidget + + + Finish Setup + ตั้งค่าเสร็จสิ้น + + + + Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer. + จับคู่อุปกรณ์ของคุณกับ comma connect (connect.comma.ai) และรับข้อเสนอ comma prime ของคุณ + + + + Pair device + จับคู่อุปกรณ์ + + + + Sidebar + + + + CONNECT + เชื่อมต่อ + + + + OFFLINE + ออฟไลน์ + + + + + ONLINE + ออนไลน์ + + + + ERROR + เกิดข้อผิดพลาด + + + + + + TEMP + อุณหภูมิ + + + + HIGH + สูง + + + + GOOD + ดี + + + + OK + พอใช้ + + + + VEHICLE + รถยนต์ + + + + NO + ไม่พบ + + + + PANDA + PANDA + + + + GPS + จีพีเอส + + + + SEARCH + ค้นหา + + + + -- + -- + + + + Wi-Fi + Wi-Fi + + + + ETH + ETH + + + + 2G + 2G + + + + 3G + 3G + + + + LTE + LTE + + + + 5G + 5G + + + + 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 + + + + UNINSTALL + ถอนการติดตั้ง + + + + Are you sure you want to uninstall? + คุณแน่ใจหรือไม่ว่าต้องการถอนการติดตั้ง? + + + + failed to fetch update + โหลดข้อมูลอัปเดตไม่สำเร็จ + + + + + CHECK + ตรวจสอบ + + + + SshControl + + + SSH Keys + คีย์ SSH + + + + 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. + คำเตือน: สิ่งนี้ให้สิทธิ์ SSH เข้าถึงคีย์สาธารณะทั้งหมดใน GitHub ของคุณ อย่าป้อนชื่อผู้ใช้ GitHub อื่นนอกเหนือจากของคุณเอง พนักงาน comma จะไม่ขอให้คุณเพิ่มชื่อผู้ใช้ GitHub ของพวกเขา + + + + + ADD + เพิ่ม + + + + Enter your GitHub username + ป้อนชื่อผู้ใช้ GitHub ของคุณ + + + + LOADING + กำลังโหลด + + + + REMOVE + ลบ + + + + Username '%1' has no keys on GitHub + ชื่อผู้ใช้ '%1' ไม่มีคีย์บน GitHub + + + + Request timed out + ตรวจสอบไม่สำเร็จ เนื่องจากใช้เวลามากเกินไป + + + + Username '%1' doesn't exist on GitHub + ไม่พบชื่อผู้ใช้ '%1' บน GitHub + + + + SshToggle + + + Enable SSH + เปิดใช้งาน SSH + + + + TermsPage + + + Terms & Conditions + ข้อตกลงและเงื่อนไข + + + + Decline + ปฏิเสธ + + + + Scroll to accept + เลื่อนเพื่อตอบรับข้อตกลง + + + + Agree + ยอมรับ + + + + TogglesPanel + + + Enable openpilot + เปิดใช้งาน openpilot + + + + Use the openpilot system for adaptive cruise control and lane keep driver assistance. Your attention is required at all times to use this feature. Changing this setting takes effect when the car is powered off. + ใช้ระบบ openpilot สำหรับระบบควบคุมความเร็วอัตโนมัติ และระบบช่วยควบคุมรถให้อยู่ในเลน คุณจำเป็นต้องให้ความสนใจตลอดเวลาที่ใช้คุณสมบัตินี้ การเปลี่ยนการตั้งค่านี้จะมีผลเมื่อคุณดับเครื่องยนต์ + + + + Enable Lane Departure Warnings + เปิดใช้งานการเตือนการออกนอกเลน + + + + Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31 mph (50 km/h). + รับการแจ้งเตือนให้เลี้ยวกลับเข้าเลนเมื่อรถของคุณตรวจพบการข้ามช่องจราจรโดยไม่เปิดสัญญาณไฟเลี้ยวในขณะขับขี่ที่ความเร็วเกิน 31 ไมล์ต่อชั่วโมง (50 กม./ชม) + + + + Use Metric System + ใช้ระบบเมตริก + + + + Display speed in km/h instead of mph. + แสดงความเร็วเป็น กม./ชม. แทน ไมล์/ชั่วโมง + + + + Record and Upload Driver Camera + บันทึกและอัปโหลดภาพจากกล้องคนขับ + + + + Upload data from the driver facing camera and help improve the driver monitoring algorithm. + อัปโหลดข้อมูลจากกล้องที่หันหน้าไปทางคนขับ และช่วยปรับปรุงอัลกอริธึมการตรวจสอบผู้ขับขี่ + + + + Disengage On Accelerator Pedal + ยกเลิกระบบช่วยขับเมื่อเหยียบคันเร่ง + + + + When enabled, pressing the accelerator pedal will disengage openpilot. + เมื่อเปิดใช้งาน การกดแป้นคันเร่งจะเป็นการยกเลิกระบบช่วยขับโดย openpilot + + + + Show ETA in 24h Format + แสดงเวลา ETA ในรูปแบบ 24 ชั่วโมง + + + + Use 24h format instead of am/pm + ใช้รูปแบบเวลา 24 ชั่วโมง แทน am/pm + + + + Show Map on Left Side of UI + แสดงแผนที่ที่ด้านซ้ายของหน้าจอ + + + + 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! + + + + 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 + + + + Connect to Wi-Fi + เชื่อมต่อกับ Wi-Fi + + + + Install + ติดตั้ง + + + + Back + ย้อนกลับ + + + + Loading... + กำลังโหลด... + + + + Reboot + รีบูต + + + + Update failed + การอัปเดตล้มเหลว + + + + WifiUI + + + + Scanning for networks... + กำลังสแกนหาเครือข่าย... + + + + CONNECTING... + กำลังเชื่อมต่อ... + + + + FORGET + เลิกใช้ + + + + Forget Wi-Fi Network "%1"? + เลิกใช้เครือข่าย Wi-Fi "%1"? + + + From c8378b6ad58fc6ba68976ffaff49b03aa2224bbb Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 23 Aug 2022 16:54:45 -0700 Subject: [PATCH 067/172] update car candidate docs (#25536) * update car candidate docs * little more * that's a nice wikipedia * quotes --- docs/CARS.md | 15 ++++++++------- selfdrive/car/CARS_template.md | 14 ++++++++------ 2 files changed, 16 insertions(+), 13 deletions(-) diff --git a/docs/CARS.md b/docs/CARS.md index 24be43e4f..78b4d3b16 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -2,7 +2,7 @@ # Supported Cars -A supported vehicle is one that just works when you install a comma device. Every car performs differently with openpilot, but all supported cars should provide a better experience than any stock system. +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. # 205 Supported Cars @@ -230,13 +230,13 @@ Although they're not upstream, the community has openpilot running on other make # Don't see your car here? **openpilot can support many more cars than it currently does.** There are a few reasons your car may not be supported. -If your car doesn't fit into any of the incompatibility criteria here, then there's a good chance it can be supported! We're adding support for new cars all the time. We don't have a roadmap for car support, and in fact, most car support comes from users like you! +If your car doesn't fit into any of the incompatibility criteria here, then there's a good chance it can be supported! We're adding support for new cars all the time. **We don't have a roadmap for car support**, and in fact, most car support comes from users like you! ### Which cars are able to be supported? -openpilot uses the existing steering, gas, and brake interfaces in your car. If your car lacks any one of these interfaces, openpilot will not be able to control the car. If your car has any form of [LKAS](https://en.wikipedia.org/wiki/Automated_Lane_Keeping_Systems)/[LCA](https://en.wikipedia.org/wiki/Lane_centering) and [ACC](https://en.wikipedia.org/wiki/Adaptive_cruise_control), then it almost certainly has these interfaces. These interfaces generally started shipping on cars around 2016. +openpilot uses the existing steering, gas, and brake interfaces in your car. If your car lacks any one of these interfaces, openpilot will not be able to control the car. If your car has [ACC](https://en.wikipedia.org/wiki/Adaptive_cruise_control) and any form of [LKAS](https://en.wikipedia.org/wiki/Automated_Lane_Keeping_Systems)/[LCA](https://en.wikipedia.org/wiki/Lane_centering), then it almost certainly has these interfaces. These features generally started shipping on cars around 2016. Note that manufacturers will often make their own [marketing terms](https://en.wikipedia.org/wiki/Adaptive_cruise_control#Vehicle_models_supporting_adaptive_cruise_control) for these features, such as Hyundai's "Smart Cruise Control" branding of Adaptive Cruise Control. -If your car has the following packages or features, then it's a good candidate for support. If it does not, then it's unlikely able to be supported. +If your car has the following packages or features, then it's a good candidate for support. | Make | Required Package/Features | | ---- | ------------------------- | @@ -254,8 +254,9 @@ All the cars that openpilot supports use a [CAN bus](https://en.wikipedia.org/wi ### Toyota Security -Specific new Toyota models are shipping with a new message authentication method that openpilot does not yet support. -So far, this list includes: +openpilot does not yet support these Toyota models due to a new message authentication method. +[Vote](https://comma.ai/shop/products/vote) if you'd like to see openpilot support on these models. + * Toyota RAV4 Prime 2021+ * Toyota Sienna 2021+ * Toyota Venza 2021+ @@ -264,4 +265,4 @@ So far, this list includes: * Toyota Corolla Cross 2022+ (only US model) * Lexus NX 2022+ * Toyota bZ4x 2023+ -* Subaru Solterra 2023+ \ No newline at end of file +* Subaru Solterra 2023+ diff --git a/selfdrive/car/CARS_template.md b/selfdrive/car/CARS_template.md index d306ca5d9..2fce0f903 100644 --- a/selfdrive/car/CARS_template.md +++ b/selfdrive/car/CARS_template.md @@ -5,7 +5,7 @@ # Supported Cars -A supported vehicle is one that just works when you install a comma device. Every car performs differently with openpilot, but all supported cars should provide a better experience than any stock system. +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. # {{all_car_info | length}} Supported Cars @@ -27,13 +27,13 @@ Although they're not upstream, the community has openpilot running on other make # Don't see your car here? **openpilot can support many more cars than it currently does.** There are a few reasons your car may not be supported. -If your car doesn't fit into any of the incompatibility criteria here, then there's a good chance it can be supported! We're adding support for new cars all the time. We don't have a roadmap for car support, and in fact, most car support comes from users like you! +If your car doesn't fit into any of the incompatibility criteria here, then there's a good chance it can be supported! We're adding support for new cars all the time. **We don't have a roadmap for car support**, and in fact, most car support comes from users like you! ### Which cars are able to be supported? -openpilot uses the existing steering, gas, and brake interfaces in your car. If your car lacks any one of these interfaces, openpilot will not be able to control the car. If your car has any form of [LKAS](https://en.wikipedia.org/wiki/Automated_Lane_Keeping_Systems)/[LCA](https://en.wikipedia.org/wiki/Lane_centering) and [ACC](https://en.wikipedia.org/wiki/Adaptive_cruise_control), then it almost certainly has these interfaces. These interfaces generally started shipping on cars around 2016. +openpilot uses the existing steering, gas, and brake interfaces in your car. If your car lacks any one of these interfaces, openpilot will not be able to control the car. If your car has [ACC](https://en.wikipedia.org/wiki/Adaptive_cruise_control) and any form of [LKAS](https://en.wikipedia.org/wiki/Automated_Lane_Keeping_Systems)/[LCA](https://en.wikipedia.org/wiki/Lane_centering), then it almost certainly has these interfaces. These features generally started shipping on cars around 2016. Note that manufacturers will often make their own [marketing terms](https://en.wikipedia.org/wiki/Adaptive_cruise_control#Vehicle_models_supporting_adaptive_cruise_control) for these features, such as Hyundai's "Smart Cruise Control" branding of Adaptive Cruise Control. -If your car has the following packages or features, then it's a good candidate for support. If it does not, then it's unlikely able to be supported. +If your car has the following packages or features, then it's a good candidate for support. | Make | Required Package/Features | | ---- | ------------------------- | @@ -51,8 +51,9 @@ All the cars that openpilot supports use a [CAN bus](https://en.wikipedia.org/wi ### Toyota Security -Specific new Toyota models are shipping with a new message authentication method that openpilot does not yet support. -So far, this list includes: +openpilot does not yet support these Toyota models due to a new message authentication method. +[Vote](https://comma.ai/shop/products/vote) if you'd like to see openpilot support on these models. + * Toyota RAV4 Prime 2021+ * Toyota Sienna 2021+ * Toyota Venza 2021+ @@ -62,3 +63,4 @@ So far, this list includes: * Lexus NX 2022+ * Toyota bZ4x 2023+ * Subaru Solterra 2023+ + From 19810f2dcc11f5fe307b71a19aff419e9459d3b3 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 23 Aug 2022 17:26:29 -0700 Subject: [PATCH 068/172] Silence a PytestCollectionWarning (#25537) Silence PytestCollectionWarning: cannot collect test class 'TestRoute' because it has a __new__ constructor (from: test_models.py) --- selfdrive/car/tests/routes.py | 376 ++++++++++++++--------------- selfdrive/car/tests/test_models.py | 4 +- selfdrive/debug/test_car_model.py | 6 +- 3 files changed, 193 insertions(+), 193 deletions(-) diff --git a/selfdrive/car/tests/routes.py b/selfdrive/car/tests/routes.py index 532ab7119..a47a3447e 100644 --- a/selfdrive/car/tests/routes.py +++ b/selfdrive/car/tests/routes.py @@ -26,202 +26,202 @@ non_tested_cars = [ HYUNDAI.KIA_OPTIMA_H, ] -TestRoute = namedtuple('TestRoute', ['route', 'car_model', 'segment'], defaults=(None,)) +CarTestRoute = namedtuple('CarTestRoute', ['route', 'car_model', 'segment'], defaults=(None,)) routes = [ - TestRoute("efdf9af95e71cd84|2022-05-13--19-03-31", COMMA.BODY), - - TestRoute("0c94aa1e1296d7c6|2021-05-05--19-48-37", CHRYSLER.JEEP_CHEROKEE), - TestRoute("91dfedae61d7bd75|2021-05-22--20-07-52", CHRYSLER.JEEP_CHEROKEE_2019), - TestRoute("420a8e183f1aed48|2020-03-05--07-15-29", CHRYSLER.PACIFICA_2017_HYBRID), - TestRoute("43a685a66291579b|2021-05-27--19-47-29", CHRYSLER.PACIFICA_2018), - TestRoute("378472f830ee7395|2021-05-28--07-38-43", CHRYSLER.PACIFICA_2018_HYBRID), - TestRoute("8190c7275a24557b|2020-01-29--08-33-58", CHRYSLER.PACIFICA_2019_HYBRID), - TestRoute("3d84727705fecd04|2021-05-25--08-38-56", CHRYSLER.PACIFICA_2020), - TestRoute("221c253375af4ee9|2022-06-15--18-38-24", CHRYSLER.RAM_1500), - TestRoute("8fb5eabf914632ae|2022-08-04--17-28-53", CHRYSLER.RAM_HD, segment=6), + CarTestRoute("efdf9af95e71cd84|2022-05-13--19-03-31", COMMA.BODY), + + CarTestRoute("0c94aa1e1296d7c6|2021-05-05--19-48-37", CHRYSLER.JEEP_CHEROKEE), + CarTestRoute("91dfedae61d7bd75|2021-05-22--20-07-52", CHRYSLER.JEEP_CHEROKEE_2019), + CarTestRoute("420a8e183f1aed48|2020-03-05--07-15-29", CHRYSLER.PACIFICA_2017_HYBRID), + CarTestRoute("43a685a66291579b|2021-05-27--19-47-29", CHRYSLER.PACIFICA_2018), + CarTestRoute("378472f830ee7395|2021-05-28--07-38-43", CHRYSLER.PACIFICA_2018_HYBRID), + CarTestRoute("8190c7275a24557b|2020-01-29--08-33-58", CHRYSLER.PACIFICA_2019_HYBRID), + CarTestRoute("3d84727705fecd04|2021-05-25--08-38-56", CHRYSLER.PACIFICA_2020), + CarTestRoute("221c253375af4ee9|2022-06-15--18-38-24", CHRYSLER.RAM_1500), + CarTestRoute("8fb5eabf914632ae|2022-08-04--17-28-53", CHRYSLER.RAM_HD, segment=6), #TestRoute("f1b4c567731f4a1b|2018-04-30--10-15-35", FORD.FUSION), - TestRoute("7cc2a8365b4dd8a9|2018-12-02--12-10-44", GM.ACADIA), - TestRoute("aa20e335f61ba898|2019-02-05--16-59-04", GM.BUICK_REGAL), - TestRoute("46460f0da08e621e|2021-10-26--07-21-46", GM.ESCALADE_ESV), - TestRoute("c950e28c26b5b168|2018-05-30--22-03-41", GM.VOLT), - TestRoute("f08912a233c1584f|2022-08-11--18-02-41", GM.BOLT_EUV), - TestRoute("38aa7da107d5d252|2022-08-15--16-01-12", GM.SILVERADO), - - TestRoute("0e7a2ba168465df5|2020-10-18--14-14-22", HONDA.ACURA_RDX_3G), - TestRoute("a74b011b32b51b56|2020-07-26--17-09-36", HONDA.CIVIC), - TestRoute("a859a044a447c2b0|2020-03-03--18-42-45", HONDA.CRV_EU), - TestRoute("68aac44ad69f838e|2021-05-18--20-40-52", HONDA.CRV), - TestRoute("14fed2e5fa0aa1a5|2021-05-25--14-59-42", HONDA.CRV_HYBRID), - TestRoute("52f3e9ae60c0d886|2021-05-23--15-59-43", HONDA.FIT), - TestRoute("2c4292a5cd10536c|2021-08-19--21-32-15", HONDA.FREED), - TestRoute("03be5f2fd5c508d1|2020-04-19--18-44-15", HONDA.HRV), - TestRoute("917b074700869333|2021-05-24--20-40-20", HONDA.ACURA_ILX), - TestRoute("81722949a62ea724|2019-04-06--15-19-25", HONDA.ODYSSEY_CHN), - TestRoute("08a3deb07573f157|2020-03-06--16-11-19", HONDA.ACCORD), # 1.5T - TestRoute("1da5847ac2488106|2021-05-24--19-31-50", HONDA.ACCORD), # 2.0T - TestRoute("085ac1d942c35910|2021-03-25--20-11-15", HONDA.ACCORD), # 2021 with new style HUD msgs - TestRoute("07585b0da3c88459|2021-05-26--18-52-04", HONDA.ACCORDH), - TestRoute("f29e2b57a55e7ad5|2021-03-24--20-52-38", HONDA.ACCORDH), # 2021 with new style HUD msgs - TestRoute("1ad763dd22ef1a0e|2020-02-29--18-37-03", HONDA.CRV_5G), - TestRoute("0a96f86fcfe35964|2020-02-05--07-25-51", HONDA.ODYSSEY), - TestRoute("d83f36766f8012a5|2020-02-05--18-42-21", HONDA.CIVIC_BOSCH_DIESEL), - TestRoute("f0890d16a07a236b|2021-05-25--17-27-22", HONDA.INSIGHT), - TestRoute("07d37d27996096b6|2020-03-04--21-57-27", HONDA.PILOT), - TestRoute("684e8f96bd491a0e|2021-11-03--11-08-42", HONDA.PASSPORT), - TestRoute("0a78dfbacc8504ef|2020-03-04--13-29-55", HONDA.CIVIC_BOSCH), - TestRoute("f34a60d68d83b1e5|2020-10-06--14-35-55", HONDA.ACURA_RDX), - TestRoute("54fd8451b3974762|2021-04-01--14-50-10", HONDA.RIDGELINE), - TestRoute("2d5808fae0b38ac6|2021-09-01--17-14-11", HONDA.HONDA_E), - TestRoute("f44aa96ace22f34a|2021-12-22--06-22-31", HONDA.CIVIC_2022), - - TestRoute("6fe86b4e410e4c37|2020-07-22--16-27-13", HYUNDAI.HYUNDAI_GENESIS), - TestRoute("70c5bec28ec8e345|2020-08-08--12-22-23", HYUNDAI.GENESIS_G70), - TestRoute("6b301bf83f10aa90|2020-11-22--16-45-07", HYUNDAI.GENESIS_G80), - TestRoute("4dbd55df87507948|2022-03-01--09-45-38", HYUNDAI.SANTA_FE), - TestRoute("bf43d9df2b660eb0|2021-09-23--14-16-37", HYUNDAI.SANTA_FE_2022), - TestRoute("37398f32561a23ad|2021-11-18--00-11-35", HYUNDAI.SANTA_FE_HEV_2022), - TestRoute("656ac0d830792fcc|2021-12-28--14-45-56", HYUNDAI.SANTA_FE_PHEV_2022, segment=1), - TestRoute("e0e98335f3ebc58f|2021-03-07--16-38-29", HYUNDAI.KIA_CEED), - TestRoute("7653b2bce7bcfdaa|2020-03-04--15-34-32", HYUNDAI.KIA_OPTIMA), - TestRoute("c75a59efa0ecd502|2021-03-11--20-52-55", HYUNDAI.KIA_SELTOS), - TestRoute("5b7c365c50084530|2020-04-15--16-13-24", HYUNDAI.SONATA), - TestRoute("b2a38c712dcf90bd|2020-05-18--18-12-48", HYUNDAI.SONATA_LF), - TestRoute("fb3fd42f0baaa2f8|2022-03-30--15-25-05", HYUNDAI.TUCSON), - TestRoute("36e10531feea61a4|2022-07-25--13-37-42", HYUNDAI.TUCSON_HYBRID_4TH_GEN), - TestRoute("5875672fc1d4bf57|2020-07-23--21-33-28", HYUNDAI.KIA_SORENTO), - TestRoute("9c917ba0d42ffe78|2020-04-17--12-43-19", HYUNDAI.PALISADE), - TestRoute("22de8111a8c5463c|2022-07-29--13-34-49", HYUNDAI.IONIQ_5), - TestRoute("3f29334d6134fcd4|2022-03-30--22-00-50", HYUNDAI.IONIQ_PHEV_2019), - TestRoute("fa8db5869167f821|2021-06-10--22-50-10", HYUNDAI.IONIQ_PHEV), - TestRoute("2c5cf2dd6102e5da|2020-12-17--16-06-44", HYUNDAI.IONIQ_EV_2020), - TestRoute("610ebb9faaad6b43|2020-06-13--15-28-36", HYUNDAI.IONIQ_EV_LTD), - TestRoute("2c5cf2dd6102e5da|2020-06-26--16-00-08", HYUNDAI.IONIQ), - TestRoute("ab59fe909f626921|2021-10-18--18-34-28", HYUNDAI.IONIQ_HEV_2022), - TestRoute("22d955b2cd499c22|2020-08-10--19-58-21", HYUNDAI.KONA), - TestRoute("efc48acf44b1e64d|2021-05-28--21-05-04", HYUNDAI.KONA_EV), - TestRoute("ff973b941a69366f|2022-07-28--22-01-19", HYUNDAI.KONA_EV_2022, segment=11), - TestRoute("49f3c13141b6bc87|2021-07-28--08-05-13", HYUNDAI.KONA_HEV), - TestRoute("5dddcbca6eb66c62|2020-07-26--13-24-19", HYUNDAI.KIA_STINGER), - TestRoute("d624b3d19adce635|2020-08-01--14-59-12", HYUNDAI.VELOSTER), - TestRoute("d824e27e8c60172c|2022-05-19--16-15-28", HYUNDAI.KIA_EV6), - TestRoute("007d5e4ad9f86d13|2021-09-30--15-09-23", HYUNDAI.KIA_K5_2021), - TestRoute("50c6c9b85fd1ff03|2020-10-26--17-56-06", HYUNDAI.KIA_NIRO_EV), - TestRoute("173219cf50acdd7b|2021-07-05--10-27-41", HYUNDAI.KIA_NIRO_PHEV), - TestRoute("34a875f29f69841a|2021-07-29--13-02-09", HYUNDAI.KIA_NIRO_HEV_2021), - TestRoute("50a2212c41f65c7b|2021-05-24--16-22-06", HYUNDAI.KIA_FORTE), - TestRoute("c5ac319aa9583f83|2021-06-01--18-18-31", HYUNDAI.ELANTRA), - TestRoute("82e9cdd3f43bf83e|2021-05-15--02-42-51", HYUNDAI.ELANTRA_2021), - TestRoute("715ac05b594e9c59|2021-06-20--16-21-07", HYUNDAI.ELANTRA_HEV_2021), - TestRoute("7120aa90bbc3add7|2021-08-02--07-12-31", HYUNDAI.SONATA_HYBRID), - TestRoute("715ac05b594e9c59|2021-10-27--23-24-56", HYUNDAI.GENESIS_G70_2020), - - TestRoute("00c829b1b7613dea|2021-06-24--09-10-10", TOYOTA.ALPHARD_TSS2), - TestRoute("912119ebd02c7a42|2022-03-19--07-24-50", TOYOTA.ALPHARDH_TSS2), - TestRoute("000cf3730200c71c|2021-05-24--10-42-05", TOYOTA.AVALON), - TestRoute("0bb588106852abb7|2021-05-26--12-22-01", TOYOTA.AVALON_2019), - TestRoute("87bef2930af86592|2021-05-30--09-40-54", TOYOTA.AVALONH_2019), - TestRoute("e9966711cfb04ce3|2022-01-11--07-59-43", TOYOTA.AVALON_TSS2), - TestRoute("eca1080a91720a54|2022-03-17--13-32-29", TOYOTA.AVALONH_TSS2), - TestRoute("6cdecc4728d4af37|2020-02-23--15-44-18", TOYOTA.CAMRY), - TestRoute("3456ad0cd7281b24|2020-12-13--17-45-56", TOYOTA.CAMRY_TSS2), - TestRoute("ffccc77938ddbc44|2021-01-04--16-55-41", TOYOTA.CAMRYH_TSS2), - TestRoute("54034823d30962f5|2021-05-24--06-37-34", TOYOTA.CAMRYH), - TestRoute("4e45c89c38e8ec4d|2021-05-02--02-49-28", TOYOTA.COROLLA), - TestRoute("5f5afb36036506e4|2019-05-14--02-09-54", TOYOTA.COROLLA_TSS2), - TestRoute("5ceff72287a5c86c|2019-10-19--10-59-02", TOYOTA.COROLLAH_TSS2), - TestRoute("d2525c22173da58b|2021-04-25--16-47-04", TOYOTA.PRIUS), - TestRoute("b14c5b4742e6fc85|2020-07-28--19-50-11", TOYOTA.RAV4), - TestRoute("32a7df20486b0f70|2020-02-06--16-06-50", TOYOTA.RAV4H), - TestRoute("cdf2f7de565d40ae|2019-04-25--03-53-41", TOYOTA.RAV4_TSS2), - TestRoute("a5c341bb250ca2f0|2022-05-18--16-05-17", TOYOTA.RAV4_TSS2_2022), - TestRoute("7e34a988419b5307|2019-12-18--19-13-30", TOYOTA.RAV4H_TSS2), - TestRoute("2475fb3eb2ffcc2e|2022-04-29--12-46-23", TOYOTA.RAV4H_TSS2_2022), - TestRoute("e6a24be49a6cd46e|2019-10-29--10-52-42", TOYOTA.LEXUS_ES_TSS2), - TestRoute("25057fa6a5a63dfb|2020-03-04--08-44-23", TOYOTA.LEXUS_CTH), - TestRoute("f49e8041283f2939|2019-05-30--11-51-51", TOYOTA.LEXUS_ESH_TSS2), - TestRoute("37041c500fd30100|2020-12-30--12-17-24", TOYOTA.LEXUS_ESH), - TestRoute("32696cea52831b02|2021-11-19--18-13-30", TOYOTA.LEXUS_RC), - TestRoute("886fcd8408d570e9|2020-01-29--05-11-22", TOYOTA.LEXUS_RX), - TestRoute("886fcd8408d570e9|2020-01-29--02-18-55", TOYOTA.LEXUS_RX), - TestRoute("d27ad752e9b08d4f|2021-05-26--19-39-51", TOYOTA.LEXUS_RXH), - TestRoute("01b22eb2ed121565|2020-02-02--11-25-51", TOYOTA.LEXUS_RX_TSS2), - TestRoute("b74758c690a49668|2020-05-20--15-58-57", TOYOTA.LEXUS_RXH_TSS2), - TestRoute("ec429c0f37564e3c|2020-02-01--17-28-12", TOYOTA.LEXUS_NXH), - TestRoute("964c09eb11ca8089|2020-11-03--22-04-00", TOYOTA.LEXUS_NX), - TestRoute("3fd5305f8b6ca765|2021-04-28--19-26-49", TOYOTA.LEXUS_NX_TSS2), - TestRoute("09ae96064ed85a14|2022-06-09--12-22-31", TOYOTA.LEXUS_NXH_TSS2), - TestRoute("0a302ffddbb3e3d3|2020-02-08--16-19-08", TOYOTA.HIGHLANDER_TSS2), - TestRoute("437e4d2402abf524|2021-05-25--07-58-50", TOYOTA.HIGHLANDERH_TSS2), - TestRoute("3183cd9b021e89ce|2021-05-25--10-34-44", TOYOTA.HIGHLANDER), - TestRoute("80d16a262e33d57f|2021-05-23--20-01-43", TOYOTA.HIGHLANDERH), - TestRoute("eb6acd681135480d|2019-06-20--20-00-00", TOYOTA.SIENNA), - TestRoute("2e07163a1ba9a780|2019-08-25--13-15-13", TOYOTA.LEXUS_IS), - TestRoute("0a0de17a1e6a2d15|2020-09-21--21-24-41", TOYOTA.PRIUS_TSS2), - TestRoute("9b36accae406390e|2021-03-30--10-41-38", TOYOTA.MIRAI), - TestRoute("cd9cff4b0b26c435|2021-05-13--15-12-39", TOYOTA.CHR), - TestRoute("57858ede0369a261|2021-05-18--20-34-20", TOYOTA.CHRH), - TestRoute("14623aae37e549f3|2021-10-24--01-20-49", TOYOTA.PRIUS_V), - - TestRoute("202c40641158a6e5|2021-09-21--09-43-24", VOLKSWAGEN.ARTEON_MK1), - TestRoute("2c68dda277d887ac|2021-05-11--15-22-20", VOLKSWAGEN.ATLAS_MK1), - TestRoute("cae14e88932eb364|2021-03-26--14-43-28", VOLKSWAGEN.GOLF_MK7), - TestRoute("58a7d3b707987d65|2021-03-25--17-26-37", VOLKSWAGEN.JETTA_MK7), - TestRoute("4d134e099430fba2|2021-03-26--00-26-06", VOLKSWAGEN.PASSAT_MK8), - TestRoute("3cfdec54aa035f3f|2022-07-19--23-45-10", VOLKSWAGEN.PASSAT_NMS), - TestRoute("0cd0b7f7e31a3853|2021-11-03--19-30-22", VOLKSWAGEN.POLO_MK6), - TestRoute("7d82b2f3a9115f1f|2021-10-21--15-39-42", VOLKSWAGEN.TAOS_MK1), - TestRoute("2744c89a8dda9a51|2021-07-24--21-28-06", VOLKSWAGEN.TCROSS_MK1), - TestRoute("2cef8a0b898f331a|2021-03-25--20-13-57", VOLKSWAGEN.TIGUAN_MK2), - TestRoute("a589dcc642fdb10a|2021-06-14--20-54-26", VOLKSWAGEN.TOURAN_MK2), - TestRoute("a459f4556782eba1|2021-09-19--09-48-00", VOLKSWAGEN.TRANSPORTER_T61), - TestRoute("0cd0b7f7e31a3853|2021-11-18--00-38-32", VOLKSWAGEN.TROC_MK1), - TestRoute("07667b885add75fd|2021-01-23--19-48-42", VOLKSWAGEN.AUDI_A3_MK3), - TestRoute("6c6b466346192818|2021-06-06--14-17-47", VOLKSWAGEN.AUDI_Q2_MK1), - TestRoute("0cd0b7f7e31a3853|2021-12-03--03-12-05", VOLKSWAGEN.AUDI_Q3_MK2), - TestRoute("8f205bdd11bcbb65|2021-03-26--01-00-17", VOLKSWAGEN.SEAT_ATECA_MK1), - TestRoute("fc6b6c9a3471c846|2021-05-27--13-39-56", VOLKSWAGEN.SEAT_LEON_MK3), - TestRoute("12d6ae3057c04b0d|2021-09-15--00-04-07", VOLKSWAGEN.SKODA_KAMIQ_MK1), - TestRoute("12d6ae3057c04b0d|2021-09-04--21-21-21", VOLKSWAGEN.SKODA_KAROQ_MK1), - TestRoute("90434ff5d7c8d603|2021-03-15--12-07-31", VOLKSWAGEN.SKODA_KODIAQ_MK1), - TestRoute("66e5edc3a16459c5|2021-05-25--19-00-29", VOLKSWAGEN.SKODA_OCTAVIA_MK3), - TestRoute("026b6d18fba6417f|2021-03-26--09-17-04", VOLKSWAGEN.SKODA_SCALA_MK1), - TestRoute("b2e9858e29db492b|2021-03-26--16-58-42", VOLKSWAGEN.SKODA_SUPERB_MK3), - - TestRoute("3c8f0c502e119c1c|2020-06-30--12-58-02", SUBARU.ASCENT), - TestRoute("c321c6b697c5a5ff|2020-06-23--11-04-33", SUBARU.FORESTER), - TestRoute("791340bc01ed993d|2019-03-10--16-28-08", SUBARU.IMPREZA), - TestRoute("8bf7e79a3ce64055|2021-05-24--09-36-27", SUBARU.IMPREZA_2020), - TestRoute("1bbe6bf2d62f58a8|2022-07-14--17-11-43", SUBARU.OUTBACK, segment=3), - TestRoute("c56e69bbc74b8fad|2022-08-18--09-43-51", SUBARU.LEGACY, segment=3), + CarTestRoute("7cc2a8365b4dd8a9|2018-12-02--12-10-44", GM.ACADIA), + CarTestRoute("aa20e335f61ba898|2019-02-05--16-59-04", GM.BUICK_REGAL), + CarTestRoute("46460f0da08e621e|2021-10-26--07-21-46", GM.ESCALADE_ESV), + CarTestRoute("c950e28c26b5b168|2018-05-30--22-03-41", GM.VOLT), + CarTestRoute("f08912a233c1584f|2022-08-11--18-02-41", GM.BOLT_EUV), + CarTestRoute("38aa7da107d5d252|2022-08-15--16-01-12", GM.SILVERADO), + + CarTestRoute("0e7a2ba168465df5|2020-10-18--14-14-22", HONDA.ACURA_RDX_3G), + CarTestRoute("a74b011b32b51b56|2020-07-26--17-09-36", HONDA.CIVIC), + CarTestRoute("a859a044a447c2b0|2020-03-03--18-42-45", HONDA.CRV_EU), + CarTestRoute("68aac44ad69f838e|2021-05-18--20-40-52", HONDA.CRV), + CarTestRoute("14fed2e5fa0aa1a5|2021-05-25--14-59-42", HONDA.CRV_HYBRID), + CarTestRoute("52f3e9ae60c0d886|2021-05-23--15-59-43", HONDA.FIT), + 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 + CarTestRoute("07585b0da3c88459|2021-05-26--18-52-04", HONDA.ACCORDH), + CarTestRoute("f29e2b57a55e7ad5|2021-03-24--20-52-38", HONDA.ACCORDH), # 2021 with new style HUD msgs + CarTestRoute("1ad763dd22ef1a0e|2020-02-29--18-37-03", HONDA.CRV_5G), + CarTestRoute("0a96f86fcfe35964|2020-02-05--07-25-51", HONDA.ODYSSEY), + CarTestRoute("d83f36766f8012a5|2020-02-05--18-42-21", HONDA.CIVIC_BOSCH_DIESEL), + CarTestRoute("f0890d16a07a236b|2021-05-25--17-27-22", HONDA.INSIGHT), + CarTestRoute("07d37d27996096b6|2020-03-04--21-57-27", HONDA.PILOT), + CarTestRoute("684e8f96bd491a0e|2021-11-03--11-08-42", HONDA.PASSPORT), + CarTestRoute("0a78dfbacc8504ef|2020-03-04--13-29-55", HONDA.CIVIC_BOSCH), + CarTestRoute("f34a60d68d83b1e5|2020-10-06--14-35-55", HONDA.ACURA_RDX), + CarTestRoute("54fd8451b3974762|2021-04-01--14-50-10", HONDA.RIDGELINE), + CarTestRoute("2d5808fae0b38ac6|2021-09-01--17-14-11", HONDA.HONDA_E), + CarTestRoute("f44aa96ace22f34a|2021-12-22--06-22-31", HONDA.CIVIC_2022), + + CarTestRoute("6fe86b4e410e4c37|2020-07-22--16-27-13", HYUNDAI.HYUNDAI_GENESIS), + CarTestRoute("70c5bec28ec8e345|2020-08-08--12-22-23", HYUNDAI.GENESIS_G70), + CarTestRoute("6b301bf83f10aa90|2020-11-22--16-45-07", HYUNDAI.GENESIS_G80), + CarTestRoute("4dbd55df87507948|2022-03-01--09-45-38", HYUNDAI.SANTA_FE), + CarTestRoute("bf43d9df2b660eb0|2021-09-23--14-16-37", HYUNDAI.SANTA_FE_2022), + CarTestRoute("37398f32561a23ad|2021-11-18--00-11-35", HYUNDAI.SANTA_FE_HEV_2022), + CarTestRoute("656ac0d830792fcc|2021-12-28--14-45-56", HYUNDAI.SANTA_FE_PHEV_2022, segment=1), + CarTestRoute("e0e98335f3ebc58f|2021-03-07--16-38-29", HYUNDAI.KIA_CEED), + CarTestRoute("7653b2bce7bcfdaa|2020-03-04--15-34-32", HYUNDAI.KIA_OPTIMA), + CarTestRoute("c75a59efa0ecd502|2021-03-11--20-52-55", HYUNDAI.KIA_SELTOS), + CarTestRoute("5b7c365c50084530|2020-04-15--16-13-24", HYUNDAI.SONATA), + CarTestRoute("b2a38c712dcf90bd|2020-05-18--18-12-48", HYUNDAI.SONATA_LF), + CarTestRoute("fb3fd42f0baaa2f8|2022-03-30--15-25-05", HYUNDAI.TUCSON), + CarTestRoute("36e10531feea61a4|2022-07-25--13-37-42", HYUNDAI.TUCSON_HYBRID_4TH_GEN), + CarTestRoute("5875672fc1d4bf57|2020-07-23--21-33-28", HYUNDAI.KIA_SORENTO), + CarTestRoute("9c917ba0d42ffe78|2020-04-17--12-43-19", HYUNDAI.PALISADE), + CarTestRoute("22de8111a8c5463c|2022-07-29--13-34-49", HYUNDAI.IONIQ_5), + CarTestRoute("3f29334d6134fcd4|2022-03-30--22-00-50", HYUNDAI.IONIQ_PHEV_2019), + CarTestRoute("fa8db5869167f821|2021-06-10--22-50-10", HYUNDAI.IONIQ_PHEV), + CarTestRoute("2c5cf2dd6102e5da|2020-12-17--16-06-44", HYUNDAI.IONIQ_EV_2020), + CarTestRoute("610ebb9faaad6b43|2020-06-13--15-28-36", HYUNDAI.IONIQ_EV_LTD), + CarTestRoute("2c5cf2dd6102e5da|2020-06-26--16-00-08", HYUNDAI.IONIQ), + CarTestRoute("ab59fe909f626921|2021-10-18--18-34-28", HYUNDAI.IONIQ_HEV_2022), + CarTestRoute("22d955b2cd499c22|2020-08-10--19-58-21", HYUNDAI.KONA), + CarTestRoute("efc48acf44b1e64d|2021-05-28--21-05-04", HYUNDAI.KONA_EV), + CarTestRoute("ff973b941a69366f|2022-07-28--22-01-19", HYUNDAI.KONA_EV_2022, segment=11), + CarTestRoute("49f3c13141b6bc87|2021-07-28--08-05-13", HYUNDAI.KONA_HEV), + CarTestRoute("5dddcbca6eb66c62|2020-07-26--13-24-19", HYUNDAI.KIA_STINGER), + CarTestRoute("d624b3d19adce635|2020-08-01--14-59-12", HYUNDAI.VELOSTER), + CarTestRoute("d824e27e8c60172c|2022-05-19--16-15-28", HYUNDAI.KIA_EV6), + CarTestRoute("007d5e4ad9f86d13|2021-09-30--15-09-23", HYUNDAI.KIA_K5_2021), + CarTestRoute("50c6c9b85fd1ff03|2020-10-26--17-56-06", HYUNDAI.KIA_NIRO_EV), + CarTestRoute("173219cf50acdd7b|2021-07-05--10-27-41", HYUNDAI.KIA_NIRO_PHEV), + 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("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), + CarTestRoute("715ac05b594e9c59|2021-10-27--23-24-56", HYUNDAI.GENESIS_G70_2020), + + CarTestRoute("00c829b1b7613dea|2021-06-24--09-10-10", TOYOTA.ALPHARD_TSS2), + CarTestRoute("912119ebd02c7a42|2022-03-19--07-24-50", TOYOTA.ALPHARDH_TSS2), + CarTestRoute("000cf3730200c71c|2021-05-24--10-42-05", TOYOTA.AVALON), + CarTestRoute("0bb588106852abb7|2021-05-26--12-22-01", TOYOTA.AVALON_2019), + CarTestRoute("87bef2930af86592|2021-05-30--09-40-54", TOYOTA.AVALONH_2019), + CarTestRoute("e9966711cfb04ce3|2022-01-11--07-59-43", TOYOTA.AVALON_TSS2), + CarTestRoute("eca1080a91720a54|2022-03-17--13-32-29", TOYOTA.AVALONH_TSS2), + CarTestRoute("6cdecc4728d4af37|2020-02-23--15-44-18", TOYOTA.CAMRY), + CarTestRoute("3456ad0cd7281b24|2020-12-13--17-45-56", TOYOTA.CAMRY_TSS2), + CarTestRoute("ffccc77938ddbc44|2021-01-04--16-55-41", TOYOTA.CAMRYH_TSS2), + CarTestRoute("54034823d30962f5|2021-05-24--06-37-34", TOYOTA.CAMRYH), + CarTestRoute("4e45c89c38e8ec4d|2021-05-02--02-49-28", TOYOTA.COROLLA), + CarTestRoute("5f5afb36036506e4|2019-05-14--02-09-54", TOYOTA.COROLLA_TSS2), + CarTestRoute("5ceff72287a5c86c|2019-10-19--10-59-02", TOYOTA.COROLLAH_TSS2), + CarTestRoute("d2525c22173da58b|2021-04-25--16-47-04", TOYOTA.PRIUS), + CarTestRoute("b14c5b4742e6fc85|2020-07-28--19-50-11", TOYOTA.RAV4), + CarTestRoute("32a7df20486b0f70|2020-02-06--16-06-50", TOYOTA.RAV4H), + CarTestRoute("cdf2f7de565d40ae|2019-04-25--03-53-41", TOYOTA.RAV4_TSS2), + CarTestRoute("a5c341bb250ca2f0|2022-05-18--16-05-17", TOYOTA.RAV4_TSS2_2022), + CarTestRoute("7e34a988419b5307|2019-12-18--19-13-30", TOYOTA.RAV4H_TSS2), + CarTestRoute("2475fb3eb2ffcc2e|2022-04-29--12-46-23", TOYOTA.RAV4H_TSS2_2022), + CarTestRoute("e6a24be49a6cd46e|2019-10-29--10-52-42", TOYOTA.LEXUS_ES_TSS2), + CarTestRoute("25057fa6a5a63dfb|2020-03-04--08-44-23", TOYOTA.LEXUS_CTH), + CarTestRoute("f49e8041283f2939|2019-05-30--11-51-51", TOYOTA.LEXUS_ESH_TSS2), + CarTestRoute("37041c500fd30100|2020-12-30--12-17-24", TOYOTA.LEXUS_ESH), + CarTestRoute("32696cea52831b02|2021-11-19--18-13-30", TOYOTA.LEXUS_RC), + CarTestRoute("886fcd8408d570e9|2020-01-29--05-11-22", TOYOTA.LEXUS_RX), + CarTestRoute("886fcd8408d570e9|2020-01-29--02-18-55", TOYOTA.LEXUS_RX), + CarTestRoute("d27ad752e9b08d4f|2021-05-26--19-39-51", TOYOTA.LEXUS_RXH), + CarTestRoute("01b22eb2ed121565|2020-02-02--11-25-51", TOYOTA.LEXUS_RX_TSS2), + CarTestRoute("b74758c690a49668|2020-05-20--15-58-57", TOYOTA.LEXUS_RXH_TSS2), + CarTestRoute("ec429c0f37564e3c|2020-02-01--17-28-12", TOYOTA.LEXUS_NXH), + CarTestRoute("964c09eb11ca8089|2020-11-03--22-04-00", TOYOTA.LEXUS_NX), + CarTestRoute("3fd5305f8b6ca765|2021-04-28--19-26-49", TOYOTA.LEXUS_NX_TSS2), + CarTestRoute("09ae96064ed85a14|2022-06-09--12-22-31", TOYOTA.LEXUS_NXH_TSS2), + CarTestRoute("0a302ffddbb3e3d3|2020-02-08--16-19-08", TOYOTA.HIGHLANDER_TSS2), + CarTestRoute("437e4d2402abf524|2021-05-25--07-58-50", TOYOTA.HIGHLANDERH_TSS2), + CarTestRoute("3183cd9b021e89ce|2021-05-25--10-34-44", TOYOTA.HIGHLANDER), + CarTestRoute("80d16a262e33d57f|2021-05-23--20-01-43", TOYOTA.HIGHLANDERH), + CarTestRoute("eb6acd681135480d|2019-06-20--20-00-00", TOYOTA.SIENNA), + CarTestRoute("2e07163a1ba9a780|2019-08-25--13-15-13", TOYOTA.LEXUS_IS), + CarTestRoute("0a0de17a1e6a2d15|2020-09-21--21-24-41", TOYOTA.PRIUS_TSS2), + CarTestRoute("9b36accae406390e|2021-03-30--10-41-38", TOYOTA.MIRAI), + CarTestRoute("cd9cff4b0b26c435|2021-05-13--15-12-39", TOYOTA.CHR), + CarTestRoute("57858ede0369a261|2021-05-18--20-34-20", TOYOTA.CHRH), + CarTestRoute("14623aae37e549f3|2021-10-24--01-20-49", TOYOTA.PRIUS_V), + + CarTestRoute("202c40641158a6e5|2021-09-21--09-43-24", VOLKSWAGEN.ARTEON_MK1), + CarTestRoute("2c68dda277d887ac|2021-05-11--15-22-20", VOLKSWAGEN.ATLAS_MK1), + CarTestRoute("cae14e88932eb364|2021-03-26--14-43-28", VOLKSWAGEN.GOLF_MK7), + CarTestRoute("58a7d3b707987d65|2021-03-25--17-26-37", VOLKSWAGEN.JETTA_MK7), + CarTestRoute("4d134e099430fba2|2021-03-26--00-26-06", VOLKSWAGEN.PASSAT_MK8), + CarTestRoute("3cfdec54aa035f3f|2022-07-19--23-45-10", VOLKSWAGEN.PASSAT_NMS), + CarTestRoute("0cd0b7f7e31a3853|2021-11-03--19-30-22", VOLKSWAGEN.POLO_MK6), + CarTestRoute("7d82b2f3a9115f1f|2021-10-21--15-39-42", VOLKSWAGEN.TAOS_MK1), + CarTestRoute("2744c89a8dda9a51|2021-07-24--21-28-06", VOLKSWAGEN.TCROSS_MK1), + CarTestRoute("2cef8a0b898f331a|2021-03-25--20-13-57", VOLKSWAGEN.TIGUAN_MK2), + CarTestRoute("a589dcc642fdb10a|2021-06-14--20-54-26", VOLKSWAGEN.TOURAN_MK2), + CarTestRoute("a459f4556782eba1|2021-09-19--09-48-00", VOLKSWAGEN.TRANSPORTER_T61), + CarTestRoute("0cd0b7f7e31a3853|2021-11-18--00-38-32", VOLKSWAGEN.TROC_MK1), + CarTestRoute("07667b885add75fd|2021-01-23--19-48-42", VOLKSWAGEN.AUDI_A3_MK3), + CarTestRoute("6c6b466346192818|2021-06-06--14-17-47", VOLKSWAGEN.AUDI_Q2_MK1), + CarTestRoute("0cd0b7f7e31a3853|2021-12-03--03-12-05", VOLKSWAGEN.AUDI_Q3_MK2), + CarTestRoute("8f205bdd11bcbb65|2021-03-26--01-00-17", VOLKSWAGEN.SEAT_ATECA_MK1), + CarTestRoute("fc6b6c9a3471c846|2021-05-27--13-39-56", VOLKSWAGEN.SEAT_LEON_MK3), + CarTestRoute("12d6ae3057c04b0d|2021-09-15--00-04-07", VOLKSWAGEN.SKODA_KAMIQ_MK1), + CarTestRoute("12d6ae3057c04b0d|2021-09-04--21-21-21", VOLKSWAGEN.SKODA_KAROQ_MK1), + CarTestRoute("90434ff5d7c8d603|2021-03-15--12-07-31", VOLKSWAGEN.SKODA_KODIAQ_MK1), + CarTestRoute("66e5edc3a16459c5|2021-05-25--19-00-29", VOLKSWAGEN.SKODA_OCTAVIA_MK3), + CarTestRoute("026b6d18fba6417f|2021-03-26--09-17-04", VOLKSWAGEN.SKODA_SCALA_MK1), + CarTestRoute("b2e9858e29db492b|2021-03-26--16-58-42", VOLKSWAGEN.SKODA_SUPERB_MK3), + + CarTestRoute("3c8f0c502e119c1c|2020-06-30--12-58-02", SUBARU.ASCENT), + CarTestRoute("c321c6b697c5a5ff|2020-06-23--11-04-33", SUBARU.FORESTER), + CarTestRoute("791340bc01ed993d|2019-03-10--16-28-08", SUBARU.IMPREZA), + CarTestRoute("8bf7e79a3ce64055|2021-05-24--09-36-27", SUBARU.IMPREZA_2020), + CarTestRoute("1bbe6bf2d62f58a8|2022-07-14--17-11-43", SUBARU.OUTBACK, segment=3), + CarTestRoute("c56e69bbc74b8fad|2022-08-18--09-43-51", SUBARU.LEGACY, segment=3), # Pre-global, dashcam - TestRoute("95441c38ae8c130e|2020-06-08--12-10-17", SUBARU.FORESTER_PREGLOBAL), - TestRoute("df5ca7660000fba8|2020-06-16--17-37-19", SUBARU.LEGACY_PREGLOBAL), - TestRoute("5ab784f361e19b78|2020-06-08--16-30-41", SUBARU.OUTBACK_PREGLOBAL), - TestRoute("e19eb5d5353b1ac1|2020-08-09--14-37-56", SUBARU.OUTBACK_PREGLOBAL_2018), - - TestRoute("fbbfa6af821552b9|2020-03-03--08-09-43", NISSAN.XTRAIL), - TestRoute("5b7c365c50084530|2020-03-25--22-10-13", NISSAN.LEAF), - TestRoute("22c3dcce2dd627eb|2020-12-30--16-38-48", NISSAN.LEAF_IC), - TestRoute("059ab9162e23198e|2020-05-30--09-41-01", NISSAN.ROGUE), - TestRoute("b72d3ec617c0a90f|2020-12-11--15-38-17", NISSAN.ALTIMA), - - TestRoute("32a319f057902bb3|2020-04-27--15-18-58", MAZDA.CX5), - TestRoute("10b5a4b380434151|2020-08-26--17-11-45", MAZDA.CX9), - TestRoute("74f1038827005090|2020-08-26--20-05-50", MAZDA.MAZDA3), - TestRoute("fb53c640f499b73d|2021-06-01--04-17-56", MAZDA.MAZDA6), - TestRoute("f6d5b1a9d7a1c92e|2021-07-08--06-56-59", MAZDA.CX9_2021), - TestRoute("a4af1602d8e668ac|2022-02-03--12-17-07", MAZDA.CX5_2022), - - TestRoute("6c14ee12b74823ce|2021-06-30--11-49-02", TESLA.AP1_MODELS), - TestRoute("bb50caf5f0945ab1|2021-06-19--17-20-18", TESLA.AP2_MODELS), + CarTestRoute("95441c38ae8c130e|2020-06-08--12-10-17", SUBARU.FORESTER_PREGLOBAL), + CarTestRoute("df5ca7660000fba8|2020-06-16--17-37-19", SUBARU.LEGACY_PREGLOBAL), + CarTestRoute("5ab784f361e19b78|2020-06-08--16-30-41", SUBARU.OUTBACK_PREGLOBAL), + CarTestRoute("e19eb5d5353b1ac1|2020-08-09--14-37-56", SUBARU.OUTBACK_PREGLOBAL_2018), + + CarTestRoute("fbbfa6af821552b9|2020-03-03--08-09-43", NISSAN.XTRAIL), + CarTestRoute("5b7c365c50084530|2020-03-25--22-10-13", NISSAN.LEAF), + CarTestRoute("22c3dcce2dd627eb|2020-12-30--16-38-48", NISSAN.LEAF_IC), + CarTestRoute("059ab9162e23198e|2020-05-30--09-41-01", NISSAN.ROGUE), + CarTestRoute("b72d3ec617c0a90f|2020-12-11--15-38-17", NISSAN.ALTIMA), + + CarTestRoute("32a319f057902bb3|2020-04-27--15-18-58", MAZDA.CX5), + CarTestRoute("10b5a4b380434151|2020-08-26--17-11-45", MAZDA.CX9), + CarTestRoute("74f1038827005090|2020-08-26--20-05-50", MAZDA.MAZDA3), + CarTestRoute("fb53c640f499b73d|2021-06-01--04-17-56", MAZDA.MAZDA6), + CarTestRoute("f6d5b1a9d7a1c92e|2021-07-08--06-56-59", MAZDA.CX9_2021), + CarTestRoute("a4af1602d8e668ac|2022-02-03--12-17-07", MAZDA.CX5_2022), + + CarTestRoute("6c14ee12b74823ce|2021-06-30--11-49-02", TESLA.AP1_MODELS), + CarTestRoute("bb50caf5f0945ab1|2021-06-19--17-20-18", TESLA.AP2_MODELS), # Segments that test specific issues # Controls mismatch due to interceptor threshold - TestRoute("cfb32f0fb91b173b|2022-04-06--14-54-45", HONDA.CIVIC, segment=21), - TestRoute("5a8762b91fc70467|2022-04-14--21-26-20", TOYOTA.RAV4, segment=2), + CarTestRoute("cfb32f0fb91b173b|2022-04-06--14-54-45", HONDA.CIVIC, segment=21), + CarTestRoute("5a8762b91fc70467|2022-04-14--21-26-20", TOYOTA.RAV4, segment=2), # Controls mismatch due to standstill threshold - TestRoute("bec2dcfde6a64235|2022-04-08--14-21-32", HONDA.CRV_HYBRID, segment=22), + CarTestRoute("bec2dcfde6a64235|2022-04-08--14-21-32", HONDA.CRV_HYBRID, segment=22), ] diff --git a/selfdrive/car/tests/test_models.py b/selfdrive/car/tests/test_models.py index 6e88e227c..502df3fe3 100755 --- a/selfdrive/car/tests/test_models.py +++ b/selfdrive/car/tests/test_models.py @@ -15,7 +15,7 @@ from selfdrive.car.car_helpers import interfaces from selfdrive.car.gm.values import CAR as GM from selfdrive.car.honda.values import CAR as HONDA, HONDA_BOSCH from selfdrive.car.hyundai.values import CAR as HYUNDAI -from selfdrive.car.tests.routes import non_tested_cars, routes, TestRoute +from selfdrive.car.tests.routes import non_tested_cars, routes, CarTestRoute from selfdrive.test.openpilotci import get_url from tools.lib.logreader import LogReader from tools.lib.route import Route @@ -38,7 +38,7 @@ routes_by_car = defaultdict(set) for r in routes: routes_by_car[r.car_model].add(r) -test_cases: List[Tuple[str, Optional[TestRoute]]] = [] +test_cases: List[Tuple[str, Optional[CarTestRoute]]] = [] for i, c in enumerate(sorted(all_known_cars())): if i % NUM_JOBS == JOB_ID: test_cases.extend((c, r) for r in routes_by_car.get(c, (None, ))) diff --git a/selfdrive/debug/test_car_model.py b/selfdrive/debug/test_car_model.py index 9082dbe3d..4de5b2676 100755 --- a/selfdrive/debug/test_car_model.py +++ b/selfdrive/debug/test_car_model.py @@ -4,11 +4,11 @@ import sys from typing import List, Tuple import unittest -from selfdrive.car.tests.routes import TestRoute +from selfdrive.car.tests.routes import CarTestRoute from selfdrive.car.tests.test_models import TestCarModel -def create_test_models_suite(routes: List[Tuple[str, TestRoute]], ci=False) -> unittest.TestSuite: +def create_test_models_suite(routes: List[Tuple[str, CarTestRoute]], ci=False) -> unittest.TestSuite: test_suite = unittest.TestSuite() for car_model, test_route in routes: # create new test case and discover tests @@ -30,7 +30,7 @@ if __name__ == "__main__": parser.print_help() sys.exit() - test_route = TestRoute(args.route, args.car, segment=args.segment) + test_route = CarTestRoute(args.route, args.car, segment=args.segment) test_suite = create_test_models_suite([(args.car, test_route)], ci=args.ci) unittest.TextTestRunner().run(test_suite) From 2f604d2f1a53ebecac02612a30d16566bb7e0a74 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 23 Aug 2022 17:29:03 -0700 Subject: [PATCH 069/172] bump version to 0.8.17 --- RELEASES.md | 3 +++ common/version.h | 2 +- 2 files changed, 4 insertions(+), 1 deletion(-) diff --git a/RELEASES.md b/RELEASES.md index a6ba4558e..3ac6c8e41 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,3 +1,6 @@ +Version 0.8.17 (2022-XX-XX) +======================== + Version 0.8.16 (2022-08-26) ======================== * New driving model diff --git a/common/version.h b/common/version.h index bf1c58df1..0a109c1fa 100644 --- a/common/version.h +++ b/common/version.h @@ -1 +1 @@ -#define COMMA_VERSION "0.8.16" +#define COMMA_VERSION "0.8.17" From 70f7340c173f0a4b0d3bb98dda9032cd304f890e Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 23 Aug 2022 17:48:34 -0700 Subject: [PATCH 070/172] Toyota: log stockAeb on non-TSS2 cars (#25489) * check PRE_COLLISION * need to make sure this is right * revert * temp, stash * fixes * uncomment that * it's not really cruise/pcm, but acc remove improt * revert * Fix CI * revert exception * Revert "revert exception" This reverts commit 7e2f39097651f17cf3d2ac9f442fab5071e1b9d0. * this tested enableDsu, but we have other routes that do that * use segment from db * remove exception again --- selfdrive/car/tests/routes.py | 3 +-- selfdrive/car/toyota/carstate.py | 38 ++++++++++++++++++-------------- 2 files changed, 23 insertions(+), 18 deletions(-) diff --git a/selfdrive/car/tests/routes.py b/selfdrive/car/tests/routes.py index a47a3447e..b769cbe5f 100644 --- a/selfdrive/car/tests/routes.py +++ b/selfdrive/car/tests/routes.py @@ -140,11 +140,10 @@ routes = [ CarTestRoute("7e34a988419b5307|2019-12-18--19-13-30", TOYOTA.RAV4H_TSS2), CarTestRoute("2475fb3eb2ffcc2e|2022-04-29--12-46-23", TOYOTA.RAV4H_TSS2_2022), CarTestRoute("e6a24be49a6cd46e|2019-10-29--10-52-42", TOYOTA.LEXUS_ES_TSS2), - CarTestRoute("25057fa6a5a63dfb|2020-03-04--08-44-23", TOYOTA.LEXUS_CTH), + CarTestRoute("da23c367491f53e2|2021-05-21--09-09-11", TOYOTA.LEXUS_CTH, segment=3), CarTestRoute("f49e8041283f2939|2019-05-30--11-51-51", TOYOTA.LEXUS_ESH_TSS2), CarTestRoute("37041c500fd30100|2020-12-30--12-17-24", TOYOTA.LEXUS_ESH), CarTestRoute("32696cea52831b02|2021-11-19--18-13-30", TOYOTA.LEXUS_RC), - CarTestRoute("886fcd8408d570e9|2020-01-29--05-11-22", TOYOTA.LEXUS_RX), CarTestRoute("886fcd8408d570e9|2020-01-29--02-18-55", TOYOTA.LEXUS_RX), CarTestRoute("d27ad752e9b08d4f|2021-05-26--19-39-51", TOYOTA.LEXUS_RXH), CarTestRoute("01b22eb2ed121565|2020-02-02--11-25-51", TOYOTA.LEXUS_RX_TSS2), diff --git a/selfdrive/car/toyota/carstate.py b/selfdrive/car/toyota/carstate.py index 537915919..843e7806d 100644 --- a/selfdrive/car/toyota/carstate.py +++ b/selfdrive/car/toyota/carstate.py @@ -94,12 +94,11 @@ class CarState(CarStateBase): ret.cruiseState.available = cp.vl["PCM_CRUISE_2"]["MAIN_ON"] != 0 ret.cruiseState.speed = cp.vl["PCM_CRUISE_2"]["SET_SPEED"] * CV.KPH_TO_MS - if self.CP.carFingerprint in RADAR_ACC_CAR: - self.acc_type = cp.vl["ACC_CONTROL"]["ACC_TYPE"] - ret.stockFcw = bool(cp.vl["ACC_HUD"]["FCW"]) - elif self.CP.carFingerprint in TSS2_CAR: - self.acc_type = cp_cam.vl["ACC_CONTROL"]["ACC_TYPE"] - ret.stockFcw = bool(cp_cam.vl["ACC_HUD"]["FCW"]) + cp_acc = cp_cam if self.CP.carFingerprint in (TSS2_CAR - RADAR_ACC_CAR) else cp + + if self.CP.carFingerprint in (TSS2_CAR | RADAR_ACC_CAR): + self.acc_type = cp_acc.vl["ACC_CONTROL"]["ACC_TYPE"] + ret.stockFcw = bool(cp_acc.vl["ACC_HUD"]["FCW"]) # some TSS2 cars have low speed lockout permanently set, so ignore on those cars # these cars are identified by an ACC_TYPE value of 2. @@ -120,10 +119,11 @@ class CarState(CarStateBase): ret.cruiseState.nonAdaptive = cp.vl["PCM_CRUISE"]["CRUISE_STATE"] in (1, 2, 3, 4, 5, 6) ret.genericToggle = bool(cp.vl["LIGHT_STALK"]["AUTO_HIGH_BEAM"]) - ret.stockAeb = bool(cp_cam.vl["PRE_COLLISION"]["PRECOLLISION_ACTIVE"] and cp_cam.vl["PRE_COLLISION"]["FORCE"] < -1e-5) - ret.espDisabled = cp.vl["ESP_CONTROL"]["TC_DISABLED"] != 0 + if not self.CP.enableDsu: + ret.stockAeb = bool(cp_acc.vl["PRE_COLLISION"]["PRECOLLISION_ACTIVE"] and cp_acc.vl["PRE_COLLISION"]["FORCE"] < -1e-5) + if self.CP.enableBsm: ret.leftBlindspot = (cp.vl["BSM"]["L_ADJACENT"] == 1) or (cp.vl["BSM"]["L_APPROACHING"] == 1) ret.rightBlindspot = (cp.vl["BSM"]["R_ADJACENT"] == 1) or (cp.vl["BSM"]["R_APPROACHING"] == 1) @@ -219,25 +219,31 @@ class CarState(CarStateBase): ("ACC_HUD", 1), ] + if CP.carFingerprint not in (TSS2_CAR - RADAR_ACC_CAR) and not CP.enableDsu: + signals += [ + ("FORCE", "PRE_COLLISION"), + ("PRECOLLISION_ACTIVE", "PRE_COLLISION"), + ] + checks += [ + ("PRE_COLLISION", 33), + ] + return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 0) @staticmethod def get_cam_can_parser(CP): - signals = [ - ("FORCE", "PRE_COLLISION"), - ("PRECOLLISION_ACTIVE", "PRE_COLLISION"), - ] - - checks = [ - ("PRE_COLLISION", 0), # TODO: figure out why freq is inconsistent - ] + signals = [] + checks = [] if CP.carFingerprint in (TSS2_CAR - RADAR_ACC_CAR): signals += [ + ("PRECOLLISION_ACTIVE", "PRE_COLLISION"), + ("FORCE", "PRE_COLLISION"), ("ACC_TYPE", "ACC_CONTROL"), ("FCW", "ACC_HUD"), ] checks += [ + ("PRE_COLLISION", 33), ("ACC_CONTROL", 33), ("ACC_HUD", 1), ] From 405e6c046d45d2f15cf9a111ae84f7e6dd2b2f85 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Thu, 25 Aug 2022 02:03:12 +0800 Subject: [PATCH 071/172] CameraBuf: remove unused cur_rgb_buf (#25544) rm cur_rgb_buf --- system/camerad/cameras/camera_common.h | 1 - 1 file changed, 1 deletion(-) diff --git a/system/camerad/cameras/camera_common.h b/system/camerad/cameras/camera_common.h index 2a5605255..198efca0b 100644 --- a/system/camerad/cameras/camera_common.h +++ b/system/camerad/cameras/camera_common.h @@ -94,7 +94,6 @@ private: public: cl_command_queue q; FrameMetadata cur_frame_data; - VisionBuf *cur_rgb_buf; VisionBuf *cur_yuv_buf; VisionBuf *cur_camera_buf; std::unique_ptr camera_bufs; From f95519cb440ab25e24f14c12d37da535646d8419 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Thu, 25 Aug 2022 02:03:54 +0800 Subject: [PATCH 072/172] replay/CameraServer: yuv_buf should not be null (#25545) --- tools/replay/camera.cc | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/tools/replay/camera.cc b/tools/replay/camera.cc index 87afe63a2..1a577b40c 100644 --- a/tools/replay/camera.cc +++ b/tools/replay/camera.cc @@ -37,7 +37,8 @@ void CameraServer::startVipcServer() { void CameraServer::cameraThread(Camera &cam) { auto read_frame = [&](FrameReader *fr, int frame_id) { VisionBuf *yuv_buf = vipc_server_->get_buffer(cam.stream_type); - bool ret = fr->get(frame_id, yuv_buf ? (uint8_t *)yuv_buf->addr : nullptr); + assert(yuv_buf); + bool ret = fr->get(frame_id, (uint8_t *)yuv_buf->addr); return ret ? yuv_buf : nullptr; }; From c62447c7843141e426b24f71b7d7c5488aaf8c5d Mon Sep 17 00:00:00 2001 From: Jeroen Date: Wed, 24 Aug 2022 20:16:17 +0200 Subject: [PATCH 073/172] Fix broken url in translations README (#25546) Fix url in README.md --- selfdrive/ui/translations/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/ui/translations/README.md b/selfdrive/ui/translations/README.md index ac3112c61..91a6c3ca2 100644 --- a/selfdrive/ui/translations/README.md +++ b/selfdrive/ui/translations/README.md @@ -8,7 +8,7 @@ Before getting started, make sure you have set up the openpilot Ubuntu developme ### Policy -Most of the languages supported by openpilot come from and are maintained by the community via pull requests. A pull request likely to be merged is one that [fixes a translation or adds missing translations.](https://github.com/commaai/openpilot/blob/lang-policy/selfdrive/ui/translations/README.md#improving-an-existing-language) +Most of the languages supported by openpilot come from and are maintained by the community via pull requests. A pull request likely to be merged is one that [fixes a translation or adds missing translations.](https://github.com/commaai/openpilot/blob/master/selfdrive/ui/translations/README.md#improving-an-existing-language) We also generally merge pull requests adding support for a new language if there are community members willing to maintain it. Maintaining a language is ensuring quality and completion of translations before each openpilot release. From 70f2891928a3b7b89d19d57dfd7f1197806e2204 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Wed, 24 Aug 2022 16:06:11 -0700 Subject: [PATCH 074/172] Chrysler: whitelist FPv2 queries (#25549) * Add whitelist to Chrysler queries * gateway will respond to both (same 29-bit rx addr) * missing esp --- selfdrive/car/fw_versions.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/selfdrive/car/fw_versions.py b/selfdrive/car/fw_versions.py index 9d2fd11b4..66a19a610 100755 --- a/selfdrive/car/fw_versions.py +++ b/selfdrive/car/fw_versions.py @@ -208,12 +208,14 @@ REQUESTS: List[Request] = [ "chrysler", [CHRYSLER_VERSION_REQUEST], [CHRYSLER_VERSION_RESPONSE], + whitelist_ecus=[Ecu.esp, Ecu.eps, Ecu.srs, Ecu.gateway, Ecu.fwdRadar, Ecu.fwdCamera, Ecu.combinationMeter], rx_offset=CHRYSLER_RX_OFFSET, ), Request( "chrysler", [CHRYSLER_VERSION_REQUEST], [CHRYSLER_VERSION_RESPONSE], + whitelist_ecus=[Ecu.engine, Ecu.transmission], ), # Ford Request( From 2f46fe5d856be0637cb55e460ea3f2d34be1703c Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Thu, 25 Aug 2022 00:01:21 -0700 Subject: [PATCH 075/172] Nuclear Grade Model: less memory, more accuracy (#25524) * c9d10c64-bea4-41ec-8ca3-d8c886fda172/440 6d1c8a6b-4070-4780-80f1-6f08f234275e/900 * update ref --- selfdrive/modeld/models/supercombo.dlc | 2 +- selfdrive/modeld/models/supercombo.onnx | 4 ++-- selfdrive/test/process_replay/model_replay_ref_commit | 2 +- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/selfdrive/modeld/models/supercombo.dlc b/selfdrive/modeld/models/supercombo.dlc index fe3ad5102..fe133523f 100644 --- a/selfdrive/modeld/models/supercombo.dlc +++ b/selfdrive/modeld/models/supercombo.dlc @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:3c5c8d71a8a1434ef79073362e608b9fe02f22ce7478f11bc71c6806c1e00091 +oid sha256:93d265fc88f05746ce47257e15fc2afe43b250b44715313049f829e8aa30a9d6 size 94302331 diff --git a/selfdrive/modeld/models/supercombo.onnx b/selfdrive/modeld/models/supercombo.onnx index 39e874364..7b11edbe0 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:15d9eb01edd98998abceaa092d33fab149ff4a8942646b20a7c1403f999f4eca -size 95165081 +oid sha256:50c7fc8565ac69a4b9a0de122e961326820e78bf13659255a89d0ed04be030d5 +size 95167481 diff --git a/selfdrive/test/process_replay/model_replay_ref_commit b/selfdrive/test/process_replay/model_replay_ref_commit index e5bbfa74c..80be9b464 100644 --- a/selfdrive/test/process_replay/model_replay_ref_commit +++ b/selfdrive/test/process_replay/model_replay_ref_commit @@ -1 +1 @@ -507241e0a41ee757cca4eb6ff12cff3f02c0b98a +ca90e11f8d59902af38d3785ddd91a27d0fbb411 From 6e46587cc619681e32c8b8813fd70e9afd280471 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Thu, 25 Aug 2022 10:15:50 -0700 Subject: [PATCH 076/172] Update RELEASES.md --- RELEASES.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/RELEASES.md b/RELEASES.md index 3ac6c8e41..d2ae440f2 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,5 +1,7 @@ Version 0.8.17 (2022-XX-XX) ======================== +New driving model +* Internal feature space accuracy increased tenfold, this makes the model dramatically more accurate. Version 0.8.16 (2022-08-26) ======================== From ce14deb83f0db5ee020add8887f6ec4f5cf76d4e Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Thu, 25 Aug 2022 10:16:11 -0700 Subject: [PATCH 077/172] Update RELEASES.md --- RELEASES.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/RELEASES.md b/RELEASES.md index d2ae440f2..5f349e50e 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,7 +1,7 @@ Version 0.8.17 (2022-XX-XX) ======================== -New driving model -* Internal feature space accuracy increased tenfold, this makes the model dramatically more accurate. +* New driving model + * Internal feature space accuracy increased tenfold, this makes the model dramatically more accurate. Version 0.8.16 (2022-08-26) ======================== From dfad3d22dcbe5ae9ec97d787f86ebd9be37804e6 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Thu, 25 Aug 2022 10:24:05 -0700 Subject: [PATCH 078/172] Update RELEASES.md --- RELEASES.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/RELEASES.md b/RELEASES.md index 5f349e50e..28a010968 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,7 +1,7 @@ Version 0.8.17 (2022-XX-XX) ======================== * New driving model - * Internal feature space accuracy increased tenfold, this makes the model dramatically more accurate. + * Internal feature space accuracy increased tenfold during training, this makes the model dramatically more accurate. Version 0.8.16 (2022-08-26) ======================== From 08510e2b0a77a2adab90c24c5f560b7a0e3816f7 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 25 Aug 2022 11:44:57 -0700 Subject: [PATCH 079/172] Chrysler: add engine-specific FW request for some cars (#25503) * Try to get Chrysler engine FW * try this * Get engine FW for certain Chrysler * Add our Ram's engine FW * better name * no whitelist * engine and transmission only --- selfdrive/car/chrysler/values.py | 1 + selfdrive/car/fw_versions.py | 11 +++++++++++ 2 files changed, 12 insertions(+) diff --git a/selfdrive/car/chrysler/values.py b/selfdrive/car/chrysler/values.py index 10478efa8..ef5471490 100644 --- a/selfdrive/car/chrysler/values.py +++ b/selfdrive/car/chrysler/values.py @@ -170,6 +170,7 @@ FW_VERSIONS = { b'68448163AJ', b'68500630AD', b'68539650AD', + b'68378758AM ', ], (Ecu.transmission, 0x7e1, None): [ b'68360078AL', diff --git a/selfdrive/car/fw_versions.py b/selfdrive/car/fw_versions.py index 66a19a610..886bf4aff 100755 --- a/selfdrive/car/fw_versions.py +++ b/selfdrive/car/fw_versions.py @@ -97,6 +97,11 @@ CHRYSLER_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ CHRYSLER_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ p16(0xf132) +CHRYSLER_SOFTWARE_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ + p16(uds.DATA_IDENTIFIER_TYPE.SYSTEM_SUPPLIER_ECU_SOFTWARE_NUMBER) +CHRYSLER_SOFTWARE_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ + p16(uds.DATA_IDENTIFIER_TYPE.SYSTEM_SUPPLIER_ECU_SOFTWARE_NUMBER) + CHRYSLER_RX_OFFSET = -0x280 FORD_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ @@ -217,6 +222,12 @@ REQUESTS: List[Request] = [ [CHRYSLER_VERSION_RESPONSE], whitelist_ecus=[Ecu.engine, Ecu.transmission], ), + Request( + "chrysler", + [CHRYSLER_SOFTWARE_VERSION_REQUEST], + [CHRYSLER_SOFTWARE_VERSION_RESPONSE], + whitelist_ecus=[Ecu.engine, Ecu.transmission], + ), # Ford Request( "ford", From 8245ba4d307f16e853c0cc4288a217770d2049b4 Mon Sep 17 00:00:00 2001 From: royjr Date: Thu, 25 Aug 2022 15:16:34 -0400 Subject: [PATCH 080/172] Add Arabic Translation (#25269) * arabic * update to add plurals * Update translations * don't show lang for now Co-authored-by: Shane Smiskol --- selfdrive/ui/translations/main_ar.ts | 1323 ++++++++++++++++++++++++++ 1 file changed, 1323 insertions(+) create mode 100644 selfdrive/ui/translations/main_ar.ts diff --git a/selfdrive/ui/translations/main_ar.ts b/selfdrive/ui/translations/main_ar.ts new file mode 100644 index 000000000..284208720 --- /dev/null +++ b/selfdrive/ui/translations/main_ar.ts @@ -0,0 +1,1323 @@ + + + + + AbstractAlert + + + Close + أغلق + + + + Snooze Update + تأخير التحديث + + + + Reboot and Update + إعادة التشغيل والتحديث + + + + AdvancedNetworking + + + Back + خلف + + + + Enable Tethering + تمكين الربط + + + + Tethering Password + كلمة مرور للربط + + + + + EDIT + تعديل + + + + Enter new tethering password + أدخل كلمة مرور جديدة للربط + + + + IP Address + عنوان IP + + + + Enable Roaming + تمكين التجوال + + + + APN Setting + إعداد APN + + + + Enter APN + أدخل APN + + + + leave blank for automatic configuration + اتركه فارغا للتكوين التلقائي + + + + ConfirmationDialog + + + + Ok + موافق + + + + Cancel + إلغاء + + + + DeclinePage + + + You must accept the Terms and Conditions in order to use openpilot. + يجب عليك قبول الشروط والأحكام من أجل استخدام openpilot. + + + + Back + خلف + + + + Decline, uninstall %1 + رفض ، قم بإلغاء تثبيت %1 + + + + DevicePanel + + + Dongle ID + معرف دونجل + + + + N/A + غير متاح + + + + Serial + التسلسلي + + + + Driver Camera + كاميرا السائق + + + + PREVIEW + لمح + + + + Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off) + قم بمعاينة الكاميرا المواجهة للسائق للتأكد من أن نظام مراقبة السائق يتمتع برؤية جيدة. (يجب أن تكون السيارة معطلة) + + + + Reset Calibration + إعادة ضبط المعايرة + + + + RESET + إعادة تعيين + + + + Are you sure you want to reset calibration? + هل أنت متأكد أنك تريد إعادة ضبط المعايرة؟ + + + + Review Training Guide + مراجعة دليل التدريب + + + + REVIEW + مراجعة + + + + Review the rules, features, and limitations of openpilot + راجع القواعد والميزات والقيود الخاصة بـ openpilot + + + + Are you sure you want to review the training guide? + هل أنت متأكد أنك تريد مراجعة دليل التدريب؟ + + + + Regulatory + تنظيمية + + + + VIEW + عرض + + + + Change Language + تغيير اللغة + + + + CHANGE + تغيير + + + + Select a language + اختر لغة + + + + Reboot + اعادة التشغيل + + + + Power Off + أطفاء + + + + 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 بالمعايرة بشكل مستمر ، ونادراً ما تكون إعادة الضبط مطلوبة. + + + + Your device is pointed %1° %2 and %3° %4. + جهازك يشير %1° %2 و %3° %4. + + + + down + لأسفل + + + + up + إلى أعلى + + + + left + إلى اليسار + + + + right + إلى اليمين + + + + Are you sure you want to reboot? + هل أنت متأكد أنك تريد إعادة التشغيل؟ + + + + Disengage to Reboot + فك الارتباط لإعادة التشغيل + + + + Are you sure you want to power off? + هل أنت متأكد أنك تريد إيقاف التشغيل؟ + + + + Disengage to Power Off + فك الارتباط لإيقاف التشغيل + + + + DriveStats + + + Drives + أرقام القيادة + + + + Hours + ساعات + + + + ALL TIME + في كل وقت + + + + PAST WEEK + الأسبوع الماضي + + + + KM + كم + + + + Miles + اميال + + + + DriverViewScene + + + camera starting + بدء تشغيل الكاميرا + + + + InputDialog + + + Cancel + إلغاء + + + + Need at least %n character(s)! + + تحتاج على الأقل %n حرف! + تحتاج على الأقل %n حرف! + تحتاج على الأقل %n احرف! + تحتاج على الأقل %n احرف! + تحتاج على الأقل %n احرف! + تحتاج على الأقل %n احرف! + + + + + Installer + + + Installing... + جارٍ التثبيت ... + + + + Receiving objects: + استقبال الكائنات: + + + + Resolving deltas: + حل دلتا: + + + + Updating files: + جارٍ تحديث الملفات: + + + + MapETA + + + eta + eta + + + + min + دق + + + + hr + سع + + + + km + كم + + + + mi + مل + + + + MapInstructions + + + km + كم + + + + m + م + + + + mi + مل + + + + ft + قد + + + + MapPanel + + + Current Destination + الوجهة الحالية + + + + CLEAR + مسح + + + + Recent Destinations + الوجهات الأخيرة + + + + Try the Navigation Beta + جرب التنقل التجريبي + + + + Get turn-by-turn directions displayed and more with a comma +prime subscription. Sign up now: https://connect.comma.ai + احصل على الاتجاهات خطوة بخطوة معروضة والمزيد باستخدام comma +الاشتراك الرئيسي. اشترك الآن: https://connect.comma.ai + + + + No home +location set + لم يتم تعيين +موقع المنزل + + + + No work +location set + لم يتم تعيين +موقع العمل + + + + no recent destinations + لا توجد وجهات حديثة + + + + MapWindow + + + Map Loading + تحميل الخريطة + + + + Waiting for GPS + في انتظار GPS + + + + MultiOptionDialog + + + Select + اختر + + + + Cancel + إلغاء + + + + Networking + + + Advanced + متقدم + + + + Enter password + أدخل كلمة المرور + + + + + for "%1" + ل "%1" + + + + Wrong password + كلمة مرور خاطئة + + + + NvgWindow + + + km/h + km/h + + + + mph + mph + + + + + MAX + الأعلى + + + + + SPEED + سرعة + + + + + LIMIT + حد + + + + OffroadHome + + + UPDATE + تحديث + + + + ALERTS + تنبيهات + + + + ALERT + تنبيه + + + + PairingPopup + + + Pair your device to your comma account + قم بإقران جهازك بحساب comma الخاص بك + + + + Go to https://connect.comma.ai on your phone + اذهب إلى https://connect.comma.ai من هاتفك + + + + Click "add new device" and scan the QR code on the right + انقر على "إضافة جهاز جديد" وامسح رمز الاستجابة السريعة على اليمين + + + + Bookmark connect.comma.ai to your home screen to use it like an app + ضع إشارة مرجعية على connect.comma.ai على شاشتك الرئيسية لاستخدامه مثل أي تطبيق + + + + PrimeAdWidget + + + Upgrade Now + قم بالترقية الآن + + + + Become a comma prime member at connect.comma.ai + كن عضوًا comme prime في connect.comma.ai + + + + PRIME FEATURES: + ميزات PRIME: + + + + Remote access + الوصول عن بعد + + + + 1 year of storage + سنة واحدة من التخزين + + + + Developer perks + امتيازات المطور + + + + PrimeUserWidget + + + ✓ SUBSCRIBED + ✓ مشترك + + + + comma prime + comma prime + + + + CONNECT.COMMA.AI + CONNECT.COMMA.AI + + + + COMMA POINTS + COMMA POINTS + + + + QObject + + + Reboot + اعادة التشغيل + + + + Exit + أغلق + + + + dashcam + dashcam + + + + openpilot + openpilot + + + + %n minute(s) ago + + منذ %n دقيقة + منذ %n دقيقة + منذ %n دقائق + منذ %n دقائق + منذ %n دقائق + منذ %n دقائق + + + + + %n hour(s) ago + + منذ %n ساعة + منذ %n ساعة + منذ %n ساعات + منذ %n ساعات + منذ %n ساعات + منذ %n ساعات + + + + + %n day(s) ago + + منذ %n يوم + منذ %n يوم + منذ %n ايام + منذ %n ايام + منذ %n ايام + منذ %n ايام + + + + + Reset + + + Reset failed. Reboot to try again. + فشل إعادة التعيين. أعد التشغيل للمحاولة مرة أخرى. + + + + Are you sure you want to reset your device? + هل أنت متأكد أنك تريد إعادة ضبط جهازك؟ + + + + Resetting device... + جارٍ إعادة ضبط الجهاز ... + + + + System Reset + إعادة تعيين النظام + + + + System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot. + تم تشغيل إعادة تعيين النظام. اضغط على تأكيد لمسح كل المحتوى والإعدادات. اضغط على إلغاء لاستئناف التمهيد. + + + + Cancel + إلغاء + + + + Reboot + اعادة التشغيل + + + + Confirm + تأكيد + + + + Unable to mount data partition. Press confirm to reset your device. + تعذر تحميل قسم البيانات. اضغط على تأكيد لإعادة ضبط جهازك. + + + + RichTextDialog + + + Ok + موافق + + + + SettingsWindow + + + × + x + + + + Device + جهاز + + + + + Network + شبكة الاتصال + + + + Toggles + التبديل + + + + Software + برمجة + + + + Navigation + ملاحة + + + + Setup + + + WARNING: Low Voltage + تحذير: الجهد المنخفض + + + + Power your device in a car with a harness or proceed at your own risk. + قم بتشغيل جهازك في سيارة باستخدام أداة تثبيت أو المضي قدمًا على مسؤوليتك الخاصة. + + + + Power off + اطفئ الجهاز + + + + + + Continue + أكمل + + + + Getting Started + ابدء + + + + Before we get on the road, let’s finish installation and cover some details. + قبل أن ننطلق على الطريق ، دعنا ننتهي من التثبيت ونغطي بعض التفاصيل. + + + + Connect to Wi-Fi + اتصل بشبكة Wi-Fi + + + + + Back + خلف + + + + Continue without Wi-Fi + استمر بدون Wi-Fi + + + + Waiting for internet + في انتظار الاتصال بالإنترنت + + + + Choose Software to Install + اختر البرنامج المراد تثبيته + + + + Dashcam + Dashcam + + + + Custom Software + برامج مخصصة + + + + Enter URL + إدخال عنوان الموقع + + + + for Custom Software + للبرامج المخصصة + + + + Downloading... + جارى التحميل... + + + + Download Failed + فشل التنزيل + + + + Ensure the entered URL is valid, and the device’s internet connection is good. + تأكد من أن عنوان موقع الويب الذي تم إدخاله صالح ، وأن اتصال الجهاز بالإنترنت جيد. + + + + Reboot device + إعادة تشغيل الجهاز + + + + Start over + ابدأ من جديد + + + + SetupWidget + + + Finish Setup + إنهاء الإعداد + + + + Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer. + قم بإقران جهازك بفاصلة connect (connect.comma.ai) واطلب عرض comma prime الخاص بك. + + + + Pair device + إقران الجهاز + + + + Sidebar + + + + CONNECT + الاتصال + + + + OFFLINE + غير متصل + + + + + ONLINE + متصل + + + + ERROR + خطأ + + + + + + TEMP + درجة الحرارة + + + + HIGH + عالي + + + + GOOD + جيد + + + + OK + موافق + + + + VEHICLE + مركبة + + + + NO + لا + + + + PANDA + PANDA + + + + GPS + GPS + + + + SEARCH + بحث + + + + -- + -- + + + + Wi-Fi + Wi-Fi + + + + ETH + ETH + + + + 2G + 2G + + + + 3G + 3G + + + + LTE + LTE + + + + 5G + 5G + + + + 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 + تبديل الفرع + + + + ENTER + أدخل + + + + + The new branch will be pulled the next time the updater runs. + سيتم سحب الفرع الجديد في المرة التالية التي يتم فيها تشغيل أداة التحديث. + + + + Enter branch name + أدخل اسم الفرع + + + + UNINSTALL + الغاء التثبيت + + + + Uninstall %1 + الغاء التثبيت %1 + + + + Are you sure you want to uninstall? + هل أنت متأكد أنك تريد إلغاء التثبيت؟ + + + + failed to fetch update + فشل في جلب التحديث + + + + + CHECK + تأكد الان + + + + SshControl + + + SSH Keys + SSH Keys + + + + 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. + تحذير: هذا يمنح SSH الوصول إلى جميع المفاتيح العامة في إعدادات GitHub. لا تدخل أبدًا اسم مستخدم GitHub بخلاف اسم المستخدم الخاص بك. لن يطلب منك موظف comma أبدًا إضافة اسم مستخدم GitHub الخاص به. + + + + + ADD + أضف + + + + Enter your GitHub username + أدخل اسم مستخدم GitHub الخاص بك + + + + LOADING + جار التحميل + + + + REMOVE + نزع + + + + Username '%1' has no keys on GitHub + لا يحتوي اسم المستخدم '%1' على مفاتيح على GitHub + + + + Request timed out + انتهت مهلة الطلب + + + + Username '%1' doesn't exist on GitHub + اسم المستخدم '%1' غير موجود على GitHub + + + + SshToggle + + + Enable SSH + تفعيل SSH + + + + TermsPage + + + Terms & Conditions + البنود و الظروف + + + + Decline + انحدار + + + + Scroll to accept + قم بالتمرير للقبول + + + + Agree + موافق + + + + TogglesPanel + + + Enable openpilot + تمكين openpilot + + + + Use the openpilot system for adaptive cruise control and lane keep driver assistance. Your attention is required at all times to use this feature. Changing this setting takes effect when the car is powered off. + استخدم نظام الطيار المفتوح للتحكم التكيفي في ثبات السرعة والحفاظ على مساعدة السائق. انتباهك مطلوب في جميع الأوقات لاستخدام هذه الميزة. يسري تغيير هذا الإعداد عند إيقاف تشغيل السيارة. + + + + Enable Lane Departure Warnings + قم بتمكين تحذيرات مغادرة حارة السير + + + + Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31 mph (50 km/h). + تلقي تنبيهات للتوجه مرة أخرى إلى الحارة عندما تنجرف سيارتك فوق خط المسار المكتشف دون تنشيط إشارة الانعطاف أثناء القيادة لمسافة تزيد عن 31 ميلاً في الساعة (50 كم / ساعة). + + + + Use Metric System + استخدم النظام المتري + + + + Display speed in km/h instead of mph. + عرض السرعة بالكيلو متر في الساعة بدلاً من ميل في الساعة. + + + + Record and Upload Driver Camera + تسجيل وتحميل كاميرا السائق + + + + Upload data from the driver facing camera and help improve the driver monitoring algorithm. + قم بتحميل البيانات من الكاميرا المواجهة للسائق وساعد في تحسين خوارزمية مراقبة السائق. + + + + Disengage On Accelerator Pedal + فك الارتباط على دواسة التسريع + + + + When enabled, pressing the accelerator pedal will disengage openpilot. + عند التمكين ، سيؤدي الضغط على دواسة الوقود إلى فصل الطيار المفتوح. + + + + Show ETA in 24h Format + إظهار الوقت المقدر للوصول بتنسيق 24 ساعة + + + + Use 24h format instead of am/pm + استخدم تنسيق 24 ساعة بدلاً من صباحًا / مساءً + + + + Show Map on Left Side of UI + إظهار الخريطة على الجانب الأيسر من واجهة المستخدم + + + + 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! + + + + 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 للحصول على أسرع تجربة تحديث. حجم التنزيل 1 غيغابايت تقريبًا. + + + + Connect to Wi-Fi + اتصل بشبكة Wi-Fi + + + + Install + ثبيت + + + + Back + خلف + + + + Loading... + جار التحميل... + + + + Reboot + اعادة التشغيل + + + + Update failed + فشل التحديث + + + + WifiUI + + + + Scanning for networks... + جارٍ البحث عن شبكات ... + + + + CONNECTING... + جارٍ الاتصال ... + + + + FORGET + نزع + + + + Forget Wi-Fi Network "%1"? + نزع شبكة اWi-Fi "%1"? + + + From fb99766323d3f4090c2671332b2f8c0ae57f723e Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 25 Aug 2022 12:24:35 -0700 Subject: [PATCH 081/172] Toyota: don't send ACC_HUD on Prius V (#25539) * Prius v also doesn't send ACC_HUD * common --- selfdrive/car/toyota/carcontroller.py | 45 ++++++++++++++------------- 1 file changed, 23 insertions(+), 22 deletions(-) diff --git a/selfdrive/car/toyota/carcontroller.py b/selfdrive/car/toyota/carcontroller.py index 3326d7c96..3288bcaed 100644 --- a/selfdrive/car/toyota/carcontroller.py +++ b/selfdrive/car/toyota/carcontroller.py @@ -109,28 +109,29 @@ class CarController: can_sends.append(create_gas_interceptor_command(self.packer, interceptor_gas_cmd, self.frame // 2)) self.gas = interceptor_gas_cmd - # ui mesg is at 1Hz but we send asap if: - # - there is something to display - # - there is something to stop displaying - fcw_alert = hud_control.visualAlert == VisualAlert.fcw - steer_alert = hud_control.visualAlert in (VisualAlert.steerRequired, VisualAlert.ldw) - - send_ui = False - if ((fcw_alert or steer_alert) and not self.alert_active) or \ - (not (fcw_alert or steer_alert) and self.alert_active): - send_ui = True - self.alert_active = not self.alert_active - elif pcm_cancel_cmd: - # forcing the pcm to disengage causes a bad fault sound so play a good sound instead - send_ui = True - - if (self.frame % 100 == 0 or send_ui) and (self.CP.carFingerprint != CAR.PRIUS_V): - can_sends.append(create_ui_command(self.packer, steer_alert, pcm_cancel_cmd, hud_control.leftLaneVisible, - hud_control.rightLaneVisible, hud_control.leftLaneDepart, - hud_control.rightLaneDepart, CC.enabled)) - - if (self.frame % 100 == 0 or send_ui) and self.CP.enableDsu: - can_sends.append(create_fcw_command(self.packer, fcw_alert)) + if self.CP.carFingerprint != CAR.PRIUS_V: + # ui mesg is at 1Hz but we send asap if: + # - there is something to display + # - there is something to stop displaying + fcw_alert = hud_control.visualAlert == VisualAlert.fcw + steer_alert = hud_control.visualAlert in (VisualAlert.steerRequired, VisualAlert.ldw) + + send_ui = False + if ((fcw_alert or steer_alert) and not self.alert_active) or \ + (not (fcw_alert or steer_alert) and self.alert_active): + send_ui = True + self.alert_active = not self.alert_active + elif pcm_cancel_cmd: + # forcing the pcm to disengage causes a bad fault sound so play a good sound instead + send_ui = True + + if self.frame % 100 == 0 or send_ui: + can_sends.append(create_ui_command(self.packer, steer_alert, pcm_cancel_cmd, hud_control.leftLaneVisible, + hud_control.rightLaneVisible, hud_control.leftLaneDepart, + hud_control.rightLaneDepart, CC.enabled)) + + if (self.frame % 100 == 0 or send_ui) and self.CP.enableDsu: + can_sends.append(create_fcw_command(self.packer, fcw_alert)) # *** static msgs *** for addr, cars, bus, fr_step, vl in STATIC_DSU_MSGS: From 3bb2b4df498ef925b9b5e39cc72ed53143ac63a6 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Fri, 26 Aug 2022 04:13:38 +0800 Subject: [PATCH 082/172] getTextRect: pass text by const reference (#25555) --- selfdrive/ui/qt/util.cc | 2 +- selfdrive/ui/qt/util.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/ui/qt/util.cc b/selfdrive/ui/qt/util.cc index 4be88aaf1..c5697c104 100644 --- a/selfdrive/ui/qt/util.cc +++ b/selfdrive/ui/qt/util.cc @@ -162,7 +162,7 @@ QPixmap loadPixmap(const QString &fileName, const QSize &size, Qt::AspectRatioMo } } -QRect getTextRect(QPainter &p, int flags, QString text) { +QRect getTextRect(QPainter &p, int flags, const QString &text) { QFontMetrics fm(p.font()); QRect init_rect = fm.boundingRect(text); return fm.boundingRect(init_rect, flags, text); diff --git a/selfdrive/ui/qt/util.h b/selfdrive/ui/qt/util.h index f0e57526c..209f05196 100644 --- a/selfdrive/ui/qt/util.h +++ b/selfdrive/ui/qt/util.h @@ -24,6 +24,6 @@ void initApp(int argc, char *argv[]); QWidget* topWidget (QWidget* widget); QPixmap loadPixmap(const QString &fileName, const QSize &size = {}, Qt::AspectRatioMode aspectRatioMode = Qt::KeepAspectRatio); -QRect getTextRect(QPainter &p, int flags, QString text); +QRect getTextRect(QPainter &p, int flags, const QString &text); void drawRoundedRect(QPainter &painter, const QRectF &rect, qreal xRadiusTop, qreal yRadiusTop, qreal xRadiusBottom, qreal yRadiusBottom); QColor interpColor(float xv, std::vector xp, std::vector fp); From c2fee2d45e23a4bcd758d4c056940f6e5e8cc9f7 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 25 Aug 2022 16:22:52 -0700 Subject: [PATCH 083/172] build test files by default (#25515) * build test files by default * only on master based --- .github/workflows/selfdrive_tests.yaml | 8 ++++---- SConstruct | 10 ++++++---- 2 files changed, 10 insertions(+), 8 deletions(-) diff --git a/.github/workflows/selfdrive_tests.yaml b/.github/workflows/selfdrive_tests.yaml index 8529da8e8..d2b8cde7a 100644 --- a/.github/workflows/selfdrive_tests.yaml +++ b/.github/workflows/selfdrive_tests.yaml @@ -74,11 +74,11 @@ jobs: with: save-cache: true - name: Build openpilot with all flags - run: ${{ env.RUN }} "scons -j$(nproc) --extras --test && release/check-dirty.sh" + run: ${{ env.RUN }} "scons -j$(nproc) --extras && release/check-dirty.sh" - name: Cleanup scons cache run: | ${{ env.RUN }} "rm -rf /tmp/scons_cache/* && \ - scons -j$(nproc) --extras --test --cache-populate" + scons -j$(nproc) --extras --cache-populate" #build_mac: # name: build macos @@ -225,7 +225,7 @@ jobs: - name: Run unit tests run: | ${{ env.RUN }} "export SKIP_LONG_TESTS=1 && \ - scons -j$(nproc) --test && \ + scons -j$(nproc) && \ $UNIT_TEST common && \ $UNIT_TEST opendbc/can && \ $UNIT_TEST selfdrive/boardd && \ @@ -356,7 +356,7 @@ jobs: key: car_models-${{ hashFiles('selfdrive/car/tests/test_models.py', 'selfdrive/car/tests/routes.py') }}-${{ matrix.job }} - name: Test car models run: | - ${{ env.RUN }} "scons -j$(nproc) --test && \ + ${{ env.RUN }} "scons -j$(nproc) && \ coverage run -m pytest selfdrive/car/tests/test_models.py && \ coverage xml && \ chmod -R 777 /tmp/comma_download_cache" diff --git a/SConstruct b/SConstruct index 49685b19b..7d5ebbd25 100644 --- a/SConstruct +++ b/SConstruct @@ -10,10 +10,6 @@ AGNOS = TICI Decider('MD5-timestamp') -AddOption('--test', - action='store_true', - help='build test files') - AddOption('--extras', action='store_true', help='build misc extras, like setup and installer files') @@ -53,6 +49,12 @@ AddOption('--no-thneed', dest='no_thneed', help='avoid using thneed') +AddOption('--no-test', + action='store_false', + dest='test', + default=os.path.isfile(Dir('#laika_repo').abspath), + help='skip building test files') + real_arch = arch = subprocess.check_output(["uname", "-m"], encoding='utf8').rstrip() if platform.system() == "Darwin": arch = "Darwin" From aece21c7cb1bd58e9a3939dca3e4439461e870ec Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Fri, 26 Aug 2022 07:57:34 +0800 Subject: [PATCH 084/172] V4LEncoder: set bytesused to buf->len (#25050) --- selfdrive/loggerd/encoder/v4l_encoder.cc | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/selfdrive/loggerd/encoder/v4l_encoder.cc b/selfdrive/loggerd/encoder/v4l_encoder.cc index 016e6c570..88aeb2125 100644 --- a/selfdrive/loggerd/encoder/v4l_encoder.cc +++ b/selfdrive/loggerd/encoder/v4l_encoder.cc @@ -37,11 +37,11 @@ static void dequeue_buffer(int fd, v4l2_buf_type buf_type, unsigned int *index=N assert(v4l_buf.m.planes[0].data_offset == 0); } -static void queue_buffer(int fd, v4l2_buf_type buf_type, unsigned int index, VisionBuf *buf, struct timeval timestamp={0}, unsigned int bytesused=0) { +static void queue_buffer(int fd, v4l2_buf_type buf_type, unsigned int index, VisionBuf *buf, struct timeval timestamp={}) { v4l2_plane plane = { .length = (unsigned int)buf->len, .m = { .userptr = (unsigned long)buf->addr, }, - .bytesused = bytesused, + .bytesused = (uint32_t)buf->len, .reserved = {(unsigned int)buf->fd} }; @@ -51,7 +51,6 @@ static void queue_buffer(int fd, v4l2_buf_type buf_type, unsigned int index, Vis .memory = V4L2_MEMORY_USERPTR, .m = { .planes = &plane, }, .length = 1, - .bytesused = 0, .flags = V4L2_BUF_FLAG_TIMESTAMP_COPY, .timestamp = timestamp }; From 051e1e0a062e0eb398e9bb16291b95ba3ae497eb Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 25 Aug 2022 17:00:02 -0700 Subject: [PATCH 085/172] update webcam readme --- tools/webcam/README.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/tools/webcam/README.md b/tools/webcam/README.md index 1e07bdbbe..f896e19b8 100644 --- a/tools/webcam/README.md +++ b/tools/webcam/README.md @@ -1,3 +1,5 @@ +# NOTE: this README is outdated. #24590 tracks adding back webcam support + # Run openpilot with webcam on PC What's needed: From e9d27750af866cd0191a3512f52dce0cbb8fbb15 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 25 Aug 2022 17:30:00 -0700 Subject: [PATCH 086/172] more reliable check --- SConstruct | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/SConstruct b/SConstruct index 7d5ebbd25..d375900f2 100644 --- a/SConstruct +++ b/SConstruct @@ -52,7 +52,7 @@ AddOption('--no-thneed', AddOption('--no-test', action='store_false', dest='test', - default=os.path.isfile(Dir('#laika_repo').abspath), + default=os.path.islink(Dir('#laika/').abspath), help='skip building test files') real_arch = arch = subprocess.check_output(["uname", "-m"], encoding='utf8').rstrip() From 6bbea8080eaaeb6413ed098abf6d0226c6841282 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 25 Aug 2022 19:59:22 -0700 Subject: [PATCH 087/172] only build camera test on pc --- system/camerad/SConscript | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/system/camerad/SConscript b/system/camerad/SConscript index 25e366210..38ca558f8 100644 --- a/system/camerad/SConscript +++ b/system/camerad/SConscript @@ -14,7 +14,7 @@ if arch == "larch64": cameras, ], LIBS=libs) -if GetOption("test"): +if GetOption("test") and arch == "x86_64": env.Program('test/ae_gray_test', [ 'test/ae_gray_test.cc', 'cameras/camera_common.cc', From 94f353a5e331efdd8ca7097d9e1e391c5c926422 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 25 Aug 2022 20:30:43 -0700 Subject: [PATCH 088/172] controlsd: disambiguate can error and can socket lag (#25559) --- selfdrive/controls/controlsd.py | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 1f394d487..b8b66a567 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -161,14 +161,14 @@ class Controls: self.state = State.disabled self.enabled = False self.active = False - self.can_rcv_error = False + self.can_rcv_timeout = False self.soft_disable_timer = 0 self.v_cruise_kph = V_CRUISE_INITIAL self.v_cruise_cluster_kph = V_CRUISE_INITIAL self.v_cruise_kph_last = 0 self.mismatch_counter = 0 self.cruise_mismatch_counter = 0 - self.can_rcv_error_counter = 0 + self.can_rcv_timeout_counter = 0 self.last_blinker_frame = 0 self.distance_traveled = 0 self.last_functional_fan_frame = 0 @@ -339,19 +339,19 @@ class Controls: # generic catch-all. ideally, a more specific event should be added above instead has_disable_events = self.events.any(ET.NO_ENTRY) and (self.events.any(ET.SOFT_DISABLE) or self.events.any(ET.IMMEDIATE_DISABLE)) no_system_errors = (not has_disable_events) or (len(self.events) == num_events) - if (not self.sm.all_checks() or self.can_rcv_error) and no_system_errors: + if (not self.sm.all_checks() or self.can_rcv_timeout) and no_system_errors: if not self.sm.all_alive(): self.events.add(EventName.commIssue) elif not self.sm.all_freq_ok(): self.events.add(EventName.commIssueAvgFreq) - else: # invalid or can_rcv_error. + else: # invalid or can_rcv_timeout. self.events.add(EventName.commIssue) logs = { 'invalid': [s for s, valid in self.sm.valid.items() if not valid], 'not_alive': [s for s, alive in self.sm.alive.items() if not alive], 'not_freq_ok': [s for s, freq_ok in self.sm.freq_ok.items() if not freq_ok], - 'can_error': self.can_rcv_error, + 'can_rcv_timeout': self.can_rcv_timeout, } if logs != self.logged_comm_issue: cloudlog.event("commIssue", error=True, **logs) @@ -440,10 +440,10 @@ class Controls: # Check for CAN timeout if not can_strs: - self.can_rcv_error_counter += 1 - self.can_rcv_error = True + self.can_rcv_timeout_counter += 1 + self.can_rcv_timeout = True else: - self.can_rcv_error = False + self.can_rcv_timeout = False # When the panda and controlsd do not agree on controls_allowed # we want to disengage openpilot. However the status from the panda goes through @@ -785,7 +785,7 @@ class Controls: controlsState.cumLagMs = -self.rk.remaining * 1000. controlsState.startMonoTime = int(start_time * 1e9) controlsState.forceDecel = bool(force_decel) - controlsState.canErrorCounter = self.can_rcv_error_counter + controlsState.canErrorCounter = self.can_rcv_timeout_counter lat_tuning = self.CP.lateralTuning.which() if self.joystick_mode: From 2ebbe7eac658c5961434c8701364e4ac018a0cb3 Mon Sep 17 00:00:00 2001 From: guilhermicas <51837210+guilhermicas@users.noreply.github.com> Date: Fri, 26 Aug 2022 07:13:31 +0100 Subject: [PATCH 089/172] Portuguese: grammar and semantic corrections (#25554) * Grammar and semantic corrections of Portuguese translation * Revert "Grammar and semantic corrections of Portuguese translation" This reverts commit 87c88c24f8872ffa87de16a63151240b7d7c7716. * fix and improve pt-BR translation * rename file Co-authored-by: Shane Smiskol Co-authored-by: AlexandreSato --- selfdrive/ui/translations/languages.json | 2 +- .../{main_pt.ts => main_pt-BR.ts} | 32 +++++++++---------- 2 files changed, 17 insertions(+), 17 deletions(-) rename selfdrive/ui/translations/{main_pt.ts => main_pt-BR.ts} (98%) diff --git a/selfdrive/ui/translations/languages.json b/selfdrive/ui/translations/languages.json index 2559b2d26..072d320c1 100644 --- a/selfdrive/ui/translations/languages.json +++ b/selfdrive/ui/translations/languages.json @@ -1,6 +1,6 @@ { "English": "main_en", - "Português": "main_pt", + "Português": "main_pt-BR", "中文(繁體)": "main_zh-CHT", "中文(简体)": "main_zh-CHS", "한국어": "main_ko", diff --git a/selfdrive/ui/translations/main_pt.ts b/selfdrive/ui/translations/main_pt-BR.ts similarity index 98% rename from selfdrive/ui/translations/main_pt.ts rename to selfdrive/ui/translations/main_pt-BR.ts index 3d5eda118..40897186f 100644 --- a/selfdrive/ui/translations/main_pt.ts +++ b/selfdrive/ui/translations/main_pt-BR.ts @@ -29,12 +29,12 @@ Enable Tethering - Ativar Theter + Ativar Tether Tethering Password - Senha Thetering + Senha Tethering @@ -45,12 +45,12 @@ Enter new tethering password - Insira nova senha thetering + Insira nova senha tethering IP Address - IP Endereço + Endereço IP @@ -125,7 +125,7 @@ Driver Camera - Câmera Motorista + Câmera voltada para o Motorista @@ -140,7 +140,7 @@ Reset Calibration - Limpar Calibragem + Resetar Calibragem @@ -150,7 +150,7 @@ Are you sure you want to reset calibration? - Tem certeza que quer limpar calibragem? + Tem certeza que quer resetar a calibragem? @@ -165,7 +165,7 @@ Review the rules, features, and limitations of openpilot - Revisar regras, features e limitações do openpilot + Revisar regras, aprimoramentos e limitações do openpilot @@ -210,7 +210,7 @@ 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. - o openpilot requer que o dispositivo seja montado dentro de 4° esquerda ou direita e dentro de 5° para cima ou 8° para baixo. o openpilot está continuamente calibrando, a redefinição raramente é necessária. + o openpilot requer que o dispositivo seja montado dentro de 4° esquerda ou direita e dentro de 5° para cima ou 8° para baixo. o openpilot está continuamente calibrando, resetar raramente é necessário. @@ -296,7 +296,7 @@ camera starting - camera iniciando + câmera iniciando @@ -416,7 +416,7 @@ Get turn-by-turn directions displayed and more with a comma prime subscription. Sign up now: https://connect.comma.ai Obtenha instruções passo a passo exibidas e muito mais com -uma assinatura prime Increva-se agora:https://connect.comma.ai +uma assinatura prime Inscreva-se agora: https://connect.comma.ai @@ -429,7 +429,7 @@ residência definido No work location set - Sem local + Sem local de trabalho definido @@ -542,7 +542,7 @@ trabalho definido Pair your device to your comma account - Pareie seu dispositivo a sua conta comma + Pareie seu dispositivo à sua conta comma @@ -557,7 +557,7 @@ trabalho definido Bookmark connect.comma.ai to your home screen to use it like an app - Salve connect.comma.ai como sua página inicial para utilizar com um app + Salve connect.comma.ai como sua página inicial para utilizar como um app @@ -575,7 +575,7 @@ trabalho definido PRIME FEATURES: - PRIME FEATURES: + APRIMORAMENTOS PRIME: @@ -1146,7 +1146,7 @@ trabalho definido Scroll to accept - Role para aceitar + Role a tela para aceitar From 715eabf733f87b9ab47c52fb19ca45abf5368ea5 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 25 Aug 2022 23:29:34 -0700 Subject: [PATCH 090/172] Toyota: add missing engine FW for 2019 RAV4 (#25563) Add missing engine FW from 28947140cc79e4cf --- 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 7b4031ca6..f6e9d9ad4 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -1266,6 +1266,7 @@ FW_VERSIONS = { b'\x02896634A18100\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', b'\x02896634A43000\x00\x00\x00\x00897CF4201001\x00\x00\x00\x00', b'\x02896634A47000\x00\x00\x00\x00897CF4201001\x00\x00\x00\x00', + b'\x028966342Z8000\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', ], (Ecu.esp, 0x7b0, None): [ b'\x01F15260R210\x00\x00\x00\x00\x00\x00', From 68b1dbc0ea563d923aaf82df1bef097761b82aa7 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Sat, 27 Aug 2022 02:19:05 +0800 Subject: [PATCH 091/172] modeld: delete wide_frame in model_free (#25562) --- selfdrive/modeld/models/driving.cc | 1 + selfdrive/modeld/models/driving.h | 4 ++-- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/selfdrive/modeld/models/driving.cc b/selfdrive/modeld/models/driving.cc index 9bf7e6218..8bfe58472 100644 --- a/selfdrive/modeld/models/driving.cc +++ b/selfdrive/modeld/models/driving.cc @@ -97,6 +97,7 @@ ModelOutput* model_eval_frame(ModelState* s, VisionBuf* buf, VisionBuf* wbuf, void model_free(ModelState* s) { delete s->frame; + delete s->wide_frame; } void fill_lead(cereal::ModelDataV2::LeadDataV3::Builder lead, const ModelOutputLeads &leads, int t_idx, float prob_t) { diff --git a/selfdrive/modeld/models/driving.h b/selfdrive/modeld/models/driving.h index d551bdf48..e2ee812e4 100644 --- a/selfdrive/modeld/models/driving.h +++ b/selfdrive/modeld/models/driving.h @@ -253,8 +253,8 @@ constexpr int NET_OUTPUT_SIZE = OUTPUT_SIZE + TEMPORAL_SIZE; // TODO: convert remaining arrays to std::array and update model runners struct ModelState { - ModelFrame *frame; - ModelFrame *wide_frame; + ModelFrame *frame = nullptr; + ModelFrame *wide_frame = nullptr; std::array output = {}; std::unique_ptr m; #ifdef DESIRE From cca8ef4f93ef738b2a56d849dbf673be935993f9 Mon Sep 17 00:00:00 2001 From: AlexandreSato <66435071+AlexandreSato@users.noreply.github.com> Date: Fri, 26 Aug 2022 15:41:44 -0300 Subject: [PATCH 092/172] pt-BR Shorter phrase for Finish Setup (#25566) * fix and improve pt-BR translation * Shorter phrase for Finish Setup * Concluir are better than Encerrar bacause means sucessfuly --- selfdrive/ui/translations/main_pt-BR.ts | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/ui/translations/main_pt-BR.ts b/selfdrive/ui/translations/main_pt-BR.ts index 40897186f..c6c7ca26d 100644 --- a/selfdrive/ui/translations/main_pt-BR.ts +++ b/selfdrive/ui/translations/main_pt-BR.ts @@ -864,7 +864,7 @@ trabalho definido Finish Setup - Terminar Configuração + Concluir From c62619857567e8641fd375f35888f828b2bc5a2e Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 26 Aug 2022 20:44:29 -0700 Subject: [PATCH 093/172] webcam isn't a special build anymore --- .github/workflows/selfdrive_tests.yaml | 27 ++------------------------ SConstruct | 3 +-- system/camerad/SConscript | 2 +- 3 files changed, 4 insertions(+), 28 deletions(-) diff --git a/.github/workflows/selfdrive_tests.yaml b/.github/workflows/selfdrive_tests.yaml index d2b8cde7a..9606c0563 100644 --- a/.github/workflows/selfdrive_tests.yaml +++ b/.github/workflows/selfdrive_tests.yaml @@ -41,6 +41,8 @@ jobs: - name: Build devel run: TARGET_DIR=$STRIPPED_DIR release/build_devel.sh - uses: ./.github/workflows/setup + with: + save-cache: true - name: Check submodules if: github.ref == 'refs/heads/master' && github.repository == 'commaai/openpilot' run: release/check-submodules.sh @@ -71,8 +73,6 @@ jobs: with: submodules: true - uses: ./.github/workflows/setup - with: - save-cache: true - name: Build openpilot with all flags run: ${{ env.RUN }} "scons -j$(nproc) --extras && release/check-dirty.sh" - name: Cleanup scons cache @@ -137,29 +137,6 @@ jobs: # done # comm -13 <(echo "$EXISTING_CELLAR") <(echo "$new_cellar") | tee ~/github_brew_cache_entries.txt - build_webcam: - name: build webcam - runs-on: ubuntu-20.04 - timeout-minutes: 90 - env: - IMAGE_NAME: openpilotwebcamci - steps: - - uses: actions/checkout@v3 - with: - submodules: true - - uses: ./.github/workflows/setup - - name: Build Docker image - run: | - docker pull $DOCKER_REGISTRY/$IMAGE_NAME:latest || true - docker build --cache-from $DOCKER_REGISTRY/$IMAGE_NAME:latest -t $DOCKER_REGISTRY/$IMAGE_NAME:latest -f tools/webcam/Dockerfile . - - name: Build openpilot - run: docker run --shm-size 1G --rm -v $PWD:/tmp/openpilot -e PYTHONPATH=/tmp/openpilot $DOCKER_REGISTRY/$IMAGE_NAME /bin/sh -c "cd /tmp/openpilot && USE_WEBCAM=1 scons -j$(nproc)" - - name: Push to container registry - if: github.ref == 'refs/heads/master' && github.repository == 'commaai/openpilot' - run: | - $DOCKER_LOGIN - docker push $DOCKER_REGISTRY/$IMAGE_NAME:latest - docker_push: name: docker push runs-on: ubuntu-20.04 diff --git a/SConstruct b/SConstruct index d375900f2..878244768 100644 --- a/SConstruct +++ b/SConstruct @@ -62,7 +62,6 @@ if platform.system() == "Darwin": if arch == "aarch64" and AGNOS: arch = "larch64" -USE_WEBCAM = os.getenv("USE_WEBCAM") is not None lenv = { "PATH": os.environ['PATH'], @@ -331,7 +330,7 @@ if GetOption("clazy"): qt_env['ENV']['CLAZY_IGNORE_DIRS'] = qt_dirs[0] qt_env['ENV']['CLAZY_CHECKS'] = ','.join(checks) -Export('env', 'qt_env', 'arch', 'real_arch', 'SHARED', 'USE_WEBCAM') +Export('env', 'qt_env', 'arch', 'real_arch', 'SHARED') SConscript(['common/SConscript']) Import('_common', '_gpucommon') diff --git a/system/camerad/SConscript b/system/camerad/SConscript index 38ca558f8..b03fbdc9a 100644 --- a/system/camerad/SConscript +++ b/system/camerad/SConscript @@ -1,4 +1,4 @@ -Import('env', 'arch', 'cereal', 'messaging', 'common', 'gpucommon', 'visionipc', 'USE_WEBCAM') +Import('env', 'arch', 'cereal', 'messaging', 'common', 'gpucommon', 'visionipc') libs = ['m', 'pthread', common, 'jpeg', 'OpenCL', 'yuv', cereal, messaging, 'zmq', 'capnp', 'kj', visionipc, gpucommon] From 90a4565eb29fe95fc83acf6e4f0ea0851c284d61 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 26 Aug 2022 20:46:19 -0700 Subject: [PATCH 094/172] params: make python and c++ API match (#25573) * params: make python and c++ API match * few more --- common/params_pyx.pyx | 2 +- common/tests/test_params.py | 6 +++--- selfdrive/athena/athenad.py | 6 +++--- selfdrive/athena/manage_athenad.py | 2 +- selfdrive/boardd/pandad.py | 2 +- selfdrive/controls/lib/alertmanager.py | 2 +- selfdrive/locationd/test/test_laikad.py | 4 ++-- selfdrive/locationd/test/test_locationd.py | 2 +- selfdrive/manager/manager.py | 2 +- selfdrive/navd/navd.py | 2 +- selfdrive/test/process_replay/process_replay.py | 2 +- selfdrive/test/test_updated.py | 6 +++--- selfdrive/thermald/tests/test_power_monitoring.py | 4 ++-- selfdrive/updated.py | 2 +- system/camerad/snapshot/snapshot.py | 2 +- tools/sim/bridge.py | 2 +- 16 files changed, 24 insertions(+), 24 deletions(-) diff --git a/common/params_pyx.pyx b/common/params_pyx.pyx index 36c8cf777..8d52b8d3f 100755 --- a/common/params_pyx.pyx +++ b/common/params_pyx.pyx @@ -90,7 +90,7 @@ cdef class Params: with nogil: self.p.putBool(k, val) - def delete(self, key): + def remove(self, key): cdef string k = self.check_key(key) with nogil: self.p.remove(k) diff --git a/common/tests/test_params.py b/common/tests/test_params.py index f99ac81a3..899a47fe3 100644 --- a/common/tests/test_params.py +++ b/common/tests/test_params.py @@ -59,13 +59,13 @@ class TestParams(unittest.TestCase): with self.assertRaises(UnknownKeyName): self.params.put_bool("swag", True) - def test_delete_not_there(self): + def test_remove_not_there(self): assert self.params.get("CarParams") is None - self.params.delete("CarParams") + self.params.remove("CarParams") assert self.params.get("CarParams") is None def test_get_bool(self): - self.params.delete("IsMetric") + self.params.remove("IsMetric") self.assertFalse(self.params.get_bool("IsMetric")) self.params.put_bool("IsMetric", True) diff --git a/selfdrive/athena/athenad.py b/selfdrive/athena/athenad.py index 6ccd6c3de..5b351ca0f 100755 --- a/selfdrive/athena/athenad.py +++ b/selfdrive/athena/athenad.py @@ -739,14 +739,14 @@ def main(): break except (ConnectionError, TimeoutError, WebSocketException): conn_retries += 1 - params.delete("LastAthenaPingTime") + params.remove("LastAthenaPingTime") except socket.timeout: - params.delete("LastAthenaPingTime") + params.remove("LastAthenaPingTime") except Exception: cloudlog.exception("athenad.main.exception") conn_retries += 1 - params.delete("LastAthenaPingTime") + params.remove("LastAthenaPingTime") time.sleep(backoff(conn_retries)) diff --git a/selfdrive/athena/manage_athenad.py b/selfdrive/athena/manage_athenad.py index 6bbb03a79..59ca2430c 100755 --- a/selfdrive/athena/manage_athenad.py +++ b/selfdrive/athena/manage_athenad.py @@ -27,7 +27,7 @@ def main(): except Exception: cloudlog.exception("manage_athenad.exception") finally: - params.delete(ATHENA_MGR_PID_PARAM) + params.remove(ATHENA_MGR_PID_PARAM) if __name__ == '__main__': diff --git a/selfdrive/boardd/pandad.py b/selfdrive/boardd/pandad.py index 54a28a678..971756002 100755 --- a/selfdrive/boardd/pandad.py +++ b/selfdrive/boardd/pandad.py @@ -83,7 +83,7 @@ def main() -> NoReturn: while True: try: - params.delete("PandaSignatures") + params.remove("PandaSignatures") # Flash all Pandas in DFU mode for p in PandaDFU.list(): diff --git a/selfdrive/controls/lib/alertmanager.py b/selfdrive/controls/lib/alertmanager.py index 2dad05e21..cb878483d 100644 --- a/selfdrive/controls/lib/alertmanager.py +++ b/selfdrive/controls/lib/alertmanager.py @@ -22,7 +22,7 @@ def set_offroad_alert(alert: str, show_alert: bool, extra_text: Optional[str] = a['text'] += extra_text Params().put(alert, json.dumps(a)) else: - Params().delete(alert) + Params().remove(alert) @dataclass diff --git a/selfdrive/locationd/test/test_laikad.py b/selfdrive/locationd/test/test_laikad.py index 418625f9b..198ecfe93 100755 --- a/selfdrive/locationd/test/test_laikad.py +++ b/selfdrive/locationd/test/test_laikad.py @@ -65,7 +65,7 @@ class TestLaikad(unittest.TestCase): cls.first_gps_time = first_gps_time def setUp(self): - Params().delete(EPHEMERIS_CACHE) + Params().remove(EPHEMERIS_CACHE) def test_fetch_orbits_non_blocking(self): gpstime = GPSTime.from_datetime(datetime(2021, month=3, day=1)) @@ -226,7 +226,7 @@ class TestLaikad(unittest.TestCase): # Test cache with no ephemeris laikad.cache_ephemeris(t=GPSTime(0, 0)) wait_for_cache() - Params().delete(EPHEMERIS_CACHE) + Params().remove(EPHEMERIS_CACHE) laikad.astro_dog.get_navs(self.first_gps_time) laikad.fetch_orbits(self.first_gps_time, block=True) diff --git a/selfdrive/locationd/test/test_locationd.py b/selfdrive/locationd/test/test_locationd.py index 29036b838..e30331a46 100755 --- a/selfdrive/locationd/test/test_locationd.py +++ b/selfdrive/locationd/test/test_locationd.py @@ -62,7 +62,7 @@ class TestLocationdProc(unittest.TestCase): def test_params_gps(self): # first reset params - Params().delete('LastGPSPosition') + Params().remove('LastGPSPosition') self.lat = 30 + (random.random() * 10.0) self.lon = -70 + (random.random() * 10.0) diff --git a/selfdrive/manager/manager.py b/selfdrive/manager/manager.py index 9c370cb3d..a065242bb 100755 --- a/selfdrive/manager/manager.py +++ b/selfdrive/manager/manager.py @@ -49,7 +49,7 @@ def manager_init() -> None: params.put_bool("RecordFront", True) if not params.get_bool("DisableRadar_Allow"): - params.delete("DisableRadar") + params.remove("DisableRadar") # set unset params for k, v in default_params: diff --git a/selfdrive/navd/navd.py b/selfdrive/navd/navd.py index 89a1c9bdf..3c2a7f555 100755 --- a/selfdrive/navd/navd.py +++ b/selfdrive/navd/navd.py @@ -236,7 +236,7 @@ class RouteEngine: self.recompute_countdown = 0 else: cloudlog.warning("Destination reached") - Params().delete("NavDestination") + Params().remove("NavDestination") # Clear route if driving away from destination dist = self.nav_destination.distance_to(self.last_position) diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index 8b9c77625..b4e3f6265 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -418,7 +418,7 @@ def setup_env(simulation=False, CP=None, cfg=None, controlsState=None): if controlsState is not None: params.put("ReplayControlsState", controlsState.as_builder().to_bytes()) else: - params.delete("ReplayControlsState") + params.remove("ReplayControlsState") # Regen or python process if CP is not None: diff --git a/selfdrive/test/test_updated.py b/selfdrive/test/test_updated.py index 4c0ed2fdd..aab8b256a 100755 --- a/selfdrive/test/test_updated.py +++ b/selfdrive/test/test_updated.py @@ -113,7 +113,7 @@ class TestUpdated(unittest.TestCase): def _wait_for_update(self, timeout=30, clear_param=False): if clear_param: - self.params.delete("LastUpdateTime") + self.params.remove("LastUpdateTime") self._update_now() t = self._read_param("LastUpdateTime", timeout=timeout) @@ -166,7 +166,7 @@ class TestUpdated(unittest.TestCase): last_update_time = datetime.datetime.fromisoformat(t) td = datetime.datetime.utcnow() - last_update_time self.assertLess(td.total_seconds(), 10) - self.params.delete("LastUpdateTime") + self.params.remove("LastUpdateTime") # wait a bit for the rest of the params to be written time.sleep(0.1) @@ -232,7 +232,7 @@ class TestUpdated(unittest.TestCase): # run for a cycle with no update self._wait_for_update(clear_param=True) - self.params.delete("LastUpdateTime") + self.params.remove("LastUpdateTime") first_mtime = os.path.getmtime(overlay_init_fn) # touch a file in the basedir diff --git a/selfdrive/thermald/tests/test_power_monitoring.py b/selfdrive/thermald/tests/test_power_monitoring.py index efe607155..adcdaf427 100755 --- a/selfdrive/thermald/tests/test_power_monitoring.py +++ b/selfdrive/thermald/tests/test_power_monitoring.py @@ -31,8 +31,8 @@ def pm_patch(name, value, constant=False): class TestPowerMonitoring(unittest.TestCase): def setUp(self): # Clear stored capacity before each test - params.delete("CarBatteryCapacity") - params.delete("DisablePowerDown") + params.remove("CarBatteryCapacity") + params.remove("DisablePowerDown") def mock_peripheralState(self, hw_type, car_voltage=12): ps = messaging.new_message('peripheralState').peripheralState diff --git a/selfdrive/updated.py b/selfdrive/updated.py index e8905962b..7278ef5a8 100755 --- a/selfdrive/updated.py +++ b/selfdrive/updated.py @@ -116,7 +116,7 @@ def set_params(new_version: bool, failed_count: int, exception: Optional[str]) - pass if exception is None: - params.delete("LastUpdateException") + params.remove("LastUpdateException") else: params.put("LastUpdateException", exception) diff --git a/system/camerad/snapshot/snapshot.py b/system/camerad/snapshot/snapshot.py index 946c220a7..48dfc9e02 100755 --- a/system/camerad/snapshot/snapshot.py +++ b/system/camerad/snapshot/snapshot.py @@ -91,7 +91,7 @@ def snapshot(): subprocess.check_call(["pgrep", "camerad"]) print("Camerad already running") params.put_bool("IsTakingSnapshot", False) - params.delete("Offroad_IsTakingSnapshot") + params.remove("Offroad_IsTakingSnapshot") return None, None except subprocess.CalledProcessError: pass diff --git a/tools/sim/bridge.py b/tools/sim/bridge.py index f008b9e71..71a92ac77 100755 --- a/tools/sim/bridge.py +++ b/tools/sim/bridge.py @@ -548,4 +548,4 @@ if __name__ == "__main__": finally: # Try cleaning up the wide camera param # in case users want to use replay after - Params().delete("WideCameraOnly") + Params().remove("WideCameraOnly") From 13489d092e2c09119e880022507d7331cf54c615 Mon Sep 17 00:00:00 2001 From: Robbe Derks Date: Fri, 26 Aug 2022 23:11:46 -0700 Subject: [PATCH 095/172] Pigeond (#25561) * split out pigeond from boardd * also want to turn off power * fix manager calls * move to sensord folder * release files: * add assistnow code * no bare except * add test script to test TTFF Co-authored-by: Comma Device --- common/params.cc | 1 + release/files_common | 3 +- selfdrive/boardd/SConscript | 2 +- selfdrive/boardd/boardd.cc | 53 ----- selfdrive/boardd/pigeon.cc | 333 ---------------------------- selfdrive/boardd/pigeon.h | 58 ----- selfdrive/locationd/test/ubloxd.py | 14 +- selfdrive/manager/process_config.py | 1 + selfdrive/sensord/pigeond.py | 255 +++++++++++++++++++++ selfdrive/sensord/test/ttff_test.py | 48 ++++ 10 files changed, 314 insertions(+), 454 deletions(-) delete mode 100644 selfdrive/boardd/pigeon.cc delete mode 100644 selfdrive/boardd/pigeon.h create mode 100755 selfdrive/sensord/pigeond.py create mode 100755 selfdrive/sensord/test/ttff_test.py diff --git a/common/params.cc b/common/params.cc index f89e7ff00..a25cd278a 100644 --- a/common/params.cc +++ b/common/params.cc @@ -84,6 +84,7 @@ private: std::unordered_map keys = { {"AccessToken", CLEAR_ON_MANAGER_START | DONT_LOG}, + {"AssistNowToken", PERSISTENT}, {"AthenadPid", PERSISTENT}, {"AthenadUploadQueue", PERSISTENT}, {"CalibrationParams", PERSISTENT}, diff --git a/release/files_common b/release/files_common index 663d6d355..04d13c8a5 100644 --- a/release/files_common +++ b/release/files_common @@ -90,8 +90,6 @@ selfdrive/boardd/boardd_api_impl.pyx selfdrive/boardd/can_list_to_can_capnp.cc selfdrive/boardd/panda.cc selfdrive/boardd/panda.h -selfdrive/boardd/pigeon.cc -selfdrive/boardd/pigeon.h selfdrive/boardd/set_time.py selfdrive/boardd/pandad.py @@ -282,6 +280,7 @@ selfdrive/sensord/sensors_qcom2.cc selfdrive/sensord/sensors/*.cc selfdrive/sensord/sensors/*.h selfdrive/sensord/sensord +selfdrive/sensord/pigeond.py selfdrive/thermald/thermald.py selfdrive/thermald/power_monitoring.py diff --git a/selfdrive/boardd/SConscript b/selfdrive/boardd/SConscript index 922107509..dcbea03d3 100644 --- a/selfdrive/boardd/SConscript +++ b/selfdrive/boardd/SConscript @@ -1,7 +1,7 @@ Import('env', 'envCython', 'common', 'cereal', 'messaging') libs = ['usb-1.0', common, cereal, messaging, 'pthread', 'zmq', 'capnp', 'kj'] -env.Program('boardd', ['main.cc', 'boardd.cc', 'panda.cc', 'pigeon.cc'], LIBS=libs) +env.Program('boardd', ['main.cc', 'boardd.cc', 'panda.cc'], LIBS=libs) env.Library('libcan_list_to_can_capnp', ['can_list_to_can_capnp.cc']) envCython.Program('boardd_api_impl.so', 'boardd_api_impl.pyx', LIBS=["can_list_to_can_capnp", 'capnp', 'kj'] + envCython["LIBS"]) diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index 23bf8f292..bd3a6c438 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -29,8 +29,6 @@ #include "common/util.h" #include "system/hardware/hw.h" -#include "selfdrive/boardd/pigeon.h" - // -- Multi-panda conventions -- // Ordering: // - The internal panda will always be the first panda @@ -561,56 +559,6 @@ void peripheral_control_thread(Panda *panda) { } } -static void pigeon_publish_raw(PubMaster &pm, const std::string &dat) { - // create message - MessageBuilder msg; - msg.initEvent().setUbloxRaw(capnp::Data::Reader((uint8_t*)dat.data(), dat.length())); - pm.send("ubloxRaw", msg); -} - -void pigeon_thread(Panda *panda) { - util::set_thread_name("boardd_pigeon"); - - PubMaster pm({"ubloxRaw"}); - bool ignition_last = false; - - std::unique_ptr pigeon(Hardware::TICI() ? Pigeon::connect("/dev/ttyHS0") : Pigeon::connect(panda)); - - while (!do_exit && panda->connected) { - bool need_reset = false; - bool ignition_local = ignition; - std::string recv = pigeon->receive(); - - // Check based on null bytes - if (ignition_local && recv.length() > 0 && recv[0] == (char)0x00) { - need_reset = true; - LOGW("received invalid ublox message while onroad, resetting panda GPS"); - } - - if (recv.length() > 0) { - pigeon_publish_raw(pm, recv); - } - - // init pigeon on rising ignition edge - // since it was turned off in low power mode - if((ignition_local && !ignition_last) || need_reset) { - pigeon_active = true; - pigeon->init(); - } else if (!ignition_local && ignition_last) { - // power off on falling edge of ignition - LOGD("powering off pigeon\n"); - pigeon->stop(); - pigeon->set_power(false); - pigeon_active = false; - } - - ignition_last = ignition_local; - - // 10ms - 100 Hz - util::sleep_for(10); - } -} - void boardd_main_thread(std::vector serials) { PubMaster pm({"pandaStates", "peripheralState"}); LOGW("attempting to connect"); @@ -649,7 +597,6 @@ void boardd_main_thread(std::vector serials) { threads.emplace_back(panda_state_thread, &pm, pandas, getenv("STARTED") != nullptr); threads.emplace_back(peripheral_control_thread, peripheral_panda); - threads.emplace_back(pigeon_thread, peripheral_panda); threads.emplace_back(can_send_thread, pandas, getenv("FAKESEND") != nullptr); threads.emplace_back(can_recv_thread, pandas); diff --git a/selfdrive/boardd/pigeon.cc b/selfdrive/boardd/pigeon.cc deleted file mode 100644 index d23ff90d3..000000000 --- a/selfdrive/boardd/pigeon.cc +++ /dev/null @@ -1,333 +0,0 @@ -#include "selfdrive/boardd/pigeon.h" - -#include -#include -#include - -#include -#include -#include - -#include "common/gpio.h" -#include "common/swaglog.h" -#include "common/util.h" -#include "selfdrive/locationd/ublox_msg.h" - -// Termios on macos doesn't define all baud rate constants -#ifndef B460800 -#define B460800 0010004 -#endif - -using namespace std::string_literals; - -extern ExitHandler do_exit; - -const std::string ack = "\xb5\x62\x05\x01\x02\x00"; -const std::string nack = "\xb5\x62\x05\x00\x02\x00"; -const std::string sos_save_ack = "\xb5\x62\x09\x14\x08\x00\x02\x00\x00\x00\x01\x00\x00\x00"; -const std::string sos_save_nack = "\xb5\x62\x09\x14\x08\x00\x02\x00\x00\x00\x00\x00\x00\x00"; - -Pigeon * Pigeon::connect(Panda * p) { - PandaPigeon * pigeon = new PandaPigeon(); - pigeon->connect(p); - - return pigeon; -} - -Pigeon * Pigeon::connect(const char * tty) { - TTYPigeon * pigeon = new TTYPigeon(); - pigeon->connect(tty); - - return pigeon; -} - -bool Pigeon::wait_for_ack(const std::string &ack_, const std::string &nack_, int timeout_ms) { - std::string s; - const double start_t = millis_since_boot(); - while (!do_exit) { - s += receive(); - - if (s.find(ack_) != std::string::npos) { - LOGD("Received ACK from ublox"); - return true; - } else if (s.find(nack_) != std::string::npos) { - LOGE("Received NACK from ublox"); - return false; - } else if (s.size() > 0x1000 || ((millis_since_boot() - start_t) > timeout_ms)) { - LOGE("No response from ublox"); - return false; - } - - util::sleep_for(1); // Allow other threads to be scheduled - } - return false; -} - -bool Pigeon::wait_for_ack() { - return wait_for_ack(ack, nack); -} - -bool Pigeon::send_with_ack(const std::string &cmd) { - send(cmd); - return wait_for_ack(); -} - -sos_restore_response Pigeon::wait_for_backup_restore_status(int timeout_ms) { - std::string s; - const double start_t = millis_since_boot(); - while (!do_exit) { - s += receive(); - - size_t position = s.find("\xb5\x62\x09\x14\x08\x00\x03"); - if (position != std::string::npos && s.size() >= (position + 11)) { - return static_cast(s[position + 10]); - } else if (s.size() > 0x1000 || ((millis_since_boot() - start_t) > timeout_ms)) { - LOGE("No backup restore response from ublox"); - return error; - } - - util::sleep_for(1); // Allow other threads to be scheduled - } - return error; -} - -void Pigeon::init() { - for (int i = 0; i < 10; i++) { - if (do_exit) return; - LOGW("panda GPS start"); - - // power off pigeon - set_power(false); - util::sleep_for(100); - - // 9600 baud at init - set_baud(9600); - - // power on pigeon - set_power(true); - util::sleep_for(500); - - // baud rate upping - send("\x24\x50\x55\x42\x58\x2C\x34\x31\x2C\x31\x2C\x30\x30\x30\x37\x2C\x30\x30\x30\x33\x2C\x34\x36\x30\x38\x30\x30\x2C\x30\x2A\x31\x35\x0D\x0A"s); - util::sleep_for(100); - - // set baud rate to 460800 - set_baud(460800); - - // init from ubloxd - // To generate this data, run selfdrive/locationd/test/ubloxd.py - if (!send_with_ack("\xB5\x62\x06\x00\x14\x00\x03\xFF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x01\x00\x01\x00\x00\x00\x00\x00\x1E\x7F"s)) continue; - if (!send_with_ack("\xB5\x62\x06\x00\x14\x00\x00\xFF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x19\x35"s)) continue; - if (!send_with_ack("\xB5\x62\x06\x00\x14\x00\x01\x00\x00\x00\xC0\x08\x00\x00\x00\x08\x07\x00\x01\x00\x01\x00\x00\x00\x00\x00\xF4\x80"s)) continue; - if (!send_with_ack("\xB5\x62\x06\x00\x14\x00\x04\xFF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x1D\x85"s)) continue; - if (!send_with_ack("\xB5\x62\x06\x00\x00\x00\x06\x18"s)) continue; - if (!send_with_ack("\xB5\x62\x06\x00\x01\x00\x01\x08\x22"s)) continue; - if (!send_with_ack("\xB5\x62\x06\x00\x01\x00\x03\x0A\x24"s)) continue; - if (!send_with_ack("\xB5\x62\x06\x08\x06\x00\x64\x00\x01\x00\x00\x00\x79\x10"s)) continue; - if (!send_with_ack("\xB5\x62\x06\x24\x24\x00\x05\x00\x04\x03\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x5A\x63"s)) continue; - if (!send_with_ack("\xB5\x62\x06\x1E\x14\x00\x00\x00\x00\x00\x01\x03\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x3C\x37"s)) continue; - if (!send_with_ack("\xB5\x62\x06\x39\x08\x00\xFF\xAD\x62\xAD\x1E\x63\x00\x00\x83\x0C"s)) continue; - if (!send_with_ack("\xB5\x62\x06\x24\x00\x00\x2A\x84"s)) continue; - if (!send_with_ack("\xB5\x62\x06\x23\x00\x00\x29\x81"s)) continue; - if (!send_with_ack("\xB5\x62\x06\x1E\x00\x00\x24\x72"s)) continue; - if (!send_with_ack("\xB5\x62\x06\x39\x00\x00\x3F\xC3"s)) continue; - if (!send_with_ack("\xB5\x62\x06\x01\x03\x00\x01\x07\x01\x13\x51"s)) continue; - if (!send_with_ack("\xB5\x62\x06\x01\x03\x00\x02\x15\x01\x22\x70"s)) continue; - if (!send_with_ack("\xB5\x62\x06\x01\x03\x00\x02\x13\x01\x20\x6C"s)) continue; - if (!send_with_ack("\xB5\x62\x06\x01\x03\x00\x0A\x09\x01\x1E\x70"s)) continue; - if (!send_with_ack("\xB5\x62\x06\x01\x03\x00\x0A\x0B\x01\x20\x74"s)) continue; - - // check the backup restore status - send("\xB5\x62\x09\x14\x00\x00\x1D\x60"s); - sos_restore_response restore_status = wait_for_backup_restore_status(); - switch(restore_status) { - case restored: - LOGW("almanac backup restored"); - // clear the backup - send_with_ack("\xB5\x62\x06\x01\x03\x00\x0A\x0B\x01\x20\x74"s); - break; - case no_backup: - LOGW("no almanac backup found"); - break; - default: - LOGE("failed to restore almanac backup, status: %d", restore_status); - } - - auto time = util::get_time(); - if (util::time_valid(time)) { - LOGW("Sending current time to ublox"); - send(ublox::build_ubx_mga_ini_time_utc(time)); - } - - LOGW("panda GPS on"); - return; - } - LOGE("failed to initialize panda GPS"); -} - -void Pigeon::stop() { - LOGW("Storing almanac in ublox flash"); - - // Controlled GNSS stop - send("\xB5\x62\x06\x04\x04\x00\x00\x00\x08\x00\x16\x74"s); - - // Store almanac in flash - send("\xB5\x62\x09\x14\x04\x00\x00\x00\x00\x00\x21\xEC"s); - - if (wait_for_ack(sos_save_ack, sos_save_nack)) { - LOGW("Done storing almanac"); - } else { - LOGE("Error storing almanac"); - } -} - -void PandaPigeon::connect(Panda * p) { - panda = p; -} - -void PandaPigeon::set_baud(int baud) { - panda->usb_write(0xe2, 1, 0); - panda->usb_write(0xe4, 1, baud/300); -} - -void PandaPigeon::send(const std::string &s) { - int len = s.length(); - const char * dat = s.data(); - - unsigned char a[0x20+1]; - a[0] = 1; - for (int i=0; iusb_bulk_write(2, a, ll+1); - } -} - -std::string PandaPigeon::receive() { - std::string r; - r.reserve(0x1000 + 0x40); - unsigned char dat[0x40]; - while (r.length() < 0x1000) { - int len = panda->usb_read(0xe0, 1, 0, dat, sizeof(dat)); - if (len <= 0) break; - r.append((char*)dat, len); - } - - return r; -} - -void PandaPigeon::set_power(bool power) { - panda->usb_write(0xd9, power, 0); -} - -PandaPigeon::~PandaPigeon() { -} - -void handle_tty_issue(int err, const char func[]) { - LOGE_100("tty error %d \"%s\" in %s", err, strerror(err), func); -} - -void TTYPigeon::connect(const char * tty) { - pigeon_tty_fd = HANDLE_EINTR(open(tty, O_RDWR)); - if (pigeon_tty_fd < 0) { - handle_tty_issue(errno, __func__); - assert(pigeon_tty_fd >= 0); - } - int err = tcgetattr(pigeon_tty_fd, &pigeon_tty); - assert(err == 0); - - // configure tty - pigeon_tty.c_cflag &= ~PARENB; // disable parity - pigeon_tty.c_cflag &= ~CSTOPB; // single stop bit - pigeon_tty.c_cflag |= CS8; // 8 bits per byte - pigeon_tty.c_cflag &= ~CRTSCTS; // no RTS/CTS flow control - pigeon_tty.c_cflag |= CREAD | CLOCAL; // turn on READ & ignore ctrl lines - pigeon_tty.c_lflag &= ~ICANON; // disable canonical mode - pigeon_tty.c_lflag &= ~ISIG; // disable interpretation of INTR, QUIT and SUSP - pigeon_tty.c_iflag &= ~(IXON | IXOFF | IXANY); // turn off software flow ctrl - pigeon_tty.c_iflag &= ~(IGNBRK|BRKINT|PARMRK|ISTRIP|INLCR|IGNCR|ICRNL); // disable any special handling of received bytes - pigeon_tty.c_oflag &= ~OPOST; // prevent special interpretation of output bytes - pigeon_tty.c_oflag &= ~ONLCR; // prevent conversion of newline to carriage return/line feed - - // configure blocking behavior - pigeon_tty.c_cc[VMIN] = 0; // min amount of characters returned - pigeon_tty.c_cc[VTIME] = 0; // max blocking time in s/10 (0=inf) - - err = tcsetattr(pigeon_tty_fd, TCSANOW, &pigeon_tty); - assert(err == 0); -} - -void TTYPigeon::set_baud(int baud) { - speed_t baud_const = 0; - switch(baud) { - case 9600: - baud_const = B9600; - break; - case 460800: - baud_const = B460800; - break; - default: - assert(false); - } - - // make sure everything is tx'ed before changing baud - int err = tcdrain(pigeon_tty_fd); - assert(err == 0); - - // change baud - err = tcgetattr(pigeon_tty_fd, &pigeon_tty); - assert(err == 0); - err = cfsetspeed(&pigeon_tty, baud_const); - assert(err == 0); - err = tcsetattr(pigeon_tty_fd, TCSANOW, &pigeon_tty); - assert(err == 0); - - // flush - err = tcflush(pigeon_tty_fd, TCIOFLUSH); - assert(err == 0); -} - -void TTYPigeon::send(const std::string &s) { - int err = HANDLE_EINTR(write(pigeon_tty_fd, s.data(), s.length())); - - if(err < 0) { handle_tty_issue(err, __func__); } - err = tcdrain(pigeon_tty_fd); - if(err < 0) { handle_tty_issue(err, __func__); } -} - -std::string TTYPigeon::receive() { - std::string r; - r.reserve(0x1000 + 0x40); - char dat[0x40]; - while (r.length() < 0x1000) { - int len = read(pigeon_tty_fd, dat, sizeof(dat)); - if(len < 0) { - handle_tty_issue(len, __func__); - } else if (len == 0) { - break; - } else { - r.append(dat, len); - } - - } - return r; -} - -void TTYPigeon::set_power(bool power) { -#ifdef QCOM2 - int err = 0; - err += gpio_init(GPIO_UBLOX_RST_N, true); - err += gpio_init(GPIO_UBLOX_SAFEBOOT_N, true); - err += gpio_init(GPIO_UBLOX_PWR_EN, true); - - err += gpio_set(GPIO_UBLOX_RST_N, power); - err += gpio_set(GPIO_UBLOX_SAFEBOOT_N, power); - err += gpio_set(GPIO_UBLOX_PWR_EN, power); - assert(err == 0); -#endif -} - -TTYPigeon::~TTYPigeon() { - close(pigeon_tty_fd); -} diff --git a/selfdrive/boardd/pigeon.h b/selfdrive/boardd/pigeon.h deleted file mode 100644 index c9ea4739d..000000000 --- a/selfdrive/boardd/pigeon.h +++ /dev/null @@ -1,58 +0,0 @@ -#pragma once - -#include - -#include -#include - -#include "selfdrive/boardd/panda.h" - -enum sos_restore_response : int { - unknown = 0, - failed = 1, - restored = 2, - no_backup = 3, - error = -1 -}; - -class Pigeon { - public: - static Pigeon* connect(Panda * p); - static Pigeon* connect(const char * tty); - virtual ~Pigeon(){}; - - void init(); - void stop(); - bool wait_for_ack(); - bool wait_for_ack(const std::string &ack, const std::string &nack, int timeout_ms = 1000); - bool send_with_ack(const std::string &cmd); - sos_restore_response wait_for_backup_restore_status(int timeout_ms = 1000); - virtual void set_baud(int baud) = 0; - virtual void send(const std::string &s) = 0; - virtual std::string receive() = 0; - virtual void set_power(bool power) = 0; -}; - -class PandaPigeon : public Pigeon { - Panda * panda = NULL; -public: - ~PandaPigeon(); - void connect(Panda * p); - void set_baud(int baud); - void send(const std::string &s); - std::string receive(); - void set_power(bool power); -}; - - -class TTYPigeon : public Pigeon { - int pigeon_tty_fd = -1; - struct termios pigeon_tty; -public: - ~TTYPigeon(); - void connect(const char* tty); - void set_baud(int baud); - void send(const std::string &s); - std::string receive(); - void set_power(bool power); -}; diff --git a/selfdrive/locationd/test/ubloxd.py b/selfdrive/locationd/test/ubloxd.py index af9b86127..b0339851d 100755 --- a/selfdrive/locationd/test/ubloxd.py +++ b/selfdrive/locationd/test/ubloxd.py @@ -41,13 +41,13 @@ def configure_ublox(dev): ITMF_config2 = 25374 payload = struct.pack(' 0: + assert dat[:2] == b"\xB5\x62" + msg_len = 6 + (dat[5] << 8 | dat[4]) + 2 + msgs.append(dat[:msg_len]) + dat = dat[msg_len:] + return msgs + + +class TTYPigeon(): + def __init__(self, path): + self.path = path + self.tty = serial.VTIMESerial(UBLOX_TTY, baudrate=9600, timeout=0) + + def send(self, dat): + self.tty.write(dat) + + def receive(self): + dat = b'' + while len(dat) < 0x1000: + d = self.tty.read(0x40) + dat += d + if len(d) == 0: + break + return dat + + def set_baud(self, baud): + self.tty.baudrate = baud + + def wait_for_ack(self, ack=UBLOX_ACK, nack=UBLOX_NACK, timeout=0.5): + dat = b'' + st = time.monotonic() + while True: + dat += self.receive() + if ack in dat: + cloudlog.debug("Received ACK from ublox") + return True + elif nack in dat: + cloudlog.error("Received NACK from ublox") + return False + elif time.monotonic() - st > timeout: + cloudlog.error("No response from ublox") + raise TimeoutError('No response from ublox') + time.sleep(0.001) + + def send_with_ack(self, dat, ack=UBLOX_ACK, nack=UBLOX_NACK): + self.send(dat) + self.wait_for_ack(ack, nack) + + def wait_for_backup_restore_status(self, timeout=1): + dat = b'' + st = time.monotonic() + while True: + dat += self.receive() + position = dat.find(UBLOX_BACKUP_RESTORE_MSG) + if position >= 0 and len(dat) >= position + 11: + return dat[position + 10] + elif time.monotonic() - st > timeout: + cloudlog.error("No backup restore response from ublox") + raise TimeoutError('No response from ublox') + time.sleep(0.001) + + +def initialize_pigeon(pigeon): + # try initializing a few times + for _ in range(10): + try: + pigeon.set_baud(9600) + + # up baud rate + pigeon.send(b"\x24\x50\x55\x42\x58\x2C\x34\x31\x2C\x31\x2C\x30\x30\x30\x37\x2C\x30\x30\x30\x33\x2C\x34\x36\x30\x38\x30\x30\x2C\x30\x2A\x31\x35\x0D\x0A") + time.sleep(0.1) + pigeon.set_baud(460800) + + # other configuration messages + pigeon.send_with_ack(b"\xB5\x62\x06\x00\x14\x00\x03\xFF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x01\x00\x01\x00\x00\x00\x00\x00\x1E\x7F") + pigeon.send_with_ack(b"\xB5\x62\x06\x00\x14\x00\x00\xFF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x19\x35") + pigeon.send_with_ack(b"\xB5\x62\x06\x00\x14\x00\x01\x00\x00\x00\xC0\x08\x00\x00\x00\x08\x07\x00\x01\x00\x01\x00\x00\x00\x00\x00\xF4\x80") + pigeon.send_with_ack(b"\xB5\x62\x06\x00\x14\x00\x04\xFF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x1D\x85") + pigeon.send_with_ack(b"\xB5\x62\x06\x00\x00\x00\x06\x18") + pigeon.send_with_ack(b"\xB5\x62\x06\x00\x01\x00\x01\x08\x22") + pigeon.send_with_ack(b"\xB5\x62\x06\x00\x01\x00\x03\x0A\x24") + pigeon.send_with_ack(b"\xB5\x62\x06\x08\x06\x00\x64\x00\x01\x00\x00\x00\x79\x10") + pigeon.send_with_ack(b"\xB5\x62\x06\x24\x24\x00\x05\x00\x04\x03\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x5A\x63") + pigeon.send_with_ack(b"\xB5\x62\x06\x1E\x14\x00\x00\x00\x00\x00\x01\x03\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x3C\x37") + pigeon.send_with_ack(b"\xB5\x62\x06\x39\x08\x00\xFF\xAD\x62\xAD\x1E\x63\x00\x00\x83\x0C") + pigeon.send_with_ack(b"\xB5\x62\x06\x23\x28\x00\x00\x00\x00\x04\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x01\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x56\x24") + pigeon.send_with_ack(b"\xB5\x62\x06\x24\x00\x00\x2A\x84") + pigeon.send_with_ack(b"\xB5\x62\x06\x23\x00\x00\x29\x81") + pigeon.send_with_ack(b"\xB5\x62\x06\x1E\x00\x00\x24\x72") + pigeon.send_with_ack(b"\xB5\x62\x06\x39\x00\x00\x3F\xC3") + pigeon.send_with_ack(b"\xB5\x62\x06\x01\x03\x00\x01\x07\x01\x13\x51") + pigeon.send_with_ack(b"\xB5\x62\x06\x01\x03\x00\x02\x15\x01\x22\x70") + pigeon.send_with_ack(b"\xB5\x62\x06\x01\x03\x00\x02\x13\x01\x20\x6C") + pigeon.send_with_ack(b"\xB5\x62\x06\x01\x03\x00\x0A\x09\x01\x1E\x70") + pigeon.send_with_ack(b"\xB5\x62\x06\x01\x03\x00\x0A\x0B\x01\x20\x74") + cloudlog.debug("pigeon configured") + + # try restoring almanac backup + pigeon.send(b"\xB5\x62\x09\x14\x00\x00\x1D\x60") + restore_status = pigeon.wait_for_backup_restore_status() + if restore_status == 2: + cloudlog.warning("almanac backup restored") + elif restore_status == 3: + cloudlog.warning("no almanac backup found") + else: + cloudlog.error(f"failed to restore almanac backup, status: {restore_status}") + + # sending time to ublox + t_now = datetime.utcnow() + if t_now >= datetime(2021, 6, 1): + cloudlog.warning("Sending current time to ublox") + + # UBX-MGA-INI-TIME_UTC + msg = add_ubx_checksum(b"\xB5\x62\x13\x40\x18\x00" + struct.pack(" 0: + if dat[0] == 0x00: + cloudlog.warning("received invalid data from ublox, re-initing!") + initialize_pigeon(pigeon) + continue + + # send out to socket + msg = messaging.new_message('ubloxRaw', len(dat)) + msg.ubloxRaw = dat[:] + pm.send('ubloxRaw', msg) + +if __name__ == "__main__": + main() diff --git a/selfdrive/sensord/test/ttff_test.py b/selfdrive/sensord/test/ttff_test.py new file mode 100755 index 000000000..e2cbc6d14 --- /dev/null +++ b/selfdrive/sensord/test/ttff_test.py @@ -0,0 +1,48 @@ +#!/usr/bin/env python3 + +import time +import atexit + +from cereal import messaging +from selfdrive.manager.process_config import managed_processes + +TIMEOUT = 10*60 + +def kill(): + for proc in ['ubloxd', 'pigeond']: + managed_processes[proc].stop(retry=True, block=True) + +if __name__ == "__main__": + # start ubloxd + managed_processes['ubloxd'].start() + atexit.register(kill) + + sm = messaging.SubMaster(['ubloxGnss']) + + times = [] + for i in range(20): + # start pigeond + st = time.monotonic() + managed_processes['pigeond'].start() + + # wait for a >4 satellite fix + while True: + sm.update(0) + msg = sm['ubloxGnss'] + if msg.which() == 'measurementReport' and sm.updated["ubloxGnss"]: + report = msg.measurementReport + if report.numMeas > 4: + times.append(time.monotonic() - st) + print(f"\033[94m{i}: Got a fix in {round(times[-1], 2)} seconds\033[0m") + break + + if time.monotonic() - st > TIMEOUT: + raise TimeoutError("\033[91mFailed to get a fix in {TIMEOUT} seconds!\033[0m") + + time.sleep(0.1) + + # stop pigeond + managed_processes['pigeond'].stop(retry=True, block=True) + time.sleep(20) + + print(f"\033[92mAverage TTFF: {round(sum(times) / len(times), 2)}s\033[0m") From 72a73f359103420152d1a1377d139e58a32fafb6 Mon Sep 17 00:00:00 2001 From: Jason Young <46612682+jyoung8607@users.noreply.github.com> Date: Sun, 28 Aug 2022 18:55:30 -0500 Subject: [PATCH 096/172] VW MQB: Add FW for 2017 Volkswagen Golf R (#25585) --- selfdrive/car/volkswagen/values.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/car/volkswagen/values.py b/selfdrive/car/volkswagen/values.py index 58f071901..954b7060c 100755 --- a/selfdrive/car/volkswagen/values.py +++ b/selfdrive/car/volkswagen/values.py @@ -369,6 +369,7 @@ FW_VERSIONS = { b'\xf1\x870D9300012 \xf1\x894937', b'\xf1\x870D9300012 \xf1\x895045', b'\xf1\x870D9300014M \xf1\x895004', + b'\xf1\x870D9300014Q \xf1\x895006', b'\xf1\x870D9300020S \xf1\x895201', b'\xf1\x870D9300040A \xf1\x893613', b'\xf1\x870D9300040S \xf1\x894311', From 21d7c540d2cbe37bbfc4bb979a1b155bcabdeb29 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 28 Aug 2022 21:20:19 -0700 Subject: [PATCH 097/172] fix encoderd cpu usage --- selfdrive/test/test_onroad.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py index 93598a1b0..c5fc0395d 100755 --- a/selfdrive/test/test_onroad.py +++ b/selfdrive/test/test_onroad.py @@ -23,7 +23,7 @@ from tools.lib.logreader import LogReader PROCS = { "selfdrive.controls.controlsd": 35.0, "./loggerd": 10.0, - "./encoderd": 12.5, + "./encoderd": 17.0, "./camerad": 14.5, "./locationd": 9.1, "selfdrive.controls.plannerd": 11.7, From bf68681f8d03bb1ae12f1f776cef964ebaf0b6fc Mon Sep 17 00:00:00 2001 From: Joseph Wagner <68037585+wjoseph0@users.noreply.github.com> Date: Mon, 29 Aug 2022 00:20:47 -0400 Subject: [PATCH 098/172] README.md: 200+ cars (#25587) --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 0b6fc2010..c2c90b0e6 100755 --- a/README.md +++ b/README.md @@ -42,7 +42,7 @@ To use openpilot in a car, you need four things * A supported device to run this software: a [comma three](https://comma.ai/shop/products/three). * This software. The setup procedure of the comma three allows the user to enter a URL for custom software. The URL, openpilot.comma.ai will install the release version of openpilot. To install openpilot master, you can use installer.comma.ai/commaai/master, and replacing commaai with another GitHub username can install a fork. -* One of [the 150+ supported cars](docs/CARS.md). We support Honda, Toyota, Hyundai, Nissan, Kia, Chrysler, Lexus, Acura, Audi, VW, and more. If your car is not supported but has adaptive cruise control and lane-keeping assist, it's likely able to run openpilot. +* One of [the 200+ supported cars](docs/CARS.md). We support Honda, Toyota, Hyundai, Nissan, Kia, Chrysler, Lexus, Acura, Audi, VW, and more. If your car is not supported but has adaptive cruise control and lane-keeping assist, it's likely able to run openpilot. * A [car harness](https://comma.ai/shop/products/car-harness) to connect to your car. We have detailed instructions for [how to mount the device in a car](https://comma.ai/setup). From cd32f64d0111dc8a304e378207c5666ebab6a025 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Tue, 30 Aug 2022 02:53:11 +0800 Subject: [PATCH 099/172] replay: add missing format specifier (#25590) --- tools/replay/camera.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tools/replay/camera.cc b/tools/replay/camera.cc index 1a577b40c..ef4f4dcb4 100644 --- a/tools/replay/camera.cc +++ b/tools/replay/camera.cc @@ -57,7 +57,7 @@ void CameraServer::cameraThread(Camera &cam) { }; vipc_server_->send(yuv, &extra, false); } else { - rError("camera[%d] failed to get frame:", cam.type, eidx.getSegmentId()); + rError("camera[%d] failed to get frame: %lu", cam.type, eidx.getSegmentId()); } cam.cached_id = id + 1; From 8f3b259f7ce85f0c72a913cdaea53d48b1112e92 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Tue, 30 Aug 2022 02:56:18 +0800 Subject: [PATCH 100/172] replay/camera: set frame id before send (#25591) --- tools/replay/camera.cc | 1 + 1 file changed, 1 insertion(+) diff --git a/tools/replay/camera.cc b/tools/replay/camera.cc index ef4f4dcb4..72b385dca 100644 --- a/tools/replay/camera.cc +++ b/tools/replay/camera.cc @@ -55,6 +55,7 @@ void CameraServer::cameraThread(Camera &cam) { .timestamp_sof = eidx.getTimestampSof(), .timestamp_eof = eidx.getTimestampEof(), }; + yuv->set_frame_id(eidx.getFrameId()); vipc_server_->send(yuv, &extra, false); } else { rError("camera[%d] failed to get frame: %lu", cam.type, eidx.getSegmentId()); From ee5b6d812d433d013cbb837a850c5df64c10a4d0 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 29 Aug 2022 12:06:09 -0700 Subject: [PATCH 101/172] Ram: don't check FW revision (#25589) * Don't check revision * fix --- selfdrive/car/chrysler/interface.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/car/chrysler/interface.py b/selfdrive/car/chrysler/interface.py index 9bb22b607..131f813c6 100755 --- a/selfdrive/car/chrysler/interface.py +++ b/selfdrive/car/chrysler/interface.py @@ -60,7 +60,7 @@ class CarInterface(CarInterfaceBase): ret.minSteerSpeed = 14.5 if car_fw is not None: for fw in car_fw: - if fw.ecu == 'eps' and fw.fwVersion in (b"68312176AE", b"68312176AG", b"68273275AG"): + if fw.ecu == 'eps' and fw.fwVersion[:8] in (b"68312176", b"68273275"): ret.minSteerSpeed = 0. elif candidate == CAR.RAM_HD: From cc90c6c97eb91bd9f4c23ae8baf230784482e8b8 Mon Sep 17 00:00:00 2001 From: Erich Moraga <33645296+ErichMoraga@users.noreply.github.com> Date: Mon, 29 Aug 2022 14:19:01 -0500 Subject: [PATCH 102/172] Add missing HIGHLANDERH_TSS2 engine f/w (#25582) `EAAUSANG#8056` 2022 Highlander Hybrid DongleID/route 9179d81377e52625|2022-08-27--13-24-33 --- selfdrive/car/toyota/values.py | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index f6e9d9ad4..5649e7d65 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -974,15 +974,16 @@ FW_VERSIONS = { b'\x01F152648J6000\x00\x00\x00\x00', ], (Ecu.engine, 0x700, None): [ - b'\x01896630EE4000\x00\x00\x00\x00', - b'\x01896630EE6000\x00\x00\x00\x00', b'\x01896630E67000\x00\x00\x00\x00', b'\x01896630EA1000\x00\x00\x00\x00', - b'\x01896630EA1000\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', + b'\x01896630EE4000\x00\x00\x00\x00', + b'\x01896630EE4100\x00\x00\x00\x00', + b'\x01896630EE6000\x00\x00\x00\x00', b'\x02896630E66000\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', + b'\x02896630E66100\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', + b'\x01896630EA1000\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', b'\x02896630EB3000\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', b'\x02896630EB3100\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', - b'\x02896630E66100\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 0xf): [ b'\x018821F3301400\x00\x00\x00\x00', From acbb230e0a2887971d906d9ae057ba0a7db44316 Mon Sep 17 00:00:00 2001 From: Mitchell Goff Date: Mon, 29 Aug 2022 13:31:43 -0700 Subject: [PATCH 103/172] Update DATA_ENDPOINT default to data-raw.comma.internal (#25597) --- tools/lib/filereader.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tools/lib/filereader.py b/tools/lib/filereader.py index 4ea9ad429..215f7b218 100644 --- a/tools/lib/filereader.py +++ b/tools/lib/filereader.py @@ -1,7 +1,7 @@ import os from tools.lib.url_file import URLFile -DATA_ENDPOINT = os.getenv("DATA_ENDPOINT", "http://data-raw.internal/") +DATA_ENDPOINT = os.getenv("DATA_ENDPOINT", "http://data-raw.comma.internal/") def FileReader(fn, debug=False): if fn.startswith("cd:/"): From a548e1b909a65ff52452b3b33370781c831de3ad Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 29 Aug 2022 13:47:19 -0700 Subject: [PATCH 104/172] FW tests: use subtests (#25598) Use subtests for FW tests Use subtests for FW tests --- selfdrive/car/tests/test_fw_fingerprint.py | 48 +++++++++------------- 1 file changed, 19 insertions(+), 29 deletions(-) diff --git a/selfdrive/car/tests/test_fw_fingerprint.py b/selfdrive/car/tests/test_fw_fingerprint.py index cda241c73..697aa4165 100755 --- a/selfdrive/car/tests/test_fw_fingerprint.py +++ b/selfdrive/car/tests/test_fw_fingerprint.py @@ -37,44 +37,34 @@ class TestFwFingerprint(unittest.TestCase): self.assertFingerprints(matches, car_model) def test_no_duplicate_fw_versions(self): - passed = True for car_model, ecus in FW_VERSIONS.items(): - for ecu, ecu_fw in ecus.items(): - duplicates = {fw for fw in ecu_fw if ecu_fw.count(fw) > 1} - if len(duplicates): - print(car_model, ECU_NAME[ecu[0]], duplicates) - passed = False - - self.assertTrue(passed, "Duplicate FW versions found") + with self.subTest(car_model=car_model): + for ecu, ecu_fw in ecus.items(): + with self.subTest(ecu): + 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_blacklisted_ecus(self): - passed = True blacklisted_addrs = (0x7c4, 0x7d0) # includes A/C ecu and an unknown ecu for car_model, ecus in FW_VERSIONS.items(): - CP = interfaces[car_model][0].get_params(car_model) - if CP.carName == 'subaru': - for ecu in ecus.keys(): - if ecu[1] in blacklisted_addrs: - print(f'{car_model}: Blacklisted ecu: (Ecu.{ECU_NAME[ecu[0]]}, {hex(ecu[1])})') - passed = False - - self.assertTrue(passed, "Blacklisted FW versions found") + with self.subTest(car_model=car_model): + CP = interfaces[car_model][0].get_params(car_model) + if CP.carName == 'subaru': + for ecu in ecus.keys(): + self.assertNotIn(ecu[1], blacklisted_addrs, f'{car_model}: Blacklisted ecu: (Ecu.{ECU_NAME[ecu[0]]}, {hex(ecu[1])})') def test_fw_request_ecu_whitelist(self): - passed = True - brands = set(r.brand for r in REQUESTS) - for brand in brands: - whitelisted_ecus = [ecu for r in REQUESTS for ecu in r.whitelist_ecus if r.brand == brand] - brand_ecus = set([fw[0] for car_fw in VERSIONS[brand].values() for fw in car_fw]) + for brand in set(r.brand for r in REQUESTS): + with self.subTest(brand=brand): + whitelisted_ecus = [ecu for r in REQUESTS for ecu in r.whitelist_ecus if r.brand == brand] + brand_ecus = set([fw[0] for car_fw in VERSIONS[brand].values() for fw in car_fw]) - # each ecu in brand's fw versions needs to be whitelisted at least once - ecus_not_whitelisted = set(brand_ecus) - set(whitelisted_ecus) - if len(whitelisted_ecus) and len(ecus_not_whitelisted): - ecu_strings = ", ".join([f'Ecu.{ECU_NAME[ecu]}' for ecu in ecus_not_whitelisted]) - print(f'{brand.title()}: FW query whitelist missing ecus: {ecu_strings}') - passed = False + # each ecu in brand's fw versions needs to be whitelisted at least once + ecus_not_whitelisted = set(brand_ecus) - set(whitelisted_ecus) - self.assertTrue(passed, "Not all ecus in FW versions found in query whitelists") + ecu_strings = ", ".join([f'Ecu.{ECU_NAME[ecu]}' for ecu in ecus_not_whitelisted]) + self.assertFalse(len(whitelisted_ecus) and len(ecus_not_whitelisted), + f'{brand.title()}: FW query whitelist missing ecus: {ecu_strings}') if __name__ == "__main__": From 63349809498ffdb1678cbd2aa399a67fc59c66b2 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 29 Aug 2022 14:08:21 -0700 Subject: [PATCH 105/172] laikad: fix cache path --- selfdrive/locationd/laikad.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/locationd/laikad.py b/selfdrive/locationd/laikad.py index 830eb3320..c7f2d2cea 100755 --- a/selfdrive/locationd/laikad.py +++ b/selfdrive/locationd/laikad.py @@ -28,7 +28,7 @@ from system.swaglog import cloudlog MAX_TIME_GAP = 10 EPHEMERIS_CACHE = 'LaikadEphemeris' -DOWNLOADS_CACHE_FOLDER = "/tmp/comma_download_cache" +DOWNLOADS_CACHE_FOLDER = "/tmp/comma_download_cache/" CACHE_VERSION = 0.1 POS_FIX_RESIDUAL_THRESHOLD = 100.0 From 19e088de0aad1673243a03173fccd948280b2925 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 29 Aug 2022 14:23:11 -0700 Subject: [PATCH 106/172] Chrysler: add FW tests (#25599) * stash * make sure no transmission FW is added for HD trucks * Remove * consistency --- selfdrive/car/tests/test_fw_fingerprint.py | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/selfdrive/car/tests/test_fw_fingerprint.py b/selfdrive/car/tests/test_fw_fingerprint.py index 697aa4165..2a47c60bf 100755 --- a/selfdrive/car/tests/test_fw_fingerprint.py +++ b/selfdrive/car/tests/test_fw_fingerprint.py @@ -53,6 +53,12 @@ class TestFwFingerprint(unittest.TestCase): for ecu in ecus.keys(): self.assertNotIn(ecu[1], blacklisted_addrs, f'{car_model}: Blacklisted ecu: (Ecu.{ECU_NAME[ecu[0]]}, {hex(ecu[1])})') + elif CP.carName == "chrysler": + # Some HD trucks have a combined TCM and ECM + if CP.carFingerprint.startswith("RAM HD"): + for ecu in ecus.keys(): + self.assertNotEqual(ecu[0], Ecu.transmission, f"{car_model}: Blacklisted ecu: (Ecu.{ECU_NAME[ecu[0]]}, {hex(ecu[1])})") + def test_fw_request_ecu_whitelist(self): for brand in set(r.brand for r in REQUESTS): with self.subTest(brand=brand): From f86163fc7bff333754785f8086530dc293e6b56e Mon Sep 17 00:00:00 2001 From: sleepysilkbee <48108267+sleepysilkbee@users.noreply.github.com> Date: Mon, 29 Aug 2022 16:44:02 -0500 Subject: [PATCH 107/172] Grammatically updated the tech docs. (#25588) --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index c2c90b0e6..7335bab26 100755 --- a/README.md +++ b/README.md @@ -50,7 +50,7 @@ We have detailed instructions for [how to mount the device in a car](https://com Running on PC ------ -All of openpilot's services can run as normal on a PC, even without special hardware or a car. To develop or experiment with openpilot you can run openpilot on recorded or simulated data. +All openpilot services can run as usual on a PC without requiring special hardware or a car. You can also run openpilot on recorded or simulated data to develop or experiment with openpilot. With openpilot's tools, you can plot logs, replay drives, and watch the full-res camera streams. See [the tools README](tools/README.md) for more information. From 365b37edd5a404dba8ebe91808af890840162ca6 Mon Sep 17 00:00:00 2001 From: Jason Wen <47793918+sunnyhaibin@users.noreply.github.com> Date: Mon, 29 Aug 2022 20:55:42 -0400 Subject: [PATCH 108/172] Hyundai: Add missing safety param to separate CAN-FD cruise button messages (#25605) --- selfdrive/car/hyundai/interface.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index fbf233498..bbb797c2e 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -299,6 +299,7 @@ class CarInterface(CarInterfaceBase): # non-HDA2 if 0x1cf not in fingerprint[4]: ret.flags |= HyundaiFlags.CANFD_ALT_BUTTONS.value + ret.safetyConfigs[1].safetyParam |= Panda.FLAG_HYUNDAI_CANFD_ALT_BUTTONS else: ret.enableBsm = 0x58b in fingerprint[0] From f3be0b5873224c1aabce9ec4942ba12b701c7cb4 Mon Sep 17 00:00:00 2001 From: Cameron Clough Date: Mon, 29 Aug 2022 19:11:53 -0700 Subject: [PATCH 109/172] ford: passthru mystery signals (#25575) * ford: passthru mystery signals * simple * types * bump opendbc * bump opendbc --- opendbc | 2 +- selfdrive/car/ford/carstate.py | 3 ++- selfdrive/car/ford/fordcan.py | 49 +++++----------------------------- 3 files changed, 10 insertions(+), 44 deletions(-) diff --git a/opendbc b/opendbc index b913296c9..778894f12 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit b913296c9123441b2b271c00239929ed388169b5 +Subproject commit 778894f128f9acd83b983688542c3d4e9f47307f diff --git a/selfdrive/car/ford/carstate.py b/selfdrive/car/ford/carstate.py index aaa3af612..3c9961e9e 100644 --- a/selfdrive/car/ford/carstate.py +++ b/selfdrive/car/ford/carstate.py @@ -203,7 +203,8 @@ class CarState(CarStateBase): ("DasStats_D_Dsply", "IPMA_Data"), # DAS status ("DasWarn_D_Dsply", "IPMA_Data"), # DAS warning ("AhbHiBeam_D_Rq", "IPMA_Data"), # AHB status - ("Set_Me_X1", "IPMA_Data"), + ("Passthru_63", "IPMA_Data"), + ("Passthru_48", "IPMA_Data"), ] checks = [ diff --git a/selfdrive/car/ford/fordcan.py b/selfdrive/car/ford/fordcan.py index 29fec1f2d..bb104aaf3 100644 --- a/selfdrive/car/ford/fordcan.py +++ b/selfdrive/car/ford/fordcan.py @@ -51,7 +51,7 @@ def create_tja_command(packer, lca_rq: int, ramp_type: int, precision: int, path return packer.make_can_msg("LateralMotionControl", 0, values) -def create_lkas_ui_command(packer, main_on: bool, enabled: bool, steer_alert: bool, stock_values): +def create_lkas_ui_command(packer, main_on: bool, enabled: bool, steer_alert: bool, stock_values: dict): """ Creates a CAN message for the Ford IPC IPMA/LKAS status. @@ -72,25 +72,14 @@ def create_lkas_ui_command(packer, main_on: bool, enabled: bool, steer_alert: bo lines = 30 values = { - "FeatConfigIpmaActl": stock_values["FeatConfigIpmaActl"], # [0|65535] - "FeatNoIpmaActl": stock_values["FeatNoIpmaActl"], # [0|65535] - "PersIndexIpma_D_Actl": stock_values["PersIndexIpma_D_Actl"], # [0|7] - "AhbcRampingV_D_Rq": stock_values["AhbcRampingV_D_Rq"], # AHB ramping [0|3] - "LaActvStats_D_Dsply": lines, # LKAS status (lines) [0|31] - "LaDenyStats_B_Dsply": stock_values["LaDenyStats_B_Dsply"], # LKAS error [0|1] - "LaHandsOff_D_Dsply": 2 if steer_alert else 0, # 0=HandsOn, 1=Level1 (w/o chime), 2=Level2 (w/ chime), 3=Suppressed - "CamraDefog_B_Req": stock_values["CamraDefog_B_Req"], # Windshield heater? [0|1] - "CamraStats_D_Dsply": stock_values["CamraStats_D_Dsply"], # Camera status [0|3] - "DasAlrtLvl_D_Dsply": stock_values["DasAlrtLvl_D_Dsply"], # DAS alert level [0|7] - "DasStats_D_Dsply": stock_values["DasStats_D_Dsply"], # DAS status [0|3] - "DasWarn_D_Dsply": stock_values["DasWarn_D_Dsply"], # DAS warning [0|3] - "AhbHiBeam_D_Rq": stock_values["AhbHiBeam_D_Rq"], # AHB status [0|3] - "Set_Me_X1": stock_values["Set_Me_X1"], # [0|15] + **stock_values, + "LaActvStats_D_Dsply": lines, # LKAS status (lines) [0|31] + "LaHandsOff_D_Dsply": 2 if steer_alert else 0, # 0=HandsOn, 1=Level1 (w/o chime), 2=Level2 (w/ chime), 3=Suppressed } return packer.make_can_msg("IPMA_Data", 0, values) -def create_acc_ui_command(packer, main_on: bool, enabled: bool, stock_values): +def create_acc_ui_command(packer, main_on: bool, enabled: bool, stock_values: dict): """ Creates a CAN message for the Ford IPC adaptive cruise, forward collision warning and traffic jam assist status. @@ -101,32 +90,8 @@ def create_acc_ui_command(packer, main_on: bool, enabled: bool, stock_values): """ values = { - "HaDsply_No_Cs": stock_values["HaDsply_No_Cs"], # [0|255] - "HaDsply_No_Cnt": stock_values["HaDsply_No_Cnt"], # [0|15] - "AccStopStat_D_Dsply": stock_values["AccStopStat_D_Dsply"], # ACC stopped status message: 0=NoDisplay, 1=ResumeReady, 2=Stopped, 3=PressResume [0|3] - "AccTrgDist2_D_Dsply": stock_values["AccTrgDist2_D_Dsply"], # ACC target distance [0|15] - "AccStopRes_B_Dsply": stock_values["AccStopRes_B_Dsply"], # [0|1] - "TjaWarn_D_Rq": stock_values["TjaWarn_D_Rq"], # TJA warning: 0=NoWarning, 1=Cancel, 2=HardTakeOverLevel1, 3=HardTakeOverLevel2 [0|7] - "Tja_D_Stat": 2 if enabled else (1 if main_on else 0), # TJA status: 0=Off, 1=Standby, 2=Active, 3=InterventionLeft, 4=InterventionRight, 5=WarningLeft, 6=WarningRight, 7=NotUsed [0|7] - "TjaMsgTxt_D_Dsply": stock_values["TjaMsgTxt_D_Dsply"], # TJA text [0|7] - "IaccLamp_D_Rq": stock_values["IaccLamp_D_Rq"], # iACC status icon [0|3] - "AccMsgTxt_D2_Rq": stock_values["AccMsgTxt_D2_Rq"], # ACC text [0|15] - "FcwDeny_B_Dsply": stock_values["FcwDeny_B_Dsply"], # FCW disabled [0|1] - "FcwMemStat_B_Actl": stock_values["FcwMemStat_B_Actl"], # FCW enabled setting [0|1] - "AccTGap_B_Dsply": stock_values["AccTGap_B_Dsply"], # ACC time gap display setting [0|1] - "CadsAlignIncplt_B_Actl": stock_values["CadsAlignIncplt_B_Actl"], # Radar alignment? [0|1] - "AccFllwMde_B_Dsply": stock_values["AccFllwMde_B_Dsply"], # ACC follow mode display setting [0|1] - "CadsRadrBlck_B_Actl": stock_values["CadsRadrBlck_B_Actl"], # Radar blocked? [0|1] - "CmbbPostEvnt_B_Dsply": stock_values["CmbbPostEvnt_B_Dsply"], # AEB event status [0|1] - "AccStopMde_B_Dsply": stock_values["AccStopMde_B_Dsply"], # ACC stop mode display setting [0|1] - "FcwMemSens_D_Actl": stock_values["FcwMemSens_D_Actl"], # FCW sensitivity setting [0|3] - "FcwMsgTxt_D_Rq": stock_values["FcwMsgTxt_D_Rq"], # FCW text [0|7] - "AccWarn_D_Dsply": stock_values["AccWarn_D_Dsply"], # ACC warning [0|3] - "FcwVisblWarn_B_Rq": stock_values["FcwVisblWarn_B_Rq"], # FCW alert: 0=Off, 1=On [0|1] - "FcwAudioWarn_B_Rq": stock_values["FcwAudioWarn_B_Rq"], # FCW audio: 0=Off, 1=On [0|1] - "AccTGap_D_Dsply": stock_values["AccTGap_D_Dsply"], # ACC time gap: 1=Time_Gap_1, 2=Time_Gap_2, ..., 5=Time_Gap_5 [0|7] - "AccMemEnbl_B_RqDrv": stock_values["AccMemEnbl_B_RqDrv"], # ACC setting: 0=NormalCruise, 1=AdaptiveCruise [0|1] - "FdaMem_B_Stat": stock_values["FdaMem_B_Stat"], # FDA enabled setting [0|1] + **stock_values, + "Tja_D_Stat": 2 if enabled else (1 if main_on else 0), # TJA status: 0=Off, 1=Standby, 2=Active, 3=InterventionLeft, 4=InterventionRight, 5=WarningLeft, 6=WarningRight, 7=NotUsed [0|7] } return packer.make_can_msg("ACCDATA_3", 0, values) From 0697ca223974f2361ca655506ceab7d18917b9de Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 29 Aug 2022 22:51:50 -0700 Subject: [PATCH 110/172] VIN: query physical addresses (#25122) * Try engine and VMCU addrs for VIN * Add address for Honda * Update selfdrive/car/vin.py * Update selfdrive/car/vin.py * Update selfdrive/car/vin.py --- selfdrive/car/vin.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/car/vin.py b/selfdrive/car/vin.py index 5ace68649..ae3aa675c 100755 --- a/selfdrive/car/vin.py +++ b/selfdrive/car/vin.py @@ -5,7 +5,6 @@ import traceback import cereal.messaging as messaging import panda.python.uds as uds -from panda.python.uds import FUNCTIONAL_ADDRS from selfdrive.car.isotp_parallel_query import IsoTpParallelQuery from system.swaglog import cloudlog @@ -24,10 +23,11 @@ def is_valid_vin(vin: str): def get_vin(logcan, sendcan, bus, timeout=0.1, retry=5, debug=False): + addrs = [0x7e0, 0x7e2, 0x18da10f1, 0x18da0ef1] # engine, VMCU, 29-bit engine, PGM-FI for i in range(retry): for request, response in ((UDS_VIN_REQUEST, UDS_VIN_RESPONSE), (OBD_VIN_REQUEST, OBD_VIN_RESPONSE)): try: - query = IsoTpParallelQuery(sendcan, logcan, bus, FUNCTIONAL_ADDRS, [request, ], [response, ], functional_addr=True, debug=debug) + query = IsoTpParallelQuery(sendcan, logcan, bus, addrs, [request, ], [response, ], debug=debug) for (addr, rx_addr), vin in query.get_data(timeout).items(): # Honda Bosch response starts with a length, trim to correct length From ff3ebbb13b04efc44773cda75bc6a390f7764159 Mon Sep 17 00:00:00 2001 From: qadmus <42746943+qadmus@users.noreply.github.com> Date: Tue, 30 Aug 2022 02:40:23 -0700 Subject: [PATCH 111/172] plotjuggler readme: refer to openpilot env setup (#25609) * plotjuggler readme: refer to openpilot env setup * Update tools/plotjuggler/README.md Co-authored-by: Shane Smiskol Co-authored-by: Shane Smiskol --- tools/plotjuggler/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tools/plotjuggler/README.md b/tools/plotjuggler/README.md index 25fcb5931..b4190384d 100644 --- a/tools/plotjuggler/README.md +++ b/tools/plotjuggler/README.md @@ -4,7 +4,7 @@ ## Installation -Once you've cloned and are in openpilot, this command will download PlotJuggler and install our plugins: +Once you've [set up the openpilot environment](../README.md), this command will download PlotJuggler and install our plugins: `cd tools/plotjuggler && ./juggle.py --install` From 6590fb2b93baedb2e1c5267b4f191f8e20fcd1d2 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 30 Aug 2022 11:20:55 -0700 Subject: [PATCH 112/172] pre-commit: add codespell (#25571) --- .github/PULL_REQUEST_TEMPLATE/car_bugfix.md | 2 +- .pre-commit-config.yaml | 9 +++++++++ README.md | 2 +- RELEASES.md | 6 +++--- SConstruct | 2 +- cereal | 2 +- common/tests/test_util.cc | 2 +- opendbc | 2 +- panda | 2 +- selfdrive/boardd/boardd.cc | 4 ++-- selfdrive/car/car_helpers.py | 2 +- selfdrive/car/tests/test_fingerprints.py | 2 +- selfdrive/car/tests/test_models.py | 2 +- selfdrive/controls/lib/tests/test_vehicle_model.py | 2 +- selfdrive/controls/tests/test_alerts.py | 2 +- selfdrive/debug/README.md | 2 +- selfdrive/debug/cpu_usage_stat.py | 4 ++-- selfdrive/debug/hyundai_enable_radar_points.py | 2 +- selfdrive/debug/internal/power_monitor.py | 2 +- selfdrive/debug/test_fw_query_on_routes.py | 2 +- selfdrive/locationd/locationd.cc | 6 +++--- selfdrive/locationd/models/loc_kf.py | 2 +- selfdrive/locationd/test/ubloxd.py | 2 +- selfdrive/loggerd/logger.cc | 2 +- selfdrive/loggerd/tests/test_logger.cc | 2 +- selfdrive/loggerd/tests/test_loggerd.py | 2 +- selfdrive/manager/helpers.py | 2 +- selfdrive/modeld/transforms/transform.cc | 2 +- selfdrive/navd/navd.py | 8 ++++---- selfdrive/sensord/sensors/lsm6ds3_accel.cc | 2 +- selfdrive/test/process_replay/model_replay.py | 2 +- selfdrive/ui/SConscript | 2 +- selfdrive/ui/installer/installer.cc | 2 +- system/camerad/cameras/camera_qcom2.cc | 8 ++++---- system/hardware/tici/agnos.py | 4 ++-- system/hardware/tici/hardware.py | 2 +- system/proclogd/proclog.cc | 2 +- tools/README.md | 4 ++-- tools/camerastream/compressed_vipc.py | 2 +- tools/latencylogger/latency_logger.py | 4 ++-- tools/lib/README.md | 2 +- tools/lib/tests/test_readers.py | 4 ++-- tools/plotjuggler/juggle.py | 4 ++-- tools/plotjuggler/layouts/max-torque-debug.xml | 4 ++-- tools/replay/framereader.cc | 2 +- tools/replay/replay.cc | 2 +- tools/replay/replay.h | 2 +- tools/sim/bridge.py | 2 +- 48 files changed, 74 insertions(+), 65 deletions(-) diff --git a/.github/PULL_REQUEST_TEMPLATE/car_bugfix.md b/.github/PULL_REQUEST_TEMPLATE/car_bugfix.md index d0c8bc58e..76c86346c 100644 --- a/.github/PULL_REQUEST_TEMPLATE/car_bugfix.md +++ b/.github/PULL_REQUEST_TEMPLATE/car_bugfix.md @@ -1,6 +1,6 @@ --- name: Car Bug fix -about: For vehicle/brand specifc bug fixes +about: For vehicle/brand specific bug fixes title: '' labels: 'car bug fix' assignees: '' diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index e273cd9ae..85bd06c5f 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -15,6 +15,15 @@ repos: - id: check-symlinks - id: check-added-large-files args: ['--maxkb=100'] +- repo: https://github.com/codespell-project/codespell + rev: v2.2.1 + hooks: + - id: codespell + exclude: '^(pyextra/)|(third_party/)|(body/)|(cereal/)|(rednose/)|(panda/)|(laika/)|(opendbc/)|(laika_repo/)|(rednose_repo/)|(include/)|(selfdrive/ui/translations/.*.ts)|(selfdrive/controls/lib/cluster)' + args: + # if you've got a short variable name that's getting flagged, add it here + - -L bu,ro,te,ue,alo,hda,ois,nam,nams,ned,som,parm,setts,inout,warmup + - --builtins clear,rare,informal,usage,code,names,en-GB_to_en-US - repo: https://github.com/pre-commit/mirrors-mypy rev: v0.931 hooks: diff --git a/README.md b/README.md index 7335bab26..cfeb625bf 100755 --- a/README.md +++ b/README.md @@ -119,7 +119,7 @@ Directory Structure ├── debug # Tools to help you debug and do car ports ├── locationd # Precise localization and vehicle parameter estimation ├── loggerd # Logger and uploader of car data - ├── manager # Deamon that starts/stops all other daemons as needed + ├── manager # Daemon that starts/stops all other daemons as needed ├── modeld # Driving and monitoring model runners ├── monitoring # Daemon to determine driver attention ├── navd # Turn-by-turn navigation diff --git a/RELEASES.md b/RELEASES.md index 28a010968..56cffeebe 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -78,7 +78,7 @@ Version 0.8.14 (2022-06-01) Version 0.8.13 (2022-02-18) ======================== * Improved driver monitoring - * Retuned driver pose learner for relaxed driving positions + * Re-tuned driver pose learner for relaxed driving positions * Added reliance on driving model to be more scene adaptive * Matched strictness between comma two and comma three * Improved performance in turns by compensating for the road bank angle @@ -224,7 +224,7 @@ Version 0.8.4 (2021-05-17) * Delay controls start until system is ready * Fuzzy car identification, enabled with Community Features toggle * Localizer optimized for increased precision and less CPU usage - * Retuned lateral control to be more aggressive when model is confident + * Re-tuned lateral control to be more aggressive when model is confident * Toyota Mirai 2021 support * Lexus NX 300 2020 support thanks to goesreallyfast! * Volkswagen Atlas 2018-19 support thanks to jyoung8607! @@ -389,7 +389,7 @@ Version 0.7 (2019-12-13) * Improve GM longitudinal control: proper computations for 15Hz radar * Move GM port, Toyota with DSU removed, comma pedal in community features; toggle switch required * Remove upload over cellular toggle: only upload qlog and qcamera files if not on wifi - * Refactor Panda code towards ISO26262 and SIL2 compliancy + * Refactor Panda code towards ISO26262 and SIL2 compliance * Forward stock FCW for Honda Nidec * Volkswagen port now standard: comma Harness intercepts stock camera diff --git a/SConstruct b/SConstruct index 878244768..d4155f4f8 100644 --- a/SConstruct +++ b/SConstruct @@ -254,7 +254,7 @@ def abspath(x): # rpath works elsewhere return x[0].path.rsplit("/", 1)[1][:-3] -# Cython build enviroment +# Cython build environment py_include = sysconfig.get_paths()['include'] envCython = env.Clone() envCython["CPPPATH"] += [py_include, np.get_include()] diff --git a/cereal b/cereal index 589ef049a..c4cc38c46 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 589ef049a7b0bac31f4c8987c0fc539839fae489 +Subproject commit c4cc38c4689b5e06be1cbfbb26c0463c377c0a6d diff --git a/common/tests/test_util.cc b/common/tests/test_util.cc index 62e73275d..25ecf09aa 100644 --- a/common/tests/test_util.cc +++ b/common/tests/test_util.cc @@ -136,7 +136,7 @@ TEST_CASE("util::create_directories") { REQUIRE(util::create_directories(dir + "/file", 0755) == false); REQUIRE(util::create_directories(dir + "/file/1/2/3", 0755) == false); } - SECTION("end with slashs") { + SECTION("end with slashes") { REQUIRE(util::create_directories(dir + "/", 0755)); } SECTION("empty") { diff --git a/opendbc b/opendbc index 778894f12..8c634615c 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit 778894f128f9acd83b983688542c3d4e9f47307f +Subproject commit 8c634615c5b6eb05ebdecc097bdc72f5403a3afa diff --git a/panda b/panda index 9d6496ece..1776165a3 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 9d6496ece8465dfe30997b31dfb352e1e51dde6c +Subproject commit 1776165a3d902d6320965b6b6b1715bb9a25915b diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index bd3a6c438..59579a7fc 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -34,7 +34,7 @@ // - The internal panda will always be the first panda // - Consecutive pandas will be sorted based on panda type, and then serial number // Connecting: -// - If a panda connection is dropped, boardd wil reconnect to all pandas +// - If a panda connection is dropped, boardd will reconnect to all pandas // - If a panda is added, we will only reconnect when we are offroad // CAN buses: // - Each panda will have it's block of 4 buses. E.g.: the second panda will use @@ -44,7 +44,7 @@ // Safety: // - SafetyConfig is a list, which is mapped to the connected pandas // - If there are more pandas connected than there are SafetyConfigs, -// the excess pandas will remain in "silent" ot "noOutput" mode +// the excess pandas will remain in "silent" or "noOutput" mode // Ignition: // - If any of the ignition sources in any panda is high, ignition is high diff --git a/selfdrive/car/car_helpers.py b/selfdrive/car/car_helpers.py index aa4b37d57..9e1260a6d 100644 --- a/selfdrive/car/car_helpers.py +++ b/selfdrive/car/car_helpers.py @@ -82,7 +82,7 @@ def fingerprint(logcan, sendcan): ecu_rx_addrs = set() if not fixed_fingerprint and not skip_fw_query: - # Vin query only reliably works thorugh OBDII + # Vin query only reliably works through OBDII bus = 1 cached_params = Params().get("CarParamsCache") diff --git a/selfdrive/car/tests/test_fingerprints.py b/selfdrive/car/tests/test_fingerprints.py index 9dd28b2d5..26ade29e4 100755 --- a/selfdrive/car/tests/test_fingerprints.py +++ b/selfdrive/car/tests/test_fingerprints.py @@ -94,4 +94,4 @@ if __name__ == "__main__": print("TEST FAILED") sys.exit(1) else: - print("TEST SUCESSFUL") + print("TEST SUCCESSFUL") diff --git a/selfdrive/car/tests/test_models.py b/selfdrive/car/tests/test_models.py index 502df3fe3..edfa07a8c 100755 --- a/selfdrive/car/tests/test_models.py +++ b/selfdrive/car/tests/test_models.py @@ -137,7 +137,7 @@ class TestCarModelBase(unittest.TestCase): elif tuning == 'indi': self.assertTrue(len(self.CP.lateralTuning.indi.outerLoopGainV)) else: - raise Exception("unkown tuning") + raise Exception("unknown tuning") def test_car_interface(self): # TODO: also check for checksum violations from can parser diff --git a/selfdrive/controls/lib/tests/test_vehicle_model.py b/selfdrive/controls/lib/tests/test_vehicle_model.py index f2636027e..3e08cb0aa 100755 --- a/selfdrive/controls/lib/tests/test_vehicle_model.py +++ b/selfdrive/controls/lib/tests/test_vehicle_model.py @@ -41,7 +41,7 @@ class TestVehicleModel(unittest.TestCase): self.assertAlmostEqual(float(yr1), yr2) def test_syn_ss_sol_simulate(self): - """Verifies that dyn_ss_sol mathes a simulation""" + """Verifies that dyn_ss_sol matches a simulation""" for roll in np.linspace(math.radians(-20), math.radians(20), num=11): for u in np.linspace(1, 30, num=10): diff --git a/selfdrive/controls/tests/test_alerts.py b/selfdrive/controls/tests/test_alerts.py index 79c56d6bc..9ed7eee12 100755 --- a/selfdrive/controls/tests/test_alerts.py +++ b/selfdrive/controls/tests/test_alerts.py @@ -52,7 +52,7 @@ class TestAlerts(unittest.TestCase): bold_font_path = os.path.join(font_path, "Inter-Bold.ttf") semibold_font_path = os.path.join(font_path, "Inter-SemiBold.ttf") - max_text_width = 2160 - 300 # full screen width is useable, minus sidebar + max_text_width = 2160 - 300 # full screen width is usable, minus sidebar draw = ImageDraw.Draw(Image.new('RGB', (0, 0))) fonts = { diff --git a/selfdrive/debug/README.md b/selfdrive/debug/README.md index f6903170a..83b8a994d 100644 --- a/selfdrive/debug/README.md +++ b/selfdrive/debug/README.md @@ -19,7 +19,7 @@ optional arguments: ``` usage: dump.py [-h] [--pipe] [--raw] [--json] [--dump-json] [--no-print] [--addr ADDR] [--values VALUES] [socket [socket ...]] -Dump communcation sockets. See cereal/services.py for a complete list of available sockets. +Dump communication sockets. See cereal/services.py for a complete list of available sockets. positional arguments: socket socket names to dump. defaults to all services defined in cereal diff --git a/selfdrive/debug/cpu_usage_stat.py b/selfdrive/debug/cpu_usage_stat.py index 76e809d2c..b3294c872 100755 --- a/selfdrive/debug/cpu_usage_stat.py +++ b/selfdrive/debug/cpu_usage_stat.py @@ -5,8 +5,8 @@ System tools like top/htop can only show current cpu usage values, so I write th Features: Use psutil library to sample cpu usage(avergage for all cores) of openpilot processes, at a rate of 5 samples/sec. Do cpu usage statistics periodically, 5 seconds as a cycle. - Caculate the average cpu usage within this cycle. - Caculate minumium/maximium/accumulated_average cpu usage as long term inspections. + Calculate the average cpu usage within this cycle. + Calculate minumium/maximum/accumulated_average cpu usage as long term inspections. Monitor multiple processes simuteneously. Sample usage: root@localhost:/data/openpilot$ python selfdrive/debug/cpu_usage_stat.py boardd,ubloxd diff --git a/selfdrive/debug/hyundai_enable_radar_points.py b/selfdrive/debug/hyundai_enable_radar_points.py index f182026aa..ac7e7102d 100755 --- a/selfdrive/debug/hyundai_enable_radar_points.py +++ b/selfdrive/debug/hyundai_enable_radar_points.py @@ -6,7 +6,7 @@ firmware versions. If you want to try on a new radar make sure to note the defau in case it's different from the other radars and you need to revert the changes. After changing the config the car should not show any faults when openpilot is not running. -These config changes are persistent accross car reboots. You need to run this script again +These config changes are persistent across car reboots. You need to run this script again to go back to the default values. USE AT YOUR OWN RISK! Safety features, like AEB and FCW, might be affected by these changes.""" diff --git a/selfdrive/debug/internal/power_monitor.py b/selfdrive/debug/internal/power_monitor.py index 09fb89835..34d2a12ad 100755 --- a/selfdrive/debug/internal/power_monitor.py +++ b/selfdrive/debug/internal/power_monitor.py @@ -59,6 +59,6 @@ if __name__ == '__main__': print(f" {(stop_time - start_time).total_seconds():.2f} Seconds {voltage_average[1]} samples") print("----------------------------------------------------------------") - # reenable charging + # re-enable charging os.system('echo "1" > /sys/class/power_supply/battery/charging_enabled') print("charging enabled\n") diff --git a/selfdrive/debug/test_fw_query_on_routes.py b/selfdrive/debug/test_fw_query_on_routes.py index 868813b0f..6cc7da5f1 100755 --- a/selfdrive/debug/test_fw_query_on_routes.py +++ b/selfdrive/debug/test_fw_query_on_routes.py @@ -168,7 +168,7 @@ if __name__ == "__main__": break print() - # Print FW versions that need to be added seperated out by car and address + # Print FW versions that need to be added separated out by car and address for car, m in sorted(mismatches.items()): print(car) addrs = defaultdict(list) diff --git a/selfdrive/locationd/locationd.cc b/selfdrive/locationd/locationd.cc index 7714931b9..2fb3e0081 100755 --- a/selfdrive/locationd/locationd.cc +++ b/selfdrive/locationd/locationd.cc @@ -476,9 +476,9 @@ bool Localizer::isGpsOK() { } void Localizer::determine_gps_mode(double current_time) { - // 1. If the pos_std is greater than what's not acceptible and localizer is in gps-mode, reset to no-gps-mode - // 2. If the pos_std is greater than what's not acceptible and localizer is in no-gps-mode, fake obs - // 3. If the pos_std is smaller than what's not acceptible, let gps-mode be whatever it is + // 1. If the pos_std is greater than what's not acceptable and localizer is in gps-mode, reset to no-gps-mode + // 2. If the pos_std is greater than what's not acceptable and localizer is in no-gps-mode, fake obs + // 3. If the pos_std is smaller than what's not acceptable, let gps-mode be whatever it is VectorXd current_pos_std = this->kf->get_P().block(STATE_ECEF_POS_ERR_START, STATE_ECEF_POS_ERR_START).diagonal().array().sqrt(); if (current_pos_std.norm() > SANE_GPS_UNCERTAINTY){ if (this->gps_mode){ diff --git a/selfdrive/locationd/models/loc_kf.py b/selfdrive/locationd/models/loc_kf.py index 25bf36d2c..4c947422b 100755 --- a/selfdrive/locationd/models/loc_kf.py +++ b/selfdrive/locationd/models/loc_kf.py @@ -33,7 +33,7 @@ class States(): ACCELEROMETER_BIAS = slice(30, 33) # bias of mems accelerometer # TODO the offset is likely a translation of the sensor, not a rotation of the camera WIDE_FROM_DEVICE_EULER = slice(33, 36) # wide camera offset angles in radians (tici only) - # We curently do not use ACCELEROMETER_SCALE to avoid instability due to too many free variables (ACCELEROMETER_SCALE, ACCELEROMETER_BIAS, IMU_FROM_DEVICE_EULER). + # We currently do not use ACCELEROMETER_SCALE to avoid instability due to too many free variables (ACCELEROMETER_SCALE, ACCELEROMETER_BIAS, IMU_FROM_DEVICE_EULER). # From experiments we see that ACCELEROMETER_BIAS is more correct than ACCELEROMETER_SCALE # Error-state has different slices because it is an ESKF diff --git a/selfdrive/locationd/test/ubloxd.py b/selfdrive/locationd/test/ubloxd.py index b0339851d..82aa502ce 100755 --- a/selfdrive/locationd/test/ubloxd.py +++ b/selfdrive/locationd/test/ubloxd.py @@ -65,7 +65,7 @@ def configure_ublox(dev): print("backup restore polling message (implement custom response handler!):") dev.configure_poll(0x09, 0x14) - print("if succesfull, send this to clear the flash:") + print("if successful, send this to clear the flash:") dev.send_message(0x09, 0x14, b"\x01\x00\x00\x00") print("send on stop:") diff --git a/selfdrive/loggerd/logger.cc b/selfdrive/loggerd/logger.cc index da3710cc7..aaf267e52 100644 --- a/selfdrive/loggerd/logger.cc +++ b/selfdrive/loggerd/logger.cc @@ -182,7 +182,7 @@ int logger_next(LoggerState *s, const char* root_path, pthread_mutex_unlock(&s->lock); - // write beggining of log metadata + // write beginning of log metadata log_init_data(s); lh_log_sentinel(s->cur_handle, is_start_of_route ? SentinelType::START_OF_ROUTE : SentinelType::START_OF_SEGMENT); return 0; diff --git a/selfdrive/loggerd/tests/test_logger.cc b/selfdrive/loggerd/tests/test_logger.cc index c8f662092..18a0e57df 100644 --- a/selfdrive/loggerd/tests/test_logger.cc +++ b/selfdrive/loggerd/tests/test_logger.cc @@ -47,7 +47,7 @@ void verify_segment(const std::string &route_path, int segment, int max_segment, } ++i; } catch (const kj::Exception &ex) { - INFO("failed parse " << i << " excpetion :" << ex.getDescription()); + INFO("failed parse " << i << " exception :" << ex.getDescription()); REQUIRE(0); break; } diff --git a/selfdrive/loggerd/tests/test_loggerd.py b/selfdrive/loggerd/tests/test_loggerd.py index 9dbc7ac33..b0907c54a 100755 --- a/selfdrive/loggerd/tests/test_loggerd.py +++ b/selfdrive/loggerd/tests/test_loggerd.py @@ -186,7 +186,7 @@ class TestLoggerd(unittest.TestCase): pm = messaging.PubMaster(services) # sleep enough for the first poll to time out - # TOOD: fix loggerd bug dropping the msgs from the first poll + # TODO: fix loggerd bug dropping the msgs from the first poll managed_processes["loggerd"].start() for s in services: while not pm.all_readers_updated(s): diff --git a/selfdrive/manager/helpers.py b/selfdrive/manager/helpers.py index b07362dd4..983c7cc0b 100644 --- a/selfdrive/manager/helpers.py +++ b/selfdrive/manager/helpers.py @@ -33,6 +33,6 @@ def unblock_stdout() -> None: pass # os.wait() returns a tuple with the pid and a 16 bit value - # whose low byte is the signal number and whose high byte is the exit satus + # whose low byte is the signal number and whose high byte is the exit status exit_status = os.wait()[1] >> 8 os._exit(exit_status) diff --git a/selfdrive/modeld/transforms/transform.cc b/selfdrive/modeld/transforms/transform.cc index cabc58a46..f34131414 100644 --- a/selfdrive/modeld/transforms/transform.cc +++ b/selfdrive/modeld/transforms/transform.cc @@ -32,7 +32,7 @@ void transform_queue(Transform* s, const int zero = 0; // sampled using pixel center origin - // (because thats how fastcv and opencv does it) + // (because that's how fastcv and opencv does it) mat3 projection_y = projection; diff --git a/selfdrive/navd/navd.py b/selfdrive/navd/navd.py index 3c2a7f555..ee5425207 100755 --- a/selfdrive/navd/navd.py +++ b/selfdrive/navd/navd.py @@ -194,10 +194,10 @@ class RouteEngine: parse_banner_instructions(msg.navInstruction, step['bannerInstructions'], distance_to_maneuver_along_geometry) # Compute total remaining time and distance - remaning = 1.0 - along_geometry / max(step['distance'], 1) - total_distance = step['distance'] * remaning - total_time = step['duration'] * remaning - total_time_typical = step['duration_typical'] * remaning + remaining = 1.0 - along_geometry / max(step['distance'], 1) + total_distance = step['distance'] * remaining + total_time = step['duration'] * remaining + total_time_typical = step['duration_typical'] * remaining # Add up totals for future steps for i in range(self.step_idx + 1, len(self.route)): diff --git a/selfdrive/sensord/sensors/lsm6ds3_accel.cc b/selfdrive/sensord/sensors/lsm6ds3_accel.cc index bcac7de9f..d923986db 100644 --- a/selfdrive/sensord/sensors/lsm6ds3_accel.cc +++ b/selfdrive/sensord/sensors/lsm6ds3_accel.cc @@ -27,7 +27,7 @@ int LSM6DS3_Accel::init() { source = cereal::SensorEventData::SensorSource::LSM6DS3TRC; } - // TODO: set scale and bandwith. Default is +- 2G, 50 Hz + // TODO: set scale and bandwidth. Default is +- 2G, 50 Hz ret = set_register(LSM6DS3_ACCEL_I2C_REG_CTRL1_XL, LSM6DS3_ACCEL_ODR_104HZ); if (ret < 0) { goto fail; diff --git a/selfdrive/test/process_replay/model_replay.py b/selfdrive/test/process_replay/model_replay.py index d2090aa76..ccd89bea9 100755 --- a/selfdrive/test/process_replay/model_replay.py +++ b/selfdrive/test/process_replay/model_replay.py @@ -173,7 +173,7 @@ if __name__ == "__main__": 'driverStateV2.modelExecutionTime', 'driverStateV2.dspExecutionTime' ] - # TODO this tolerence is absurdly large + # TODO this tolerance is absurdly large tolerance = 5e-1 if PC else None results: Any = {TEST_ROUTE: {}} log_paths: Any = {TEST_ROUTE: {"models": {'ref': BASE_URL + log_fn, 'new': log_fn}}} diff --git a/selfdrive/ui/SConscript b/selfdrive/ui/SConscript index 9e89576a5..c62a6b19d 100644 --- a/selfdrive/ui/SConscript +++ b/selfdrive/ui/SConscript @@ -78,7 +78,7 @@ if GetOption('extras'): if GetOption('extras'): - # buidl updater UI + # build updater UI qt_env.Program("qt/setup/updater", ["qt/setup/updater.cc", asset_obj], LIBS=qt_libs) # build mui diff --git a/selfdrive/ui/installer/installer.cc b/selfdrive/ui/installer/installer.cc index ee98c4d3d..db33e1cd6 100644 --- a/selfdrive/ui/installer/installer.cc +++ b/selfdrive/ui/installer/installer.cc @@ -107,7 +107,7 @@ void Installer::doInstall() { qDebug() << "Waiting for valid time"; } - // cleanup previous install attemps + // cleanup previous install attempts run("rm -rf " TMP_INSTALL_PATH " " INSTALL_PATH); // do the install diff --git a/system/camerad/cameras/camera_qcom2.cc b/system/camerad/cameras/camera_qcom2.cc index 31af284d5..b6a156445 100644 --- a/system/camerad/cameras/camera_qcom2.cc +++ b/system/camerad/cameras/camera_qcom2.cc @@ -949,7 +949,7 @@ std::map> CameraState::ar0231_build_register_lut(u // // 0xAA is used to indicate the MSB of the address, 0xA5 for the LSB of the address. // Every byte of data (MSB and LSB) is preceded by 0x5A. Specifying an address is optional - // for contigous ranges. See page 27-29 of the AR0231 Developer guide for more information. + // for contiguous ranges. See page 27-29 of the AR0231 Developer guide for more information. int max_i[] = {1828 / 2 * 3, 1500 / 2 * 3}; auto get_next_idx = [](int cur_idx) { @@ -1077,7 +1077,7 @@ void CameraState::set_camera_exposure(float grey_frac) { // It takes 3 frames for the commanded exposure settings to take effect. The first frame is already started by the time // we reach this function, the other 2 are due to the register buffering in the sensor. // Therefore we use the target EV from 3 frames ago, the grey fraction that was just measured was the result of that control action. - // TODO: Lower latency to 2 frames, by using the histogram outputed by the sensor we can do AE before the debayering is complete + // TODO: Lower latency to 2 frames, by using the histogram outputted by the sensor we can do AE before the debayering is complete const float cur_ev_ = cur_ev[buf.cur_frame_data.frame_id % 3]; @@ -1110,7 +1110,7 @@ void CameraState::set_camera_exposure(float grey_frac) { // Compute optimal time for given gain int t = std::clamp(int(std::round(desired_ev / gain)), EXPOSURE_TIME_MIN, EXPOSURE_TIME_MAX); - // Only go below recomended gain when absolutely necessary to not overexpose + // Only go below recommended gain when absolutely necessary to not overexpose if (g < ANALOG_GAIN_REC_IDX && t > 20 && g < gain_idx) { continue; } @@ -1118,7 +1118,7 @@ void CameraState::set_camera_exposure(float grey_frac) { // Compute error to desired ev float score = std::abs(desired_ev - (t * gain)) * 10; - // Going below recomended gain needs lower penalty to not overexpose + // Going below recommended gain needs lower penalty to not overexpose float m = g > ANALOG_GAIN_REC_IDX ? 5.0 : 0.1; score += std::abs(g - (int)ANALOG_GAIN_REC_IDX) * m; diff --git a/system/hardware/tici/agnos.py b/system/hardware/tici/agnos.py index ca2498a00..9a1759e99 100755 --- a/system/hardware/tici/agnos.py +++ b/system/hardware/tici/agnos.py @@ -241,7 +241,7 @@ def flash_partition(target_slot_number: int, partition: dict, cloudlog, standalo else: extract_compressed_image(target_slot_number, partition, cloudlog) - # Write hash after successfull flash + # Write hash after successful flash if not full_check: with open(path, 'wb+') as out: out.seek(partition['size']) @@ -257,7 +257,7 @@ def swap(manifest_path: str, target_slot_number: int, cloudlog) -> None: while True: out = subprocess.check_output(f"abctl --set_active {target_slot_number}", shell=True, stderr=subprocess.STDOUT, encoding='utf8') if ("No such file or directory" not in out) and ("lun as boot lun" in out): - cloudlog.info(f"Swap successfull {out}") + cloudlog.info(f"Swap successful {out}") break else: cloudlog.error(f"Swap failed {out}") diff --git a/system/hardware/tici/hardware.py b/system/hardware/tici/hardware.py index c3f8c7f82..14a7101c6 100644 --- a/system/hardware/tici/hardware.py +++ b/system/hardware/tici/hardware.py @@ -287,7 +287,7 @@ class Tici(HardwareBase): ] upload = [ - # Create root Hierarchy Token Bucket that sends all trafic to 1:20 + # Create root Hierarchy Token Bucket that sends all traffic to 1:20 (True, tc + ["qdisc", "add", "dev", adapter, "root", "handle", "1:", "htb", "default", "20"]), # Create class 1:20 with specified rate limit diff --git a/system/proclogd/proclog.cc b/system/proclogd/proclog.cc index 9064547d2..cbe3b5349 100644 --- a/system/proclogd/proclog.cc +++ b/system/proclogd/proclog.cc @@ -72,7 +72,7 @@ std::optional procStat(std::string stat) { } std::string name = stat.substr(open_paren + 1, close_paren - open_paren - 1); - // repace space in name with _ + // replace space in name with _ std::replace(&stat[open_paren], &stat[close_paren], ' ', '_'); std::istringstream iss(stat); std::vector v{std::istream_iterator(iss), diff --git a/tools/README.md b/tools/README.md index a61d9268d..59eea3230 100644 --- a/tools/README.md +++ b/tools/README.md @@ -2,7 +2,7 @@ ## System Requirements -openpilot is developed and tested on **Ubuntu 20.04**, which is the primary development target aside from the [supported embdedded hardware](https://github.com/commaai/openpilot#running-on-pc). We also have a CI test to verify that openpilot builds on macOS, but the tools are untested. For the best experience, stick to Ubuntu 20.04, otherwise openpilot and the tools should work with minimal to no modifications on macOS and other Linux systems. +openpilot is developed and tested on **Ubuntu 20.04**, which is the primary development target aside from the [supported embedded hardware](https://github.com/commaai/openpilot#running-on-pc). We also have a CI test to verify that openpilot builds on macOS, but the tools are untested. For the best experience, stick to Ubuntu 20.04, otherwise openpilot and the tools should work with minimal to no modifications on macOS and other Linux systems. ## Setup your PC @@ -39,7 +39,7 @@ scons -u -j$(nproc) ### Windows -Neither openpilot nor any of the tools are developed or tested on Windows, but the [Windows Subsystem for Linux (WSL)](https://docs.microsoft.com/en-us/windows/wsl/about) should get Windows users a similiar experience to Ubuntu. [WSL 2](https://docs.microsoft.com/en-us/windows/wsl/compare-versions) specifically has been reported by several users to be a seamless experience. +Neither openpilot nor any of the tools are developed or tested on Windows, but the [Windows Subsystem for Linux (WSL)](https://docs.microsoft.com/en-us/windows/wsl/about) should get Windows users a similar experience to Ubuntu. [WSL 2](https://docs.microsoft.com/en-us/windows/wsl/compare-versions) specifically has been reported by several users to be a seamless experience. Follow [these instructions](https://docs.microsoft.com/en-us/windows/wsl/install) to setup the WSL and install the `Ubuntu-20.04` distribution. Once your Ubuntu WSL environment is setup, follow the Linux setup instructions to finish setting up your environment. diff --git a/tools/camerastream/compressed_vipc.py b/tools/camerastream/compressed_vipc.py index d321d6fd2..4322ce279 100755 --- a/tools/camerastream/compressed_vipc.py +++ b/tools/camerastream/compressed_vipc.py @@ -86,7 +86,7 @@ def decoder(addr, sock_name, vipc_server, vst, nvidia): print("%2d %4d %.3f %.3f roll %6.2f ms latency %6.2f ms + %6.2f ms + %6.2f ms = %6.2f ms" % (len(msgs), evta.idx.encodeId, evt.logMonoTime/1e9, evta.idx.timestampEof/1e6, frame_latency, process_latency, network_latency, pc_latency, process_latency+network_latency+pc_latency ), len(evta.data), sock_name) if __name__ == "__main__": - parser = argparse.ArgumentParser(description="Decode video streams and broacast on VisionIPC") + parser = argparse.ArgumentParser(description="Decode video streams and broadcast on VisionIPC") parser.add_argument("addr", help="Address of comma three") parser.add_argument("--nvidia", action="store_true", help="Use nvidia instead of ffmpeg") parser.add_argument("--cams", default="0,1,2", help="Cameras to decode") diff --git a/tools/latencylogger/latency_logger.py b/tools/latencylogger/latency_logger.py index 161befbc7..81a4790de 100755 --- a/tools/latencylogger/latency_logger.py +++ b/tools/latencylogger/latency_logger.py @@ -13,7 +13,7 @@ from tools.lib.logreader import logreader_from_route_or_segment DEMO_ROUTE = "9f583b1d93915c31|2022-05-18--10-49-51--0" SERVICES = ['camerad', 'modeld', 'plannerd', 'controlsd', 'boardd'] -# Retrive controlsd frameId from lateralPlan, mismatch with longitudinalPlan will be ignored +# Retrieve controlsd frameId from lateralPlan, mismatch with longitudinalPlan will be ignored MONOTIME_KEYS = ['modelMonoTime', 'lateralPlanMonoTime'] MSGQ_TO_SERVICE = { 'roadCameraState': 'camerad', @@ -79,7 +79,7 @@ def read_logs(lr): if not data['start'][frame_id][service]: data['start'][frame_id][service] = msg_obj.timestampSof elif msg.which() == 'controlsState': - # Sendcan is published before controlsState, but the frameId is retrived in CS + # Sendcan is published before controlsState, but the frameId is retrieved in CS data['timestamp'][frame_id][service].append(("sendcan published", latest_sendcan_monotime)) elif msg.which() == 'modelV2': if msg_obj.frameIdExtra != frame_id: diff --git a/tools/lib/README.md b/tools/lib/README.md index 241232eae..3cf239d2d 100644 --- a/tools/lib/README.md +++ b/tools/lib/README.md @@ -1,6 +1,6 @@ ## LogReader -Route is a class for conviently accessing all the [logs](/selfdrive/loggerd/) from your routes. The LogReader class reads the non-video logs, i.e. rlog.bz2 and qlog.bz2. There's also a matching FrameReader class for reading the videos. +Route is a class for conveniently accessing all the [logs](/selfdrive/loggerd/) from your routes. The LogReader class reads the non-video logs, i.e. rlog.bz2 and qlog.bz2. There's also a matching FrameReader class for reading the videos. ```python from tools.lib.route import Route diff --git a/tools/lib/tests/test_readers.py b/tools/lib/tests/test_readers.py index 1d8918ba5..c982459f9 100755 --- a/tools/lib/tests/test_readers.py +++ b/tools/lib/tests/test_readers.py @@ -10,7 +10,7 @@ from tools.lib.logreader import LogReader class TestReaders(unittest.TestCase): - @unittest.skip("skip for bandwith reasons") + @unittest.skip("skip for bandwidth reasons") def test_logreader(self): def _check_data(lr): hist = defaultdict(int) @@ -31,7 +31,7 @@ class TestReaders(unittest.TestCase): lr_url = LogReader("https://github.com/commaai/comma2k19/blob/master/Example_1/b0c9d2329ad1606b%7C2018-08-02--08-34-47/40/raw_log.bz2?raw=true") _check_data(lr_url) - @unittest.skip("skip for bandwith reasons") + @unittest.skip("skip for bandwidth reasons") def test_framereader(self): def _check_data(f): self.assertEqual(f.frame_count, 1200) diff --git a/tools/plotjuggler/juggle.py b/tools/plotjuggler/juggle.py index a25a5640d..e3d0aec59 100755 --- a/tools/plotjuggler/juggle.py +++ b/tools/plotjuggler/juggle.py @@ -110,8 +110,8 @@ def juggle_route(route_or_segment_name, segment_count, qlog, can, layout, dbc=No logs = logs[segment_start:segment_end] if None in logs: - ans = input(f"{logs.count(None)}/{len(logs)} of the rlogs in this segment are missing, would you like to fall back to the qlogs? (y/n) ") - if ans == 'y': + resp = input(f"{logs.count(None)}/{len(logs)} of the rlogs in this segment are missing, would you like to fall back to the qlogs? (y/n) ") + if resp == 'y': logs = r.qlog_paths()[segment_start:segment_end] else: print("Please try a different route or segment") diff --git a/tools/plotjuggler/layouts/max-torque-debug.xml b/tools/plotjuggler/layouts/max-torque-debug.xml index 6903ca8b1..20a49c218 100644 --- a/tools/plotjuggler/layouts/max-torque-debug.xml +++ b/tools/plotjuggler/layouts/max-torque-debug.xml @@ -16,7 +16,7 @@ - + @@ -53,7 +53,7 @@ - + if (v3 == 0 and v4 == 1) then return (value * v1 ^ 2) - (v2 * 9.81) diff --git a/tools/replay/framereader.cc b/tools/replay/framereader.cc index ecde9ad5d..a1ff7b9f8 100644 --- a/tools/replay/framereader.cc +++ b/tools/replay/framereader.cc @@ -133,7 +133,7 @@ bool FrameReader::load(const std::byte *data, size_t size, bool no_hw_decoder, s break; } packets.push_back(pkt); - // some stream seems to contian no keyframes + // some stream seems to contain no keyframes key_frames_count_ += pkt->flags & AV_PKT_FLAG_KEY; } valid_ = valid_ && !packets.empty(); diff --git a/tools/replay/replay.cc b/tools/replay/replay.cc index 4b983fff8..ed8dea612 100644 --- a/tools/replay/replay.cc +++ b/tools/replay/replay.cc @@ -81,7 +81,7 @@ void Replay::start(int seconds) { } void Replay::updateEvents(const std::function &lambda) { - // set updating_events to true to force stream thread relase the lock and wait for evnets_udpated. + // set updating_events to true to force stream thread release the lock and wait for evnets_udpated. updating_events_ = true; { std::unique_lock lk(stream_lock_); diff --git a/tools/replay/replay.h b/tools/replay/replay.h index 86d609683..e4217736d 100644 --- a/tools/replay/replay.h +++ b/tools/replay/replay.h @@ -61,7 +61,7 @@ signals: void streamStarted(); protected slots: - void segmentLoadFinished(bool sucess); + void segmentLoadFinished(bool success); protected: typedef std::map> SegmentMap; diff --git a/tools/sim/bridge.py b/tools/sim/bridge.py index 71a92ac77..0e4f47963 100755 --- a/tools/sim/bridge.py +++ b/tools/sim/bridge.py @@ -346,7 +346,7 @@ class CarlaBridge: vehicle_state = VehicleState() - # reenable IMU + # re-enable IMU imu_bp = blueprint_library.find('sensor.other.imu') imu = world.spawn_actor(imu_bp, transform, attach_to=vehicle) imu.listen(lambda imu: imu_callback(imu, vehicle_state)) From ed8d676870267c09377627a5b69d6ce1244ccc6f Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 30 Aug 2022 11:23:42 -0700 Subject: [PATCH 113/172] Car docs diff bot: remove tier (#25611) * fix car docs diff bot * rm line --- selfdrive/car/docs_definitions.py | 1 - selfdrive/debug/print_docs_diff.py | 8 ++------ 2 files changed, 2 insertions(+), 7 deletions(-) diff --git a/selfdrive/car/docs_definitions.py b/selfdrive/car/docs_definitions.py index 52d6388d7..499732ffe 100644 --- a/selfdrive/car/docs_definitions.py +++ b/selfdrive/car/docs_definitions.py @@ -193,4 +193,3 @@ class CarInfo: item += footnote_tag.format(f'{",".join(map(str, sups))}') return item - diff --git a/selfdrive/debug/print_docs_diff.py b/selfdrive/debug/print_docs_diff.py index b7721ca3a..0f8f2b33c 100755 --- a/selfdrive/debug/print_docs_diff.py +++ b/selfdrive/debug/print_docs_diff.py @@ -81,10 +81,6 @@ def print_car_info_diff(path): changes["additions"].append(format_row([car_info.get_column(column, STAR_ICON, FOOTNOTE_TAG) for column in Column])) for new_car, base_car in car_changes: - # Tier changes - if base_car.tier != new_car.tier: - changes["tier"].append(f"- Tier for {base_car.name} changed! ({base_car.tier.name.title()} {ARROW_SYMBOL} {new_car.tier.name.title()})") - # Column changes row_diff = build_column_diff(base_car, new_car) if ARROW_SYMBOL in row_diff: @@ -102,10 +98,10 @@ def print_car_info_diff(path): if any(len(c) for c in changes.values()): markdown_builder = ["### ⚠️ This PR makes changes to [CARS.md](../blob/master/docs/CARS.md) ⚠️"] - for title, category in (("## 🏅 Tier Changes", "tier"), ("## 🔀 Column Changes", "column"), ("## ❌ Removed", "removals"), ("## ➕ Added", "additions"), ("## 📖 Detail Sentence Changes", "detail")): + for title, category in (("## 🔀 Column Changes", "column"), ("## ❌ Removed", "removals"), ("## ➕ Added", "additions"), ("## 📖 Detail Sentence Changes", "detail")): if len(changes[category]): markdown_builder.append(title) - if category not in ("tier", "detail"): + if category not in ("detail",): markdown_builder.append(COLUMNS) markdown_builder.append(COLUMN_HEADER) markdown_builder.extend(changes[category]) From c6b749fb96b3b6332fd850e733140357f84d53a4 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 30 Aug 2022 15:10:52 -0700 Subject: [PATCH 114/172] add pyside2 package (#25602) --- .pre-commit-config.yaml | 4 + Pipfile | 1 + Pipfile.lock | 1301 ++++++++++------- selfdrive/athena/tests/helpers.py | 2 +- selfdrive/navd/navd.py | 2 +- selfdrive/ui/translations/create_badges.py | 2 +- system/hardware/tici/agnos.py | 2 +- system/hardware/tici/test_agnos_updater.py | 2 +- .../tici/tests/compare_casync_manifest.py | 2 +- tools/joystick/joystickd.py | 2 +- tools/lib/tests/test_readers.py | 4 +- tools/plotjuggler/juggle.py | 2 +- tools/scripts/fetch_image_from_route.py | 2 +- tools/scripts/setup_ssh_keys.py | 2 +- update_requirements.sh | 4 +- 15 files changed, 752 insertions(+), 582 deletions(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 85bd06c5f..50554acce 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -56,6 +56,10 @@ repos: language: system types: [python] exclude: '^(pyextra/)|(cereal/)|(rednose/)|(panda/)|(laika/)|(laika_repo/)|(rednose_repo/)' + args: + - -rn + - -sn + - --rcfile=.pylintrc - repo: local hooks: - id: cppcheck diff --git a/Pipfile b/Pipfile index 81669e480..644fd2a90 100644 --- a/Pipfile +++ b/Pipfile @@ -88,6 +88,7 @@ urllib3 = "*" utm = "*" websocket_client = "*" hatanaka = "==2.4" +PySide2 = "*" [requires] python_version = "3.8" diff --git a/Pipfile.lock b/Pipfile.lock index 0612d0ff3..e6f05fbcd 100644 --- a/Pipfile.lock +++ b/Pipfile.lock @@ -1,7 +1,7 @@ { "_meta": { "hash": { - "sha256": "c92514c0e6968af008916446514f41b4e004aa7aa4a2951cc1e9e258ac072111" + "sha256": "adf64558652d394d9de8e45777f1a2f50ed1ac37b75664206e7957792832b5a4" }, "pipfile-spec": 6, "requires": { @@ -18,19 +18,18 @@ "default": { "astroid": { "hashes": [ - "sha256:4f933d0bf5e408b03a6feb5d23793740c27e07340605f236496cd6ce552043d6", - "sha256:ba33a82a9a9c06a5ceed98180c5aab16e29c285b828d94696bf32d6015ea82a9" + "sha256:396c88d0a58d7f8daadf730b2ce90838bf338c6752558db719ec6f99c18ec20e", + "sha256:d612609242996c4365aeb0345e61edba34363eaaba55f1c0addf6a98f073bef6" ], - "markers": "python_full_version >= '3.6.2'", - "version": "==2.11.6" + "markers": "python_full_version >= '3.7.2'", + "version": "==2.12.5" }, "atomicwrites": { "hashes": [ - "sha256:6d1784dea7c0c8d4a5172b6c620f40b6e4cbfdf96d783691f2e1302a7b88e197", - "sha256:ae70396ad1a434f9c7046fd2dd196fc04b12f9e91ffb859164193be8b6168a7a" + "sha256:81b2c9071a49367a7f770170e5eec8cb66567cfbbc8c73d20ce5ca4a8d71cf11" ], "index": "pypi", - "version": "==1.4.0" + "version": "==1.4.1" }, "casadi": { "hashes": [ @@ -157,11 +156,11 @@ }, "charset-normalizer": { "hashes": [ - "sha256:5189b6f22b01957427f35b6a08d9a0bc45b46d3788ef5a92e978433c7a35f8a5", - "sha256:575e708016ff3a5e3681541cb9d79312c416835686d054a23accb873b254f413" + "sha256:5a3d016c7c547f69d6f81fb0db9449ce888b418b5b9952cc5e6e66843e9dd845", + "sha256:83e9a75d1911279afd89352c68b45348559d1fc0506b054b346651b5e7fee29f" ], "markers": "python_version >= '3.6'", - "version": "==2.1.0" + "version": "==2.1.1" }, "click": { "hashes": [ @@ -171,6 +170,14 @@ "markers": "python_version >= '3.7'", "version": "==8.1.3" }, + "coloredlogs": { + "hashes": [ + "sha256:612ee75c546f53e92e70049c9dbfcc18c935a2b9a53b66085ce9ef6a6e5c0934", + "sha256:7c991aa71a4577af2f82600d8f8f3a89f936baeaf9b50a9c197da014e5bf16b0" + ], + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3, 3.4'", + "version": "==15.0.1" + }, "crcmod": { "hashes": [ "sha256:50586ab48981f11e5b117523d97bb70864a2a1af246cf6e4f5c4a21ef4611cd1", @@ -211,49 +218,49 @@ }, "cython": { "hashes": [ - "sha256:019d330ac580b2ca4a457c464ac0b8c35009d820ef5d09f328d6e31a10e1ce89", - "sha256:0b83a342a071c4f14e7410568e0c0bd95e2f20c0b32944e3a721649a1357fda4", - "sha256:0cd6c932e945af15ae4ddcf8fdc0532bda48784c92ed0a53cf4fae897067ccd1", - "sha256:1e078943bbde703ca08d43e719480eb8b187d9023cbd91798619f5b5e18d0d71", - "sha256:20778297c8bcba201ca122a2f792a9899d6e64c68a92363dd7eb24306d54d7ce", - "sha256:2235b62da8fe6fa8b99422c8e583f2fb95e143867d337b5c75e4b9a1a865f9e3", - "sha256:28db751e2d8365b39664d9cb62dc1668688b8fcc5b954e9ca9d20e0b8e03d8b0", - "sha256:3993aafd68a7311ef94e00e44a137f6a50a69af0575ebcc8a0a074ad4152a2b2", - "sha256:3d0239c7a22a0f3fb1deec75cab0078eba4dd17868aa992a54a178851e0c8684", - "sha256:5183356c756b56c2df12d96300d602e47ffb89943c5a0bded66faca5d3da7be0", - "sha256:58d2b734250c1093bc69c1c3a6f5736493b9f8b34eb765f0a28a4a09468c0b00", - "sha256:5a8a3709ad9343a1dc02b8ec9cf6bb284be248d2c64af85464d9c3525eec74a5", - "sha256:5c7cfd908efc77306ddd41ef07f5a7a352c9205ced5c1e00a0e5ece4391707c4", - "sha256:5f2dae7dd56860018d5fd5032a71f11fdc224020932b463d0511a1536f27df85", - "sha256:60d370c33d56077d30e5f425026e58c2559e93b4784106f61581cf54071f6270", - "sha256:6b389a94b42909ff56d3491fde7c44802053a103701a7d210dcdd449a5b4f7b4", - "sha256:71fd1d910aced510c001936667fc7f2901c49b2ca7a2ad67358979c94a7f42ac", - "sha256:786ee7b0cdb508b6de64c0f1f9c74f207186dfafad1ef938f25b7494cc481a80", - "sha256:7eff71c39b98078deaad1d1bdbf10864d234e2ab5d5257e980a6926a8523f697", - "sha256:80a7255ad84620f53235c0720cdee2bc7431d9e3db7b3742823a606c329eb539", - "sha256:88c5e2f92f16cd999ddfc43d572639679e8a057587088e627e98118e46a803e6", - "sha256:8e08f18d249b9b65e272a5a60f3360a8922c4c149036b98fc821fe1afad5bdae", - "sha256:9462e9cf284d9b1d2c5b53d62188e3c09cc5c7a0018ba349d99b73cf930238de", - "sha256:9826981308802c61a76f967875b31b7c683b7fc369eabaa6cbc22efeb12c90e8", - "sha256:9f1fe924c920b699af27aefebd722df4cfbb85206291623cd37d1a7ddfd57792", - "sha256:a30092c6e2d24255fbfe0525f9a750554f96a263ed986d12ac3c9f7d9a85a424", - "sha256:abcaf99f90cddc0f53600613eaafc81d27c4ac0671f0df8bce5466d4e86d54a1", - "sha256:acb72e0b42079862cf2f894964b41f261e941e75677e902c5f4304b3eb00af33", - "sha256:b17639b6a155abaa61a89f6f1323fb57b138d0529911ca03978d594945d062ba", - "sha256:c299c5b250ae9f81c38200441b6f1d023aeee9d8e7f61c04001c7437181ccb06", - "sha256:c79685dd4631a188e2385dc6a232896c7b67ea2e3e5f8b5555b4b743f475d6d7", - "sha256:d0859a958e0155b6ae4dee04170ccfac2c3d613a7e3bee8749614530b9e3b4a4", - "sha256:d0f34b44078e3e0b2f1be2b99044619b37127128e7d55c54bbd2438adcaf31d3", - "sha256:d166d9f853db436f5e10733a9bd615699ddb4238feadcbdf5ae50dc0b18b18f5", - "sha256:d52d5733dcb144deca8985f0a197c19cf71e6bd6bd9d8034f3f67b2dea68d12b", - "sha256:e29d3487f357108b711f2f29319811d92166643d29aec1b8e063aad46a346775", - "sha256:e36755e71fd20eceb410cc441b7f2586654c2edb013f4663842fdaf60b96c1ca", - "sha256:e5cb144728a335d7a7fd0a61dff6abb7a9aeff9acd46d50b886b7d9a95bb7311", - "sha256:e605635a92ae862cb46d84d1d6883324518f9aaff4a71cede6d61df20b6a410c", - "sha256:ffa8c09617833ff0824aa7926fa4fa9d2ec3929c67168e89105f276b7f36a63e" - ], - "index": "pypi", - "version": "==0.29.30" + "sha256:061e25151c38f2361bc790d3bcf7f9d9828a0b6a4d5afa56fbed3bd33fb2373a", + "sha256:06be83490c906b6429b4389e13487a26254ccaad2eef6f3d4ee21d8d3a4aaa2b", + "sha256:07d173d3289415bb496e72cb0ddd609961be08fe2968c39094d5712ffb78672b", + "sha256:0bbc27abdf6aebfa1bce34cd92bd403070356f28b0ecb3198ff8a182791d58b9", + "sha256:0ea8267fc373a2c5064ad77d8ff7bf0ea8b88f7407098ff51829381f8ec1d5d9", + "sha256:3875c2b2ea752816a4d7ae59d45bb546e7c4c79093c83e3ba7f4d9051dd02928", + "sha256:39afb4679b8c6bf7ccb15b24025568f4f9b4d7f9bf3cbd981021f542acecd75b", + "sha256:3f85eb2343d20d91a4ea9cf14e5748092b376a64b7e07fc224e85b2753e9070b", + "sha256:40eff7aa26e91cf108fd740ffd4daf49f39b2fdffadabc7292b4b7dc5df879f0", + "sha256:479690d2892ca56d34812fe6ab8f58e4b2e0129140f3d94518f15993c40553da", + "sha256:4a4b03ab483271f69221c3210f7cde0dcc456749ecf8243b95bc7a701e5677e0", + "sha256:513e9707407608ac0d306c8b09d55a28be23ea4152cbd356ceaec0f32ef08d65", + "sha256:5514f3b4122cb22317122a48e175a7194e18e1803ca555c4c959d7dfe68eaf98", + "sha256:5ba622326f2862f9c1f99ca8d47ade49871241920a352c917e16861e25b0e5c3", + "sha256:63b79d9e1f7c4d1f498ab1322156a0d7dc1b6004bf981a8abda3f66800e140cd", + "sha256:656dc5ff1d269de4d11ee8542f2ffd15ab466c447c1f10e5b8aba6f561967276", + "sha256:67fdd2f652f8d4840042e2d2d91e15636ba2bcdcd92e7e5ffbc68e6ef633a754", + "sha256:79e3bab19cf1b021b613567c22eb18b76c0c547b9bc3903881a07bfd9e7e64cf", + "sha256:856d2fec682b3f31583719cb6925c6cdbb9aa30f03122bcc45c65c8b6f515754", + "sha256:8669cadeb26d9a58a5e6b8ce34d2c8986cc3b5c0bfa77eda6ceb471596cb2ec3", + "sha256:8733cf4758b79304f2a4e39ebfac5e92341bce47bcceb26c1254398b2f8c1af7", + "sha256:97335b2cd4acebf30d14e2855d882de83ad838491a09be2011745579ac975833", + "sha256:afbce249133a830f121b917f8c9404a44f2950e0e4f5d1e68f043da4c2e9f457", + "sha256:b0595aee62809ba353cebc5c7978e0e443760c3e882e2c7672c73ffe46383673", + "sha256:b6da3063c5c476f5311fd76854abae6c315f1513ef7d7904deed2e774623bbb9", + "sha256:c8e8025f496b5acb6ba95da2fb3e9dacffc97d9a92711aacfdd42f9c5927e094", + "sha256:cddc47ec746a08603037731f5d10aebf770ced08666100bd2cdcaf06a85d4d1b", + "sha256:cdf10af3e2e3279dc09fdc5f95deaa624850a53913f30350ceee824dc14fc1a6", + "sha256:d968ffc403d92addf20b68924d95428d523436adfd25cf505d427ed7ba3bee8b", + "sha256:dbee03b8d42dca924e6aa057b836a064c769ddfd2a4c2919e65da2c8a362d528", + "sha256:e1958e0227a4a6a2c06fd6e35b7469de50adf174102454db397cec6e1403cce3", + "sha256:e6ffa08aa1c111a1ebcbd1cf4afaaec120bc0bbdec3f2545f8bb7d3e8e77a1cd", + "sha256:e83228e0994497900af954adcac27f64c9a57cd70a9ec768ab0cb2c01fd15cf1", + "sha256:ea1dcc07bfb37367b639415333cfbfe4a93c3be340edf1db10964bc27d42ed64", + "sha256:eca3065a1279456e81c615211d025ea11bfe4e19f0c5650b859868ca04b3fcbd", + "sha256:ed087eeb88a8cf96c60fb76c5c3b5fb87188adee5e179f89ec9ad9a43c0c54b3", + "sha256:eeb475eb6f0ccf6c039035eb4f0f928eb53ead88777e0a760eccb140ad90930b", + "sha256:eefd2b9a5f38ded8d859fe96cc28d7d06e098dc3f677e7adbafda4dcdd4a461c", + "sha256:f3fd44cc362eee8ae569025f070d56208908916794b6ab21e139cea56470a2b3", + "sha256:f9944013588a3543fca795fffb0a070a31a243aa4f2d212f118aa95e69485831" + ], + "index": "pypi", + "version": "==0.29.32" }, "dill": { "hashes": [ @@ -265,26 +272,26 @@ }, "flake8": { "hashes": [ - "sha256:479b1304f72536a55948cb40a32dce8bb0ffe3501e26eaf292c7e60eb5e0428d", - "sha256:806e034dda44114815e23c16ef92f95c91e4c71100ff52813adf7132a6ad870d" + "sha256:6fbe320aad8d6b95cec8b8e47bc933004678dc63095be98528b7bdd2a9f510db", + "sha256:7a1cf6b73744f5806ab95e526f6f0d8c01c66d7bbe349562d22dfca20610b248" ], "index": "pypi", - "version": "==4.0.1" + "version": "==5.0.4" }, "flask": { "hashes": [ - "sha256:315ded2ddf8a6281567edb27393010fe3406188bafbfe65a3339d5787d89e477", - "sha256:fad5b446feb0d6db6aec0c3184d16a8c1f6c3e464b511649c8918a9be100b4fe" + "sha256:642c450d19c4ad482f96729bd2a8f6d32554aa1e231f4f6b4e7e5264b16cca2b", + "sha256:b9c46cc36662a7949f34b52d8ec7bb59c0d74ba08ba6cb9ce9adc1d8676d9526" ], "index": "pypi", - "version": "==2.1.2" + "version": "==2.2.2" }, "flatbuffers": { "hashes": [ - "sha256:12158ab0272375eab8db2d663ae97370c33f152b27801fa6024e1d6105fd4dd2", - "sha256:3751954f0604580d3219ae49a85fafec9d85eec599c0b96226e1bc0b48e57474" + "sha256:0ae7d69c5b82bf41962ca5fde9cc43033bc9501311d975fd5a25e8a7d29c1245", + "sha256:71e135d533be527192819aaab757c5e3d109cb10fbb01e687f6bdb7a61ad39d1" ], - "version": "==2.0" + "version": "==2.0.7" }, "future-fstrings": { "hashes": [ @@ -356,6 +363,14 @@ "index": "pypi", "version": "==3.3" }, + "humanfriendly": { + "hashes": [ + "sha256:1697e1a8a8f550fd43c2865cd84542fc175a61dcb779b6fee18cf6b6ccba1477", + "sha256:6b0b831ce8f15f7300721aa49829fc4e83921a9a301cc7f606be6686a2288ddc" + ], + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3, 3.4'", + "version": "==10.0" + }, "idna": { "hashes": [ "sha256:84d9dd047ffa80596e0f246e2eab0b391788b0503584e8945f2368256d2735ff", @@ -374,18 +389,18 @@ }, "importlib-resources": { "hashes": [ - "sha256:568c9f16cb204f9decc8d6d24a572eeea27dacbb4cee9e6b03a8025736769751", - "sha256:7952325ffd516c05a8ad0858c74dff2c3343f136fe66a6002b2623dd1d43f223" + "sha256:5481e97fb45af8dcf2f798952625591c58fe599d0735d86b10f54de086a61681", + "sha256:f78a8df21a79bcc30cfd400bdc38f314333de7c0fb619763f6b9dabab8268bb7" ], "markers": "python_version >= '3.7'", - "version": "==5.8.0" + "version": "==5.9.0" }, "isort": { "hashes": [ "sha256:6f62d78e2f89b4500b080fe3a81690850cd254227f27f75c3a0c491a1f351ba7", "sha256:e8443a5e7a020e9d7f97f1d7d9cd17c88bcb3bc7e218bf9cf5095fe550be2951" ], - "markers": "python_version < '4' and python_full_version >= '3.6.1'", + "markers": "python_version < '4.0' and python_full_version >= '3.6.1'", "version": "==5.10.1" }, "itsdangerous": { @@ -513,10 +528,11 @@ }, "mccabe": { "hashes": [ - "sha256:ab8a6258860da4b6677da4bd2fe5dc2c659cff31b3ee4f7f5d64e79735b80d42", - "sha256:dd8d182285a0fe56bace7f45b5e7d1a6ebcbf524e8f3bd87eb0f125271b8831f" + "sha256:348e0240c33b60bbdf4e523192ef919f28cb2c3d7d5c7794f74009290f236325", + "sha256:6c2d30ab6be0e4a46919781807b4f0d834ebdd6c6e3dca0bda5a15f863427b6e" ], - "version": "==0.6.1" + "markers": "python_version >= '3.6'", + "version": "==0.7.0" }, "mpmath": { "hashes": [ @@ -577,31 +593,37 @@ }, "numpy": { "hashes": [ - "sha256:092f5e6025813e64ad6d1b52b519165d08c730d099c114a9247c9bb635a2a450", - "sha256:196cd074c3f97c4121601790955f915187736f9cf458d3ee1f1b46aff2b1ade0", - "sha256:1c29b44905af288b3919803aceb6ec7fec77406d8b08aaa2e8b9e63d0fe2f160", - "sha256:2b2da66582f3a69c8ce25ed7921dcd8010d05e59ac8d89d126a299be60421171", - "sha256:5043bcd71fcc458dfb8a0fc5509bbc979da0131b9d08e3d5f50fb0bbb36f169a", - "sha256:58bfd40eb478f54ff7a5710dd61c8097e169bc36cc68333d00a9bcd8def53b38", - "sha256:79a506cacf2be3a74ead5467aee97b81fca00c9c4c8b3ba16dbab488cd99ba10", - "sha256:94b170b4fa0168cd6be4becf37cb5b127bd12a795123984385b8cd4aca9857e5", - "sha256:97a76604d9b0e79f59baeca16593c711fddb44936e40310f78bfef79ee9a835f", - "sha256:98e8e0d8d69ff4d3fa63e6c61e8cfe2d03c29b16b58dbef1f9baa175bbed7860", - "sha256:ac86f407873b952679f5f9e6c0612687e51547af0e14ddea1eedfcb22466babd", - "sha256:ae8adff4172692ce56233db04b7ce5792186f179c415c37d539c25de7298d25d", - "sha256:bd3fa4fe2e38533d5336e1272fc4e765cabbbde144309ccee8675509d5cd7b05", - "sha256:d0d2094e8f4d760500394d77b383a1b06d3663e8892cdf5df3c592f55f3bff66", - "sha256:d54b3b828d618a19779a84c3ad952e96e2c2311b16384e973e671aa5be1f6187", - "sha256:d6ca8dabe696c2785d0c8c9b0d8a9b6e5fdbe4f922bde70d57fa1a2848134f95", - "sha256:d8cc87bed09de55477dba9da370c1679bd534df9baa171dd01accbb09687dac3", - "sha256:f0f18804df7370571fb65db9b98bf1378172bd4e962482b857e612d1fec0f53e", - "sha256:f1d88ef79e0a7fa631bb2c3dda1ea46b32b1fe614e10fedd611d3d5398447f2f", - "sha256:f9c3fc2adf67762c9fe1849c859942d23f8d3e0bee7b5ed3d4a9c3eeb50a2f07", - "sha256:fc431493df245f3c627c0c05c2bd134535e7929dbe2e602b80e42bf52ff760bc", - "sha256:fe8b9683eb26d2c4d5db32cd29b38fdcf8381324ab48313b5b69088e0e355379" - ], - "index": "pypi", - "version": "==1.23.0" + "sha256:17e5226674f6ea79e14e3b91bfbc153fdf3ac13f5cc54ee7bc8fdbe820a32da0", + "sha256:2bd879d3ca4b6f39b7770829f73278b7c5e248c91d538aab1e506c628353e47f", + "sha256:4f41f5bf20d9a521f8cab3a34557cd77b6f205ab2116651f12959714494268b0", + "sha256:5593f67e66dea4e237f5af998d31a43e447786b2154ba1ad833676c788f37cde", + "sha256:5e28cd64624dc2354a349152599e55308eb6ca95a13ce6a7d5679ebff2962913", + "sha256:633679a472934b1c20a12ed0c9a6c9eb167fbb4cb89031939bfd03dd9dbc62b8", + "sha256:806970e69106556d1dd200e26647e9bee5e2b3f1814f9da104a943e8d548ca38", + "sha256:806cc25d5c43e240db709875e947076b2826f47c2c340a5a2f36da5bb10c58d6", + "sha256:8247f01c4721479e482cc2f9f7d973f3f47810cbc8c65e38fd1bbd3141cc9842", + "sha256:8ebf7e194b89bc66b78475bd3624d92980fca4e5bb86dda08d677d786fefc414", + "sha256:8ecb818231afe5f0f568c81f12ce50f2b828ff2b27487520d85eb44c71313b9e", + "sha256:8f9d84a24889ebb4c641a9b99e54adb8cab50972f0166a3abc14c3b93163f074", + "sha256:909c56c4d4341ec8315291a105169d8aae732cfb4c250fbc375a1efb7a844f8f", + "sha256:9b83d48e464f393d46e8dd8171687394d39bc5abfe2978896b77dc2604e8635d", + "sha256:ac987b35df8c2a2eab495ee206658117e9ce867acf3ccb376a19e83070e69418", + "sha256:b78d00e48261fbbd04aa0d7427cf78d18401ee0abd89c7559bbf422e5b1c7d01", + "sha256:b8b97a8a87cadcd3f94659b4ef6ec056261fa1e1c3317f4193ac231d4df70215", + "sha256:bd5b7ccae24e3d8501ee5563e82febc1771e73bd268eef82a1e8d2b4d556ae66", + "sha256:bdc02c0235b261925102b1bd586579b7158e9d0d07ecb61148a1799214a4afd5", + "sha256:be6b350dfbc7f708d9d853663772a9310783ea58f6035eec649fb9c4371b5389", + "sha256:c403c81bb8ffb1c993d0165a11493fd4bf1353d258f6997b3ee288b0a48fce77", + "sha256:cf8c6aed12a935abf2e290860af8e77b26a042eb7f2582ff83dc7ed5f963340c", + "sha256:d98addfd3c8728ee8b2c49126f3c44c703e2b005d4a95998e2167af176a9e722", + "sha256:dc76bca1ca98f4b122114435f83f1fcf3c0fe48e4e6f660e07996abf2f53903c", + "sha256:dec198619b7dbd6db58603cd256e092bcadef22a796f778bf87f8592b468441d", + "sha256:df28dda02c9328e122661f399f7655cdcbcf22ea42daa3650a26bce08a187450", + "sha256:e603ca1fb47b913942f3e660a15e55a9ebca906857edfea476ae5f0fe9b457d5", + "sha256:ecfdd68d334a6b97472ed032b5b37a30d8217c097acfff15e8452c710e775524" + ], + "index": "pypi", + "version": "==1.23.2" }, "onnx": { "hashes": [ @@ -632,16 +654,26 @@ }, "onnxruntime-gpu": { "hashes": [ - "sha256:3f1363e9ba30051cc3d649beefbd12047e1c41b5c47bcacfbfb23b74a7d68f7b", - "sha256:3fad0d3df58815c11160714433ca3bcff6d9a06f721bcc97ade46abce30aea72", - "sha256:a4f5317838f4816a9b21fcb43d551ac95f9d35ca8ecd5c959419b3b94d458342", - "sha256:be1766a9d60ec774e1a7a0279ade5ec001c5d528f2f2dbe9f8d02133e49d1d68", - "sha256:c79f42cbdee18e059c0ba43f0efeb7117539dfb76d6ed0e4a9ecc34093ed97b3", - "sha256:dc34be44224aa855d7ab17f61942b665788a2136ae4f71ee857fa47b38d1fdb8" + "sha256:296bd9733986cb7517d15bef5535c555d3f863963a71e6575e92d2a854aee61d", + "sha256:42b0393c5122ed90fa2eb76192a486261d86e9526ccb78b2a98923c22791d2d1", + "sha256:8e46d0724ce54c5908c5760037b78de741fbd48962b370c29ebc20e608b30eda", + "sha256:b37872527d03d3df10756408ca44014bd6ac354a044ab1c4286cd42dc138e518", + "sha256:d73204323aefebe4eecab9fcf76e22b1a00394e3d838c2962a28a27301186b73", + "sha256:e2be6f7f5a1ce0bc8471ce42e10eab92cfb19d0748b857edcb5320b5e98311b7", + "sha256:ecfe97335027e569d4f46725ba89316041e562b8c499690e25e11cfee4601cd1", + "sha256:fd919373be35b9ba54210688265df38ad5e19a530449385c40dab51da407345d" ], "index": "pypi", "markers": "platform_system != 'Darwin'", - "version": "==1.11.1" + "version": "==1.12.1" + }, + "packaging": { + "hashes": [ + "sha256:dd47c42927d89ab911e606518907cc2d3a1f38bbd026385970643f9c5b8ecfeb", + "sha256:ef103e05f519cdc783ae24ea4e2e0f508a9c99b2d4969652eed6a2e1ea5bd522" + ], + "markers": "python_version >= '3.6'", + "version": "==21.3" }, "pillow": { "hashes": [ @@ -818,11 +850,11 @@ }, "pycodestyle": { "hashes": [ - "sha256:720f8b39dde8b293825e7ff02c475f3077124006db4f440dcbc9a20b76548a20", - "sha256:eddd5847ef438ea1c7870ca7eb78a9d47ce0cdb4851a5523949f2601d0cbbe7f" + "sha256:2c9607871d58c76354b697b42f5d57e1ada7d261c261efac224b664affdc5785", + "sha256:d1735fc58b418fd7c5f658d28d943854f8a849b01a5d0a1e6f3f3fdd0166804b" ], - "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3, 3.4'", - "version": "==2.8.0" + "markers": "python_version >= '3.6'", + "version": "==2.9.1" }, "pycparser": { "hashes": [ @@ -869,11 +901,11 @@ }, "pyflakes": { "hashes": [ - "sha256:05a85c2872edf37a4ed30b0cce2f6093e1d0581f8c19d7393122da7e25b2b24c", - "sha256:3bb3a3f256f4b7968c9c788781e4ff07dce46bdf12339dcda61053375426ee2e" + "sha256:4579f67d887f804e67edb544428f264b7b24f435b263c4614f384135cea553d2", + "sha256:491feb020dca48ccc562a8c0cbe8df07ee13078df59813b83959cbdada312ea3" ], - "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", - "version": "==2.4.0" + "markers": "python_version >= '3.6'", + "version": "==2.5.0" }, "pyjwt": { "hashes": [ @@ -885,11 +917,11 @@ }, "pylint": { "hashes": [ - "sha256:47705453aa9dce520e123a7d51843d5f0032cbfa06870f89f00927aa1f735a4a", - "sha256:89b61867db16eefb7b3c5b84afc94081edaf11544189e2b238154677529ad69f" + "sha256:4b124affc198b7f7c9b5f9ab690d85db48282a025ef9333f51d2d7281b92a6c3", + "sha256:4f3f7e869646b0bd63b3dfb79f3c0f28fc3d2d923ea220d52620fd625aed92b0" ], "index": "pypi", - "version": "==2.14.4" + "version": "==2.15.0" }, "pyopencl": { "hashes": [ @@ -934,6 +966,14 @@ "index": "pypi", "version": "==2022.1.6" }, + "pyparsing": { + "hashes": [ + "sha256:2b020ecf7d21b687f219b71ecad3631f644a47f01403fa1d1036b0c6416d70fb", + "sha256:5026bae9a10eeaefb61dab2f09052b9f4307d44aee4eda64b309723d8d206bbc" + ], + "markers": "python_full_version >= '3.6.8'", + "version": "==3.0.9" + }, "pyserial": { "hashes": [ "sha256:3c77e014170dfffbd816e6ffc205e9842efb10be9f58ec16d3e8675b4925cddb", @@ -942,6 +982,18 @@ "index": "pypi", "version": "==3.5" }, + "pyside2": { + "hashes": [ + "sha256:235240b6ec8206d9fdf0232472c6ef3241783d480425e5b54796f06e39ed23da", + "sha256:23886c6391ebd916e835fa1b5ae66938048504fd3a2934ae3189a96cd5ac0b46", + "sha256:439509e53cfe05abbf9a99422a2cbad086408b0f9bf5e6f642ff1b13b1f8b055", + "sha256:a9e2e6bbcb5d2ebb421e46e72244a0f4fe0943b2288115f80a863aacc1de1f06", + "sha256:af6b263fe63ba6dea7eaebae80aa7b291491fe66f4f0057c0aafe780cc83da9d", + "sha256:b5e1d92f26b0bbaefff67727ccbb2e1b577f2c0164b349b3d6e80febb4c5bde2" + ], + "index": "pypi", + "version": "==5.15.2.1" + }, "python-dateutil": { "hashes": [ "sha256:0123cacc1627ae19ddf3c27a5de5bd67ee4586fbdd6440d9748f8abb483d3e86", @@ -998,66 +1050,82 @@ }, "pyzmq": { "hashes": [ - "sha256:004a431dfa0459123e6f4660d7e3c4ac19217d134ca38bacfffb2e78716fe944", - "sha256:057b154471e096e2dda147f7b057041acc303bb7ca4aa24c3b88c6cecdd78717", - "sha256:0e08671dc202a1880fa522f921f35ca5925ba30da8bc96228d74a8f0643ead9c", - "sha256:1b2a21f595f8cc549abd6c8de1fcd34c83441e35fb24b8a59bf161889c62a486", - "sha256:21552624ce69e69f7924f413b802b1fb554f4c0497f837810e429faa1cd4f163", - "sha256:22ac0243a41798e3eb5d5714b28c2f28e3d10792dffbc8a5fca092f975fdeceb", - "sha256:2b054525c9f7e240562185bf21671ca16d56bde92e9bd0f822c07dec7626b704", - "sha256:30c365e60c39c53f8eea042b37ea28304ffa6558fb7241cf278745095a5757da", - "sha256:3a4d87342c2737fbb9eee5c33c792db27b36b04957b4e6b7edd73a5b239a2a13", - "sha256:420b9abd1a7330687a095373b8280a20cdee04342fbc8ccb3b56d9ec8efd4e62", - "sha256:444f7d615d5f686d0ef508b9edfa8a286e6d89f449a1ba37b60ef69d869220a3", - "sha256:558f5f636e3e65f261b64925e8b190e8689e334911595394572cc7523879006d", - "sha256:5592fb4316f895922b1cacb91b04a0fa09d6f6f19bbab4442b4d0a0825177b93", - "sha256:59928dfebe93cf1e203e3cb0fd5d5dd384da56b99c8305f2e1b0a933751710f6", - "sha256:5cb642e94337b0c76c9c8cb9bfb0f8a78654575847d080d3e1504f312d691fc3", - "sha256:5d57542429df6acff02ff022067aa75b677603cee70e3abb9742787545eec966", - "sha256:5d92e7cbeab7f70b08cc0f27255b0bb2500afc30f31075bca0b1cb87735d186c", - "sha256:602835e5672ca9ca1d78e6c148fb28c4f91b748ebc41fbd2f479d8763d58bc9b", - "sha256:60746a7e8558655420a69441c0a1d47ed225ed3ac355920b96a96d0554ef7e6b", - "sha256:61b97f624da42813f74977425a3a6144d604ea21cf065616d36ea3a866d92c1c", - "sha256:693c96ae4d975eb8efa1639670e9b1fac0c3f98b7845b65c0f369141fb4bb21f", - "sha256:814e5aaf0c3be9991a59066eafb2d6e117aed6b413e3e7e9be45d4e55f5e2748", - "sha256:83005d8928f8a5cebcfb33af3bfb84b1ad65d882b899141a331cc5d07d89f093", - "sha256:831da96ba3f36cc892f0afbb4fb89b28b61b387261676e55d55a682addbd29f7", - "sha256:8355744fdbdeac5cfadfa4f38b82029b5f2b8cab7472a33453a217a7f3a9dce2", - "sha256:8496a2a5efd055c61ac2c6a18116c768a25c644b6747dcfde43e91620ab3453c", - "sha256:859059caf564f0c9398c9005278055ed3d37af4d73de6b1597821193b04ca09b", - "sha256:8c0f4d6f8c985bab83792be26ff3233940ba42e22237610ac50cbcfc10a5c235", - "sha256:8c2d8b69a2bf239ae3d987537bf3fbc2b044a405394cf4c258fc684971dd48b2", - "sha256:984b232802eddf9f0be264a4d57a10b3a1fd7319df14ee6fc7b41c6d155a3e6c", - "sha256:99cedf38eaddf263cf7e2a50e405f12c02cedf6d9df00a0d9c5d7b9417b57f76", - "sha256:a3dc339f7bc185d5fd0fd976242a5baf35de404d467e056484def8a4dd95868b", - "sha256:a51f12a8719aad9dcfb55d456022f16b90abc8dde7d3ca93ce3120b40e3fa169", - "sha256:bbabd1df23bf63ae829e81200034c0e433499275a6ed29ca1a912ea7629426d9", - "sha256:bcc6953e47bcfc9028ddf9ab2a321a3c51d7cc969db65edec092019bb837959f", - "sha256:c0a5f987d73fd9b46c3d180891f829afda714ab6bab30a1218724d4a0a63afd8", - "sha256:c223a13555444707a0a7ebc6f9ee63053147c8c082bd1a31fd1207a03e8b0500", - "sha256:c616893a577e9d6773a3836732fd7e2a729157a108b8fccd31c87512fa01671a", - "sha256:c882f1d4f96fbd807e92c334251d8ebd159a1ef89059ccd386ddea83fdb91bd8", - "sha256:c8dec8a2f3f0bb462e6439df436cd8c7ec37968e90b4209ac621e7fbc0ed3b00", - "sha256:c9638e0057e3f1a8b7c5ce33c7575349d9183a033a19b5676ad55096ae36820b", - "sha256:ce4f71e17fa849de41a06109030d3f6815fcc33338bf98dd0dde6d456d33c929", - "sha256:ced12075cdf3c7332ecc1960f77f7439d5ebb8ea20bbd3c34c8299e694f1b0a1", - "sha256:d11628212fd731b8986f1561d9bb3f8c38d9c15b330c3d8a88963519fbcd553b", - "sha256:d1610260cc672975723fcf7705c69a95f3b88802a594c9867781bedd9b13422c", - "sha256:d4651de7316ec8560afe430fb042c0782ed8ac54c0be43a515944d7c78fddac8", - "sha256:da338e2728410d74ddeb1479ec67cfba73311607037455a40f92b6f5c62bf11d", - "sha256:de727ea906033b30527b4a99498f19aca3f4d1073230a958679a5b726e2784e0", - "sha256:e2e2db5c6ef376e97c912733dfc24406f5949474d03e800d5f07b6aca4d870af", - "sha256:e669913cb2179507628419ec4f0e453e48ce6f924de5884d396f18c31836089c", - "sha256:eb4a573a8499685d62545e806d8fd143c84ac8b3439f925cd92c8763f0ed9bd7", - "sha256:f146648941cadaaaf01254a75651a23c08159d009d36c5af42a7cc200a5e53ec", - "sha256:f3ff6abde52e702397949054cb5b06c1c75b5d6542f6a2ce029e46f71ffbbbf2", - "sha256:f5aa9da520e4bb8cee8189f2f541701405e7690745094ded7a37b425d60527ea", - "sha256:f5fdb00d65ec44b10cc6b9b6318ef1363b81647a4aa3270ca39565eadb2d1201", - "sha256:f685003d836ad0e5d4f08d1e024ee3ac7816eb2f873b2266306eef858f058133", - "sha256:fee86542dc4ee8229e023003e3939b4d58cc2453922cf127778b69505fc9064b" - ], - "index": "pypi", - "version": "==23.2.0" + "sha256:022cf5ea7bcaa8a06a03c2706e0ae66904b6138b2155577cd34c64bc7cc637ab", + "sha256:044447ae4b2016a6b8697571fd633f799f860b19b76c4a2fd9b1140d52ee6745", + "sha256:07ed8aaf7ffe150af873269690cc654ffeca7491f62aae0f3821baa181f8d5fe", + "sha256:10d1910ec381b851aeb024a042a13db178cb1edf125e76a4e9d2548ad103aadb", + "sha256:12e62ff0d5223ec09b597ab6d73858b9f64a51221399f3cb08aa495e1dff7935", + "sha256:1f368a82b29f80071781b20663c0fc0c8f6b13273f9f5abe1526af939534f90f", + "sha256:20bafc4095eab00f41a510579363a3f5e1f5c69d7ee10f1d88895c4df0259183", + "sha256:2141e6798d5981be04c08996d27962086a1aa3ea536fe9cf7e89817fd4523f86", + "sha256:23e708fbfdf4ee3107422b69ca65da1b9f056b431fc0888096a8c1d6cd908e8f", + "sha256:28dbdb90b2f6b131f8f10e6081012e4e25234213433420e67e0c1162de537113", + "sha256:29b74774a0bfd3c4d98ac853f0bdca55bd9ec89d5b0def5486407cca54472ef8", + "sha256:2b381aa867ece7d0a82f30a0c7f3d4387b7cf2e0697e33efaa5bed6c5784abcd", + "sha256:2f67b63f53c6994d601404fd1a329e6d940ac3dd1d92946a93b2b9c70df67b9f", + "sha256:342ca3077f47ec2ee41b9825142b614e03e026347167cbc72a59b618c4f6106c", + "sha256:35e635343ff367f697d00fa1484262bb68e36bc74c9b80737eac5a1e04c4e1b1", + "sha256:385609812eafd9970c3752c51f2f6c4f224807e3e441bcfd8c8273877d00c8a8", + "sha256:38e106b64bad744fe469dc3dd864f2764d66399178c1bf39d45294cc7980f14f", + "sha256:39dd252b683816935702825e5bf775df16090619ced9bb4ba68c2d0b6f0c9b18", + "sha256:407f909c4e8fde62fbdad9ebd448319792258cc0550c2815567a4d9d8d9e6d18", + "sha256:415ff62ac525d9add1e3550430a09b9928d2d24a20cc4ce809e67caac41219ab", + "sha256:4805af9614b0b41b7e57d17673459facf85604dac502a5a9244f6e8c9a4de658", + "sha256:48400b96788cdaca647021bf19a9cd668384f46e4d9c55cf045bdd17f65299c8", + "sha256:49d30ba7074f469e8167917abf9eb854c6503ae10153034a6d4df33618f1db5f", + "sha256:4bb798bef181648827019001f6be43e1c48b34b477763b37a8d27d8c06d197b8", + "sha256:4d6f110c56f7d5b4d64dde3a382ae61b6d48174e30742859d8e971b18b6c9e5c", + "sha256:55568a020ad2cae9ae36da6058e7ca332a56df968f601cbdb7cf6efb2a77579a", + "sha256:565bd5ab81f6964fc4067ccf2e00877ad0fa917308975694bbb54378389215f8", + "sha256:5c558b50402fca1acc94329c5d8f12aa429738904a5cfb32b9ed3c61235221bb", + "sha256:5e05492be125dce279721d6b54fd1b956546ecc4bcdfcf8e7b4c413bc0874c10", + "sha256:624fd38071a817644acdae075b92a23ea0bdd126a58148288e8284d23ec361ce", + "sha256:650389bbfca73955b262b2230423d89992f38ec48033307ae80e700eaa2fbb63", + "sha256:67975a9e1237b9ccc78f457bef17691bbdd2055a9d26e81ee914ba376846d0ce", + "sha256:6b1e79bba24f6df1712e3188d5c32c480d8eda03e8ecff44dc8ecb0805fa62f3", + "sha256:6fd5d0d50cbcf4bc376861529a907bed026a4cbe8c22a500ff8243231ef02433", + "sha256:71b32a1e827bdcbf73750e60370d3b07685816ff3d8695f450f0f8c3226503f8", + "sha256:794871988c34727c7f79bdfe2546e6854ae1fa2e1feb382784f23a9c6c63ecb3", + "sha256:79a87831b47a9f6161ad23fa5e89d5469dc585abc49f90b9b07fea8905ae1234", + "sha256:7e0113d70b095339e99bb522fe7294f5ae6a7f3b2b8f52f659469a74b5cc7661", + "sha256:84678153432241bcdca2210cf4ff83560b200556867aea913ffbb960f5d5f340", + "sha256:8a68f57b7a3f7b6b52ada79876be1efb97c8c0952423436e84d70cc139f16f0d", + "sha256:8c02a0cd39dc01659b3d6cb70bb3a41aebd9885fd78239acdd8d9c91351c4568", + "sha256:8c842109d31a9281d678f668629241c405928afbebd913c48a5a8e7aee61f63d", + "sha256:8dc66f109a245653b19df0f44a5af7a3f14cb8ad6c780ead506158a057bd36ce", + "sha256:90d88f9d9a2ae6cfb1dc4ea2d1710cdf6456bc1b9a06dd1bb485c5d298f2517e", + "sha256:9269fbfe3a4eb2009199120861c4571ef1655fdf6951c3e7f233567c94e8c602", + "sha256:929d548b74c0f82f7f95b54e4a43f9e4ce2523cfb8a54d3f7141e45652304b2a", + "sha256:99a5a77a10863493a1ee8dece02578c6b32025fb3afff91b40476bc489e81648", + "sha256:9a39ddb0431a68954bd318b923230fa5b649c9c62b0e8340388820c5f1b15bd2", + "sha256:9d0ab2936085c85a1fc6f9fd8f89d5235ae99b051e90ec5baa5e73ad44346e1f", + "sha256:9e5bf6e7239fc9687239de7a283aa8b801ab85371116045b33ae20132a1325d6", + "sha256:a0f09d85c45f58aa8e715b42f8b26beba68b3b63a8f7049113478aca26efbc30", + "sha256:a114992a193577cb62233abf8cb2832970f9975805a64740e325d2f895e7f85a", + "sha256:a3fd44b5046d247e7f0f1660bcafe7b5fb0db55d0934c05dd57dda9e1f823ce7", + "sha256:ad28ddb40db8e450d7d4bf8a1d765d3f87b63b10e7e9a825a3c130c6371a8c03", + "sha256:aecd6ceaccc4b594e0092d6513ef3f1c0fa678dd89f86bb8ff1a47014b8fca35", + "sha256:b815991c7d024bf461f358ad871f2be1135576274caed5749c4828859e40354e", + "sha256:b861db65f6b8906c8d6db51dde2448f266f0c66bf28db2c37aea50f58a849859", + "sha256:c3ebf1668664d20c8f7d468955f18379b7d1f7bc8946b13243d050fa3888c7ff", + "sha256:c56b1a62a1fb87565343c57b6743fd5da6e138b8c6562361d7d9b5ce4acf399a", + "sha256:c780acddd2934c6831ff832ecbf78a45a7b62d4eb216480f863854a8b7d54fa7", + "sha256:c890309296f53f9aa32ffcfc51d805705e1982bffd27c9692a8f1e1b8de279f4", + "sha256:c9cfaf530e6a7ff65f0afe275e99f983f68b54dfb23ea401f0bc297a632766b6", + "sha256:d904f6595acfaaf99a1a61881fea068500c40374d263e5e073aa4005e5f9c28a", + "sha256:e06747014a5ad1b28cebf5bc1ddcdaccfb44e9b441d35e6feb1286c8a72e54be", + "sha256:e1fe30bcd5aea5948c42685fad910cd285eacb2518ea4dc6c170d6b535bee95d", + "sha256:e753eee6d3b93c5354e8ba0a1d62956ee49355f0a36e00570823ef64e66183f5", + "sha256:ec9803aca9491fd6f0d853d2a6147f19f8deaaa23b1b713d05c5d09e56ea7142", + "sha256:efb9e38b2a590282704269585de7eb33bf43dc294cad092e1b172e23d4c217e5", + "sha256:f07016e3cf088dbfc6e7c5a7b3f540db5c23b0190d539e4fd3e2b5e6beffa4b5", + "sha256:f392cbea531b7142d1958c0d4a0c9c8d760dc451e5848d8dd3387804d3e3e62c", + "sha256:f619fd38fc2641abfb53cca719c165182500600b82c695cc548a0f05f764be05", + "sha256:fefdf9b685fda4141b95ebec975946076a5e0723ff70b037032b2085c5317684", + "sha256:ffc6b1623d0f9affb351db4ca61f432dca3628a5ee015f9bf2bfbe9c6836881c" + ], + "index": "pypi", + "version": "==23.2.1" }, "requests": { "hashes": [ @@ -1069,104 +1137,105 @@ }, "scons": { "hashes": [ - "sha256:8c13911a2aa40552553488f7d625af4c0768fc8cdedab4a858d8ce42c8c3664d", - "sha256:d47081587e3675cc168f1f54f0d74a69b328a2fc90ec4feb85f728677419b879" + "sha256:7703c4e9d2200b4854a31800c1dbd4587e1fa86e75f58795c740bcfa7eca7eaa", + "sha256:cbbd73b83cf85f1aaaf986370359de1bbfd3af97a765cb3554734f6dcec734e1" ], "index": "pypi", - "version": "==4.3.0" + "version": "==4.4.0" }, "sentry-sdk": { "hashes": [ - "sha256:b82ad57306d5546713f15d5d70daea0408cf7f998c7566db16e0e6257e51e561", - "sha256:ddbd191b6f4e696b7845b4d87389898ae1207981faf114f968a57363aa6be03c" + "sha256:2d7ec7bc88ebbdf2c4b6b2650b3257893d386325a96c9b723adcd31033469b63", + "sha256:b4b41f90951ed83e7b4c176eef021b19ecba39da5b73aca106c97a9b7e279a90" ], "index": "pypi", - "version": "==1.6.0" + "version": "==1.9.5" }, "setproctitle": { "hashes": [ - "sha256:01cef383afc7ea7a3b1696818c8712029bf2f1d64f5d4777dbaf0166becf2c00", - "sha256:0670f2130a7ca0e167d3d5a7c8e3c707340b8693d6af7416ff55c18ab2a0a43f", - "sha256:06aab65e68163ead9d046b452dd9ad1fc6834ce6bde490f63fdce3be53e9cc73", - "sha256:0a668acec8b61a971de54bc4c733869ea7b0eb1348eae5a32b9477f788908e5c", - "sha256:0b207de9e4f4aa5265b36dd826a1f6ef6566b064a042033bd7447efb7e9a7664", - "sha256:0b444ed4051161a3b0a85dec2bb9b50922f37c75f5fb86f7784b235cf6754336", - "sha256:138bfa853e607f06d95b0f253e9152b32a00af3d0dbec96abf0871236a483932", - "sha256:14641a4ec2f2110cf4afc666eaecc82ba67814e927e02647fa1f4cf74476e752", - "sha256:21d6e064b8fee4e58eb00cdd8771c638de1bc30bb6c02d0208af9ca0a1c00898", - "sha256:25538341e56f9e75e9759229ff674282dccb5b1ce79a974f968d36208d465674", - "sha256:28e0df80d5069586a08a3cb463fb23503a37cbb805826ef93164bc4bfb5f35b9", - "sha256:2c0be45535e934deab3aa72ed1a8487174af4ea12cec124478c68a312e1c8b13", - "sha256:2c8c245e08f6a296fdaa1b36894ec40e20464a4fc6458e6178c8d55a2f83457a", - "sha256:2d083cae02e344e760bd21c28d591ac5f7ddbd6e1a0ecba62092ae724abd5c28", - "sha256:32a84cc309b9e595f06a55bec2fa335a23c307a55d2989864b60ecd71ea87897", - "sha256:335750c9eb5b18326a138a09266862a52b4f474277c3e410b419bea9a1df8bee", - "sha256:35b869e416a105c59133a48b569c6e808159485d916f55e80c7394a42667a386", - "sha256:38855b06a124361dc73c198853dee3f2b775531c4f4b7472f0e3d441192b3d8a", - "sha256:3b1883ccdbee624386dc046cfbcd80c4e75e24c478f35627984a79892e088b88", - "sha256:3dbe87e76197f9a303451512088c18c96f09a6fc4f871a92e5bd695f46f94a26", - "sha256:3f55493c987935fa540ef9ffb7ee7db03b4a18a9d5cc103681e2e6a6dfbd7054", - "sha256:4051c3a3b07f8a4cca205cd45366a22f322da2f26491c0d6b313a10f8c77b734", - "sha256:409a39f92e123be061626fdfd3e76625b04db103479bb4ba1c85b587db0b9498", - "sha256:423f8a6d8116acf975ebf93d6b5c4a752f7d2039fa9aafe175a62de86e17016e", - "sha256:47f97f591ea2335b7d35f5e9ad7d806385338182dc6de5732d091e9c70ed1cc0", - "sha256:48ac48a94040ef21be37366cbc8270fcba2ca103d6c64da6099d5a7b034f72d0", - "sha256:4eed53c12146de5df959d84384ffc2774651cab406ee4854e12728cf0eee5297", - "sha256:501c084cf3df7d848e91c97d4f8c44d799ba545858a79c6960326ce6f285b4e4", - "sha256:52265182fe5ac237d179d8e949248d307882a2e6ec7f189c8dac1c9d1b3631fa", - "sha256:5464e6812d050c986e6e9b97d54ab88c23dbe9d81151a2fa10b48bb5133a1e2c", - "sha256:54c7315e53b49ef2227d47a75c3d28c4c51ea9ee46a066460732c0d0f8e605a7", - "sha256:60f7a2f5da36a3075dda7edbee2173be5b765b0460b8d401ee01a11f68dee1d2", - "sha256:65a9384cafdfed98f91416e93705ad08f049c298afcb9c515882beba23153bd0", - "sha256:71d00ef63a1f78e13c236895badac77b6c8503377467b9c1a4f81fe729d16e03", - "sha256:76f59444a25fb42ca07f53a4474b1545d97a06f016e6c6b8246eee5b146820b5", - "sha256:791bed39e4ecbdd008b64999a60c9cc560d17b3836ca0c27cd4708e8e1bcf495", - "sha256:7a72bbe53191fbe574c94c0f8b9451dce535b398b7c47ce2e26e21d55eaa1d7e", - "sha256:97accd117392b1e57e09888792750c403d7729b7e4b193005178b3736b325ea0", - "sha256:9a92978030616f5e20617b7b832efee398df82072b7239c53db41c8026f5fe55", - "sha256:9fb5d2e66f94eebc3d06cda9e71a3fffef24c5273971180a4b5628a37fae05a5", - "sha256:a39b30d7400c0d50941fe19e1fe0b7d35676186fec4d9c010129ac91b883fd26", - "sha256:a4a3cb19346a0cd680617742f5e39fdd14596f6fd91d6c9038272663e37441b4", - "sha256:a546cd2dfaecb227d24122257b98b2e062762871888835c7b608f1c41c3a77ad", - "sha256:a81067bdc015fee1cc148c79b346f24fdad1224a8898b4239c7cbdee1add8a60", - "sha256:a912df3f065572cef211e9ed9f157a0dd2bd73d150281f18f00728afa1b1e5d2", - "sha256:a993610383028f093112dce7f77b262e88fce9d70127535fcdc78953179857e8", - "sha256:b213376fc779c0e1a4b60008f3fd03f74e9baa9665db37fa6646e98d31baa6d8", - "sha256:b2fa9f4b382a6cf88f2f345044d0916a92f37cac21355585bd14bc7ee91af187", - "sha256:b9d905ac84dde5227de6516ec08639759f99684148bb88ba05f4cbdaebff5d69", - "sha256:be0b46beeb1c92450079a7f30a025d69b63fd6a5de040ebc478fd6e6bf3b63fc", - "sha256:c93a2272740e60cddf59d3e1d35dbb89fcc3676f5ca9618bb4e6ae9633fdf13c", - "sha256:ccb0b5334dbf248f7504d88b5e9e9a09a0da119eeafacd6f7247f7c055443522", - "sha256:d312a170f539895c8093b5e68ba126aa131c9f0d00f6360410db27ec50bf7afa", - "sha256:d45dbe4171f8c27a515ecb4562f4cd9ef67d98474bea18e0c14dfbdc2b225050", - "sha256:d8e4da68d4d4ba46d4c5db6ae5eb61b11de9c520f25ae8334570f4d0018a8611", - "sha256:e24fa9251cc22ddb88ef183070063fdca826c9636381f1c4fb9d2a1dccb7c2a4", - "sha256:e2ac0ebd9c63c3d19f768966be2f771bf088bc7373c63ed6fcbb3444a30d0f62", - "sha256:e40c35564081983eab6a07f9eb5693867bc447b0edf9c61b69446223d6593814", - "sha256:e80fc59739a738b5c67afbbb9d1c238aa47b6d290c2ada872b15c819350ec5f8", - "sha256:eb06c1086cf8c8cf12ce45a02450befcb408dfd646d0ccb47d388fd6e73c333a", - "sha256:eb82a49aaf440232c762539ab3737b5174d31aba0141fd4bf4d8739c28d18624", - "sha256:ec7c3a27460ae7811e868e5494e3d8aee5012912744c48fa2d80b5e614b1b972", - "sha256:ecf28b1c07a799d76f4326e508157b71aeda07b84b90368ea451c0710dbd32c0", - "sha256:efb3001fd9e71d3ae939d826bf436f0446fd30a6ac01e0ce08cd7eb55ee5ac57", - "sha256:f06ff922254023eaabef6af6631f89e5f2f420cf0112865d57d7703f933d4e9f", - "sha256:f272b84d79bbe15af26ecf6f7c129bbe642f628866c9253659cdb519216f138f", - "sha256:f2a137984d3436f13e4bf7c8ca6f6f292df119c009c5e39556cabba4f4bfbf92", - "sha256:f47f6704880869d8e8f52efac2f2f60f5ed4cb9662b98fc1c7e916eefe76e61d", - "sha256:f9cf1098205c23fbcaaaef798afaff714fa9ffadf24166f5e85e6d16b9ef82a1", - "sha256:fc586f002fd5dd8695718e22a83771fd9f744f081a2b8e614bf6b5f44135964a", - "sha256:fdb2231db176e0848b757fc5d9bed08bc8a498b5b9abb8b640f39e9720f309fc" - ], - "index": "pypi", - "version": "==1.2.3" + "sha256:1c5d5dad7c28bdd1ec4187d818e43796f58a845aa892bb4481587010dc4d362b", + "sha256:1c8d9650154afaa86a44ff195b7b10d683c73509d085339d174e394a22cccbb9", + "sha256:1f0cde41857a644b7353a0060b5f94f7ba7cf593ebde5a1094da1be581ac9a31", + "sha256:1f29b75e86260b0ab59adb12661ef9f113d2f93a59951373eb6d68a852b13e83", + "sha256:1fa1a0fbee72b47dc339c87c890d3c03a72ea65c061ade3204f285582f2da30f", + "sha256:1ff863a20d1ff6ba2c24e22436a3daa3cd80be1dfb26891aae73f61b54b04aca", + "sha256:265ecbe2c6eafe82e104f994ddd7c811520acdd0647b73f65c24f51374cf9494", + "sha256:288943dec88e178bb2fd868adf491197cc0fc8b6810416b1c6775e686bab87fe", + "sha256:2e3ac25bfc4a0f29d2409650c7532d5ddfdbf29f16f8a256fc31c47d0dc05172", + "sha256:2fbd8187948284293f43533c150cd69a0e4192c83c377da837dbcd29f6b83084", + "sha256:4058564195b975ddc3f0462375c533cce310ccdd41b80ac9aed641c296c3eff4", + "sha256:4749a2b0c9ac52f864d13cee94546606f92b981b50e46226f7f830a56a9dc8e1", + "sha256:4d8938249a7cea45ab7e1e48b77685d0f2bab1ebfa9dde23e94ab97968996a7c", + "sha256:5194b4969f82ea842a4f6af2f82cd16ebdc3f1771fb2771796e6add9835c1973", + "sha256:55ce1e9925ce1765865442ede9dca0ba9bde10593fcd570b1f0fa25d3ec6b31c", + "sha256:589be87172b238f839e19f146b9ea47c71e413e951ef0dc6db4218ddacf3c202", + "sha256:5b932c3041aa924163f4aab970c2f0e6b4d9d773f4d50326e0ea1cd69240e5c5", + "sha256:5fb4f769c02f63fac90989711a3fee83919f47ae9afd4758ced5d86596318c65", + "sha256:630f6fe5e24a619ccf970c78e084319ee8be5be253ecc9b5b216b0f474f5ef18", + "sha256:65d884e22037b23fa25b2baf1a3316602ed5c5971eb3e9d771a38c3a69ce6e13", + "sha256:6c877691b90026670e5a70adfbcc735460a9f4c274d35ec5e8a43ce3f8443005", + "sha256:710e16fa3bade3b026907e4a5e841124983620046166f355bbb84be364bf2a02", + "sha256:7a55fe05f15c10e8c705038777656fe45e3bd676d49ad9ac8370b75c66dd7cd7", + "sha256:7aa0aac1711fadffc1d51e9d00a3bea61f68443d6ac0241a224e4d622489d665", + "sha256:7f0bed90a216ef28b9d227d8d73e28a8c9b88c0f48a082d13ab3fa83c581488f", + "sha256:7f2719a398e1a2c01c2a63bf30377a34d0b6ef61946ab9cf4d550733af8f1ef1", + "sha256:7fe9df7aeb8c64db6c34fc3b13271a363475d77bc157d3f00275a53910cb1989", + "sha256:8ff3c8cb26afaed25e8bca7b9dd0c1e36de71f35a3a0706b5c0d5172587a3827", + "sha256:9124bedd8006b0e04d4e8a71a0945da9b67e7a4ab88fdad7b1440dc5b6122c42", + "sha256:92c626edc66169a1b09e9541b9c0c9f10488447d8a2b1d87c8f0672e771bc927", + "sha256:a149a5f7f2c5a065d4e63cb0d7a4b6d3b66e6e80f12e3f8827c4f63974cbf122", + "sha256:a47d97a75fd2d10c37410b180f67a5835cb1d8fdea2648fd7f359d4277f180b9", + "sha256:a499fff50387c1520c085a07578a000123f519e5f3eee61dd68e1d301659651f", + "sha256:ab45146c71ca6592c9cc8b354a2cc9cc4843c33efcbe1d245d7d37ce9696552d", + "sha256:b2c9cb2705fc84cb8798f1ba74194f4c080aaef19d9dae843591c09b97678e98", + "sha256:b34baef93bfb20a8ecb930e395ccd2ae3268050d8cf4fe187de5e2bd806fd796", + "sha256:b617f12c9be61e8f4b2857be4a4319754756845dbbbd9c3718f468bbb1e17bcb", + "sha256:b9fb97907c830d260fa0658ed58afd48a86b2b88aac521135c352ff7fd3477fd", + "sha256:bae283e85fc084b18ffeb92e061ff7ac5af9e183c9d1345c93e178c3e5069cbe", + "sha256:c2c46200656280a064073447ebd363937562debef329482fd7e570c8d498f806", + "sha256:c8a09d570b39517de10ee5b718730e171251ce63bbb890c430c725c8c53d4484", + "sha256:c91b9bc8985d00239f7dc08a49927a7ca1ca8a6af2c3890feec3ed9665b6f91e", + "sha256:dad42e676c5261eb50fdb16bdf3e2771cf8f99a79ef69ba88729aeb3472d8575", + "sha256:de3a540cd1817ede31f530d20e6a4935bbc1b145fd8f8cf393903b1e02f1ae76", + "sha256:e00c9d5c541a2713ba0e657e0303bf96ddddc412ef4761676adc35df35d7c246", + "sha256:e1aafc91cbdacc9e5fe712c52077369168e6b6c346f3a9d51bf600b53eae56bb", + "sha256:e425be62524dc0c593985da794ee73eb8a17abb10fe692ee43bb39e201d7a099", + "sha256:e43f315c68aa61cbdef522a2272c5a5b9b8fd03c301d3167b5e1343ef50c676c", + "sha256:e49ae693306d7624015f31cb3e82708916759d592c2e5f72a35c8f4cc8aef258", + "sha256:e5c50e164cd2459bc5137c15288a9ef57160fd5cbf293265ea3c45efe7870865", + "sha256:e8579a43eafd246e285eb3a5b939e7158073d5087aacdd2308f23200eac2458b", + "sha256:e85e50b9c67854f89635a86247412f3ad66b132a4d8534ac017547197c88f27d", + "sha256:f0452282258dfcc01697026a8841258dd2057c4438b43914b611bccbcd048f10", + "sha256:f4bfc89bd33ebb8e4c0e9846a09b1f5a4a86f5cb7a317e75cc42fee1131b4f4f", + "sha256:fa2f50678f04fda7a75d0fe5dd02bbdd3b13cbe6ed4cf626e4472a7ccf47ae94", + "sha256:faec934cfe5fd6ac1151c02e67156c3f526e82f96b24d550b5d51efa4a5527c6", + "sha256:fcd3cf4286a60fdc95451d8d14e0389a6b4f5cebe02c7f2609325eb016535963", + "sha256:fe8a988c7220c002c45347430993830666e55bc350179d91fcee0feafe64e1d4", + "sha256:fed18e44711c5af4b681c2b3b18f85e6f0f1b2370a28854c645d636d5305ccd8", + "sha256:ffc61a388a5834a97953d6444a2888c24a05f2e333f9ed49f977a87bb1ad4761" + ], + "index": "pypi", + "version": "==1.3.2" }, "setuptools": { "hashes": [ - "sha256:16923d366ced322712c71ccb97164d07472abeecd13f3a6c283f6d5d26722793", - "sha256:db3b8e2f922b2a910a29804776c643ea609badb6a32c4bcc226fd4fd902cce65" + "sha256:2e24e0bec025f035a2e72cdd1961119f557d78ad331bb00ff82efb2ab8da8e82", + "sha256:7732871f4f7fa58fb6bdcaeadb0161b2bd046c85905dbaa066bdcbcc81953b57" ], "markers": "python_version >= '3.7'", - "version": "==63.1.0" + "version": "==65.3.0" + }, + "shiboken2": { + "hashes": [ + "sha256:63debfcc531b6a2b4985aa9b71433d2ad3bac542acffc729cc0ecaa3854390c0", + "sha256:87079c07587859a525b9800d60b1be971338ce9b371d6ead81f15ee5a46d448b", + "sha256:a0d0fdeb12b72c8af349b9642ccc67afd783dca449309f45e78cda50272fd6b7", + "sha256:eb0da44b6fa60c6bd317b8f219e500595e94e0322b33ec5b4e9f406bedaee555", + "sha256:f890f5611ab8f48b88cfecb716da2ac55aef99e2923198cefcf781842888ea65", + "sha256:ffd3d0ec3d508e592d7ee3885d27fee1f279a49989f734eb130f46d9501273a9" + ], + "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3, 3.4' and python_version < '3.11'", + "version": "==5.15.2.1" }, "six": { "hashes": [ @@ -1186,19 +1255,19 @@ }, "sympy": { "hashes": [ - "sha256:5939eeffdf9e152172601463626c022a2c27e75cf6278de8d401d50c9d58787b", - "sha256:df75d738930f6fe9ebe7034e59d56698f29e85f443f743e51e47df0caccc2130" + "sha256:1fe96b4c56bb7a7630cdf150a6cd98bc97a79e6be233e30502aba1cf54dee33d", + "sha256:b53069f5f30e4a4690b57cdb8e3d0d9065fff42627239db718214f804e442481" ], "index": "pypi", - "version": "==1.10.1" + "version": "==1.11" }, "timezonefinder": { "hashes": [ - "sha256:0471463083b5fef7a656c7e31a7376fa1941bf6a41a0750c6e0ca151e43646e7", - "sha256:2e8e958814f21fa809b16e98bd2f99082b69a0f88b864a4a1f2944d5a7e61827" + "sha256:2791ad459b85c110226057cb5ebdd6503f4fb0a33cc4f76fb93e98ed545edd68", + "sha256:406bea77a7baec5e2b1c2b4793ff8f40c174b6d8e894631e60864d956139afef" ], "index": "pypi", - "version": "==6.0.1" + "version": "==6.1.1" }, "tomli": { "hashes": [ @@ -1210,11 +1279,11 @@ }, "tomlkit": { "hashes": [ - "sha256:1c5bebdf19d5051e2e1de6cf70adfc5948d47221f097fcff7a3ffc91e953eaf5", - "sha256:61901f81ff4017951119cd0d1ed9b7af31c821d6845c8c477587bbdcd5e5854e" + "sha256:25d4e2e446c453be6360c67ddfb88838cfc42026322770ba13d1fbd403a93a5c", + "sha256:3235a9010fae54323e727c3ac06fb720752fe6635b3426e379daec60fbd44a83" ], - "markers": "python_version >= '3.6' and python_version < '4'", - "version": "==0.11.1" + "markers": "python_version >= '3.6' and python_version < '4.0'", + "version": "==0.11.4" }, "tqdm": { "hashes": [ @@ -1229,16 +1298,16 @@ "sha256:25642c956049920a5aa49edcdd6ab1e06d7e5d467fc00e0506c44ac86fbfca02", "sha256:e6d2677a32f47fc7eb2795db1dd15c1f34eff616bcaf2cfb5e997f854fa1c4a6" ], - "markers": "python_version >= '3.7'", + "markers": "python_version < '3.10'", "version": "==4.3.0" }, "urllib3": { "hashes": [ - "sha256:8298d6d56d39be0e3bc13c1c97d133f9b45d797169a0e11cdd0e0489d786f7ec", - "sha256:879ba4d1e89654d9769ce13121e0f94310ea32e8d2f8cf587b77c08bbcdb30d6" + "sha256:3fa96cf423e6987997fc326ae8df396db2a8b7c667747d47ddd8ecba91f4a74e", + "sha256:b930dd878d5a8afb066a637fbb35144fe7901e3b209d1cd4f524bd0e9deee997" ], "index": "pypi", - "version": "==1.26.10" + "version": "==1.26.12" }, "utm": { "hashes": [ @@ -1249,19 +1318,19 @@ }, "websocket-client": { "hashes": [ - "sha256:5d55652dc1d0b3c734f044337d929aaf83f4f9138816ec680c1aefefb4dc4877", - "sha256:d58c5f284d6a9bf8379dab423259fe8f85b70d5fa5d2916d5791a84594b122b1" + "sha256:33ad3cf0aef4270b95d10a5a66b670a66be1f5ccf10ce390b3644f9eddfdca9d", + "sha256:79d730c9776f4f112f33b10b78c8d209f23b5806d9a783e296b3813fc5add2f1" ], "index": "pypi", - "version": "==1.3.3" + "version": "==1.4.0" }, "werkzeug": { "hashes": [ - "sha256:1ce08e8093ed67d638d63879fd1ba3735817f7a80de3674d293f5984f25fb6e6", - "sha256:72a4b735692dd3135217911cbeaa1be5fa3f62bffb8745c5215420a03dc55255" + "sha256:7ea2d48322cc7c0f8b3a215ed73eabd7b5d75d0b50e31ab006286ccff9e00b8f", + "sha256:f979ab81f58d7318e064e99c4506445d60135ac5cd2e177a2de0089bfd4c9bd5" ], "markers": "python_version >= '3.7'", - "version": "==2.1.2" + "version": "==2.2.2" }, "wrapt": { "hashes": [ @@ -1330,16 +1399,16 @@ "sha256:ee6acae74a2b91865910eef5e7de37dc6895ad96fa23603d1d27ea69df545015", "sha256:ef3f72c9666bba2bab70d2a8b79f2c6d2c1a42a7f7e2b0ec83bb2f9e383950af" ], - "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3, 3.4'", + "markers": "python_version < '3.11'", "version": "==1.14.1" }, "zipp": { "hashes": [ - "sha256:56bf8aadb83c24db6c4b577e13de374ccfb67da2078beba1d037c17980bf43ad", - "sha256:c4f6e5bbf48e74f7a38e7cc5b0480ff42b0ae5178957d564d18932525d5cf099" + "sha256:05b45f1ee8f807d0cc928485ca40a07cb491cf092ff587c0df9cb1fd154848d2", + "sha256:47c40d7fe183a6f21403a199b3e4192cca5774656965b0a4988ad2f8feb5f009" ], "markers": "python_version >= '3.7'", - "version": "==3.8.0" + "version": "==3.8.1" } }, "develop": { @@ -1352,11 +1421,11 @@ }, "attrs": { "hashes": [ - "sha256:2d27e3784d7a565d36ab851fe94887c5eccd6a463168875832a1be79c82828b4", - "sha256:626ba8234211db98e869df76230a137c4c40a12d72445c45d5f5b716f076e2fd" + "sha256:29adc2665447e5191d0e7c568fde78b21f9672d344281d0c6e1ab085429b22b6", + "sha256:86efa402f67bf2df34f51a335487cf46b1ec130d02b8d39fd248abfd30da551c" ], - "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3, 3.4'", - "version": "==21.4.0" + "markers": "python_version >= '3.5'", + "version": "==22.1.0" }, "av": { "hashes": [ @@ -1434,20 +1503,21 @@ }, "bcrypt": { "hashes": [ - "sha256:2b02d6bfc6336d1094276f3f588aa1225a598e27f8e3388f4db9948cb707b521", - "sha256:433c410c2177057705da2a9f2cd01dd157493b2a7ac14c8593a16b3dab6b6bfb", - "sha256:4e029cef560967fb0cf4a802bcf4d562d3d6b4b1bf81de5ec1abbe0f1adb027e", - "sha256:61bae49580dce88095d669226d5076d0b9d927754cedbdf76c6c9f5099ad6f26", - "sha256:6d2cb9d969bfca5bc08e45864137276e4c3d3d7de2b162171def3d188bf9d34a", - "sha256:7180d98a96f00b1050e93f5b0f556e658605dd9f524d0b0e68ae7944673f525e", - "sha256:7d9ba2e41e330d2af4af6b1b6ec9e6128e91343d0b4afb9282e54e5508f31baa", - "sha256:7ff2069240c6bbe49109fe84ca80508773a904f5a8cb960e02a977f7f519b129", - "sha256:88273d806ab3a50d06bc6a2fc7c87d737dd669b76ad955f449c43095389bc8fb", - "sha256:a2c46100e315c3a5b90fdc53e429c006c5f962529bc27e1dfd656292c20ccc40", - "sha256:cd43303d6b8a165c29ec6756afd169faba9396a9472cdff753fe9f19b96ce2fa" + "sha256:0b0f0c7141622a31e9734b7f649451147c04ebb5122327ac0bd23744df84be90", + "sha256:1c3334446fac200499e8bc04a530ce3cf0b3d7151e0e4ac5c0dddd3d95e97843", + "sha256:2d0dd19aad87e4ab882ef1d12df505f4c52b28b69666ce83c528f42c07379227", + "sha256:594780b364fb45f2634c46ec8d3e61c1c0f1811c4f2da60e8eb15594ecbf93ed", + "sha256:7c7dd6c1f05bf89e65261d97ac3a6520f34c2acb369afb57e3ea4449be6ff8fd", + "sha256:845b1daf4df2dd94d2fdbc9454953ca9dd0e12970a0bfc9f3dcc6faea3fa96e4", + "sha256:8780e69f9deec9d60f947b169507d2c9816e4f11548f1f7ebee2af38b9b22ae4", + "sha256:bf413f2a9b0a2950fc750998899013f2e718d20fa4a58b85ca50b6df5ed1bbf9", + "sha256:bfb67f6a6c72dfb0a02f3df51550aa1862708e55128b22543e2b42c74f3620d7", + "sha256:c59c170fc9225faad04dde1ba61d85b413946e8ce2e5f5f5ff30dfd67283f319", + "sha256:dc6ec3dc19b1c193b2f7cf279d3e32e7caf447532fbcb7af0906fe4398900c33", + "sha256:ede0f506554571c8eda80db22b83c139303ec6b595b8f60c4c8157bdd0bdee36" ], "markers": "python_version >= '3.6'", - "version": "==3.2.2" + "version": "==4.0.0" }, "breathe": { "hashes": [ @@ -1559,11 +1629,11 @@ }, "charset-normalizer": { "hashes": [ - "sha256:5189b6f22b01957427f35b6a08d9a0bc45b46d3788ef5a92e978433c7a35f8a5", - "sha256:575e708016ff3a5e3681541cb9d79312c416835686d054a23accb873b254f413" + "sha256:5a3d016c7c547f69d6f81fb0db9449ce888b418b5b9952cc5e6e66843e9dd845", + "sha256:83e9a75d1911279afd89352c68b45348559d1fc0506b054b346651b5e7fee29f" ], "markers": "python_version >= '3.6'", - "version": "==2.1.0" + "version": "==2.1.1" }, "control": { "hashes": [ @@ -1574,50 +1644,59 @@ }, "coverage": { "hashes": [ - "sha256:01c5615d13f3dd3aa8543afc069e5319cfa0c7d712f6e04b920431e5c564a749", - "sha256:106c16dfe494de3193ec55cac9640dd039b66e196e4641fa8ac396181578b982", - "sha256:129cd05ba6f0d08a766d942a9ed4b29283aff7b2cccf5b7ce279d50796860bb3", - "sha256:145f296d00441ca703a659e8f3eb48ae39fb083baba2d7ce4482fb2723e050d9", - "sha256:1480ff858b4113db2718848d7b2d1b75bc79895a9c22e76a221b9d8d62496428", - "sha256:269eaa2c20a13a5bf17558d4dc91a8d078c4fa1872f25303dddcbba3a813085e", - "sha256:26dff09fb0d82693ba9e6231248641d60ba606150d02ed45110f9ec26404ed1c", - "sha256:2bd9a6fc18aab8d2e18f89b7ff91c0f34ff4d5e0ba0b33e989b3cd4194c81fd9", - "sha256:309ce4a522ed5fca432af4ebe0f32b21d6d7ccbb0f5fcc99290e71feba67c264", - "sha256:3384f2a3652cef289e38100f2d037956194a837221edd520a7ee5b42d00cc605", - "sha256:342d4aefd1c3e7f620a13f4fe563154d808b69cccef415415aece4c786665397", - "sha256:39ee53946bf009788108b4dd2894bf1349b4e0ca18c2016ffa7d26ce46b8f10d", - "sha256:4321f075095a096e70aff1d002030ee612b65a205a0a0f5b815280d5dc58100c", - "sha256:4803e7ccf93230accb928f3a68f00ffa80a88213af98ed338a57ad021ef06815", - "sha256:4ce1b258493cbf8aec43e9b50d89982346b98e9ffdfaae8ae5793bc112fb0068", - "sha256:664a47ce62fe4bef9e2d2c430306e1428ecea207ffd68649e3b942fa8ea83b0b", - "sha256:75ab269400706fab15981fd4bd5080c56bd5cc07c3bccb86aab5e1d5a88dc8f4", - "sha256:83c4e737f60c6936460c5be330d296dd5b48b3963f48634c53b3f7deb0f34ec4", - "sha256:84631e81dd053e8a0d4967cedab6db94345f1c36107c71698f746cb2636c63e3", - "sha256:84e65ef149028516c6d64461b95a8dbcfce95cfd5b9eb634320596173332ea84", - "sha256:865d69ae811a392f4d06bde506d531f6a28a00af36f5c8649684a9e5e4a85c83", - "sha256:87f4f3df85aa39da00fd3ec4b5abeb7407e82b68c7c5ad181308b0e2526da5d4", - "sha256:8c08da0bd238f2970230c2a0d28ff0e99961598cb2e810245d7fc5afcf1254e8", - "sha256:961e2fb0680b4f5ad63234e0bf55dfb90d302740ae9c7ed0120677a94a1590cb", - "sha256:9b3e07152b4563722be523e8cd0b209e0d1a373022cfbde395ebb6575bf6790d", - "sha256:a7f3049243783df2e6cc6deafc49ea123522b59f464831476d3d1448e30d72df", - "sha256:bf5601c33213d3cb19d17a796f8a14a9eaa5e87629a53979a5981e3e3ae166f6", - "sha256:cec3a0f75c8f1031825e19cd86ee787e87cf03e4fd2865c79c057092e69e3a3b", - "sha256:d42c549a8f41dc103a8004b9f0c433e2086add8a719da00e246e17cbe4056f72", - "sha256:d67d44996140af8b84284e5e7d398e589574b376fb4de8ccd28d82ad8e3bea13", - "sha256:d9c80df769f5ec05ad21ea34be7458d1dc51ff1fb4b2219e77fe24edf462d6df", - "sha256:e57816f8ffe46b1df8f12e1b348f06d164fd5219beba7d9433ba79608ef011cc", - "sha256:ee2ddcac99b2d2aec413e36d7a429ae9ebcadf912946b13ffa88e7d4c9b712d6", - "sha256:f02cbbf8119db68455b9d763f2f8737bb7db7e43720afa07d8eb1604e5c5ae28", - "sha256:f1d5aa2703e1dab4ae6cf416eb0095304f49d004c39e9db1d86f57924f43006b", - "sha256:f5b66caa62922531059bc5ac04f836860412f7f88d38a476eda0a6f11d4724f4", - "sha256:f69718750eaae75efe506406c490d6fc5a6161d047206cc63ce25527e8a3adad", - "sha256:fb73e0011b8793c053bfa85e53129ba5f0250fdc0392c1591fd35d915ec75c46", - "sha256:fd180ed867e289964404051a958f7cccabdeed423f91a899829264bb7974d3d3", - "sha256:fdb6f7bd51c2d1714cea40718f6149ad9be6a2ee7d93b19e9f00934c0f2a74d9", - "sha256:ffa9297c3a453fba4717d06df579af42ab9a28022444cae7fa605af4df612d54" - ], - "index": "pypi", - "version": "==6.4.1" + "sha256:01778769097dbd705a24e221f42be885c544bb91251747a8a3efdec6eb4788f2", + "sha256:08002f9251f51afdcc5e3adf5d5d66bb490ae893d9e21359b085f0e03390a820", + "sha256:1238b08f3576201ebf41f7c20bf59baa0d05da941b123c6656e42cdb668e9827", + "sha256:14a32ec68d721c3d714d9b105c7acf8e0f8a4f4734c811eda75ff3718570b5e3", + "sha256:15e38d853ee224e92ccc9a851457fb1e1f12d7a5df5ae44544ce7863691c7a0d", + "sha256:354df19fefd03b9a13132fa6643527ef7905712109d9c1c1903f2133d3a4e145", + "sha256:35ef1f8d8a7a275aa7410d2f2c60fa6443f4a64fae9be671ec0696a68525b875", + "sha256:4179502f210ebed3ccfe2f78bf8e2d59e50b297b598b100d6c6e3341053066a2", + "sha256:42c499c14efd858b98c4e03595bf914089b98400d30789511577aa44607a1b74", + "sha256:4b7101938584d67e6f45f0015b60e24a95bf8dea19836b1709a80342e01b472f", + "sha256:564cd0f5b5470094df06fab676c6d77547abfdcb09b6c29c8a97c41ad03b103c", + "sha256:5f444627b3664b80d078c05fe6a850dd711beeb90d26731f11d492dcbadb6973", + "sha256:6113e4df2fa73b80f77663445be6d567913fb3b82a86ceb64e44ae0e4b695de1", + "sha256:61b993f3998ee384935ee423c3d40894e93277f12482f6e777642a0141f55782", + "sha256:66e6df3ac4659a435677d8cd40e8eb1ac7219345d27c41145991ee9bf4b806a0", + "sha256:67f9346aeebea54e845d29b487eb38ec95f2ecf3558a3cffb26ee3f0dcc3e760", + "sha256:6913dddee2deff8ab2512639c5168c3e80b3ebb0f818fed22048ee46f735351a", + "sha256:6a864733b22d3081749450466ac80698fe39c91cb6849b2ef8752fd7482011f3", + "sha256:7026f5afe0d1a933685d8f2169d7c2d2e624f6255fb584ca99ccca8c0e966fd7", + "sha256:783bc7c4ee524039ca13b6d9b4186a67f8e63d91342c713e88c1865a38d0892a", + "sha256:7a98d6bf6d4ca5c07a600c7b4e0c5350cd483c85c736c522b786be90ea5bac4f", + "sha256:8d032bfc562a52318ae05047a6eb801ff31ccee172dc0d2504614e911d8fa83e", + "sha256:98c0b9e9b572893cdb0a00e66cf961a238f8d870d4e1dc8e679eb8bdc2eb1b86", + "sha256:9c7b9b498eb0c0d48b4c2abc0e10c2d78912203f972e0e63e3c9dc21f15abdaa", + "sha256:9cc4f107009bca5a81caef2fca843dbec4215c05e917a59dec0c8db5cff1d2aa", + "sha256:9d6e1f3185cbfd3d91ac77ea065d85d5215d3dfa45b191d14ddfcd952fa53796", + "sha256:a095aa0a996ea08b10580908e88fbaf81ecf798e923bbe64fb98d1807db3d68a", + "sha256:a3b2752de32c455f2521a51bd3ffb53c5b3ae92736afde67ce83477f5c1dd928", + "sha256:ab066f5ab67059d1f1000b5e1aa8bbd75b6ed1fc0014559aea41a9eb66fc2ce0", + "sha256:c1328d0c2f194ffda30a45f11058c02410e679456276bfa0bbe0b0ee87225fac", + "sha256:c35cca192ba700979d20ac43024a82b9b32a60da2f983bec6c0f5b84aead635c", + "sha256:cbbb0e4cd8ddcd5ef47641cfac97d8473ab6b132dd9a46bacb18872828031685", + "sha256:cdbb0d89923c80dbd435b9cf8bba0ff55585a3cdb28cbec65f376c041472c60d", + "sha256:cf2afe83a53f77aec067033199797832617890e15bed42f4a1a93ea24794ae3e", + "sha256:d5dd4b8e9cd0deb60e6fcc7b0647cbc1da6c33b9e786f9c79721fd303994832f", + "sha256:dfa0b97eb904255e2ab24166071b27408f1f69c8fbda58e9c0972804851e0558", + "sha256:e16c45b726acb780e1e6f88b286d3c10b3914ab03438f32117c4aa52d7f30d58", + "sha256:e1fabd473566fce2cf18ea41171d92814e4ef1495e04471786cbc943b89a3781", + "sha256:e3d3c4cc38b2882f9a15bafd30aec079582b819bec1b8afdbde8f7797008108a", + "sha256:e431e305a1f3126477abe9a184624a85308da8edf8486a863601d58419d26ffa", + "sha256:e7b4da9bafad21ea45a714d3ea6f3e1679099e420c8741c74905b92ee9bfa7cc", + "sha256:ee2b2fb6eb4ace35805f434e0f6409444e1466a47f620d1d5763a22600f0f892", + "sha256:ee6ae6bbcac0786807295e9687169fba80cb0617852b2fa118a99667e8e6815d", + "sha256:ef6f44409ab02e202b31a05dd6666797f9de2aa2b4b3534e9d450e42dea5e817", + "sha256:f67cf9f406cf0d2f08a3515ce2db5b82625a7257f88aad87904674def6ddaec1", + "sha256:f855b39e4f75abd0dfbcf74a82e84ae3fc260d523fcb3532786bcbbcb158322c", + "sha256:fc600f6ec19b273da1d85817eda339fb46ce9eef3e89f220055d8696e0a06908", + "sha256:fcbe3d9a53e013f8ab88734d7e517eb2cd06b7e689bedf22c0eb68db5e4a0a19", + "sha256:fde17bc42e0716c94bf19d92e4c9f5a00c5feb401f5bc01101fdf2a8b7cacf60", + "sha256:ff934ced84054b9018665ca3967fc48e1ac99e811f6cc99ea65978e1d384454b" + ], + "index": "pypi", + "version": "==6.4.4" }, "cryptography": { "hashes": [ @@ -1665,10 +1744,10 @@ }, "distlib": { "hashes": [ - "sha256:6564fe0a8f51e734df6333d08b8b94d4ea8ee6b99b5ed50613f731fd4089f34b", - "sha256:e4b58818180336dc9c529bfb9a0b58728ffc09ad92027a3f30b7cd91e3458579" + "sha256:14bad2d9b04d3a36127ac97f30b12a19268f211063d8f8ee4f47108896e11b46", + "sha256:f35c4b692542ca110de7ef0bea44d73981caeb34ca0b9b6b2e6d7790dda8f80e" ], - "version": "==0.3.4" + "version": "==0.3.6" }, "docutils": { "hashes": [ @@ -1731,46 +1810,52 @@ }, "filelock": { "hashes": [ - "sha256:37def7b658813cda163b56fc564cdc75e86d338246458c4c28ae84cabefa2404", - "sha256:3a0fd85166ad9dbab54c9aec96737b744106dc5f15c0b09a6744a445299fcf04" + "sha256:55447caa666f2198c5b6b13a26d2084d26fa5b115c00d065664b2124680c4edc", + "sha256:617eb4e5eedc82fc5f47b6d61e4d11cb837c56cb4544e39081099fa17ad109d4" ], "markers": "python_version >= '3.7'", - "version": "==3.7.1" + "version": "==3.8.0" }, "fonttools": { "hashes": [ - "sha256:9a1c52488045cd6c6491fd07711a380f932466e317cb8e016fc4e99dc7eac2f0", - "sha256:d73f25b283cd8033367451122aa868a23de0734757a01984e4b30b18b9050c72" + "sha256:4606e1a88ee1f6699d182fea9511bd9a8a915d913eab4584e5226da1180fcce7", + "sha256:fff6b752e326c15756c819fe2fe7ceab69f96a1dbcfe8911d0941cdb49905007" ], "markers": "python_version >= '3.7'", - "version": "==4.34.4" + "version": "==4.37.1" }, "ft4222": { "hashes": [ - "sha256:1489b08e4042cb2b24894495c1c8514fa115122e9f8a739f665f0e4d8c53d3f4", - "sha256:1c71913f9fb862634fb77eb6efeea38b2b839e09f739aee5864b9549bcf1c4a9", - "sha256:1f9be0961bd7f3e0c1729c9692f602244e93898610611602ce1fa16059ac5bfa", - "sha256:208cde748fc2bf4a753e217ee2844e75d7d1b6d370a8937a2055f9de8906f933", - "sha256:372be3d7d04c0f6dfa62ff66b3d4be5c39d57c258ab562d9eb0d7cdd3a90ed0f", - "sha256:3ebf9380315c6af8f9f3bc5c5c7a5ae06498349c14a7b2e65d5067b20462d21b", - "sha256:422740efac86f3fdd971bb9a94d9974e56cfe062284a2be1a85db96dd0e77e5e", - "sha256:4414ef82a6321c5205ab0e3dab2bf072f14b4dd3262e5f392560adf107210d41", - "sha256:459894dcca7db71a0d58e6f3abb4c9dd67654c92ad9d934f1e32dc08bed87645", - "sha256:4b7e4c8b5e4a8fe769127d3db99b7b410468ffe2718a07f7b317e7dc1ad9ca4f", - "sha256:68e6b357ea2287fe0e8dac287efbac2f0ce9632d65e828d422d3a0604555c174", - "sha256:800a26a4a8fc854f41e4de41e45b6deafdeb78ae5eff48818f710bb2d94a8c11", - "sha256:8790e96b4c3f8d1fb768f689f1c437a59b20889e4726ed7457ff3d188f0a3274", - "sha256:9369b55393b2e1f58f8b8516bcf9cd6fd34c05e77377c4cc48be39a49cad7be5", - "sha256:a6236f05b8948cd9c113c7159e3fdde202a0f73dce6440da078fd2fc9e411123", - "sha256:b7f58cd16213a5c92503c530b301f071d67283c80c1e8cb43d6f3ec5c186df35", - "sha256:cc368b06b92529a11add37d14196d2e2aaae19c6ffc51b9457513a0d05ceae1a", - "sha256:d479c037b417ff289727112f1d4725563b78448d3765f457c8bf6884e4d83abd", - "sha256:dce00d513be811f738954c5593c52b533a02331e8a26983280dea3f4d864962f", - "sha256:eadcbc1dd20ed6d7d07dc53354ea137bcea30fb0889d74bedcd189cdb4f61c84", - "sha256:ec984bd7e9300e5f2e50823dcd5874d54aa3e7503e69afe7eb3b4cea77071084" + "sha256:074f4eb234450306b9040d721eb5ab2a423d3b07d6f4a30824198afeb0a9bbb6", + "sha256:09f18a5610d0d81c568c9095798f542166b98025d119c9fa91555fa5bfddc2ee", + "sha256:0cceacb43d75a5cb3cdf2d95d4164fb2c1cfde007d9782538150bc10d7933680", + "sha256:10136015000719f68b2a4b319b612183a1601816870521e6a45c8c0b67d38325", + "sha256:1894469abffd739fc3a83f818ea29532283965c74c3c64e5c9b9e6b454971d03", + "sha256:24cdb72a7cd420c1ed009c0821555b9818b8828dc31a1a01224a35d4757c7e5d", + "sha256:286a2f3c023e9beb5c6ca6b692c3ed92a1fe44b326f7cb58807d0b99f372c7d7", + "sha256:28b472bbbb18e6f65dacd139231a53640827f2e486c54750fbcff7a16454cb6d", + "sha256:296555ca4096b5ce13e79b089622de5cf9236f3d32b074c8483ae72490e7448b", + "sha256:396f5c7c38e0c8dc1b31d5d9709d7eb86ef0ee75412867ccc352506aa3a29ae4", + "sha256:39a7d8795d32b8c126ed253a0c1a9d7971f3af83d2ceb796af47fbef03485741", + "sha256:50e37f59b8e553384cdbfab64096e3fb1c7ca9f15ae419ae0d0fdda3a2e05f54", + "sha256:511b785a23ba2fc8480dbaeda33e1f22ffe5dd58731e1c53e379989731fb42ad", + "sha256:5f91e530ee6fe6a13c08ec4dc3c7f54a704fc642b3d73f4392a9db22c5e243dd", + "sha256:65e5b7bfbe3552b771770807df0a251616bb2c8f7541e4e9f350715f225a71c0", + "sha256:6e208af13621b8a79a8c623c8deb3b971f4d4e4587156622a6558b91719f9d33", + "sha256:70aec6df75d1f8ee051c5d16a48363e4d3552feecf3466cec2700415c073e5e4", + "sha256:9670396daab3deb91847ee40c0338bca07f4041176b2aed1c49277dc1ef3497f", + "sha256:a300c2749adb674ef3d95b17a1311deaf0a3318e14ee7e9d7e56317e307b0012", + "sha256:a675b88124dfb1d2744f27823e3dfd094c0236674e453e83d486fc17358761ff", + "sha256:ab5ea9522bd0fd1b87348bf26d0a1131e87f586366271581c9b1d0acdf870173", + "sha256:baf80af3de3af376080bfb8f75f3d6aba9e9415001a6f72299cbb344e6b739cb", + "sha256:bb3cb6485d7a0d1eac0e0027eab6b9ec95e5f5722e853cdc2850d2ae70086eea", + "sha256:c5a993dd3af47ab69f5b58920dba15c98658de7a73b9c81d402fe6eaf292edab", + "sha256:c7e31cefcdcfe3653df35cd993f821b746e747b294ded8bff27d1f8bd8c5e43b", + "sha256:caec2458db0d8e29888da2c22aa4427c1d993e943ed325ef7a6b8eb24f55d163", + "sha256:d688830cf004cde39b3cc757fef8ec31ae266fceda1566ca53b3b79e5ab7b6e4" ], "index": "pypi", - "version": "==1.4.1" + "version": "==1.5.0" }, "hexdump": { "hashes": [ @@ -1791,11 +1876,11 @@ }, "identify": { "hashes": [ - "sha256:0dca2ea3e4381c435ef9c33ba100a78a9b40c0bab11189c7cf121f75815efeaa", - "sha256:3d11b16f3fe19f52039fb7e39c9c884b21cb1b586988114fbe42671f03de3e82" + "sha256:25851c8c1370effb22aaa3c987b30449e9ff0cece408f810ae6ce408fdd20893", + "sha256:887e7b91a1be152b0d46bbf072130235a8117392b9f1828446079a816a05ef44" ], "markers": "python_version >= '3.7'", - "version": "==2.5.1" + "version": "==2.5.3" }, "idna": { "hashes": [ @@ -1846,59 +1931,131 @@ }, "kiwisolver": { "hashes": [ - "sha256:007799c7fa934646318fc128b033bb6e6baabe7fbad521bfb2279aac26225cd7", - "sha256:130c6c35eded399d3967cf8a542c20b671f5ba85bd6f210f8b939f868360e9eb", - "sha256:1858ad3cb686eccc7c6b7c5eac846a1cfd45aacb5811b2cf575e80b208f5622a", - "sha256:1ae7aa0784aeadfbd693c27993727792fbe1455b84d49970bad5886b42976b18", - "sha256:1d2c744aeedce22c122bb42d176b4aa6d063202a05a4abdacb3e413c214b3694", - "sha256:21a3a98f0a21fc602663ca9bce2b12a4114891bdeba2dea1e9ad84db59892fca", - "sha256:22ccba48abae827a0f952a78a7b1a7ff01866131e5bbe1f826ce9bda406bf051", - "sha256:26b5a70bdab09e6a2f40babc4f8f992e3771751e144bda1938084c70d3001c09", - "sha256:2d76780d9c65c7529cedd49fa4802d713e60798d8dc3b0d5b12a0a8f38cca51c", - "sha256:325fa1b15098e44fe4590a6c5c09a212ca10c6ebb5d96f7447d675f6c8340e4e", - "sha256:3a297d77b3d6979693f5948df02b89431ae3645ec95865e351fb45578031bdae", - "sha256:3b1dcbc49923ac3c973184a82832e1f018dec643b1e054867d04a3a22255ec6a", - "sha256:40240da438c0ebfe2aa76dd04b844effac6679423df61adbe3437d32f23468d9", - "sha256:46c6e5018ba31d5ee7582f323d8661498a154dea1117486a571db4c244531f24", - "sha256:46fb56fde006b7ef5f8eaa3698299b0ea47444238b869ff3ced1426aa9fedcb5", - "sha256:4dc350cb65fe4e3f737d50f0465fa6ea0dcae0e5722b7edf5d5b0a0e3cd2c3c7", - "sha256:51078855a16b7a4984ed2067b54e35803d18bca9861cb60c60f6234b50869a56", - "sha256:547111ef7cf13d73546c2de97ce434935626c897bdec96a578ca100b5fcd694b", - "sha256:5fb73cc8a34baba1dfa546ae83b9c248ef6150c238b06fc53d2773685b67ec67", - "sha256:654280c5f41831ddcc5a331c0e3ce2e480bbc3d7c93c18ecf6236313aae2d61a", - "sha256:6b3136eecf7e1b4a4d23e4b19d6c4e7a8e0b42d55f30444e3c529700cdacaa0d", - "sha256:7118ca592d25b2957ff7b662bc0fe4f4c2b5d5b27814b9b1bc9f2fb249a970e7", - "sha256:71af5b43e4fa286a35110fc5bb740fdeae2b36ca79fbcf0a54237485baeee8be", - "sha256:747190fcdadc377263223f8f72b038381b3b549a8a3df5baf4d067da4749b046", - "sha256:8395064d63b26947fa2c9faeea9c3eee35e52148c5339c37987e1d96fbf009b3", - "sha256:84f85adfebd7d3c3db649efdf73659e1677a2cf3fa6e2556a3f373578af14bf7", - "sha256:86bcf0009f2012847a688f2f4f9b16203ca4c835979a02549aa0595d9f457cc8", - "sha256:ab8a15c2750ae8d53e31f77a94f846d0a00772240f1c12817411fa2344351f86", - "sha256:af24b21c2283ca69c416a8a42cde9764dc36c63d3389645d28c69b0e93db3cd7", - "sha256:afe173ac2646c2636305ab820cc0380b22a00a7bca4290452e7166b4f4fa49d0", - "sha256:b9eb88593159a53a5ee0b0159daee531ff7dd9c87fa78f5d807ca059c7eb1b2b", - "sha256:c16635f8dddbeb1b827977d0b00d07b644b040aeb9ff8607a9fc0997afa3e567", - "sha256:ca3eefb02ef17257fae8b8555c85e7c1efdfd777f671384b0e4ef27409b02720", - "sha256:caa59e2cae0e23b1e225447d7a9ddb0f982f42a6a22d497a484dfe62a06f7c0e", - "sha256:cb55258931448d61e2d50187de4ee66fc9d9f34908b524949b8b2b93d0c57136", - "sha256:d248c46c0aa406695bda2abf99632db991f8b3a6d46018721a2892312a99f069", - "sha256:d2578e5149ff49878934debfacf5c743fab49eca5ecdb983d0b218e1e554c498", - "sha256:dd22085446f3eca990d12a0878eeb5199dc9553b2e71716bfe7bed9915a472ab", - "sha256:e7cf940af5fee00a92e281eb157abe8770227a5255207818ea9a34e54a29f5b2", - "sha256:f70f3d028794e31cf9d1a822914efc935aadb2438ec4e8d4871d95eb1ce032d6", - "sha256:fd2842a0faed9ab9aba0922c951906132d9384be89690570f0ed18cd4f20e658", - "sha256:fd628e63ffdba0112e3ddf1b1e9f3db29dd8262345138e08f4938acbc6d0805a", - "sha256:ffd7cf165ff71afb202b3f36daafbf298932bee325aac9f58e1c9cd55838bef0" + "sha256:02f79693ec433cb4b5f51694e8477ae83b3205768a6fb48ffba60549080e295b", + "sha256:03baab2d6b4a54ddbb43bba1a3a2d1627e82d205c5cf8f4c924dc49284b87166", + "sha256:1041feb4cda8708ce73bb4dcb9ce1ccf49d553bf87c3954bdfa46f0c3f77252c", + "sha256:10ee06759482c78bdb864f4109886dff7b8a56529bc1609d4f1112b93fe6423c", + "sha256:1d1573129aa0fd901076e2bfb4275a35f5b7aa60fbfb984499d661ec950320b0", + "sha256:283dffbf061a4ec60391d51e6155e372a1f7a4f5b15d59c8505339454f8989e4", + "sha256:28bc5b299f48150b5f822ce68624e445040595a4ac3d59251703779836eceff9", + "sha256:2a66fdfb34e05b705620dd567f5a03f239a088d5a3f321e7b6ac3239d22aa286", + "sha256:2e307eb9bd99801f82789b44bb45e9f541961831c7311521b13a6c85afc09767", + "sha256:2e407cb4bd5a13984a6c2c0fe1845e4e41e96f183e5e5cd4d77a857d9693494c", + "sha256:2f5e60fabb7343a836360c4f0919b8cd0d6dbf08ad2ca6b9cf90bf0c76a3c4f6", + "sha256:36dafec3d6d6088d34e2de6b85f9d8e2324eb734162fba59d2ba9ed7a2043d5b", + "sha256:3fe20f63c9ecee44560d0e7f116b3a747a5d7203376abeea292ab3152334d004", + "sha256:41dae968a94b1ef1897cb322b39360a0812661dba7c682aa45098eb8e193dbdf", + "sha256:4bd472dbe5e136f96a4b18f295d159d7f26fd399136f5b17b08c4e5f498cd494", + "sha256:4ea39b0ccc4f5d803e3337dd46bcce60b702be4d86fd0b3d7531ef10fd99a1ac", + "sha256:5853eb494c71e267912275e5586fe281444eb5e722de4e131cddf9d442615626", + "sha256:5bce61af018b0cb2055e0e72e7d65290d822d3feee430b7b8203d8a855e78766", + "sha256:6295ecd49304dcf3bfbfa45d9a081c96509e95f4b9d0eb7ee4ec0530c4a96514", + "sha256:62ac9cc684da4cf1778d07a89bf5f81b35834cb96ca523d3a7fb32509380cbf6", + "sha256:70e7c2e7b750585569564e2e5ca9845acfaa5da56ac46df68414f29fea97be9f", + "sha256:7577c1987baa3adc4b3c62c33bd1118c3ef5c8ddef36f0f2c950ae0b199e100d", + "sha256:75facbe9606748f43428fc91a43edb46c7ff68889b91fa31f53b58894503a191", + "sha256:787518a6789009c159453da4d6b683f468ef7a65bbde796bcea803ccf191058d", + "sha256:78d6601aed50c74e0ef02f4204da1816147a6d3fbdc8b3872d263338a9052c51", + "sha256:7c43e1e1206cd421cd92e6b3280d4385d41d7166b3ed577ac20444b6995a445f", + "sha256:81e38381b782cc7e1e46c4e14cd997ee6040768101aefc8fa3c24a4cc58e98f8", + "sha256:841293b17ad704d70c578f1f0013c890e219952169ce8a24ebc063eecf775454", + "sha256:872b8ca05c40d309ed13eb2e582cab0c5a05e81e987ab9c521bf05ad1d5cf5cb", + "sha256:877272cf6b4b7e94c9614f9b10140e198d2186363728ed0f701c6eee1baec1da", + "sha256:8c808594c88a025d4e322d5bb549282c93c8e1ba71b790f539567932722d7bd8", + "sha256:8ed58b8acf29798b036d347791141767ccf65eee7f26bde03a71c944449e53de", + "sha256:91672bacaa030f92fc2f43b620d7b337fd9a5af28b0d6ed3f77afc43c4a64b5a", + "sha256:968f44fdbf6dd757d12920d63b566eeb4d5b395fd2d00d29d7ef00a00582aac9", + "sha256:9f85003f5dfa867e86d53fac6f7e6f30c045673fa27b603c397753bebadc3008", + "sha256:a553dadda40fef6bfa1456dc4be49b113aa92c2a9a9e8711e955618cd69622e3", + "sha256:a68b62a02953b9841730db7797422f983935aeefceb1679f0fc85cbfbd311c32", + "sha256:abbe9fa13da955feb8202e215c4018f4bb57469b1b78c7a4c5c7b93001699938", + "sha256:ad881edc7ccb9d65b0224f4e4d05a1e85cf62d73aab798943df6d48ab0cd79a1", + "sha256:b1792d939ec70abe76f5054d3f36ed5656021dcad1322d1cc996d4e54165cef9", + "sha256:b428ef021242344340460fa4c9185d0b1f66fbdbfecc6c63eff4b7c29fad429d", + "sha256:b533558eae785e33e8c148a8d9921692a9fe5aa516efbdff8606e7d87b9d5824", + "sha256:ba59c92039ec0a66103b1d5fe588fa546373587a7d68f5c96f743c3396afc04b", + "sha256:bc8d3bd6c72b2dd9decf16ce70e20abcb3274ba01b4e1c96031e0c4067d1e7cd", + "sha256:bc9db8a3efb3e403e4ecc6cd9489ea2bac94244f80c78e27c31dcc00d2790ac2", + "sha256:bf7d9fce9bcc4752ca4a1b80aabd38f6d19009ea5cbda0e0856983cf6d0023f5", + "sha256:c2dbb44c3f7e6c4d3487b31037b1bdbf424d97687c1747ce4ff2895795c9bf69", + "sha256:c79ebe8f3676a4c6630fd3f777f3cfecf9289666c84e775a67d1d358578dc2e3", + "sha256:c97528e64cb9ebeff9701e7938653a9951922f2a38bd847787d4a8e498cc83ae", + "sha256:d0611a0a2a518464c05ddd5a3a1a0e856ccc10e67079bb17f265ad19ab3c7597", + "sha256:d06adcfa62a4431d404c31216f0f8ac97397d799cd53800e9d3efc2fbb3cf14e", + "sha256:d41997519fcba4a1e46eb4a2fe31bc12f0ff957b2b81bac28db24744f333e955", + "sha256:d5b61785a9ce44e5a4b880272baa7cf6c8f48a5180c3e81c59553ba0cb0821ca", + "sha256:da152d8cdcab0e56e4f45eb08b9aea6455845ec83172092f09b0e077ece2cf7a", + "sha256:da7e547706e69e45d95e116e6939488d62174e033b763ab1496b4c29b76fabea", + "sha256:db5283d90da4174865d520e7366801a93777201e91e79bacbac6e6927cbceede", + "sha256:db608a6757adabb32f1cfe6066e39b3706d8c3aa69bbc353a5b61edad36a5cb4", + "sha256:e0ea21f66820452a3f5d1655f8704a60d66ba1191359b96541eaf457710a5fc6", + "sha256:e7da3fec7408813a7cebc9e4ec55afed2d0fd65c4754bc376bf03498d4e92686", + "sha256:e92a513161077b53447160b9bd8f522edfbed4bd9759e4c18ab05d7ef7e49408", + "sha256:ecb1fa0db7bf4cff9dac752abb19505a233c7f16684c5826d1f11ebd9472b871", + "sha256:efda5fc8cc1c61e4f639b8067d118e742b812c930f708e6667a5ce0d13499e29", + "sha256:f0a1dbdb5ecbef0d34eb77e56fcb3e95bbd7e50835d9782a45df81cc46949750", + "sha256:f0a71d85ecdd570ded8ac3d1c0f480842f49a40beb423bb8014539a9f32a5897", + "sha256:f4f270de01dd3e129a72efad823da90cc4d6aafb64c410c9033aba70db9f1ff0", + "sha256:f6cb459eea32a4e2cf18ba5fcece2dbdf496384413bc1bae15583f19e567f3b2", + "sha256:f8ad8285b01b0d4695102546b342b493b3ccc6781fc28c8c6a1bb63e95d22f09", + "sha256:f9f39e2f049db33a908319cf46624a569b36983c7c78318e9726a4cb8923b26c" ], "markers": "python_version >= '3.7'", - "version": "==1.4.3" + "version": "==1.4.4" }, "lru-dict": { "hashes": [ - "sha256:45b81f67d75341d4433abade799a47e9c42a9e22a118531dcb5e549864032d7c" - ], - "index": "pypi", - "version": "==1.1.7" + "sha256:075b9dd46d7022b675419bc6e3631748ae184bc8af195d20365a98b4f3bb2914", + "sha256:0972d669e9e207617e06416166718b073a49bf449abbd23940d9545c0847a4d9", + "sha256:0f83cd70a6d32f9018d471be609f3af73058f700691657db4a3d3dd78d3f96dd", + "sha256:10fe823ff90b655f0b6ba124e2b576ecda8c61b8ead76b456db67831942d22f2", + "sha256:163079dbda54c3e6422b23da39fb3ecc561035d65e8496ff1950cbdb376018e1", + "sha256:1fe16ade5fd0a57e9a335f69b8055aaa6fb278fbfa250458e4f6b8255115578f", + "sha256:262a4e622010ceb960a6a5222ed011090e50954d45070fd369c0fa4d2ed7d9a9", + "sha256:2f340b61f3cdfee71f66da7dbfd9a5ea2db6974502ccff2065cdb76619840dca", + "sha256:348167f110494cfafae70c066470a6f4e4d43523933edf16ccdb8947f3b5fae0", + "sha256:3b1692755fef288b67af5cd8a973eb331d1f44cb02cbdc13660040809c2bfec6", + "sha256:3ca497cb25f19f24171f9172805f3ff135b911aeb91960bd4af8e230421ccb51", + "sha256:3d003a864899c29b0379e412709a6e516cbd6a72ee10b09d0b33226343617412", + "sha256:3fef595c4f573141d54a38bda9221b9ee3cbe0acc73d67304a1a6d5972eb2a02", + "sha256:484ac524e4615f06dc72ffbfd83f26e073c9ec256de5413634fbd024c010a8bc", + "sha256:55aeda6b6789b2d030066b4f5f6fc3596560ba2a69028f35f3682a795701b5b1", + "sha256:5a592363c93d6fc6472d5affe2819e1c7590746aecb464774a4f67e09fbefdfc", + "sha256:5b09dbe47bc4b4d45ffe56067aff190bc3c0049575da6e52127e114236e0a6a7", + "sha256:6e2a7aa9e36626fb48fdc341c7e3685a31a7b50ea4918677ea436271ad0d904d", + "sha256:70364e3cbef536adab8762b4835e18f5ca8e3fddd8bd0ec9258c42bbebd0ee77", + "sha256:720f5728e537f11a311e8b720793a224e985d20e6b7c3d34a891a391865af1a2", + "sha256:7284bdbc5579bbdc3fc8f869ed4c169f403835566ab0f84567cdbfdd05241847", + "sha256:7be1b66926277993cecdc174c15a20c8ce785c1f8b39aa560714a513eef06473", + "sha256:86d32a4498b74a75340497890a260d37bf1560ad2683969393032977dd36b088", + "sha256:878bc8ef4073e5cfb953dfc1cf4585db41e8b814c0106abde34d00ee0d0b3115", + "sha256:881104711900af45967c2e5ce3e62291dd57d5b2a224d58b7c9f60bf4ad41b8c", + "sha256:8c50ab9edaa5da5838426816a2b7bcde9d576b4fc50e6a8c062073dbc4969d78", + "sha256:8f6561f9cd5a452cb84905c6a87aa944fdfdc0f41cc057d03b71f9b29b2cc4bd", + "sha256:93336911544ebc0e466272043adab9fb9f6e9dcba6024b639c32553a3790e089", + "sha256:9447214e4857e16d14158794ef01e4501d8fad07d298d03308d9f90512df02fa", + "sha256:97c24ffc55de6013075979f440acd174e88819f30387074639fb7d7178ca253e", + "sha256:99f6cfb3e28490357a0805b409caf693e46c61f8dbb789c51355adb693c568d3", + "sha256:9be6c4039ef328676b868acea619cd100e3de1a35b3be211cf0eaf9775563b65", + "sha256:9d70257246b8207e8ef3d8b18457089f5ff0dfb087bd36eb33bce6584f2e0b3a", + "sha256:a777d48319d293b1b6a933d606c0e4899690a139b4c81173451913bbcab6f44f", + "sha256:add762163f4af7f4173fafa4092eb7c7f023cf139ef6d2015cfea867e1440d82", + "sha256:b6f64005ede008b7a866be8f3f6274dbf74e656e15e4004e9d99ad65efb01809", + "sha256:beb089c46bd95243d1ac5b2bd13627317b08bf40dd8dc16d4b7ee7ecb3cf65ca", + "sha256:c07163c9dcbb2eca377f366b1331f46302fd8b6b72ab4d603087feca00044bb0", + "sha256:c2fe692332c2f1d81fd27457db4b35143801475bfc2e57173a2403588dd82a42", + "sha256:ca8f89361e0e7aad0bf93ae03a31502e96280faeb7fb92267f4998fb230d36b2", + "sha256:d2ed4151445c3f30423c2698f72197d64b27b1cd61d8d56702ffe235584e47c2", + "sha256:db20597c4e67b4095b376ce2e83930c560f4ce481e8d05737885307ed02ba7c1", + "sha256:de972c7f4bc7b6002acff2a8de984c55fbd7f2289dba659cfd90f7a0f5d8f5d1", + "sha256:f1df1da204a9f0b5eb8393a46070f1d984fa8559435ee790d7f8f5602038fc00", + "sha256:f4d0a6d733a23865019b1c97ed6fb1fdb739be923192abf4dbb644f697a26a69", + "sha256:f874e9c2209dada1a080545331aa1277ec060a13f61684a8642788bf44b2325f", + "sha256:f877f53249c3e49bbd7612f9083127290bede6c7d6501513567ab1bf9c581381", + "sha256:f9d5815c0e85922cd0fb8344ca8b1c7cf020bf9fc45e670d34d51932c91fd7ec" + ], + "index": "pypi", + "version": "==1.1.8" }, "markdown-it-py": { "hashes": [ @@ -1956,44 +2113,44 @@ }, "matplotlib": { "hashes": [ - "sha256:03bbb3f5f78836855e127b5dab228d99551ad0642918ccbf3067fcd52ac7ac5e", - "sha256:24173c23d1bcbaed5bf47b8785d27933a1ac26a5d772200a0f3e0e38f471b001", - "sha256:2a0967d4156adbd0d46db06bc1a877f0370bce28d10206a5071f9ecd6dc60b79", - "sha256:2e8bda1088b941ead50caabd682601bece983cadb2283cafff56e8fcddbf7d7f", - "sha256:31fbc2af27ebb820763f077ec7adc79b5a031c2f3f7af446bd7909674cd59460", - "sha256:364e6bca34edc10a96aa3b1d7cd76eb2eea19a4097198c1b19e89bee47ed5781", - "sha256:3d8e129af95b156b41cb3be0d9a7512cc6d73e2b2109f82108f566dbabdbf377", - "sha256:44c6436868186564450df8fd2fc20ed9daaef5caad699aa04069e87099f9b5a8", - "sha256:48cf850ce14fa18067f2d9e0d646763681948487a8080ec0af2686468b4607a2", - "sha256:49a5938ed6ef9dda560f26ea930a2baae11ea99e1c2080c8714341ecfda72a89", - "sha256:4a05f2b37222319753a5d43c0a4fd97ed4ff15ab502113e3f2625c26728040cf", - "sha256:4a44cdfdb9d1b2f18b1e7d315eb3843abb097869cd1ef89cfce6a488cd1b5182", - "sha256:4fa28ca76ac5c2b2d54bc058b3dad8e22ee85d26d1ee1b116a6fd4d2277b6a04", - "sha256:5844cea45d804174bf0fac219b4ab50774e504bef477fc10f8f730ce2d623441", - "sha256:5a32ea6e12e80dedaca2d4795d9ed40f97bfa56e6011e14f31502fdd528b9c89", - "sha256:6c623b355d605a81c661546af7f24414165a8a2022cddbe7380a31a4170fa2e9", - "sha256:751d3815b555dcd6187ad35b21736dc12ce6925fc3fa363bbc6dc0f86f16484f", - "sha256:75c406c527a3aa07638689586343f4b344fcc7ab1f79c396699eb550cd2b91f7", - "sha256:77157be0fc4469cbfb901270c205e7d8adb3607af23cef8bd11419600647ceed", - "sha256:7d7705022df2c42bb02937a2a824f4ec3cca915700dd80dc23916af47ff05f1a", - "sha256:7f409716119fa39b03da3d9602bd9b41142fab7a0568758cd136cd80b1bf36c8", - "sha256:9480842d5aadb6e754f0b8f4ebeb73065ac8be1855baa93cd082e46e770591e9", - "sha256:9776e1a10636ee5f06ca8efe0122c6de57ffe7e8c843e0fb6e001e9d9256ec95", - "sha256:a91426ae910819383d337ba0dc7971c7cefdaa38599868476d94389a329e599b", - "sha256:b4fedaa5a9aa9ce14001541812849ed1713112651295fdddd640ea6620e6cf98", - "sha256:b6c63cd01cad0ea8704f1fd586e9dc5777ccedcd42f63cbbaa3eae8dd41172a1", - "sha256:b8d3f4e71e26307e8c120b72c16671d70c5cd08ae412355c11254aa8254fb87f", - "sha256:c4b82c2ae6d305fcbeb0eb9c93df2602ebd2f174f6e8c8a5d92f9445baa0c1d3", - "sha256:c772264631e5ae61f0bd41313bbe48e1b9bcc95b974033e1118c9caa1a84d5c6", - "sha256:c87973ddec10812bddc6c286b88fdd654a666080fbe846a1f7a3b4ba7b11ab78", - "sha256:e2b696699386766ef171a259d72b203a3c75d99d03ec383b97fc2054f52e15cf", - "sha256:ea75df8e567743207e2b479ba3d8843537be1c146d4b1e3e395319a4e1a77fe9", - "sha256:ebc27ad11df3c1661f4677a7762e57a8a91dd41b466c3605e90717c9a5f90c82", - "sha256:ee0b8e586ac07f83bb2950717e66cb305e2859baf6f00a9c39cc576e0ce9629c", - "sha256:ee175a571e692fc8ae8e41ac353c0e07259113f4cb063b0ec769eff9717e84bb" - ], - "index": "pypi", - "version": "==3.5.2" + "sha256:0bcdfcb0f976e1bac6721d7d457c17be23cf7501f977b6a38f9d38a3762841f7", + "sha256:1e64ac9be9da6bfff0a732e62116484b93b02a0b4d4b19934fb4f8e7ad26ad6a", + "sha256:22227c976ad4dc8c5a5057540421f0d8708c6560744ad2ad638d48e2984e1dbc", + "sha256:2886cc009f40e2984c083687251821f305d811d38e3df8ded414265e4583f0c5", + "sha256:2e6d184ebe291b9e8f7e78bbab7987d269c38ea3e062eace1fe7d898042ef804", + "sha256:3211ba82b9f1518d346f6309df137b50c3dc4421b4ed4815d1d7eadc617f45a1", + "sha256:339cac48b80ddbc8bfd05daae0a3a73414651a8596904c2a881cfd1edb65f26c", + "sha256:35a8ad4dddebd51f94c5d24bec689ec0ec66173bf614374a1244c6241c1595e0", + "sha256:3b4fa56159dc3c7f9250df88f653f085068bcd32dcd38e479bba58909254af7f", + "sha256:43e9d3fa077bf0cc95ded13d331d2156f9973dce17c6f0c8b49ccd57af94dbd9", + "sha256:57f1b4e69f438a99bb64d7f2c340db1b096b41ebaa515cf61ea72624279220ce", + "sha256:5c096363b206a3caf43773abebdbb5a23ea13faef71d701b21a9c27fdcef72f4", + "sha256:6bb93a0492d68461bd458eba878f52fdc8ac7bdb6c4acdfe43dba684787838c2", + "sha256:6ea6aef5c4338e58d8d376068e28f80a24f54e69f09479d1c90b7172bad9f25b", + "sha256:6fe807e8a22620b4cd95cfbc795ba310dc80151d43b037257250faf0bfcd82bc", + "sha256:73dd93dc35c85dece610cca8358003bf0760d7986f70b223e2306b4ea6d1406b", + "sha256:839d47b8ead7ad9669aaacdbc03f29656dc21f0d41a6fea2d473d856c39c8b1c", + "sha256:874df7505ba820e0400e7091199decf3ff1fde0583652120c50cd60d5820ca9a", + "sha256:879c7e5fce4939c6aa04581dfe08d57eb6102a71f2e202e3314d5fbc072fd5a0", + "sha256:94ff86af56a3869a4ae26a9637a849effd7643858a1a04dd5ee50e9ab75069a7", + "sha256:99482b83ebf4eb6d5fc6813d7aacdefdd480f0d9c0b52dcf9f1cc3b2c4b3361a", + "sha256:9ab29589cef03bc88acfa3a1490359000c18186fc30374d8aa77d33cc4a51a4a", + "sha256:9befa5954cdbc085e37d974ff6053da269474177921dd61facdad8023c4aeb51", + "sha256:a206a1b762b39398efea838f528b3a6d60cdb26fe9d58b48265787e29cd1d693", + "sha256:ab8d26f07fe64f6f6736d635cce7bfd7f625320490ed5bfc347f2cdb4fae0e56", + "sha256:b28de401d928890187c589036857a270a032961411934bdac4cf12dde3d43094", + "sha256:b428076a55fb1c084c76cb93e68006f27d247169f056412607c5c88828d08f88", + "sha256:bf618a825deb6205f015df6dfe6167a5d9b351203b03fab82043ae1d30f16511", + "sha256:c995f7d9568f18b5db131ab124c64e51b6820a92d10246d4f2b3f3a66698a15b", + "sha256:cd45a6f3e93a780185f70f05cf2a383daed13c3489233faad83e81720f7ede24", + "sha256:d2484b350bf3d32cae43f85dcfc89b3ed7bd2bcd781ef351f93eb6fb2cc483f9", + "sha256:d62880e1f60e5a30a2a8484432bcb3a5056969dc97258d7326ad465feb7ae069", + "sha256:dacddf5bfcec60e3f26ec5c0ae3d0274853a258b6c3fc5ef2f06a8eb23e042be", + "sha256:f3840c280ebc87a48488a46f760ea1c0c0c83fcf7abbe2e6baf99d033fd35fd8", + "sha256:f814504e459c68118bf2246a530ed953ebd18213dc20e3da524174d84ed010b2" + ], + "index": "pypi", + "version": "==3.5.3" }, "mdit-py-plugins": { "hashes": [ @@ -2005,11 +2162,11 @@ }, "mdurl": { "hashes": [ - "sha256:6a8f6804087b7128040b2fb2ebe242bdc2affaeaa034d5fc9feeed30b443651b", - "sha256:f79c9709944df218a4cdb0fcc0b0c7ead2f44594e3e84dc566606f04ad749c20" + "sha256:84008a41e51615a49fc9966191ff91509e3c40b939176e643fd50a5c2196b8f8", + "sha256:bb413d29f5eea38f31dd4754dd7377d4465116fb207585f97bf925588687c1ba" ], "markers": "python_version >= '3.7'", - "version": "==0.1.1" + "version": "==0.1.2" }, "mpld3": { "hashes": [ @@ -2021,32 +2178,32 @@ }, "mypy": { "hashes": [ - "sha256:006be38474216b833eca29ff6b73e143386f352e10e9c2fbe76aa8549e5554f5", - "sha256:03c6cc893e7563e7b2949b969e63f02c000b32502a1b4d1314cabe391aa87d66", - "sha256:0e9f70df36405c25cc530a86eeda1e0867863d9471fe76d1273c783df3d35c2e", - "sha256:1ece702f29270ec6af25db8cf6185c04c02311c6bb21a69f423d40e527b75c56", - "sha256:3e09f1f983a71d0672bbc97ae33ee3709d10c779beb613febc36805a6e28bb4e", - "sha256:439c726a3b3da7ca84a0199a8ab444cd8896d95012c4a6c4a0d808e3147abf5d", - "sha256:5a0b53747f713f490affdceef835d8f0cb7285187a6a44c33821b6d1f46ed813", - "sha256:5f1332964963d4832a94bebc10f13d3279be3ce8f6c64da563d6ee6e2eeda932", - "sha256:63e85a03770ebf403291ec50097954cc5caf2a9205c888ce3a61bd3f82e17569", - "sha256:64759a273d590040a592e0f4186539858c948302c653c2eac840c7a3cd29e51b", - "sha256:697540876638ce349b01b6786bc6094ccdaba88af446a9abb967293ce6eaa2b0", - "sha256:9940e6916ed9371809b35b2154baf1f684acba935cd09928952310fbddaba648", - "sha256:9f5f5a74085d9a81a1f9c78081d60a0040c3efb3f28e5c9912b900adf59a16e6", - "sha256:a5ea0875a049de1b63b972456542f04643daf320d27dc592d7c3d9cd5d9bf950", - "sha256:b117650592e1782819829605a193360a08aa99f1fc23d1d71e1a75a142dc7e15", - "sha256:b24be97351084b11582fef18d79004b3e4db572219deee0212078f7cf6352723", - "sha256:b88f784e9e35dcaa075519096dc947a388319cb86811b6af621e3523980f1c8a", - "sha256:bdd5ca340beffb8c44cb9dc26697628d1b88c6bddf5c2f6eb308c46f269bb6f3", - "sha256:d5aaf1edaa7692490f72bdb9fbd941fbf2e201713523bdb3f4038be0af8846c6", - "sha256:e999229b9f3198c0c880d5e269f9f8129c8862451ce53a011326cad38b9ccd24", - "sha256:f4a21d01fc0ba4e31d82f0fff195682e29f9401a8bdb7173891070eb260aeb3b", - "sha256:f4b794db44168a4fc886e3450201365c9526a522c46ba089b55e1f11c163750d", - "sha256:f730d56cb924d371c26b8eaddeea3cc07d78ff51c521c6d04899ac6904b75492" - ], - "index": "pypi", - "version": "==0.961" + "sha256:02ef476f6dcb86e6f502ae39a16b93285fef97e7f1ff22932b657d1ef1f28655", + "sha256:0d054ef16b071149917085f51f89555a576e2618d5d9dd70bd6eea6410af3ac9", + "sha256:19830b7dba7d5356d3e26e2427a2ec91c994cd92d983142cbd025ebe81d69cf3", + "sha256:1f7656b69974a6933e987ee8ffb951d836272d6c0f81d727f1d0e2696074d9e6", + "sha256:23488a14a83bca6e54402c2e6435467a4138785df93ec85aeff64c6170077fb0", + "sha256:23c7ff43fff4b0df93a186581885c8512bc50fc4d4910e0f838e35d6bb6b5e58", + "sha256:25c5750ba5609a0c7550b73a33deb314ecfb559c350bb050b655505e8aed4103", + "sha256:2ad53cf9c3adc43cf3bea0a7d01a2f2e86db9fe7596dfecb4496a5dda63cbb09", + "sha256:3fa7a477b9900be9b7dd4bab30a12759e5abe9586574ceb944bc29cddf8f0417", + "sha256:40b0f21484238269ae6a57200c807d80debc6459d444c0489a102d7c6a75fa56", + "sha256:4b21e5b1a70dfb972490035128f305c39bc4bc253f34e96a4adf9127cf943eb2", + "sha256:5a361d92635ad4ada1b1b2d3630fc2f53f2127d51cf2def9db83cba32e47c856", + "sha256:77a514ea15d3007d33a9e2157b0ba9c267496acf12a7f2b9b9f8446337aac5b0", + "sha256:855048b6feb6dfe09d3353466004490b1872887150c5bb5caad7838b57328cc8", + "sha256:9796a2ba7b4b538649caa5cecd398d873f4022ed2333ffde58eaf604c4d2cb27", + "sha256:98e02d56ebe93981c41211c05adb630d1d26c14195d04d95e49cd97dbc046dc5", + "sha256:b793b899f7cf563b1e7044a5c97361196b938e92f0a4343a5d27966a53d2ec71", + "sha256:d1ea5d12c8e2d266b5fb8c7a5d2e9c0219fedfeb493b7ed60cd350322384ac27", + "sha256:d2022bfadb7a5c2ef410d6a7c9763188afdb7f3533f22a0a32be10d571ee4bbe", + "sha256:d3348e7eb2eea2472db611486846742d5d52d1290576de99d59edeb7cd4a42ca", + "sha256:d744f72eb39f69312bc6c2abf8ff6656973120e2eb3f3ec4f758ed47e414a4bf", + "sha256:ef943c72a786b0f8d90fd76e9b39ce81fb7171172daf84bf43eaf937e9f220a9", + "sha256:f2899a3cbd394da157194f913a931edfd4be5f274a88041c9dc2d9cdcb1c315c" + ], + "index": "pypi", + "version": "==0.971" }, "mypy-extensions": { "hashes": [ @@ -2081,31 +2238,37 @@ }, "numpy": { "hashes": [ - "sha256:092f5e6025813e64ad6d1b52b519165d08c730d099c114a9247c9bb635a2a450", - "sha256:196cd074c3f97c4121601790955f915187736f9cf458d3ee1f1b46aff2b1ade0", - "sha256:1c29b44905af288b3919803aceb6ec7fec77406d8b08aaa2e8b9e63d0fe2f160", - "sha256:2b2da66582f3a69c8ce25ed7921dcd8010d05e59ac8d89d126a299be60421171", - "sha256:5043bcd71fcc458dfb8a0fc5509bbc979da0131b9d08e3d5f50fb0bbb36f169a", - "sha256:58bfd40eb478f54ff7a5710dd61c8097e169bc36cc68333d00a9bcd8def53b38", - "sha256:79a506cacf2be3a74ead5467aee97b81fca00c9c4c8b3ba16dbab488cd99ba10", - "sha256:94b170b4fa0168cd6be4becf37cb5b127bd12a795123984385b8cd4aca9857e5", - "sha256:97a76604d9b0e79f59baeca16593c711fddb44936e40310f78bfef79ee9a835f", - "sha256:98e8e0d8d69ff4d3fa63e6c61e8cfe2d03c29b16b58dbef1f9baa175bbed7860", - "sha256:ac86f407873b952679f5f9e6c0612687e51547af0e14ddea1eedfcb22466babd", - "sha256:ae8adff4172692ce56233db04b7ce5792186f179c415c37d539c25de7298d25d", - "sha256:bd3fa4fe2e38533d5336e1272fc4e765cabbbde144309ccee8675509d5cd7b05", - "sha256:d0d2094e8f4d760500394d77b383a1b06d3663e8892cdf5df3c592f55f3bff66", - "sha256:d54b3b828d618a19779a84c3ad952e96e2c2311b16384e973e671aa5be1f6187", - "sha256:d6ca8dabe696c2785d0c8c9b0d8a9b6e5fdbe4f922bde70d57fa1a2848134f95", - "sha256:d8cc87bed09de55477dba9da370c1679bd534df9baa171dd01accbb09687dac3", - "sha256:f0f18804df7370571fb65db9b98bf1378172bd4e962482b857e612d1fec0f53e", - "sha256:f1d88ef79e0a7fa631bb2c3dda1ea46b32b1fe614e10fedd611d3d5398447f2f", - "sha256:f9c3fc2adf67762c9fe1849c859942d23f8d3e0bee7b5ed3d4a9c3eeb50a2f07", - "sha256:fc431493df245f3c627c0c05c2bd134535e7929dbe2e602b80e42bf52ff760bc", - "sha256:fe8b9683eb26d2c4d5db32cd29b38fdcf8381324ab48313b5b69088e0e355379" - ], - "index": "pypi", - "version": "==1.23.0" + "sha256:17e5226674f6ea79e14e3b91bfbc153fdf3ac13f5cc54ee7bc8fdbe820a32da0", + "sha256:2bd879d3ca4b6f39b7770829f73278b7c5e248c91d538aab1e506c628353e47f", + "sha256:4f41f5bf20d9a521f8cab3a34557cd77b6f205ab2116651f12959714494268b0", + "sha256:5593f67e66dea4e237f5af998d31a43e447786b2154ba1ad833676c788f37cde", + "sha256:5e28cd64624dc2354a349152599e55308eb6ca95a13ce6a7d5679ebff2962913", + "sha256:633679a472934b1c20a12ed0c9a6c9eb167fbb4cb89031939bfd03dd9dbc62b8", + "sha256:806970e69106556d1dd200e26647e9bee5e2b3f1814f9da104a943e8d548ca38", + "sha256:806cc25d5c43e240db709875e947076b2826f47c2c340a5a2f36da5bb10c58d6", + "sha256:8247f01c4721479e482cc2f9f7d973f3f47810cbc8c65e38fd1bbd3141cc9842", + "sha256:8ebf7e194b89bc66b78475bd3624d92980fca4e5bb86dda08d677d786fefc414", + "sha256:8ecb818231afe5f0f568c81f12ce50f2b828ff2b27487520d85eb44c71313b9e", + "sha256:8f9d84a24889ebb4c641a9b99e54adb8cab50972f0166a3abc14c3b93163f074", + "sha256:909c56c4d4341ec8315291a105169d8aae732cfb4c250fbc375a1efb7a844f8f", + "sha256:9b83d48e464f393d46e8dd8171687394d39bc5abfe2978896b77dc2604e8635d", + "sha256:ac987b35df8c2a2eab495ee206658117e9ce867acf3ccb376a19e83070e69418", + "sha256:b78d00e48261fbbd04aa0d7427cf78d18401ee0abd89c7559bbf422e5b1c7d01", + "sha256:b8b97a8a87cadcd3f94659b4ef6ec056261fa1e1c3317f4193ac231d4df70215", + "sha256:bd5b7ccae24e3d8501ee5563e82febc1771e73bd268eef82a1e8d2b4d556ae66", + "sha256:bdc02c0235b261925102b1bd586579b7158e9d0d07ecb61148a1799214a4afd5", + "sha256:be6b350dfbc7f708d9d853663772a9310783ea58f6035eec649fb9c4371b5389", + "sha256:c403c81bb8ffb1c993d0165a11493fd4bf1353d258f6997b3ee288b0a48fce77", + "sha256:cf8c6aed12a935abf2e290860af8e77b26a042eb7f2582ff83dc7ed5f963340c", + "sha256:d98addfd3c8728ee8b2c49126f3c44c703e2b005d4a95998e2167af176a9e722", + "sha256:dc76bca1ca98f4b122114435f83f1fcf3c0fe48e4e6f660e07996abf2f53903c", + "sha256:dec198619b7dbd6db58603cd256e092bcadef22a796f778bf87f8592b468441d", + "sha256:df28dda02c9328e122661f399f7655cdcbcf22ea42daa3650a26bce08a187450", + "sha256:e603ca1fb47b913942f3e660a15e55a9ebca906857edfea476ae5f0fe9b457d5", + "sha256:ecfdd68d334a6b97472ed032b5b37a30d8217c097acfff15e8452c710e775524" + ], + "index": "pypi", + "version": "==1.23.2" }, "opencv-python-headless": { "hashes": [ @@ -2260,11 +2423,11 @@ }, "pre-commit": { "hashes": [ - "sha256:10c62741aa5704faea2ad69cb550ca78082efe5697d6f04e5710c3c229afdd10", - "sha256:4233a1e38621c87d9dda9808c6606d7e7ba0e087cd56d3fe03202a01d2919615" + "sha256:51a5ba7c480ae8072ecdb6933df22d2f812dc897d5fe848778116129a681aac7", + "sha256:a978dac7bc9ec0bcee55c18a277d553b0f419d259dadb4b9418ff2d00eb43959" ], "index": "pypi", - "version": "==2.19.0" + "version": "==2.20.0" }, "py": { "hashes": [ @@ -2354,11 +2517,11 @@ }, "pygments": { "hashes": [ - "sha256:5eb116118f9612ff1ee89ac96437bb6b49e8f04d8a13b514ba26f620208e26eb", - "sha256:dc9c10fb40944260f6ed4c688ece0cd2048414940f1cea51b8b226318411c519" + "sha256:56a8508ae95f98e2b9bdf93a6be5ae3f7d8af858b43e02c5a2ff083726be40c1", + "sha256:f643f331ab57ba3c9d89212ee4a2dabc6e94f117cf4eefde99a0574720d14c42" ], "markers": "python_version >= '3.6'", - "version": "==2.12.0" + "version": "==2.13.0" }, "pynacl": { "hashes": [ @@ -2425,10 +2588,10 @@ }, "pytz": { "hashes": [ - "sha256:1e760e2fe6a8163bc0b3d9a19c4f84342afa0a2affebfaa84b01b978a02ecaa7", - "sha256:e68985985296d9a66a881eb3193b0906246245294a881e7c8afe623866ac6a5c" + "sha256:220f481bdafa09c3955dfbdddb7b57780e9a94f5127e35456a48589b9e0c0197", + "sha256:cea221417204f2d1a2aa03ddae3e867921971d0d76f14d87abb4414415bbdcf5" ], - "version": "==2022.1" + "version": "==2022.2.1" }, "pyyaml": { "hashes": [ @@ -2486,40 +2649,40 @@ }, "scipy": { "hashes": [ - "sha256:02b567e722d62bddd4ac253dafb01ce7ed8742cf8031aea030a41414b86c1125", - "sha256:1166514aa3bbf04cb5941027c6e294a000bba0cf00f5cdac6c77f2dad479b434", - "sha256:1da52b45ce1a24a4a22db6c157c38b39885a990a566748fc904ec9f03ed8c6ba", - "sha256:23b22fbeef3807966ea42d8163322366dd89da9bebdc075da7034cee3a1441ca", - "sha256:28d2cab0c6ac5aa131cc5071a3a1d8e1366dad82288d9ec2ca44df78fb50e649", - "sha256:2ef0fbc8bcf102c1998c1f16f15befe7cffba90895d6e84861cd6c6a33fb54f6", - "sha256:3b69b90c9419884efeffaac2c38376d6ef566e6e730a231e15722b0ab58f0328", - "sha256:4b93ec6f4c3c4d041b26b5f179a6aab8f5045423117ae7a45ba9710301d7e462", - "sha256:4e53a55f6a4f22de01ffe1d2f016e30adedb67a699a310cdcac312806807ca81", - "sha256:6311e3ae9cc75f77c33076cb2794fb0606f14c8f1b1c9ff8ce6005ba2c283621", - "sha256:65b77f20202599c51eb2771d11a6b899b97989159b7975e9b5259594f1d35ef4", - "sha256:6cc6b33139eb63f30725d5f7fa175763dc2df6a8f38ddf8df971f7c345b652dc", - "sha256:70de2f11bf64ca9921fda018864c78af7147025e467ce9f4a11bc877266900a6", - "sha256:70ebc84134cf0c504ce6a5f12d6db92cb2a8a53a49437a6bb4edca0bc101f11c", - "sha256:83606129247e7610b58d0e1e93d2c5133959e9cf93555d3c27e536892f1ba1f2", - "sha256:93d07494a8900d55492401917a119948ed330b8c3f1d700e0b904a578f10ead4", - "sha256:9c4e3ae8a716c8b3151e16c05edb1daf4cb4d866caa385e861556aff41300c14", - "sha256:9dd4012ac599a1e7eb63c114d1eee1bcfc6dc75a29b589ff0ad0bb3d9412034f", - "sha256:9e3fb1b0e896f14a85aa9a28d5f755daaeeb54c897b746df7a55ccb02b340f33", - "sha256:a0aa8220b89b2e3748a2836fbfa116194378910f1a6e78e4675a095bcd2c762d", - "sha256:d3b3c8924252caaffc54d4a99f1360aeec001e61267595561089f8b5900821bb", - "sha256:e013aed00ed776d790be4cb32826adb72799c61e318676172495383ba4570aa4", - "sha256:f3e7a8867f307e3359cc0ed2c63b61a1e33a19080f92fe377bc7d49f646f2ec1" - ], - "index": "pypi", - "version": "==1.8.1" + "sha256:0419485dbcd0ed78c0d5bf234c5dd63e86065b39b4d669e45810d42199d49521", + "sha256:09412eb7fb60b8f00b328037fd814d25d261066ebc43a1e339cdce4f7502877e", + "sha256:26d28c468900e6d5fdb37d2812ab46db0ccd22c63baa095057871faa3a498bc9", + "sha256:34441dfbee5b002f9e15285014fd56e5e3372493c3e64ae297bae2c4b9659f5a", + "sha256:39ab9240cd215a9349c85ab908dda6d732f7d3b4b192fa05780812495536acc4", + "sha256:3bc1ab68b9a096f368ba06c3a5e1d1d50957a86665fc929c4332d21355e7e8f4", + "sha256:3c6f5d1d4b9a5e4fe5e14f26ffc9444fc59473bbf8d45dc4a9a15283b7063a72", + "sha256:47d1a95bd9d37302afcfe1b84c8011377c4f81e33649c5a5785db9ab827a6ade", + "sha256:71487c503e036740635f18324f62a11f283a632ace9d35933b2b0a04fd898c98", + "sha256:7a412c476a91b080e456229e413792bbb5d6202865dae963d1e6e28c2bb58691", + "sha256:825951b88f56765aeb6e5e38ac9d7d47407cfaaeb008d40aa1b45a2d7ea2731e", + "sha256:8cc81ac25659fec73599ccc52c989670e5ccd8974cf34bacd7b54a8d809aff1a", + "sha256:8d3faa40ac16c6357aaf7ea50394ea6f1e8e99d75e927a51102b1943b311b4d9", + "sha256:90c805f30c46cf60f1e76e947574f02954d25e3bb1e97aa8a07bc53aa31cf7d1", + "sha256:96d7cf7b25c9f23c59a766385f6370dab0659741699ecc7a451f9b94604938ce", + "sha256:b97b479f39c7e4aaf807efd0424dec74bbb379108f7d22cf09323086afcd312c", + "sha256:bc4e2c77d4cd015d739e75e74ebbafed59ba8497a7ed0fd400231ed7683497c4", + "sha256:c61b4a91a702e8e04aeb0bfc40460e1f17a640977c04dda8757efb0199c75332", + "sha256:d79da472015d0120ba9b357b28a99146cd6c17b9609403164b1a8ed149b4dfc8", + "sha256:e8fe305d9d67a81255e06203454729405706907dccbdfcc330b7b3482a6c371d", + "sha256:eb954f5aca4d26f468bbebcdc5448348eb287f7bea536c6306f62ea062f63d9a", + "sha256:f7c39f7dbb57cce00c108d06d731f3b0e2a4d3a95c66d96bce697684876ce4d4", + "sha256:f950a04b33e17b38ff561d5a0951caf3f5b47caa841edd772ffb7959f20a6af0" + ], + "index": "pypi", + "version": "==1.9.1" }, "setuptools": { "hashes": [ - "sha256:16923d366ced322712c71ccb97164d07472abeecd13f3a6c283f6d5d26722793", - "sha256:db3b8e2f922b2a910a29804776c643ea609badb6a32c4bcc226fd4fd902cce65" + "sha256:2e24e0bec025f035a2e72cdd1961119f557d78ad331bb00ff82efb2ab8da8e82", + "sha256:7732871f4f7fa58fb6bdcaeadb0161b2bd046c85905dbaa066bdcbcc81953b57" ], "markers": "python_version >= '3.7'", - "version": "==63.1.0" + "version": "==65.3.0" }, "six": { "hashes": [ @@ -2545,11 +2708,11 @@ }, "sphinx": { "hashes": [ - "sha256:b18e978ea7565720f26019c702cd85c84376e948370f1cd43d60265010e1c7b0", - "sha256:d3e57663eed1d7c5c50895d191fdeda0b54ded6f44d5621b50709466c338d1e8" + "sha256:309a8da80cb6da9f4713438e5b55861877d5d7976b69d87e336733637ea12693", + "sha256:ba3224a4e206e1fbdecf98a4fae4992ef9b24b85ebf7b584bb340156eaf08d89" ], "index": "pypi", - "version": "==5.0.2" + "version": "==5.1.1" }, "sphinx-rtd-theme": { "hashes": [ @@ -2661,32 +2824,32 @@ "sha256:25642c956049920a5aa49edcdd6ab1e06d7e5d467fc00e0506c44ac86fbfca02", "sha256:e6d2677a32f47fc7eb2795db1dd15c1f34eff616bcaf2cfb5e997f854fa1c4a6" ], - "markers": "python_version >= '3.7'", + "markers": "python_version < '3.10'", "version": "==4.3.0" }, "urllib3": { "hashes": [ - "sha256:8298d6d56d39be0e3bc13c1c97d133f9b45d797169a0e11cdd0e0489d786f7ec", - "sha256:879ba4d1e89654d9769ce13121e0f94310ea32e8d2f8cf587b77c08bbcdb30d6" + "sha256:3fa96cf423e6987997fc326ae8df396db2a8b7c667747d47ddd8ecba91f4a74e", + "sha256:b930dd878d5a8afb066a637fbb35144fe7901e3b209d1cd4f524bd0e9deee997" ], "index": "pypi", - "version": "==1.26.10" + "version": "==1.26.12" }, "virtualenv": { "hashes": [ - "sha256:288171134a2ff3bfb1a2f54f119e77cd1b81c29fc1265a2356f3e8d14c7d58c4", - "sha256:b30aefac647e86af6d82bfc944c556f8f1a9c90427b2fb4e3bfbf338cb82becf" + "sha256:4193b7bc8a6cd23e4eb251ac64f29b4398ab2c233531e66e40b19a6b7b0d30c1", + "sha256:d86ea0bb50e06252d79e6c241507cb904fcd66090c3271381372d6221a3970f9" ], - "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3, 3.4'", - "version": "==20.15.1" + "markers": "python_version >= '3.6'", + "version": "==20.16.3" }, "zipp": { "hashes": [ - "sha256:56bf8aadb83c24db6c4b577e13de374ccfb67da2078beba1d037c17980bf43ad", - "sha256:c4f6e5bbf48e74f7a38e7cc5b0480ff42b0ae5178957d564d18932525d5cf099" + "sha256:05b45f1ee8f807d0cc928485ca40a07cb491cf092ff587c0df9cb1fd154848d2", + "sha256:47c40d7fe183a6f21403a199b3e4192cca5774656965b0a4988ad2f8feb5f009" ], "markers": "python_version >= '3.7'", - "version": "==3.8.0" + "version": "==3.8.1" } } } diff --git a/selfdrive/athena/tests/helpers.py b/selfdrive/athena/tests/helpers.py index bb5fcd106..071393cb1 100644 --- a/selfdrive/athena/tests/helpers.py +++ b/selfdrive/athena/tests/helpers.py @@ -116,7 +116,7 @@ def with_http_server(func): with Timeout(2, 'HTTP Server seeding failed'): while True: try: - requests.put(f'http://{host}:{port}/qlog.bz2', data='') + requests.put(f'http://{host}:{port}/qlog.bz2', data='', timeout=10) break except requests.exceptions.ConnectionError: time.sleep(0.1) diff --git a/selfdrive/navd/navd.py b/selfdrive/navd/navd.py index ee5425207..72874b211 100755 --- a/selfdrive/navd/navd.py +++ b/selfdrive/navd/navd.py @@ -135,7 +135,7 @@ class RouteEngine: url = self.mapbox_host + f'/directions/v5/mapbox/driving-traffic/{self.last_position.longitude},{self.last_position.latitude};{destination.longitude},{destination.latitude}' try: - resp = requests.get(url, params=params) + resp = requests.get(url, params=params, timeout=10) resp.raise_for_status() r = resp.json() diff --git a/selfdrive/ui/translations/create_badges.py b/selfdrive/ui/translations/create_badges.py index 451fbb23e..32904f242 100755 --- a/selfdrive/ui/translations/create_badges.py +++ b/selfdrive/ui/translations/create_badges.py @@ -30,7 +30,7 @@ if __name__ == "__main__": percent_finished = int(100 - (unfinished_translations / total_translations * 100.)) color = "green" if percent_finished == 100 else "orange" if percent_finished >= 70 else "red" - r = requests.get(f"https://img.shields.io/badge/LANGUAGE {name}-{percent_finished}%25 complete-{color}") + r = requests.get(f"https://img.shields.io/badge/LANGUAGE {name}-{percent_finished}%25 complete-{color}", timeout=10) assert r.status_code == 200, "Error downloading badge" content_svg = r.content.decode("utf-8") diff --git a/system/hardware/tici/agnos.py b/system/hardware/tici/agnos.py index 9a1759e99..51998bf8b 100755 --- a/system/hardware/tici/agnos.py +++ b/system/hardware/tici/agnos.py @@ -20,7 +20,7 @@ class StreamingDecompressor: def __init__(self, url: str) -> None: self.buf = b"" - self.req = requests.get(url, stream=True, headers={'Accept-Encoding': None}) # type: ignore + self.req = requests.get(url, stream=True, headers={'Accept-Encoding': None}) # type: ignore # pylint: disable=missing-timeout self.it = self.req.iter_content(chunk_size=1024 * 1024) self.decompressor = lzma.LZMADecompressor(format=lzma.FORMAT_AUTO) self.eof = False diff --git a/system/hardware/tici/test_agnos_updater.py b/system/hardware/tici/test_agnos_updater.py index 9f188b83d..e0d6ed881 100755 --- a/system/hardware/tici/test_agnos_updater.py +++ b/system/hardware/tici/test_agnos_updater.py @@ -15,7 +15,7 @@ class TestAgnosUpdater(unittest.TestCase): m = json.load(f) for img in m: - r = requests.head(img['url']) + r = requests.head(img['url'], timeout=10) r.raise_for_status() self.assertEqual(r.headers['Content-Type'], "application/x-xz") if not img['sparse']: diff --git a/system/hardware/tici/tests/compare_casync_manifest.py b/system/hardware/tici/tests/compare_casync_manifest.py index 5e5fa2455..b462e93eb 100755 --- a/system/hardware/tici/tests/compare_casync_manifest.py +++ b/system/hardware/tici/tests/compare_casync_manifest.py @@ -17,7 +17,7 @@ def get_chunk_download_size(chunk): if os.path.isfile(path): return os.path.getsize(path) else: - r = requests.head(path) + r = requests.head(path, timeout=10) r.raise_for_status() return int(r.headers['content-length']) diff --git a/tools/joystick/joystickd.py b/tools/joystick/joystickd.py index 35ecca351..8374cf8a7 100755 --- a/tools/joystick/joystickd.py +++ b/tools/joystick/joystickd.py @@ -77,7 +77,7 @@ def send_thread(joystick): print('\n' + ', '.join(f'{name}: {round(v, 3)}' for name, v in joystick.axes_values.items())) if "WEB" in os.environ: import requests - requests.get("http://"+os.environ["WEB"]+":5000/control/%f/%f" % tuple([joystick.axes_values[a] for a in joystick.axes_order][::-1])) + requests.get("http://"+os.environ["WEB"]+":5000/control/%f/%f" % tuple([joystick.axes_values[a] for a in joystick.axes_order][::-1]), timeout=None) rk.keep_time() def joystick_thread(use_keyboard): diff --git a/tools/lib/tests/test_readers.py b/tools/lib/tests/test_readers.py index c982459f9..6efa0dc35 100755 --- a/tools/lib/tests/test_readers.py +++ b/tools/lib/tests/test_readers.py @@ -21,7 +21,7 @@ class TestReaders(unittest.TestCase): self.assertEqual(hist['logMessage'], 6857) with tempfile.NamedTemporaryFile(suffix=".bz2") as fp: - r = requests.get("https://github.com/commaai/comma2k19/blob/master/Example_1/b0c9d2329ad1606b%7C2018-08-02--08-34-47/40/raw_log.bz2?raw=true") + r = requests.get("https://github.com/commaai/comma2k19/blob/master/Example_1/b0c9d2329ad1606b%7C2018-08-02--08-34-47/40/raw_log.bz2?raw=true", timeout=10) fp.write(r.content) fp.flush() @@ -53,7 +53,7 @@ class TestReaders(unittest.TestCase): assert np.all(frame_first_30[15] == frame_15[0]) with tempfile.NamedTemporaryFile(suffix=".hevc") as fp: - r = requests.get("https://github.com/commaai/comma2k19/blob/master/Example_1/b0c9d2329ad1606b%7C2018-08-02--08-34-47/40/video.hevc?raw=true") + r = requests.get("https://github.com/commaai/comma2k19/blob/master/Example_1/b0c9d2329ad1606b%7C2018-08-02--08-34-47/40/video.hevc?raw=true", timeout=10) fp.write(r.content) fp.flush() diff --git a/tools/plotjuggler/juggle.py b/tools/plotjuggler/juggle.py index e3d0aec59..b7c32d9bf 100755 --- a/tools/plotjuggler/juggle.py +++ b/tools/plotjuggler/juggle.py @@ -37,7 +37,7 @@ def install(): os.mkdir(INSTALL_DIR) url = os.path.join(RELEASES_URL, m + ".tar.gz") - with requests.get(url, stream=True) as r, tempfile.NamedTemporaryFile() as tmp: + with requests.get(url, stream=True, timeout=10) as r, tempfile.NamedTemporaryFile() as tmp: r.raise_for_status() with open(tmp.name, 'wb') as tmpf: for chunk in r.iter_content(chunk_size=1024*1024): diff --git a/tools/scripts/fetch_image_from_route.py b/tools/scripts/fetch_image_from_route.py index 39751ba55..139373f66 100755 --- a/tools/scripts/fetch_image_from_route.py +++ b/tools/scripts/fetch_image_from_route.py @@ -18,7 +18,7 @@ segment = int(sys.argv[2]) frame = int(sys.argv[3]) url = 'https://api.commadotai.com/v1/route/'+sys.argv[1]+"/files" -r = requests.get(url, headers={"Authorization": "JWT "+jwt}) +r = requests.get(url, headers={"Authorization": "JWT "+jwt}, timeout=10) assert r.status_code == 200 print("got api response") diff --git a/tools/scripts/setup_ssh_keys.py b/tools/scripts/setup_ssh_keys.py index 5b5ebfbac..b6d448673 100755 --- a/tools/scripts/setup_ssh_keys.py +++ b/tools/scripts/setup_ssh_keys.py @@ -11,7 +11,7 @@ if __name__ == "__main__": exit(1) username = sys.argv[1] - keys = requests.get(f"https://github.com/{username}.keys") + keys = requests.get(f"https://github.com/{username}.keys", timeout=10) if keys.status_code == 200: Params().put("GithubSshKeys", keys.text) diff --git a/update_requirements.sh b/update_requirements.sh index 719a28c35..060dca76e 100755 --- a/update_requirements.sh +++ b/update_requirements.sh @@ -44,6 +44,7 @@ pip install pip==21.3.1 pip install pipenv==2021.11.23 if [ -d "./xx" ]; then + echo "WARNING: using xx Pipfile ******" export PIPENV_SYSTEM=1 export PIPENV_PIPFILE=./xx/Pipfile fi @@ -56,7 +57,8 @@ else fi echo "pip packages install..." -pipenv install --dev --deploy --clear +pipenv sync --dev +pipenv --clear pyenv rehash echo "pre-commit hooks install..." From 452d5e42ecf963fee65889937662c708f5e17474 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 30 Aug 2022 17:54:40 -0700 Subject: [PATCH 115/172] Car docs: add auto-resume column (#25572) * Move auto resume in sng to car interface * Update docs * shorter name, star * order * resumes? * add hidden detail sentence * good to know this works, but revert * VW auto resume * bump cereal to master * Update ref_commit * match cereal * try this * ? ? * like this --- cereal | 2 +- docs/CARS.md | 414 +++++++++++------------ selfdrive/car/docs_definitions.py | 8 +- selfdrive/car/gm/interface.py | 1 + selfdrive/car/interfaces.py | 5 +- selfdrive/car/nissan/interface.py | 1 + selfdrive/car/subaru/interface.py | 1 + selfdrive/car/toyota/interface.py | 1 + selfdrive/car/volkswagen/interface.py | 1 + selfdrive/test/process_replay/ref_commit | 2 +- 10 files changed, 221 insertions(+), 215 deletions(-) diff --git a/cereal b/cereal index c4cc38c46..aaf67ac78 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit c4cc38c4689b5e06be1cbfbb26c0463c377c0a6d +Subproject commit aaf67ac782c833fec2c14a11a6cf99a659080d11 diff --git a/docs/CARS.md b/docs/CARS.md index 78b4d3b16..aa7b5ecc5 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -6,213 +6,213 @@ A supported vehicle is one that just works when you install a comma three. All s # 205 Supported Cars -|Make|Model|Supported Package|ACC|No ACC accel below|No ALC below|Steering Torque|Harness| -|---|---|---|:---:|:---:|:---:|:---:|:---:| -|Acura|ILX 2016-19|AcuraWatch Plus|openpilot|25 mph|25 mph|[![star](assets/icon-star-empty.svg)](##)|Honda Nidec| -|Acura|RDX 2016-18|AcuraWatch Plus|openpilot|25 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|Honda Nidec| -|Acura|RDX 2019-22|All|Stock|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|Honda Bosch A| -|Audi|A3 2014-19|ACC + Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| -|Audi|A3 Sportback e-tron 2017-18|ACC + Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| -|Audi|Q2 2018|ACC + Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| -|Audi|Q3 2020-21|ACC + Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| -|Audi|RS3 2018|ACC + Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| -|Audi|S3 2015-17|ACC + Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| -|Cadillac|Escalade ESV 2016[1](#footnotes)|Adaptive Cruise Control (ACC) & LKAS|openpilot|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|OBD-II| -|Chevrolet|Bolt EUV 2022-23|Premier or Premier Redline Trim without Super Cruise Package|Stock|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|GM| -|Chevrolet|Silverado 1500 2020-21|Safety Package II|Stock|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|GM| -|Chevrolet|Volt 2017-18[1](#footnotes)|Adaptive Cruise Control|openpilot|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|OBD-II| -|Chrysler|Pacifica 2017-18|Adaptive Cruise Control|Stock|0 mph|9 mph|[![star](assets/icon-star-full.svg)](##)|FCA| -|Chrysler|Pacifica 2019-20|Adaptive Cruise Control|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|FCA| -|Chrysler|Pacifica 2021|All|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|FCA| -|Chrysler|Pacifica Hybrid 2017-18|Adaptive Cruise Control|Stock|0 mph|9 mph|[![star](assets/icon-star-full.svg)](##)|FCA| -|Chrysler|Pacifica Hybrid 2019-22|Adaptive Cruise Control|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|FCA| -|comma|body|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|None| -|Genesis|G70 2018-19|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai F| -|Genesis|G70 2020|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai F| -|Genesis|G80 2017-19|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai H| -|Genesis|G90 2017-18|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai C| -|GMC|Acadia 2018[1](#footnotes)|Adaptive Cruise Control|openpilot|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|OBD-II| -|GMC|Sierra 1500 2020-21|Driver Alert Package II|Stock|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|GM| -|Honda|Accord 2018-22|All|Stock|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|Honda Bosch A| -|Honda|Accord Hybrid 2018-22|All|Stock|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|Honda Bosch A| -|Honda|Civic 2016-18|Honda Sensing|openpilot|0 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|Honda Nidec| -|Honda|Civic 2019-21|All|Stock|0 mph|2 mph[2](#footnotes)|[![star](assets/icon-star-empty.svg)](##)|Honda Bosch A| -|Honda|Civic 2022|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Honda Bosch B| -|Honda|Civic Hatchback 2017-21|Honda Sensing|Stock|0 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|Honda Bosch A| -|Honda|Civic Hatchback 2022|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Honda Bosch B| -|Honda|CR-V 2015-16|Touring Trim|openpilot|25 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|Honda Nidec| -|Honda|CR-V 2017-22|Honda Sensing|Stock|0 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|Honda Bosch A| -|Honda|CR-V Hybrid 2017-19|Honda Sensing|Stock|0 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|Honda Bosch A| -|Honda|e 2020|All|Stock|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|Honda Bosch A| -|Honda|Fit 2018-20|Honda Sensing|openpilot|25 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|Honda Nidec| -|Honda|Freed 2020|Honda Sensing|openpilot|25 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|Honda Nidec| -|Honda|HR-V 2019-22|Honda Sensing|openpilot|25 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|Honda Nidec| -|Honda|Insight 2019-22|All|Stock|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|Honda Bosch A| -|Honda|Inspire 2018|All|Stock|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|Honda Bosch A| -|Honda|Odyssey 2018-20|Honda Sensing|openpilot|25 mph|0 mph|[![star](assets/icon-star-empty.svg)](##)|Honda Nidec| -|Honda|Passport 2019-21|All|openpilot|25 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|Honda Nidec| -|Honda|Pilot 2016-22|Honda Sensing|openpilot|25 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|Honda Nidec| -|Honda|Ridgeline 2017-22|Honda Sensing|openpilot|25 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|Honda Nidec| -|Hyundai|Elantra 2017-19|Smart Cruise Control (SCC) & LKAS|Stock|19 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai B| -|Hyundai|Elantra 2021-22|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai K| -|Hyundai|Elantra Hybrid 2021-22|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai K| -|Hyundai|Genesis 2015-16|Smart Cruise Control (SCC) & LKAS|Stock|19 mph|37 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai J| -|Hyundai|Ioniq 5 2022|Highway Driving Assist II|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai Q| -|Hyundai|Ioniq Electric 2019|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai C| -|Hyundai|Ioniq Electric 2020|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai H| -|Hyundai|Ioniq Hybrid 2017-19|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai C| -|Hyundai|Ioniq Hybrid 2020-22|Smart Cruise Control (SCC) & LFA|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai H| -|Hyundai|Ioniq Plug-in Hybrid 2019|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai C| -|Hyundai|Ioniq Plug-in Hybrid 2020-21|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai H| -|Hyundai|Kona 2020|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai B| -|Hyundai|Kona Electric 2018-21|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai G| -|Hyundai|Kona Electric 2022|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai O| -|Hyundai|Kona Hybrid 2020|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai I| -|Hyundai|Palisade 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai H| -|Hyundai|Santa Fe 2019-20|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai D| -|Hyundai|Santa Fe 2021-22|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai L| -|Hyundai|Santa Fe Hybrid 2022|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai L| -|Hyundai|Santa Fe Plug-in Hybrid 2022|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai L| -|Hyundai|Sonata 2018-19|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai E| -|Hyundai|Sonata 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai A| -|Hyundai|Sonata Hybrid 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai A| -|Hyundai|Tucson 2021|Smart Cruise Control (SCC)|Stock|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai L| -|Hyundai|Tucson Diesel 2019|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai L| -|Hyundai|Tucson Hybrid 2022|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai N| -|Hyundai|Veloster 2019-20|Smart Cruise Control (SCC)|Stock|5 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai E| -|Jeep|Grand Cherokee 2016-18|Adaptive Cruise Control|Stock|0 mph|9 mph|[![star](assets/icon-star-full.svg)](##)|FCA| -|Jeep|Grand Cherokee 2019-21|Adaptive Cruise Control|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|FCA| -|Kia|Ceed 2019|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai E| -|Kia|EV6 2022|Highway Driving Assist II|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai P| -|Kia|Forte 2018|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai B| -|Kia|Forte 2019-21|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai G| -|Kia|K5 2021-22|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai A| -|Kia|Niro Electric 2019|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai H| -|Kia|Niro Electric 2020|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai F| -|Kia|Niro Electric 2021|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai C| -|Kia|Niro Electric 2022|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai H| -|Kia|Niro Hybrid 2021|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai F| -|Kia|Niro Hybrid 2022|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai H| -|Kia|Niro Plug-in Hybrid 2018-19|Smart Cruise Control (SCC) & LKAS|openpilot|10 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai C| -|Kia|Optima 2017|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai B| -|Kia|Optima 2019|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai G| -|Kia|Seltos 2021|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai A| -|Kia|Sorento 2018|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai C| -|Kia|Sorento 2019|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai E| -|Kia|Stinger 2018-20|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai C| -|Kia|Telluride 2020|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Hyundai H| -|Lexus|CT Hybrid 2017-18|Lexus Safety System+|Stock[3](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Lexus|ES 2019-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Lexus|ES Hybrid 2017-18|Lexus Safety System+|Stock[3](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Lexus|ES Hybrid 2019-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Lexus|IS 2017-19|All|Stock|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Lexus|NX 2018-19|All|Stock[3](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Lexus|NX 2020-21|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Lexus|NX Hybrid 2018-19|All|Stock[3](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Lexus|NX Hybrid 2020-21|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Lexus|RC 2017-20|All|Stock|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Lexus|RX 2016-19|All|Stock[3](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Lexus|RX 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Lexus|RX Hybrid 2016-19|All|Stock[3](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Lexus|RX Hybrid 2020-21|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Lexus|UX Hybrid 2019-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Mazda|CX-5 2022|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Mazda| -|Mazda|CX-9 2021-22|All|Stock|0 mph|28 mph|[![star](assets/icon-star-full.svg)](##)|Mazda| -|Nissan|Altima 2019-20|ProPILOT Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Nissan B| -|Nissan|Leaf 2018-22|ProPILOT Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Nissan A| -|Nissan|Rogue 2018-20|ProPILOT Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Nissan A| -|Nissan|X-Trail 2017|ProPILOT Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Nissan A| -|Ram|1500 2019-22|Adaptive Cruise Control|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|Ram| -|SEAT|Ateca 2018|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| -|SEAT|Leon 2014-20|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| -|Subaru|Ascent 2019-21|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Subaru A| -|Subaru|Crosstrek 2018-19|EyeSight Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-empty.svg)](##)|Subaru A| -|Subaru|Crosstrek 2020-21|EyeSight Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Subaru A| -|Subaru|Forester 2019-21|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Subaru A| -|Subaru|Impreza 2017-19|EyeSight Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-empty.svg)](##)|Subaru A| -|Subaru|Impreza 2020-22|EyeSight Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Subaru A| -|Subaru|Legacy 2020-22|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Subaru B| -|Subaru|Outback 2020-22|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Subaru B| -|Subaru|XV 2018-19|EyeSight Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-empty.svg)](##)|Subaru A| -|Subaru|XV 2020-21|EyeSight Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Subaru A| -|Škoda|Kamiq 2021[5](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| -|Škoda|Karoq 2019-21[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| -|Škoda|Kodiaq 2018-19|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| -|Škoda|Octavia 2015, 2018-19|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| -|Škoda|Octavia RS 2016|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| -|Škoda|Scala 2020|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| -|Škoda|Superb 2015-18|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| -|Toyota|Alphard 2019-20|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Toyota|Alphard Hybrid 2021|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Toyota|Avalon 2016|Toyota Safety Sense P|Stock[3](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Toyota|Avalon 2017-18|All|Stock[3](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Toyota|Avalon 2019-21|All|Stock[3](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Toyota|Avalon 2022|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Toyota|Avalon Hybrid 2019-21|All|Stock[3](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Toyota|Avalon Hybrid 2022|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Toyota|C-HR 2017-21|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Toyota|C-HR Hybrid 2017-19|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Toyota|Camry 2018-20|All|Stock|0 mph[4](#footnotes)|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Toyota|Camry 2021-22|All|openpilot|0 mph[4](#footnotes)|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Toyota|Camry Hybrid 2018-20|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Toyota|Camry Hybrid 2021-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Toyota|Corolla 2017-19|All|Stock[3](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Toyota|Corolla 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Toyota|Corolla Cross (Non-US only) 2020-21|All|openpilot|17 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Toyota|Corolla Cross Hybrid (Non-US only) 2020-22|All|openpilot|17 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Toyota|Corolla Hatchback 2019-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Toyota|Corolla Hybrid 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Toyota|Highlander 2017-19|All|Stock[3](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Toyota|Highlander 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Toyota|Highlander Hybrid 2017-19|All|Stock[3](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Toyota|Highlander Hybrid 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Toyota|Mirai 2021|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Toyota|Prius 2016|Toyota Safety Sense P|Stock[3](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Toyota|Prius 2017-20|All|Stock[3](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Toyota|Prius 2021-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Toyota|Prius Prime 2017-20|All|Stock[3](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Toyota|Prius Prime 2021-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Toyota|Prius v 2017|Toyota Safety Sense P|Stock[3](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Toyota|RAV4 2016|Toyota Safety Sense P|Stock[3](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Toyota|RAV4 2017-18|All|Stock[3](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Toyota|RAV4 2019-21|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Toyota|RAV4 2022|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Toyota|RAV4 Hybrid 2016|Toyota Safety Sense P|Stock[3](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Toyota|RAV4 Hybrid 2017-18|All|Stock[3](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Toyota|RAV4 Hybrid 2019-21|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Toyota|RAV4 Hybrid 2022|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Toyota|Sienna 2018-20|All|Stock[3](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|Toyota| -|Volkswagen|Arteon 2018-22[7,8](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|J533| -|Volkswagen|Arteon eHybrid 2020-22[7,8](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|J533| -|Volkswagen|Arteon R 2020-22[7,8](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|J533| -|Volkswagen|Atlas 2018-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|J533| -|Volkswagen|Atlas Cross Sport 2021-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|J533| -|Volkswagen|California 2021[7](#footnotes)|Driver Assistance|Stock|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|J533| -|Volkswagen|Caravelle 2020[7](#footnotes)|Driver Assistance|Stock|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|J533| -|Volkswagen|CC 2018-22[7,8](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|J533| -|Volkswagen|e-Golf 2014-20|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| -|Volkswagen|Golf 2015-20[8](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| -|Volkswagen|Golf Alltrack 2015-19|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| -|Volkswagen|Golf GTD 2015-20|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| -|Volkswagen|Golf GTE 2015-20|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| -|Volkswagen|Golf GTI 2015-21|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| -|Volkswagen|Golf R 2015-19[8](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| -|Volkswagen|Golf SportsVan 2015-20|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| -|Volkswagen|Jetta 2018-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|J533| -|Volkswagen|Jetta GLI 2021-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|J533| -|Volkswagen|Passat 2015-22[6,7,8](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|J533| -|Volkswagen|Passat Alltrack 2015-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|J533| -|Volkswagen|Passat GTE 2015-22[7,8](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|J533| -|Volkswagen|Polo 2020-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|J533| -|Volkswagen|Polo GTI 2020-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|J533| -|Volkswagen|T-Cross 2021[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|J533| -|Volkswagen|T-Roc 2021[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|J533| -|Volkswagen|Taos 2022[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|J533| -|Volkswagen|Teramont 2018-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|J533| -|Volkswagen|Teramont Cross Sport 2021-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|J533| -|Volkswagen|Teramont X 2021-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|J533| -|Volkswagen|Tiguan 2019-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|J533| -|Volkswagen|Touran 2017|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|VW| +|Make|Model|Supported Package|ACC|No ACC accel below|No ALC below|Steering Torque|Resume from stop|Harness| +|---|---|---|:---:|:---:|:---:|:---:|:---:|:---:| +|Acura|ILX 2016-19|AcuraWatch Plus|openpilot|25 mph|25 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Nidec| +|Acura|RDX 2016-18|AcuraWatch Plus|openpilot|25 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Nidec| +|Acura|RDX 2019-22|All|Stock|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch A| +|Audi|A3 2014-19|ACC + Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|Audi|A3 Sportback e-tron 2017-18|ACC + Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|Audi|Q2 2018|ACC + Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|Audi|Q3 2020-21|ACC + Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|Audi|RS3 2018|ACC + Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|Audi|S3 2015-17|ACC + Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|Cadillac|Escalade ESV 2016[1](#footnotes)|Adaptive Cruise Control (ACC) & LKAS|openpilot|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|OBD-II| +|Chevrolet|Bolt EUV 2022-23|Premier or Premier Redline Trim without Super Cruise Package|Stock|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|GM| +|Chevrolet|Silverado 1500 2020-21|Safety Package II|Stock|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|GM| +|Chevrolet|Volt 2017-18[1](#footnotes)|Adaptive Cruise Control|openpilot|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|OBD-II| +|Chrysler|Pacifica 2017-18|Adaptive Cruise Control|Stock|0 mph|9 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|FCA| +|Chrysler|Pacifica 2019-20|Adaptive Cruise Control|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|FCA| +|Chrysler|Pacifica 2021|All|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|FCA| +|Chrysler|Pacifica Hybrid 2017-18|Adaptive Cruise Control|Stock|0 mph|9 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|FCA| +|Chrysler|Pacifica Hybrid 2019-22|Adaptive Cruise Control|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|FCA| +|comma|body|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|None| +|Genesis|G70 2018-19|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai F| +|Genesis|G70 2020|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai F| +|Genesis|G80 2017-19|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai H| +|Genesis|G90 2017-18|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C| +|GMC|Acadia 2018[1](#footnotes)|Adaptive Cruise Control|openpilot|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|OBD-II| +|GMC|Sierra 1500 2020-21|Driver Alert Package II|Stock|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|GM| +|Honda|Accord 2018-22|All|Stock|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch A| +|Honda|Accord Hybrid 2018-22|All|Stock|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch A| +|Honda|Civic 2016-18|Honda Sensing|openpilot|0 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Nidec| +|Honda|Civic 2019-21|All|Stock|0 mph|2 mph[2](#footnotes)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch A| +|Honda|Civic 2022|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch B| +|Honda|Civic Hatchback 2017-21|Honda Sensing|Stock|0 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch A| +|Honda|Civic Hatchback 2022|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch B| +|Honda|CR-V 2015-16|Touring Trim|openpilot|25 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Nidec| +|Honda|CR-V 2017-22|Honda Sensing|Stock|0 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch A| +|Honda|CR-V Hybrid 2017-19|Honda Sensing|Stock|0 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch A| +|Honda|e 2020|All|Stock|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch A| +|Honda|Fit 2018-20|Honda Sensing|openpilot|25 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Nidec| +|Honda|Freed 2020|Honda Sensing|openpilot|25 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Nidec| +|Honda|HR-V 2019-22|Honda Sensing|openpilot|25 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Nidec| +|Honda|Insight 2019-22|All|Stock|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch A| +|Honda|Inspire 2018|All|Stock|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch A| +|Honda|Odyssey 2018-20|Honda Sensing|openpilot|25 mph|0 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Nidec| +|Honda|Passport 2019-21|All|openpilot|25 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Nidec| +|Honda|Pilot 2016-22|Honda Sensing|openpilot|25 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Nidec| +|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) & LKAS|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) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai K| +|Hyundai|Elantra Hybrid 2021-22|Smart Cruise Control (SCC)|Stock|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) & LKAS|Stock|19 mph|37 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai J| +|Hyundai|Ioniq 5 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 Electric 2019|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C| +|Hyundai|Ioniq Electric 2020|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai H| +|Hyundai|Ioniq Hybrid 2017-19|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C| +|Hyundai|Ioniq Hybrid 2020-22|Smart Cruise Control (SCC) & LFA|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai H| +|Hyundai|Ioniq Plug-in Hybrid 2019|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C| +|Hyundai|Ioniq Plug-in Hybrid 2020-21|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai H| +|Hyundai|Kona 2020|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai B| +|Hyundai|Kona Electric 2018-21|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai G| +|Hyundai|Kona Electric 2022|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai O| +|Hyundai|Kona Hybrid 2020|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai I| +|Hyundai|Palisade 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai H| +|Hyundai|Santa Fe 2019-20|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai D| +|Hyundai|Santa Fe 2021-22|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai L| +|Hyundai|Santa Fe Hybrid 2022|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai L| +|Hyundai|Santa Fe Plug-in Hybrid 2022|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai L| +|Hyundai|Sonata 2018-19|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai E| +|Hyundai|Sonata 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai A| +|Hyundai|Sonata Hybrid 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai A| +|Hyundai|Tucson 2021|Smart Cruise Control (SCC)|Stock|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai L| +|Hyundai|Tucson Diesel 2019|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai L| +|Hyundai|Tucson Hybrid 2022|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai N| +|Hyundai|Veloster 2019-20|Smart Cruise Control (SCC)|Stock|5 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai E| +|Jeep|Grand Cherokee 2016-18|Adaptive Cruise Control|Stock|0 mph|9 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|FCA| +|Jeep|Grand Cherokee 2019-21|Adaptive Cruise Control|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|FCA| +|Kia|Ceed 2019|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai E| +|Kia|EV6 2022|Highway Driving Assist II|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai P| +|Kia|Forte 2018|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai B| +|Kia|Forte 2019-21|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai G| +|Kia|K5 2021-22|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai A| +|Kia|Niro Electric 2019|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai H| +|Kia|Niro Electric 2020|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai F| +|Kia|Niro Electric 2021|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C| +|Kia|Niro Electric 2022|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai H| +|Kia|Niro Hybrid 2021|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai F| +|Kia|Niro Hybrid 2022|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai H| +|Kia|Niro Plug-in Hybrid 2018-19|Smart Cruise Control (SCC) & LKAS|openpilot|10 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C| +|Kia|Optima 2017|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai B| +|Kia|Optima 2019|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai G| +|Kia|Seltos 2021|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai A| +|Kia|Sorento 2018|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C| +|Kia|Sorento 2019|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai E| +|Kia|Stinger 2018-20|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C| +|Kia|Telluride 2020|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai H| +|Lexus|CT Hybrid 2017-18|Lexus Safety System+|Stock[3](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Toyota| +|Lexus|ES 2019-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Lexus|ES Hybrid 2017-18|Lexus Safety System+|Stock[3](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Toyota| +|Lexus|ES Hybrid 2019-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Lexus|IS 2017-19|All|Stock|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Toyota| +|Lexus|NX 2018-19|All|Stock[3](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Toyota| +|Lexus|NX 2020-21|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Lexus|NX Hybrid 2018-19|All|Stock[3](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Toyota| +|Lexus|NX Hybrid 2020-21|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Lexus|RC 2017-20|All|Stock|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Toyota| +|Lexus|RX 2016-19|All|Stock[3](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Toyota| +|Lexus|RX 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Lexus|RX Hybrid 2016-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-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| +|Nissan|Rogue 2018-20|ProPILOT Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Nissan A| +|Nissan|X-Trail 2017|ProPILOT Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Nissan A| +|Ram|1500 2019-22|Adaptive Cruise Control|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Ram| +|SEAT|Ateca 2018|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|SEAT|Leon 2014-20|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|Subaru|Ascent 2019-21|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Subaru A| +|Subaru|Crosstrek 2018-19|EyeSight Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Subaru A| +|Subaru|Crosstrek 2020-21|EyeSight Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Subaru A| +|Subaru|Forester 2019-21|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Subaru A| +|Subaru|Impreza 2017-19|EyeSight Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Subaru A| +|Subaru|Impreza 2020-22|EyeSight Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Subaru A| +|Subaru|Legacy 2020-22|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Subaru B| +|Subaru|Outback 2020-22|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Subaru B| +|Subaru|XV 2018-19|EyeSight Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Subaru A| +|Subaru|XV 2020-21|EyeSight Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Subaru A| +|Škoda|Kamiq 2021[5](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|Škoda|Karoq 2019-21[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|Škoda|Kodiaq 2018-19|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|Škoda|Octavia 2015, 2018-19|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|Škoda|Octavia RS 2016|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|Škoda|Scala 2020|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|Škoda|Superb 2015-18|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|Toyota|Alphard 2019-20|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|Alphard Hybrid 2021|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|Avalon 2016|Toyota Safety Sense P|Stock[3](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Toyota| +|Toyota|Avalon 2017-18|All|Stock[3](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Toyota| +|Toyota|Avalon 2019-21|All|Stock[3](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Toyota| +|Toyota|Avalon 2022|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|Avalon Hybrid 2019-21|All|Stock[3](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Toyota| +|Toyota|Avalon Hybrid 2022|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|C-HR 2017-21|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Toyota| +|Toyota|C-HR Hybrid 2017-19|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Toyota| +|Toyota|Camry 2018-20|All|Stock|0 mph[4](#footnotes)|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Toyota| +|Toyota|Camry 2021-22|All|openpilot|0 mph[4](#footnotes)|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|Camry Hybrid 2018-20|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Toyota| +|Toyota|Camry Hybrid 2021-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|Corolla 2017-19|All|Stock[3](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Toyota| +|Toyota|Corolla 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|Corolla Cross (Non-US only) 2020-21|All|openpilot|17 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|Corolla Cross Hybrid (Non-US only) 2020-22|All|openpilot|17 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|Corolla Hatchback 2019-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|Corolla Hybrid 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|Highlander 2017-19|All|Stock[3](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Toyota| +|Toyota|Highlander 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|Highlander Hybrid 2017-19|All|Stock[3](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Toyota| +|Toyota|Highlander Hybrid 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|Mirai 2021|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|Prius 2016|Toyota Safety Sense P|Stock[3](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Toyota| +|Toyota|Prius 2017-20|All|Stock[3](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Toyota| +|Toyota|Prius 2021-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|Prius Prime 2017-20|All|Stock[3](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Toyota| +|Toyota|Prius Prime 2021-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|Prius v 2017|Toyota Safety Sense P|Stock[3](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Toyota| +|Toyota|RAV4 2016|Toyota Safety Sense P|Stock[3](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Toyota| +|Toyota|RAV4 2017-18|All|Stock[3](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Toyota| +|Toyota|RAV4 2019-21|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|RAV4 2022|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Toyota| +|Toyota|RAV4 Hybrid 2016|Toyota Safety Sense P|Stock[3](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Toyota| +|Toyota|RAV4 Hybrid 2017-18|All|Stock[3](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Toyota| +|Toyota|RAV4 Hybrid 2019-21|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Toyota| +|Toyota|RAV4 Hybrid 2022|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Toyota| +|Toyota|Sienna 2018-20|All|Stock[3](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Toyota| +|Volkswagen|Arteon 2018-22[7,8](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Arteon eHybrid 2020-22[7,8](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Arteon R 2020-22[7,8](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Atlas 2018-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Atlas Cross Sport 2021-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|California 2021[7](#footnotes)|Driver Assistance|Stock|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Caravelle 2020[7](#footnotes)|Driver Assistance|Stock|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|CC 2018-22[7,8](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|e-Golf 2014-20|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|Volkswagen|Golf 2015-20[8](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|Volkswagen|Golf Alltrack 2015-19|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|Volkswagen|Golf GTD 2015-20|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|Volkswagen|Golf GTE 2015-20|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|Volkswagen|Golf GTI 2015-21|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|Volkswagen|Golf R 2015-19[8](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|Volkswagen|Golf SportsVan 2015-20|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| +|Volkswagen|Jetta 2018-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Jetta GLI 2021-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Passat 2015-22[6,7,8](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Passat Alltrack 2015-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Passat GTE 2015-22[7,8](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Polo 2020-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Polo GTI 2020-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|T-Cross 2021[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|T-Roc 2021[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Taos 2022[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Teramont 2018-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Teramont Cross Sport 2021-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Teramont X 2021-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Tiguan 2019-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Touran 2017|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| 1Requires a community built ASCM harness. NOTE: disconnecting the ASCM disables Automatic Emergency Braking (AEB).
diff --git a/selfdrive/car/docs_definitions.py b/selfdrive/car/docs_definitions.py index 499732ffe..3f9d51b43 100644 --- a/selfdrive/car/docs_definitions.py +++ b/selfdrive/car/docs_definitions.py @@ -10,10 +10,6 @@ from common.conversions import Conversions as CV GOOD_TORQUE_THRESHOLD = 1.0 # m/s^2 MODEL_YEARS_RE = r"(?<= )((\d{4}-\d{2})|(\d{4}))(,|$)" -# Makes that lack auto-resume with stock long, and auto resume in any configuration -NO_AUTO_RESUME_STOCK_LONG = {"toyota", "gm"} -NO_AUTO_RESUME = NO_AUTO_RESUME_STOCK_LONG | {"nissan", "subaru"} - class Column(Enum): MAKE = "Make" @@ -23,6 +19,7 @@ class Column(Enum): FSR_LONGITUDINAL = "No ACC accel below" FSR_STEERING = "No ALC below" STEERING_TORQUE = "Steering Torque" + AUTO_RESUME = "Resume from stop" HARNESS = "Harness" @@ -139,6 +136,7 @@ class CarInfo: Column.FSR_LONGITUDINAL: f"{max(self.min_enable_speed * CV.MS_TO_MPH, 0):.0f} mph", Column.FSR_STEERING: f"{max(self.min_steer_speed * CV.MS_TO_MPH, 0):.0f} mph", Column.STEERING_TORQUE: Star.EMPTY, + Column.AUTO_RESUME: Star.FULL if CP.autoResumeSng else Star.EMPTY, Column.HARNESS: self.harness.value, } @@ -166,7 +164,7 @@ class CarInfo: acc = "" if self.min_enable_speed > 0: acc = f" while driving above {self.min_enable_speed * CV.MS_TO_MPH:.0f} mph" - elif CP.carName not in NO_AUTO_RESUME or (CP.carName in NO_AUTO_RESUME_STOCK_LONG and CP.openpilotLongitudinalControl): + elif CP.autoResumeSng: acc = " that automatically resumes from a stop" if self.row[Column.STEERING_TORQUE] != Star.FULL: diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py index 09d950ea8..118e54aa0 100755 --- a/selfdrive/car/gm/interface.py +++ b/selfdrive/car/gm/interface.py @@ -49,6 +49,7 @@ class CarInterface(CarInterfaceBase): ret = CarInterfaceBase.get_std_params(candidate, fingerprint) ret.carName = "gm" ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.gm)] + ret.autoResumeSng = False if candidate in EV_CAR: ret.transmissionType = TransmissionType.direct diff --git a/selfdrive/car/interfaces.py b/selfdrive/car/interfaces.py index 9da6aabd6..401b243ba 100644 --- a/selfdrive/car/interfaces.py +++ b/selfdrive/car/interfaces.py @@ -107,11 +107,14 @@ class CarInterfaceBase(ABC): ret = car.CarParams.new_message() ret.carFingerprint = candidate + # Car docs fields + ret.maxLateralAccel = get_torque_params(candidate)['MAX_LAT_ACCEL_MEASURED'] + ret.autoResumeSng = True # describes whether car can resume from a stop automatically + # standard ALC params ret.steerControlType = car.CarParams.SteerControlType.torque ret.minSteerSpeed = 0. ret.wheelSpeedFactor = 1.0 - ret.maxLateralAccel = get_torque_params(candidate)['MAX_LAT_ACCEL_MEASURED'] ret.pcmCruise = True # openpilot's state is tied to the PCM's cruise state on most cars ret.minEnableSpeed = -1. # enable is done by stock ACC, so ignore this diff --git a/selfdrive/car/nissan/interface.py b/selfdrive/car/nissan/interface.py index 9c04d975f..fe567468b 100644 --- a/selfdrive/car/nissan/interface.py +++ b/selfdrive/car/nissan/interface.py @@ -13,6 +13,7 @@ class CarInterface(CarInterfaceBase): ret = CarInterfaceBase.get_std_params(candidate, fingerprint) ret.carName = "nissan" ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.nissan)] + ret.autoResumeSng = False ret.steerLimitTimer = 1.0 diff --git a/selfdrive/car/subaru/interface.py b/selfdrive/car/subaru/interface.py index a464734a3..b84291225 100644 --- a/selfdrive/car/subaru/interface.py +++ b/selfdrive/car/subaru/interface.py @@ -15,6 +15,7 @@ class CarInterface(CarInterfaceBase): ret.carName = "subaru" ret.radarOffCan = True ret.dashcamOnly = candidate in PREGLOBAL_CARS + ret.autoResumeSng = False if candidate in PREGLOBAL_CARS: ret.enableBsm = 0x25c in fingerprint[0] diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py index 642c39952..a0d3ce9b8 100644 --- a/selfdrive/car/toyota/interface.py +++ b/selfdrive/car/toyota/interface.py @@ -218,6 +218,7 @@ class CarInterface(CarInterfaceBase): ret.openpilotLongitudinalControl = smartDsu or ret.enableDsu or candidate in (TSS2_CAR - RADAR_ACC_CAR) if not ret.openpilotLongitudinalControl: + ret.autoResumeSng = False ret.safetyConfigs[0].safetyParam |= Panda.FLAG_TOYOTA_STOCK_LONGITUDINAL # we can't use the fingerprint to detect this reliably, since diff --git a/selfdrive/car/volkswagen/interface.py b/selfdrive/car/volkswagen/interface.py index 7e686b970..6f0bb9a19 100644 --- a/selfdrive/car/volkswagen/interface.py +++ b/selfdrive/car/volkswagen/interface.py @@ -197,6 +197,7 @@ class CarInterface(CarInterfaceBase): else: raise ValueError(f"unsupported car {candidate}") + ret.autoResumeSng = ret.minEnableSpeed == -1 ret.rotationalInertia = scale_rot_inertia(ret.mass, ret.wheelbase) ret.centerToFront = ret.wheelbase * 0.45 ret.tireStiffnessFront, ret.tireStiffnessRear = scale_tire_stiffness(ret.mass, ret.wheelbase, ret.centerToFront, diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index f77f24459..591acc2f1 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -656daeb9de3680258527500ecae4ddff323b2e59 \ No newline at end of file +af74c25e869d1128c0277f789e8f88bb95c5be1b From b6e355a9334ba883da60113240245a9de0beec9a Mon Sep 17 00:00:00 2001 From: George Hotz <72895+geohot@users.noreply.github.com> Date: Tue, 30 Aug 2022 17:57:14 -0700 Subject: [PATCH 116/172] modeld: PC Thneed prereqs (#25615) * pc thneed prereqs * ugh, out of date * that can stay private * memcpy here is fine in SNPE variant * release files * thneed docs don't work anymore. they didn't look too useful Co-authored-by: Comma Device --- docs/c_docs.rst | 2 - release/files_common | 4 +- selfdrive/modeld/SConscript | 3 +- selfdrive/modeld/models/driving.cc | 2 +- selfdrive/modeld/runners/onnxmodel.cc | 2 +- selfdrive/modeld/runners/onnxmodel.h | 2 +- selfdrive/modeld/runners/runmodel.h | 1 + selfdrive/modeld/runners/snpemodel.cc | 2 +- selfdrive/modeld/runners/snpemodel.h | 2 +- selfdrive/modeld/runners/thneedmodel.cc | 4 +- selfdrive/modeld/runners/thneedmodel.h | 2 +- selfdrive/modeld/thneed/serialize.cc | 59 ++++- selfdrive/modeld/thneed/thneed.h | 8 +- selfdrive/modeld/thneed/thneed_common.cc | 236 ++++++++++++++++++ .../thneed/{thneed.cc => thneed_qcom2.cc} | 223 +---------------- 15 files changed, 312 insertions(+), 240 deletions(-) create mode 100644 selfdrive/modeld/thneed/thneed_common.cc rename selfdrive/modeld/thneed/{thneed.cc => thneed_qcom2.cc} (59%) diff --git a/docs/c_docs.rst b/docs/c_docs.rst index 94d0adb56..77be7e51d 100644 --- a/docs/c_docs.rst +++ b/docs/c_docs.rst @@ -72,8 +72,6 @@ modeld :project: selfdrive_modeld_transforms .. autodoxygenindex:: :project: selfdrive_modeld_models -.. autodoxygenindex:: - :project: selfdrive_modeld_thneed .. autodoxygenindex:: :project: selfdrive_modeld_runners diff --git a/release/files_common b/release/files_common index 04d13c8a5..ca6e91fb6 100644 --- a/release/files_common +++ b/release/files_common @@ -363,7 +363,9 @@ selfdrive/modeld/transforms/transform.h selfdrive/modeld/transforms/transform.cl selfdrive/modeld/thneed/*.py -selfdrive/modeld/thneed/thneed.* +selfdrive/modeld/thneed/thneed.h +selfdrive/modeld/thneed/thneed_common.cc +selfdrive/modeld/thneed/thneed_qcom2.cc selfdrive/modeld/thneed/serialize.cc selfdrive/modeld/thneed/compile.cc selfdrive/modeld/thneed/optimizer.cc diff --git a/selfdrive/modeld/SConscript b/selfdrive/modeld/SConscript index a108e2c9d..4feb17f23 100644 --- a/selfdrive/modeld/SConscript +++ b/selfdrive/modeld/SConscript @@ -23,7 +23,8 @@ common_src = [ ] thneed_src = [ - "thneed/thneed.cc", + "thneed/thneed_common.cc", + "thneed/thneed_qcom2.cc", "thneed/serialize.cc", "thneed/optimizer.cc", "runners/thneedmodel.cc", diff --git a/selfdrive/modeld/models/driving.cc b/selfdrive/modeld/models/driving.cc index 8bfe58472..7a7a6ff6e 100644 --- a/selfdrive/modeld/models/driving.cc +++ b/selfdrive/modeld/models/driving.cc @@ -38,7 +38,7 @@ void model_init(ModelState* s, cl_device_id device_id, cl_context context) { #else s->m = std::make_unique("models/supercombo.dlc", #endif - &s->output[0], NET_OUTPUT_SIZE, USE_GPU_RUNTIME, true); + &s->output[0], NET_OUTPUT_SIZE, USE_GPU_RUNTIME, true, false, context); #ifdef TEMPORAL s->m->addRecurrent(&s->output[OUTPUT_SIZE], TEMPORAL_SIZE); diff --git a/selfdrive/modeld/runners/onnxmodel.cc b/selfdrive/modeld/runners/onnxmodel.cc index 1f9f551ab..447d90fd7 100644 --- a/selfdrive/modeld/runners/onnxmodel.cc +++ b/selfdrive/modeld/runners/onnxmodel.cc @@ -14,7 +14,7 @@ #include "common/swaglog.h" #include "common/util.h" -ONNXModel::ONNXModel(const char *path, float *_output, size_t _output_size, int runtime, bool _use_extra, bool _use_tf8) { +ONNXModel::ONNXModel(const char *path, float *_output, size_t _output_size, int runtime, bool _use_extra, bool _use_tf8, cl_context context) { LOGD("loading model %s", path); output = _output; diff --git a/selfdrive/modeld/runners/onnxmodel.h b/selfdrive/modeld/runners/onnxmodel.h index 4ac599e2a..d5b7bfecf 100644 --- a/selfdrive/modeld/runners/onnxmodel.h +++ b/selfdrive/modeld/runners/onnxmodel.h @@ -6,7 +6,7 @@ class ONNXModel : public RunModel { public: - ONNXModel(const char *path, float *output, size_t output_size, int runtime, bool use_extra = false, bool _use_tf8 = false); + ONNXModel(const char *path, float *output, size_t output_size, int runtime, bool use_extra = false, bool _use_tf8 = false, cl_context context = NULL); ~ONNXModel(); void addRecurrent(float *state, int state_size); void addDesire(float *state, int state_size); diff --git a/selfdrive/modeld/runners/runmodel.h b/selfdrive/modeld/runners/runmodel.h index 02b8c4b20..c60781140 100644 --- a/selfdrive/modeld/runners/runmodel.h +++ b/selfdrive/modeld/runners/runmodel.h @@ -1,4 +1,5 @@ #pragma once +#include "common/clutil.h" class RunModel { public: virtual ~RunModel() {} diff --git a/selfdrive/modeld/runners/snpemodel.cc b/selfdrive/modeld/runners/snpemodel.cc index 4d6917e89..95ee5fe82 100644 --- a/selfdrive/modeld/runners/snpemodel.cc +++ b/selfdrive/modeld/runners/snpemodel.cc @@ -14,7 +14,7 @@ void PrintErrorStringAndExit() { std::exit(EXIT_FAILURE); } -SNPEModel::SNPEModel(const char *path, float *loutput, size_t loutput_size, int runtime, bool luse_extra, bool luse_tf8) { +SNPEModel::SNPEModel(const char *path, float *loutput, size_t loutput_size, int runtime, bool luse_extra, bool luse_tf8, cl_context context) { output = loutput; output_size = loutput_size; use_extra = luse_extra; diff --git a/selfdrive/modeld/runners/snpemodel.h b/selfdrive/modeld/runners/snpemodel.h index ed9d58d1e..08ae16c2b 100644 --- a/selfdrive/modeld/runners/snpemodel.h +++ b/selfdrive/modeld/runners/snpemodel.h @@ -23,7 +23,7 @@ class SNPEModel : public RunModel { public: - SNPEModel(const char *path, float *loutput, size_t loutput_size, int runtime, bool luse_extra = false, bool use_tf8 = false); + SNPEModel(const char *path, float *loutput, size_t loutput_size, int runtime, bool luse_extra = false, bool use_tf8 = false, cl_context context = NULL); void addRecurrent(float *state, int state_size); void addTrafficConvention(float *state, int state_size); void addCalib(float *state, int state_size); diff --git a/selfdrive/modeld/runners/thneedmodel.cc b/selfdrive/modeld/runners/thneedmodel.cc index dbe80a946..d55a8104e 100644 --- a/selfdrive/modeld/runners/thneedmodel.cc +++ b/selfdrive/modeld/runners/thneedmodel.cc @@ -2,8 +2,8 @@ #include -ThneedModel::ThneedModel(const char *path, float *loutput, size_t loutput_size, int runtime, bool luse_extra) { - thneed = new Thneed(true); +ThneedModel::ThneedModel(const char *path, float *loutput, size_t loutput_size, int runtime, bool luse_extra, bool luse_tf8, cl_context context) { + thneed = new Thneed(true, context); thneed->load(path); thneed->clexec(); thneed->find_inputs_outputs(); diff --git a/selfdrive/modeld/runners/thneedmodel.h b/selfdrive/modeld/runners/thneedmodel.h index fe0f9ae44..f3f34dc7f 100644 --- a/selfdrive/modeld/runners/thneedmodel.h +++ b/selfdrive/modeld/runners/thneedmodel.h @@ -5,7 +5,7 @@ class ThneedModel : public RunModel { public: - ThneedModel(const char *path, float *loutput, size_t loutput_size, int runtime, bool luse_extra = false); + ThneedModel(const char *path, float *loutput, size_t loutput_size, int runtime, bool luse_extra = false, bool use_tf8 = false, cl_context context = NULL); void addRecurrent(float *state, int state_size); void addTrafficConvention(float *state, int state_size); void addDesire(float *state, int state_size); diff --git a/selfdrive/modeld/thneed/serialize.cc b/selfdrive/modeld/thneed/serialize.cc index 136576fe1..0b8b02c6a 100644 --- a/selfdrive/modeld/thneed/serialize.cc +++ b/selfdrive/modeld/thneed/serialize.cc @@ -14,9 +14,9 @@ void Thneed::load(const char *filename) { string buf = util::read_file(filename); int jsz = *(int *)buf.data(); - string err; + string jsonerr; string jj(buf.data() + sizeof(int), jsz); - Json jdat = Json::parse(jj, err); + Json jdat = Json::parse(jj, jsonerr); map real_mem; real_mem[NULL] = NULL; @@ -48,13 +48,33 @@ void Thneed::load(const char *filename) { desc.image_width = mobj["width"].int_value(); desc.image_height = mobj["height"].int_value(); desc.image_row_pitch = mobj["row_pitch"].int_value(); + assert(sz == desc.image_height*desc.image_row_pitch); +#ifdef QCOM2 desc.buffer = clbuf; - - cl_image_format format; +#else + // TODO: we are creating unused buffers on PC + clReleaseMemObject(clbuf); +#endif + cl_image_format format = {0}; format.image_channel_order = CL_RGBA; - format.image_channel_data_type = CL_HALF_FLOAT; + format.image_channel_data_type = mobj["float32"].bool_value() ? CL_FLOAT : CL_HALF_FLOAT; + + cl_int errcode; - clbuf = clCreateImage(context, CL_MEM_READ_WRITE, &format, &desc, NULL, NULL); +#ifndef QCOM2 + if (mobj["needs_load"].bool_value()) { + clbuf = clCreateImage(context, CL_MEM_COPY_HOST_PTR | CL_MEM_READ_WRITE, &format, &desc, &buf[ptr-sz], &errcode); + } else { + clbuf = clCreateImage(context, CL_MEM_READ_WRITE, &format, &desc, NULL, &errcode); + } +#else + clbuf = clCreateImage(context, CL_MEM_READ_WRITE, &format, &desc, NULL, &errcode); +#endif + if (clbuf == NULL) { + printf("clError: %s create image %zux%zu rp %zu with buffer %p\n", cl_get_error_string(errcode), + desc.image_width, desc.image_height, desc.image_row_pitch, desc.buffer + ); + } assert(clbuf != NULL); } @@ -67,6 +87,30 @@ void Thneed::load(const char *filename) { g_programs[name] = cl_program_from_source(context, device_id, source.string_value()); } + for (auto &obj : jdat["inputs"].array_items()) { + auto mobj = obj.object_items(); + int sz = mobj["size"].int_value(); + cl_mem aa = real_mem[*(cl_mem*)(mobj["buffer_id"].string_value().data())]; + input_clmem.push_back(aa); + input_sizes.push_back(sz); + printf("Thneed::load: adding input %s with size %d\n", mobj["name"].string_value().data(), sz); + + cl_int cl_err; + void *ret = clEnqueueMapBuffer(command_queue, aa, CL_TRUE, CL_MAP_WRITE, 0, sz, 0, NULL, NULL, &cl_err); + if (cl_err != CL_SUCCESS) printf("clError: %s map %p %d\n", cl_get_error_string(cl_err), aa, sz); + assert(cl_err == CL_SUCCESS); + inputs.push_back(ret); + } + + for (auto &obj : jdat["outputs"].array_items()) { + auto mobj = obj.object_items(); + int sz = mobj["size"].int_value(); + printf("Thneed::save: adding output with size %d\n", sz); + // TODO: support multiple outputs + output = real_mem[*(cl_mem*)(mobj["buffer_id"].string_value().data())]; + assert(output != NULL); + } + for (auto &obj : jdat["binaries"].array_items()) { string name = obj["name"].string_value(); size_t length = obj["length"].int_value(); @@ -135,7 +179,7 @@ void Thneed::save(const char *filename, bool save_binaries) { }); if (k->arg_types[i] == "image2d_t" || k->arg_types[i] == "image1d_t") { - cl_mem buf; + cl_mem buf = NULL; clGetImageInfo(val, CL_IMAGE_BUFFER, sizeof(buf), &buf, NULL); string aa = string((char *)&buf, sizeof(buf)); jj["buffer_id"] = aa; @@ -149,6 +193,7 @@ void Thneed::save(const char *filename, bool save_binaries) { jj["row_pitch"] = (int)row_pitch; jj["size"] = (int)(height * row_pitch); jj["needs_load"] = false; + jj["float32"] = false; if (saved_objects.find(aa) == saved_objects.end()) { saved_objects.insert(aa); diff --git a/selfdrive/modeld/thneed/thneed.h b/selfdrive/modeld/thneed/thneed.h index 0ccea59a3..19dc46e8f 100644 --- a/selfdrive/modeld/thneed/thneed.h +++ b/selfdrive/modeld/thneed/thneed.h @@ -16,6 +16,9 @@ using namespace std; +cl_int thneed_clSetKernelArg(cl_kernel kernel, cl_uint arg_index, size_t arg_size, const void *arg_value); +cl_program thneed_clCreateProgramWithSource(cl_context context, cl_uint count, const char **strings, const size_t *lengths, cl_int *errcode_ret); + namespace json11 { class Json; } @@ -89,7 +92,7 @@ class CachedCommand: public CachedIoctl { class Thneed { public: - Thneed(bool do_clinit=false); + Thneed(bool do_clinit=false, cl_context _context = NULL); void stop(); void execute(float **finputs, float *foutput, bool slow=false); void wait(); @@ -110,9 +113,12 @@ class Thneed { bool record = false; int debug; int timestamp; + +#ifdef QCOM2 unique_ptr ram; vector > cmds; int fd; +#endif // all CL kernels void find_inputs_outputs(); diff --git a/selfdrive/modeld/thneed/thneed_common.cc b/selfdrive/modeld/thneed/thneed_common.cc new file mode 100644 index 000000000..b751cdf66 --- /dev/null +++ b/selfdrive/modeld/thneed/thneed_common.cc @@ -0,0 +1,236 @@ +#include "selfdrive/modeld/thneed/thneed.h" + +#include +#include +#include + +#include "common/clutil.h" +#include "common/timing.h" + +map, string> g_args; +map, int> g_args_size; +map g_program_source; + +void Thneed::clinit() { + device_id = cl_get_device_id(CL_DEVICE_TYPE_DEFAULT); + if (context == NULL) context = CL_CHECK_ERR(clCreateContext(NULL, 1, &device_id, NULL, NULL, &err)); + //cl_command_queue_properties props[3] = {CL_QUEUE_PROPERTIES, CL_QUEUE_PROFILING_ENABLE, 0}; + cl_command_queue_properties props[3] = {CL_QUEUE_PROPERTIES, 0, 0}; + command_queue = CL_CHECK_ERR(clCreateCommandQueueWithProperties(context, device_id, props, &err)); + printf("Thneed::clinit done\n"); +} + +cl_int Thneed::clexec() { + if (debug >= 1) printf("Thneed::clexec: running %lu queued kernels\n", kq.size()); + for (auto &k : kq) { + if (record) ckq.push_back(k); + cl_int ret = k->exec(); + assert(ret == CL_SUCCESS); + } + return clFinish(command_queue); +} + +void Thneed::copy_inputs(float **finputs) { + //cl_int ret; + for (int idx = 0; idx < inputs.size(); ++idx) { + if (debug >= 1) printf("copying %lu -- %p -> %p (cl %p)\n", input_sizes[idx], finputs[idx], inputs[idx], input_clmem[idx]); + + // TODO: fix thneed caching + if (finputs[idx] != NULL) memcpy(inputs[idx], finputs[idx], input_sizes[idx]); + //if (finputs[idx] != NULL) CL_CHECK(clEnqueueWriteBuffer(command_queue, input_clmem[idx], CL_TRUE, 0, input_sizes[idx], finputs[idx], 0, NULL, NULL)); + + // HACK + //if (input_sizes[idx] == 16) memset((char*)inputs[idx] + 8, 0, 8); + } +} + +void Thneed::copy_output(float *foutput) { + if (output != NULL) { + size_t sz; + clGetMemObjectInfo(output, CL_MEM_SIZE, sizeof(sz), &sz, NULL); + if (debug >= 1) printf("copying %lu for output %p -> %p\n", sz, output, foutput); + CL_CHECK(clEnqueueReadBuffer(command_queue, output, CL_TRUE, 0, sz, foutput, 0, NULL, NULL)); + } else { + printf("CAUTION: model output is NULL, does it have no outputs?\n"); + } +} + +// *********** CLQueuedKernel *********** + +CLQueuedKernel::CLQueuedKernel(Thneed *lthneed, + cl_kernel _kernel, + cl_uint _work_dim, + const size_t *_global_work_size, + const size_t *_local_work_size) { + thneed = lthneed; + kernel = _kernel; + work_dim = _work_dim; + assert(work_dim <= 3); + for (int i = 0; i < work_dim; i++) { + global_work_size[i] = _global_work_size[i]; + local_work_size[i] = _local_work_size[i]; + } + + char _name[0x100]; + clGetKernelInfo(kernel, CL_KERNEL_FUNCTION_NAME, sizeof(_name), _name, NULL); + name = string(_name); + clGetKernelInfo(kernel, CL_KERNEL_NUM_ARGS, sizeof(num_args), &num_args, NULL); + + // get args + for (int i = 0; i < num_args; i++) { + char arg_name[0x100] = {0}; + clGetKernelArgInfo(kernel, i, CL_KERNEL_ARG_NAME, sizeof(arg_name), arg_name, NULL); + arg_names.push_back(string(arg_name)); + clGetKernelArgInfo(kernel, i, CL_KERNEL_ARG_TYPE_NAME, sizeof(arg_name), arg_name, NULL); + arg_types.push_back(string(arg_name)); + + args.push_back(g_args[make_pair(kernel, i)]); + args_size.push_back(g_args_size[make_pair(kernel, i)]); + } + + // get program + clGetKernelInfo(kernel, CL_KERNEL_PROGRAM, sizeof(program), &program, NULL); +} + +int CLQueuedKernel::get_arg_num(const char *search_arg_name) { + for (int i = 0; i < num_args; i++) { + if (arg_names[i] == search_arg_name) return i; + } + printf("failed to find %s in %s\n", search_arg_name, name.c_str()); + assert(false); +} + +cl_int CLQueuedKernel::exec() { + if (kernel == NULL) { + kernel = clCreateKernel(program, name.c_str(), NULL); + arg_names.clear(); + arg_types.clear(); + + for (int j = 0; j < num_args; j++) { + char arg_name[0x100] = {0}; + clGetKernelArgInfo(kernel, j, CL_KERNEL_ARG_NAME, sizeof(arg_name), arg_name, NULL); + arg_names.push_back(string(arg_name)); + clGetKernelArgInfo(kernel, j, CL_KERNEL_ARG_TYPE_NAME, sizeof(arg_name), arg_name, NULL); + arg_types.push_back(string(arg_name)); + + cl_int ret; + if (args[j].size() != 0) { + assert(args[j].size() == args_size[j]); + ret = thneed_clSetKernelArg(kernel, j, args[j].size(), args[j].data()); + } else { + ret = thneed_clSetKernelArg(kernel, j, args_size[j], NULL); + } + assert(ret == CL_SUCCESS); + } + } + + if (thneed->debug >= 1) { + debug_print(thneed->debug >= 2); + } + + return clEnqueueNDRangeKernel(thneed->command_queue, + kernel, work_dim, NULL, global_work_size, local_work_size, 0, NULL, NULL); +} + +uint64_t CLQueuedKernel::benchmark() { + uint64_t ret = 0; + int old_record = thneed->record; + thneed->record = 0; + clFinish(thneed->command_queue); + // TODO: benchmarking at a lower level will make this more accurate + for (int i = 0; i < 10; i++) { + uint64_t sb = nanos_since_boot(); + exec(); + clFinish(thneed->command_queue); + uint64_t et = nanos_since_boot() - sb; + if (ret == 0 || et < ret) ret = et; + } + thneed->record = old_record; + return ret; +} + +void CLQueuedKernel::debug_print(bool verbose) { + printf("%p %56s -- ", kernel, name.c_str()); + for (int i = 0; i < work_dim; i++) { + printf("%4zu ", global_work_size[i]); + } + printf(" -- "); + for (int i = 0; i < work_dim; i++) { + printf("%4zu ", local_work_size[i]); + } + printf("\n"); + + if (verbose) { + for (int i = 0; i < num_args; i++) { + string arg = args[i]; + printf(" %s %s", arg_types[i].c_str(), arg_names[i].c_str()); + void *arg_value = (void*)arg.data(); + int arg_size = arg.size(); + if (arg_size == 0) { + printf(" (size) %d", args_size[i]); + } else if (arg_size == 1) { + printf(" = %d", *((char*)arg_value)); + } else if (arg_size == 2) { + printf(" = %d", *((short*)arg_value)); + } else if (arg_size == 4) { + if (arg_types[i] == "float") { + printf(" = %f", *((float*)arg_value)); + } else { + printf(" = %d", *((int*)arg_value)); + } + } else if (arg_size == 8) { + cl_mem val = (cl_mem)(*((uintptr_t*)arg_value)); + printf(" = %p", val); + if (val != NULL) { + cl_mem_object_type obj_type; + clGetMemObjectInfo(val, CL_MEM_TYPE, sizeof(obj_type), &obj_type, NULL); + if (arg_types[i] == "image2d_t" || arg_types[i] == "image1d_t" || obj_type == CL_MEM_OBJECT_IMAGE2D) { + cl_image_format format; + size_t width, height, depth, array_size, row_pitch, slice_pitch; + cl_mem buf; + clGetImageInfo(val, CL_IMAGE_FORMAT, sizeof(format), &format, NULL); + assert(format.image_channel_order == CL_RGBA); + assert(format.image_channel_data_type == CL_HALF_FLOAT || format.image_channel_data_type == CL_FLOAT); + clGetImageInfo(val, CL_IMAGE_WIDTH, sizeof(width), &width, NULL); + clGetImageInfo(val, CL_IMAGE_HEIGHT, sizeof(height), &height, NULL); + clGetImageInfo(val, CL_IMAGE_ROW_PITCH, sizeof(row_pitch), &row_pitch, NULL); + clGetImageInfo(val, CL_IMAGE_DEPTH, sizeof(depth), &depth, NULL); + clGetImageInfo(val, CL_IMAGE_ARRAY_SIZE, sizeof(array_size), &array_size, NULL); + clGetImageInfo(val, CL_IMAGE_SLICE_PITCH, sizeof(slice_pitch), &slice_pitch, NULL); + assert(depth == 0); + assert(array_size == 0); + assert(slice_pitch == 0); + + clGetImageInfo(val, CL_IMAGE_BUFFER, sizeof(buf), &buf, NULL); + size_t sz; + clGetMemObjectInfo(buf, CL_MEM_SIZE, sizeof(sz), &sz, NULL); + printf(" image %zu x %zu rp %zu @ %p buffer %zu", width, height, row_pitch, buf, sz); + } else { + size_t sz; + clGetMemObjectInfo(val, CL_MEM_SIZE, sizeof(sz), &sz, NULL); + printf(" buffer %zu", sz); + } + } + } + printf("\n"); + } + } +} + +cl_int thneed_clSetKernelArg(cl_kernel kernel, cl_uint arg_index, size_t arg_size, const void *arg_value) { + g_args_size[make_pair(kernel, arg_index)] = arg_size; + if (arg_value != NULL) { + g_args[make_pair(kernel, arg_index)] = string((char*)arg_value, arg_size); + } else { + g_args[make_pair(kernel, arg_index)] = string(""); + } + cl_int ret = clSetKernelArg(kernel, arg_index, arg_size, arg_value); + return ret; +} + +cl_program thneed_clCreateProgramWithSource(cl_context context, cl_uint count, const char **strings, const size_t *lengths, cl_int *errcode_ret) { + assert(count == 1); + cl_program ret = clCreateProgramWithSource(context, count, strings, lengths, errcode_ret); + g_program_source[ret] = strings[0]; + return ret; +} \ No newline at end of file diff --git a/selfdrive/modeld/thneed/thneed.cc b/selfdrive/modeld/thneed/thneed_qcom2.cc similarity index 59% rename from selfdrive/modeld/thneed/thneed.cc rename to selfdrive/modeld/thneed/thneed_qcom2.cc index d673c4f56..e79bb77ed 100644 --- a/selfdrive/modeld/thneed/thneed.cc +++ b/selfdrive/modeld/thneed/thneed_qcom2.cc @@ -14,9 +14,6 @@ Thneed *g_thneed = NULL; int g_fd = -1; -map, string> g_args; -map, int> g_args_size; -map g_program_source; void hexdump(uint8_t *d, int len) { assert((len%4) == 0); @@ -208,7 +205,9 @@ void CachedCommand::exec() { // *********** Thneed *********** -Thneed::Thneed(bool do_clinit) { +Thneed::Thneed(bool do_clinit, cl_context _context) { + // TODO: QCOM2 actually requires a different context + //context = _context; if (do_clinit) clinit(); assert(g_fd != -1); fd = g_fd; @@ -252,25 +251,6 @@ void Thneed::find_inputs_outputs() { } } -void Thneed::copy_inputs(float **finputs) { - //cl_int ret; - for (int idx = 0; idx < inputs.size(); ++idx) { - if (debug >= 1) printf("copying %lu -- %p -> %p\n", input_sizes[idx], finputs[idx], inputs[idx]); - if (finputs[idx] != NULL) memcpy(inputs[idx], finputs[idx], input_sizes[idx]); - } -} - -void Thneed::copy_output(float *foutput) { - if (output != NULL) { - size_t sz; - clGetMemObjectInfo(output, CL_MEM_SIZE, sizeof(sz), &sz, NULL); - if (debug >= 1) printf("copying %lu for output %p -> %p\n", sz, output, foutput); - clEnqueueReadBuffer(command_queue, output, CL_TRUE, 0, sz, foutput, 0, NULL, NULL); - } else { - printf("CAUTION: model output is NULL, does it have no outputs?\n"); - } -} - void Thneed::wait() { struct kgsl_device_waittimestamp_ctxtid wait; wait.context_id = context_id; @@ -335,38 +315,8 @@ void Thneed::execute(float **finputs, float *foutput, bool slow) { } } -void Thneed::clinit() { - device_id = cl_get_device_id(CL_DEVICE_TYPE_DEFAULT); - context = CL_CHECK_ERR(clCreateContext(NULL, 1, &device_id, NULL, NULL, &err)); - //cl_command_queue_properties props[3] = {CL_QUEUE_PROPERTIES, CL_QUEUE_PROFILING_ENABLE, 0}; - cl_command_queue_properties props[3] = {CL_QUEUE_PROPERTIES, 0, 0}; - command_queue = CL_CHECK_ERR(clCreateCommandQueueWithProperties(context, device_id, props, &err)); - printf("Thneed::clinit done\n"); -} - -cl_int Thneed::clexec() { - printf("Thneed::clexec: running %lu queued kernels\n", kq.size()); - for (auto &k : kq) { - if (record) ckq.push_back(k); - cl_int ret = k->exec(); - assert(ret == CL_SUCCESS); - } - return clFinish(command_queue); -} - // *********** OpenCL interceptor *********** -cl_int thneed_clSetKernelArg(cl_kernel kernel, cl_uint arg_index, size_t arg_size, const void *arg_value) { - g_args_size[make_pair(kernel, arg_index)] = arg_size; - if (arg_value != NULL) { - g_args[make_pair(kernel, arg_index)] = string((char*)arg_value, arg_size); - } else { - g_args[make_pair(kernel, arg_index)] = string(""); - } - cl_int ret = clSetKernelArg(kernel, arg_index, arg_size, arg_value); - return ret; -} - cl_int thneed_clEnqueueNDRangeKernel(cl_command_queue command_queue, cl_kernel kernel, cl_uint work_dim, @@ -415,13 +365,6 @@ cl_int thneed_clFinish(cl_command_queue command_queue) { } } -cl_program thneed_clCreateProgramWithSource(cl_context context, cl_uint count, const char **strings, const size_t *lengths, cl_int *errcode_ret) { - assert(count == 1); - cl_program ret = clCreateProgramWithSource(context, count, strings, lengths, errcode_ret); - g_program_source[ret] = strings[0]; - return ret; -} - void *dlsym(void *handle, const char *symbol) { #ifdef QCOM2 void *(*my_dlsym)(void *handle, const char *symbol) = (void *(*)(void *handle, const char *symbol))((uintptr_t)dlopen + DLSYM_OFFSET); @@ -442,163 +385,3 @@ void *dlsym(void *handle, const char *symbol) { return my_dlsym(handle, symbol); } } - -// *********** CLQueuedKernel *********** - -CLQueuedKernel::CLQueuedKernel(Thneed *lthneed, - cl_kernel _kernel, - cl_uint _work_dim, - const size_t *_global_work_size, - const size_t *_local_work_size) { - thneed = lthneed; - kernel = _kernel; - work_dim = _work_dim; - assert(work_dim <= 3); - for (int i = 0; i < work_dim; i++) { - global_work_size[i] = _global_work_size[i]; - local_work_size[i] = _local_work_size[i]; - } - - char _name[0x100]; - clGetKernelInfo(kernel, CL_KERNEL_FUNCTION_NAME, sizeof(_name), _name, NULL); - name = string(_name); - clGetKernelInfo(kernel, CL_KERNEL_NUM_ARGS, sizeof(num_args), &num_args, NULL); - - // get args - for (int i = 0; i < num_args; i++) { - char arg_name[0x100]; - clGetKernelArgInfo(kernel, i, CL_KERNEL_ARG_NAME, sizeof(arg_name), arg_name, NULL); - arg_names.push_back(string(arg_name)); - clGetKernelArgInfo(kernel, i, CL_KERNEL_ARG_TYPE_NAME, sizeof(arg_name), arg_name, NULL); - arg_types.push_back(string(arg_name)); - - args.push_back(g_args[make_pair(kernel, i)]); - args_size.push_back(g_args_size[make_pair(kernel, i)]); - } - - // get program - clGetKernelInfo(kernel, CL_KERNEL_PROGRAM, sizeof(program), &program, NULL); -} - -int CLQueuedKernel::get_arg_num(const char *search_arg_name) { - for (int i = 0; i < num_args; i++) { - if (arg_names[i] == search_arg_name) return i; - } - printf("failed to find %s in %s\n", search_arg_name, name.c_str()); - assert(false); -} - -cl_int CLQueuedKernel::exec() { - if (kernel == NULL) { - kernel = clCreateKernel(program, name.c_str(), NULL); - arg_names.clear(); - arg_types.clear(); - - for (int j = 0; j < num_args; j++) { - char arg_name[0x100]; - clGetKernelArgInfo(kernel, j, CL_KERNEL_ARG_NAME, sizeof(arg_name), arg_name, NULL); - arg_names.push_back(string(arg_name)); - clGetKernelArgInfo(kernel, j, CL_KERNEL_ARG_TYPE_NAME, sizeof(arg_name), arg_name, NULL); - arg_types.push_back(string(arg_name)); - - cl_int ret; - if (args[j].size() != 0) { - assert(args[j].size() == args_size[j]); - ret = thneed_clSetKernelArg(kernel, j, args[j].size(), args[j].data()); - } else { - ret = thneed_clSetKernelArg(kernel, j, args_size[j], NULL); - } - assert(ret == CL_SUCCESS); - } - } - - if (thneed->debug >= 1) { - debug_print(thneed->debug >= 2); - } - - return clEnqueueNDRangeKernel(thneed->command_queue, - kernel, work_dim, NULL, global_work_size, local_work_size, 0, NULL, NULL); -} - -uint64_t CLQueuedKernel::benchmark() { - uint64_t ret = 0; - int old_record = thneed->record; - thneed->record = 0; - clFinish(thneed->command_queue); - // TODO: benchmarking at a lower level will make this more accurate - for (int i = 0; i < 10; i++) { - uint64_t sb = nanos_since_boot(); - exec(); - clFinish(thneed->command_queue); - uint64_t et = nanos_since_boot() - sb; - if (ret == 0 || et < ret) ret = et; - } - thneed->record = old_record; - return ret; -} - -void CLQueuedKernel::debug_print(bool verbose) { - printf("%p %56s -- ", kernel, name.c_str()); - for (int i = 0; i < work_dim; i++) { - printf("%4zu ", global_work_size[i]); - } - printf(" -- "); - for (int i = 0; i < work_dim; i++) { - printf("%4zu ", local_work_size[i]); - } - printf("\n"); - - if (verbose) { - for (int i = 0; i < num_args; i++) { - string arg = args[i]; - printf(" %s %s", arg_types[i].c_str(), arg_names[i].c_str()); - void *arg_value = (void*)arg.data(); - int arg_size = arg.size(); - if (arg_size == 0) { - printf(" (size) %d", args_size[i]); - } else if (arg_size == 1) { - printf(" = %d", *((char*)arg_value)); - } else if (arg_size == 2) { - printf(" = %d", *((short*)arg_value)); - } else if (arg_size == 4) { - if (arg_types[i] == "float") { - printf(" = %f", *((float*)arg_value)); - } else { - printf(" = %d", *((int*)arg_value)); - } - } else if (arg_size == 8) { - cl_mem val = (cl_mem)(*((uintptr_t*)arg_value)); - printf(" = %p", val); - if (val != NULL) { - if (arg_types[i] == "image2d_t" || arg_types[i] == "image1d_t") { - cl_image_format format; - size_t width, height, depth, array_size, row_pitch, slice_pitch; - cl_mem buf; - clGetImageInfo(val, CL_IMAGE_FORMAT, sizeof(format), &format, NULL); - assert(format.image_channel_order == CL_RGBA); - assert(format.image_channel_data_type == CL_HALF_FLOAT); - clGetImageInfo(val, CL_IMAGE_WIDTH, sizeof(width), &width, NULL); - clGetImageInfo(val, CL_IMAGE_HEIGHT, sizeof(height), &height, NULL); - clGetImageInfo(val, CL_IMAGE_ROW_PITCH, sizeof(row_pitch), &row_pitch, NULL); - clGetImageInfo(val, CL_IMAGE_DEPTH, sizeof(depth), &depth, NULL); - clGetImageInfo(val, CL_IMAGE_ARRAY_SIZE, sizeof(array_size), &array_size, NULL); - clGetImageInfo(val, CL_IMAGE_SLICE_PITCH, sizeof(slice_pitch), &slice_pitch, NULL); - assert(depth == 0); - assert(array_size == 0); - assert(slice_pitch == 0); - - clGetImageInfo(val, CL_IMAGE_BUFFER, sizeof(buf), &buf, NULL); - size_t sz; - clGetMemObjectInfo(buf, CL_MEM_SIZE, sizeof(sz), &sz, NULL); - printf(" image %zu x %zu rp %zu @ %p buffer %zu", width, height, row_pitch, buf, sz); - } else { - size_t sz; - clGetMemObjectInfo(val, CL_MEM_SIZE, sizeof(sz), &sz, NULL); - printf(" buffer %zu", sz); - } - } - } - printf("\n"); - } - } -} From 61c30a95cba198efa989ed18e3b30aaa55a1c9dc Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 30 Aug 2022 21:27:18 -0700 Subject: [PATCH 117/172] Car docs diff bot: auto-generate column header (#25622) * Fix bot * test * Revert "test" This reverts commit ba4a67cd8c88f8b7e082fb1fad5a1e10b51012ab. --- selfdrive/debug/print_docs_diff.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/debug/print_docs_diff.py b/selfdrive/debug/print_docs_diff.py index 0f8f2b33c..b80428645 100755 --- a/selfdrive/debug/print_docs_diff.py +++ b/selfdrive/debug/print_docs_diff.py @@ -10,7 +10,7 @@ from selfdrive.car.docs_definitions import Column FOOTNOTE_TAG = "{}" STAR_ICON = '' COLUMNS = "|" + "|".join([column.value for column in Column]) + "|" -COLUMN_HEADER = "|---|---|---|:---:|:---:|:---:|:---:|" +COLUMN_HEADER = "|---|---|---|{}|".format("|".join([":---:"] * (len(Column) - 3))) ARROW_SYMBOL = "➡️" From c7bae57924e81856128d44f124a8e52e5aea2764 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 30 Aug 2022 23:33:35 -0700 Subject: [PATCH 118/172] Chrysler: add missing hybrid ecus (#25606) * add missing hybrid ecus * rename to hcp rename to hcp --- cereal | 2 +- selfdrive/car/chrysler/values.py | 5 +++++ selfdrive/car/fw_versions.py | 2 +- 3 files changed, 7 insertions(+), 2 deletions(-) diff --git a/cereal b/cereal index aaf67ac78..d05d3cbd0 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit aaf67ac782c833fec2c14a11a6cf99a659080d11 +Subproject commit d05d3cbd0e1243c3fef63c58ab15aeb7508159a7 diff --git a/selfdrive/car/chrysler/values.py b/selfdrive/car/chrysler/values.py index ef5471490..0df2c1886 100644 --- a/selfdrive/car/chrysler/values.py +++ b/selfdrive/car/chrysler/values.py @@ -130,6 +130,11 @@ FINGERPRINTS = { } FW_VERSIONS = { + CAR.PACIFICA_2019_HYBRID: { + (Ecu.hcp, 0x7e2, None): [], + (Ecu.esp, 0x7e4, None): [], + }, + CAR.RAM_1500: { (Ecu.combinationMeter, 0x742, None): [ b'68294063AH', diff --git a/selfdrive/car/fw_versions.py b/selfdrive/car/fw_versions.py index 886bf4aff..363b852eb 100755 --- a/selfdrive/car/fw_versions.py +++ b/selfdrive/car/fw_versions.py @@ -220,7 +220,7 @@ REQUESTS: List[Request] = [ "chrysler", [CHRYSLER_VERSION_REQUEST], [CHRYSLER_VERSION_RESPONSE], - whitelist_ecus=[Ecu.engine, Ecu.transmission], + whitelist_ecus=[Ecu.esp, Ecu.hcp, Ecu.engine, Ecu.transmission], ), Request( "chrysler", From b80424fe27459cf6f454968a3ddd558f45700453 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Bart=C5=82omiej=20Pluta?= <48262759+bpluta@users.noreply.github.com> Date: Wed, 31 Aug 2022 09:09:15 +0200 Subject: [PATCH 119/172] Added Polish translation file (#25310) * Added Polish translations * Updated Polish translation file * update to add plurals * Updated Polish translations to use plurals * remove vanished translations * update translations * remove from languages Co-authored-by: Shane Smiskol --- selfdrive/ui/translations/main_pl.ts | 1311 ++++++++++++++++++++++++++ 1 file changed, 1311 insertions(+) create mode 100644 selfdrive/ui/translations/main_pl.ts diff --git a/selfdrive/ui/translations/main_pl.ts b/selfdrive/ui/translations/main_pl.ts new file mode 100644 index 000000000..8593d6826 --- /dev/null +++ b/selfdrive/ui/translations/main_pl.ts @@ -0,0 +1,1311 @@ + + + + + AbstractAlert + + + Close + Zamknij + + + + Snooze Update + Zaktualizuj później + + + + Reboot and Update + Uruchom ponownie i zaktualizuj + + + + AdvancedNetworking + + + Back + Wróć + + + + Enable Tethering + Włącz hotspot osobisty + + + + Tethering Password + Hasło do hotspotu + + + + + EDIT + EDYTUJ + + + + Enter new tethering password + Wprowadź nowe hasło do hotspotu + + + + IP Address + Adres IP + + + + Enable Roaming + Włącz roaming danych + + + + APN Setting + Ustawienia APN + + + + Enter APN + Wprowadź APN + + + + leave blank for automatic configuration + Pozostaw puste, aby użyć domyślnej konfiguracji + + + + ConfirmationDialog + + + + Ok + Ok + + + + Cancel + Anuluj + + + + DeclinePage + + + You must accept the Terms and Conditions in order to use openpilot. + Aby korzystać z openpilota musisz zaakceptować regulamin. + + + + Back + Wróć + + + + Decline, uninstall %1 + Odrzuć, odinstaluj %1 + + + + DevicePanel + + + Dongle ID + ID adaptera + + + + N/A + N/A + + + + Serial + Numer seryjny + + + + Driver Camera + Kamera kierowcy + + + + PREVIEW + PODGLĄD + + + + Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off) + Wyświetl podgląd z kamery skierowanej na kierowcę, aby upewnić się, że monitoring kierowcy ma dobry zakres widzenia. (pojazd musi być wyłączony) + + + + Reset Calibration + Zresetuj kalibrację + + + + RESET + ZRESETUJ + + + + Are you sure you want to reset calibration? + Czy na pewno chcesz zresetować kalibrację? + + + + Review Training Guide + Zapoznaj się z samouczkiem + + + + REVIEW + ZAPOZNAJ SIĘ + + + + Review the rules, features, and limitations of openpilot + Zapoznaj się z zasadami, funkcjami i ograniczeniami openpilota + + + + Are you sure you want to review the training guide? + Czy na pewno chcesz się zapoznać z samouczkiem? + + + + Regulatory + Regulacja + + + + VIEW + WIDOK + + + + Change Language + Zmień język + + + + CHANGE + ZMIEŃ + + + + Select a language + Wybierz język + + + + Reboot + Uruchom ponownie + + + + Power Off + Wyłącz + + + + 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 wymaga, aby urządzenie było zamontowane z maksymalnym odchyłem 4° poziomo, 5° w górę oraz 8° w dół. openpilot jest ciągle kalibrowany, rzadko konieczne jest resetowania urządzenia. + + + + Your device is pointed %1° %2 and %3° %4. + Twoje urządzenie jest skierowane %1° %2 oraz %3° %4. + + + + down + w dół + + + + up + w górę + + + + left + w lewo + + + + right + w prawo + + + + Are you sure you want to reboot? + Czy na pewno chcesz uruchomić ponownie urządzenie? + + + + Disengage to Reboot + Aby uruchomić ponownie, odłącz sterowanie + + + + Are you sure you want to power off? + Czy na pewno chcesz wyłączyć urządzenie? + + + + Disengage to Power Off + Aby wyłączyć urządzenie, odłącz sterowanie + + + + DriveStats + + + Drives + Przejazdy + + + + Hours + Godziny + + + + ALL TIME + CAŁKOWICIE + + + + PAST WEEK + OSTATNI TYDZIEŃ + + + + KM + KM + + + + Miles + Mile + + + + DriverViewScene + + + camera starting + uruchamianie kamery + + + + InputDialog + + + Cancel + Anuluj + + + + Need at least %n character(s)! + + Wpisana wartość powinna składać się przynajmniej z %n znaku! + Wpisana wartość powinna skłądać się przynajmniej z %n znaków! + Wpisana wartość powinna skłądać się przynajmniej z %n znaków! + + + + + Installer + + + Installing... + Instalowanie... + + + + Receiving objects: + Odbieranie obiektów: + + + + Resolving deltas: + Rozwiązywanie różnic: + + + + Updating files: + Aktualizacja plików: + + + + MapETA + + + eta + przewidywany czas + + + + min + min + + + + hr + godz + + + + km + km + + + + mi + mi + + + + MapInstructions + + + km + km + + + + m + m + + + + mi + mi + + + + ft + ft + + + + MapPanel + + + Current Destination + Miejsce docelowe + + + + CLEAR + WYCZYŚĆ + + + + Recent Destinations + Ostatnie miejsca docelowe + + + + Try the Navigation Beta + Wypróbuj nawigację w wersji beta + + + + Get turn-by-turn directions displayed and more with a comma +prime subscription. Sign up now: https://connect.comma.ai + Odblokuj nawigację zakręt po zakęcie i wiele więcej subskrybując +comma prime. Zarejestruj się teraz: https://connect.comma.ai + + + + No home +location set + Lokalizacja domu +nie została ustawiona + + + + No work +location set + Miejsce pracy +nie zostało ustawione + + + + no recent destinations + brak ostatnich miejsc docelowych + + + + MapWindow + + + Map Loading + Ładowanie Mapy + + + + Waiting for GPS + Oczekiwanie na sygnał GPS + + + + MultiOptionDialog + + + Select + Wybierz + + + + Cancel + Anuluj + + + + Networking + + + Advanced + Zaawansowane + + + + Enter password + Wprowadź hasło + + + + + for "%1" + do "%1" + + + + Wrong password + Niepoprawne hasło + + + + NvgWindow + + + km/h + km/h + + + + mph + mph + + + + + MAX + MAX + + + + + SPEED + PRĘDKOŚĆ + + + + + LIMIT + OGRANICZENIE + + + + OffroadHome + + + UPDATE + UAKTUALNIJ + + + + ALERTS + ALERTY + + + + ALERT + ALERT + + + + PairingPopup + + + Pair your device to your comma account + Sparuj swoje urzadzenie ze swoim kontem comma + + + + Go to https://connect.comma.ai on your phone + Wejdź na stronę https://connect.comma.ai na swoim telefonie + + + + Click "add new device" and scan the QR code on the right + Kliknij "add new device" i zeskanuj kod QR znajdujący się po prawej stronie + + + + Bookmark connect.comma.ai to your home screen to use it like an app + Dodaj connect.comma.ai do zakładek na swoim ekranie początkowym, aby korzystać z niej jak z aplikacji + + + + PrimeAdWidget + + + Upgrade Now + Uaktualnij teraz + + + + Become a comma prime member at connect.comma.ai + Zostań członkiem comma prime na connect.comma.ai + + + + PRIME FEATURES: + FUNKCJE PRIME: + + + + Remote access + Zdalny dostęp + + + + 1 year of storage + 1 rok przechowywania danych + + + + Developer perks + Udogodnienia dla programistów + + + + PrimeUserWidget + + + ✓ SUBSCRIBED + ✓ ZASUBSKRYBOWANO + + + + comma prime + comma prime + + + + CONNECT.COMMA.AI + CONNECT.COMMA.AI + + + + COMMA POINTS + COMMA POINTS + + + + QObject + + + Reboot + Uruchom Ponownie + + + + Exit + Wyjdź + + + + dashcam + wideorejestrator + + + + openpilot + openpilot + + + + %n minute(s) ago + + %n minutę temu + %n minuty temu + %n minut temu + + + + + %n hour(s) ago + + % godzinę temu + %n godziny temu + %n godzin temu + + + + + %n day(s) ago + + %n dzień temu + %n dni temu + %n dni temu + + + + + Reset + + + Reset failed. Reboot to try again. + Wymazywanie zakończone niepowodzeniem. Aby spróbować ponownie, uruchom ponownie urządzenie. + + + + Are you sure you want to reset your device? + Czy na pewno chcesz wymazać urządzenie? + + + + Resetting device... + Wymazywanie urządzenia... + + + + System Reset + Przywróć do ustawień fabrycznych + + + + System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot. + Przywracanie do ustawień fabrycznych. Wciśnij potwierdź, aby usunąć wszystkie dane oraz ustawienia. Wciśnij anuluj, aby wznowić uruchamianie. + + + + Cancel + Anuluj + + + + Reboot + Uruchom ponownie + + + + Confirm + Potwiedź + + + + Unable to mount data partition. Press confirm to reset your device. + Partycja nie została zamontowana poprawnie. Wciśnij potwierdź, aby uruchomić ponownie urządzenie. + + + + RichTextDialog + + + Ok + Ok + + + + SettingsWindow + + + × + x + + + + Device + Urządzenie + + + + + Network + Sieć + + + + Toggles + Przełączniki + + + + Software + Oprogramowanie + + + + Navigation + Nawigacja + + + + Setup + + + WARNING: Low Voltage + OSTRZEŻENIE: Niskie Napięcie + + + + Power your device in a car with a harness or proceed at your own risk. + Podłącz swoje urządzenie do zasilania poprzez podłączenienie go do pojazdu lub kontynuuj na własną odpowiedzialność. + + + + Power off + Wyłącz + + + + + + Continue + Kontynuuj + + + + Getting Started + Zacznij + + + + Before we get on the road, let’s finish installation and cover some details. + Zanim ruszysz w drogę, dokończ instalację i podaj kilka szczegółów. + + + + Connect to Wi-Fi + Połącz z Wi-Fi + + + + + Back + Wróć + + + + Continue without Wi-Fi + Kontynuuj bez połączenia z Wif-Fi + + + + Waiting for internet + Oczekiwanie na połączenie sieciowe + + + + Choose Software to Install + Wybierz oprogramowanie do instalacji + + + + Dashcam + Wideorejestrator + + + + Custom Software + Własne oprogramowanie + + + + Enter URL + Wprowadź adres URL + + + + for Custom Software + do własnego oprogramowania + + + + Downloading... + Pobieranie... + + + + Download Failed + Pobieranie nie powiodło się + + + + Ensure the entered URL is valid, and the device’s internet connection is good. + Upewnij się, że wpisany adres URL jest poprawny, a połączenie internetowe działa poprawnie. + + + + Reboot device + Uruchom ponownie + + + + Start over + Zacznij od początku + + + + SetupWidget + + + Finish Setup + Zakończ konfigurację + + + + Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer. + Sparuj swoje urządzenie z comma connect (connect.comma.ai) i wybierz swoją ofertę comma prime. + + + + Pair device + Sparuj urządzenie + + + + Sidebar + + + + CONNECT + POŁĄCZENIE + + + + OFFLINE + OFFLINE + + + + + ONLINE + ONLINE + + + + ERROR + BŁĄD + + + + + + TEMP + TEMP + + + + HIGH + WYSOKA + + + + GOOD + DOBRA + + + + OK + OK + + + + VEHICLE + POJAZD + + + + NO + BRAK + + + + PANDA + PANDA + + + + GPS + GPS + + + + SEARCH + SZUKAJ + + + + -- + -- + + + + Wi-Fi + Wi-FI + + + + ETH + ETH + + + + 2G + 2G + + + + 3G + 3G + + + + LTE + LTE + + + + 5G + 5G + + + + SoftwarePanel + + + Git Branch + Gałąź Git + + + + Git Commit + Git commit + + + + OS Version + Wersja systemu + + + + Version + Wersja + + + + Last Update Check + Ostatnie sprawdzenie aktualizacji + + + + The last time openpilot successfully checked for an update. The updater only runs while the car is off. + Ostatni raz kiedy openpilot znalazł aktualizację. Aktualizator może być uruchomiony wyłącznie wtedy, kiedy pojazd jest wyłączony. + + + + Check for Update + Sprawdź uaktualnienia + + + + CHECKING + SPRAWDZANIE + + + + Switch Branch + Zmień gąłąź + + + + ENTER + WPROWADŹ + + + + + The new branch will be pulled the next time the updater runs. + Nowa gałąź będzie pobrana przy następnym uruchomieniu aktualizatora. + + + + Enter branch name + Wprowadź nazwę gałęzi + + + + Uninstall %1 + Odinstaluj %1 + + + + UNINSTALL + ODINSTALUJ + + + + Are you sure you want to uninstall? + Czy na pewno chcesz odinstalować? + + + + failed to fetch update + pobieranie aktualizacji zakończone niepowodzeniem + + + + + CHECK + SPRAWDŹ + + + + SshControl + + + SSH Keys + Klucze SSH + + + + 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. + Ostrzeżenie: To spowoduje przekazanie dostępu do wszystkich Twoich publicznych kuczy z ustawień GitHuba. Nigdy nie wprowadzaj nazwy użytkownika innej niż swoja. Pracownik comma NIGDY nie poprosi o dodanie swojej nazwy uzytkownika. + + + + + ADD + DODAJ + + + + Enter your GitHub username + Wpisz swoją nazwę użytkownika GitHub + + + + LOADING + ŁADOWANIE + + + + REMOVE + USUŃ + + + + Username '%1' has no keys on GitHub + Użytkownik '%1' nie posiada żadnych kluczy na GitHubie + + + + Request timed out + Limit czasu rządania + + + + Username '%1' doesn't exist on GitHub + Użytkownik '%1' nie istnieje na GitHubie + + + + SshToggle + + + Enable SSH + Włącz SSH + + + + TermsPage + + + Terms & Conditions + Regulamin + + + + Decline + Odrzuć + + + + Scroll to accept + Przewiń w dół, aby zaakceptować + + + + Agree + Zaakceptuj + + + + TogglesPanel + + + Enable openpilot + Włącz openpilota + + + + 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. + Użyj openpilota do zachowania bezpiecznego odstępu między pojazdami i do asystowania w utrzymywaniu pasa ruchu. Twoja pełna uwaga jest wymagana przez cały czas korzystania z tej funkcji. Ustawienie to może być wdrożone wyłącznie wtedy, gdy pojazd jest wyłączony. + + + + Enable Lane Departure Warnings + Włącz ostrzeganie przed zmianą pasa ruchu + + + + 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). + Otrzymuj alerty o powrocie na właściwy pas, kiedy Twój pojazd przekroczy linię bez włączonego kierunkowskazu jadąc powyżej 50 km/h (31 mph). + + + + Use Metric System + Korzystaj z systemu metrycznego + + + + Display speed in km/h instead of mph. + Wyświetl prędkość w km/h zamiast mph. + + + + Record and Upload Driver Camera + Nagraj i prześlij nagranie z kamery kierowcy + + + + Upload data from the driver facing camera and help improve the driver monitoring algorithm. + Prześlij dane z kamery skierowanej na kierowcę i pomóż poprawiać algorytm monitorowania kierowcy. + + + + Disengage On Accelerator Pedal + Odłącz poprzez naciśnięcie gazu + + + + When enabled, pressing the accelerator pedal will disengage openpilot. + Po włączeniu, naciśnięcie na pedał gazu odłączy openpilota. + + + + Show ETA in 24h Format + Pokaż oczekiwany czas dojazdu w formacie 24-godzinnym + + + + Use 24h format instead of am/pm + Korzystaj z formatu 24-godzinnego zamiast 12-godzinnego + + + + Show Map on Left Side of UI + Pokaż mapę po lewej stronie ekranu + + + + Show map on left side when in split screen view. + Pokaż mapę po lewej stronie kiedy ekran jest podzielony. + + + + openpilot Longitudinal Control + Kontrola wzdłużna openpilota + + + + openpilot will disable the car's radar and will take over control of gas and brakes. Warning: this disables AEB! + openpilot wyłączy radar samochodu i przejmie kontrolę nad gazem i hamulcem. Ostrzeżenie: wyłączony zostanie system AEB! + + + + Updater + + + Update Required + Wymagana Aktualizacja + + + + An operating system update is required. Connect your device to Wi-Fi for the fastest update experience. The download size is approximately 1GB. + Wymagana aktualizacja systemu operacyjnego. Aby przyspieszyć proces aktualizacji połącz swoje urzeądzenie do Wi-Fi. Rozmiar pobieranej paczki wynosi około 1GB. + + + + Connect to Wi-Fi + Połącz się z Wi-Fi + + + + Install + Zainstaluj + + + + Back + Wróć + + + + Loading... + Ładowanie... + + + + Reboot + Uruchom ponownie + + + + Update failed + Aktualizacja nie powiodła się + + + + WifiUI + + + + Scanning for networks... + Wyszukiwanie sieci... + + + + CONNECTING... + ŁĄCZENIE... + + + + FORGET + ZAPOMNIJ + + + + Forget Wi-Fi Network "%1"? + Czy chcesz zapomnieć sieć "%1"? + + + From 93e784934181b0c8a9745e884c38c6f4e5470815 Mon Sep 17 00:00:00 2001 From: salsashark37 Date: Wed, 31 Aug 2022 02:10:51 -0500 Subject: [PATCH 120/172] VW: Add fingerprint for 2018 Golf MK7 DSG Autobahn (US) (#25612) * Update values.py * Update values.py --- selfdrive/car/volkswagen/values.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/selfdrive/car/volkswagen/values.py b/selfdrive/car/volkswagen/values.py index 954b7060c..7b1b0c876 100755 --- a/selfdrive/car/volkswagen/values.py +++ b/selfdrive/car/volkswagen/values.py @@ -370,6 +370,7 @@ FW_VERSIONS = { b'\xf1\x870D9300012 \xf1\x895045', b'\xf1\x870D9300014M \xf1\x895004', b'\xf1\x870D9300014Q \xf1\x895006', + b'\xf1\x870D9300020Q \xf1\x895201', b'\xf1\x870D9300020S \xf1\x895201', b'\xf1\x870D9300040A \xf1\x893613', b'\xf1\x870D9300040S \xf1\x894311', @@ -421,6 +422,7 @@ FW_VERSIONS = { b'\xf1\x873Q0909144L \xf1\x895081\xf1\x82\x0571A0JA15A1', b'\xf1\x873Q0909144M \xf1\x895082\xf1\x82\x0571A01A18A1', b'\xf1\x873Q0909144M \xf1\x895082\xf1\x82\x0571A0JA16A1', + b'\xf1\x873QM909144 \xf1\x895072\xf1\x82\x0571A01714A1', b'\xf1\x875Q0909143K \xf1\x892033\xf1\x820519A9040203', b'\xf1\x875Q0909144AA\xf1\x891081\xf1\x82\x0521A00441A1', b'\xf1\x875Q0909144AA\xf1\x891081\xf1\x82\x0521A00608A1', From 178e4ebd416f281e3e35bdd1bc604fbfd8751f62 Mon Sep 17 00:00:00 2001 From: George Hotz Date: Wed, 31 Aug 2022 08:34:40 -0700 Subject: [PATCH 121/172] remove old replay from selfdrive/ui/.gitignore --- selfdrive/ui/.gitignore | 2 -- 1 file changed, 2 deletions(-) diff --git a/selfdrive/ui/.gitignore b/selfdrive/ui/.gitignore index 5f8a96edf..e5b27adce 100644 --- a/selfdrive/ui/.gitignore +++ b/selfdrive/ui/.gitignore @@ -4,8 +4,6 @@ moc_* _mui watch3 installer/installers/* -replay/replay -replay/tests/test_replay qt/text qt/spinner qt/setup/setup From 272b6cc8c3c7ec73ee3a259ee44cfce2c4e85a1f Mon Sep 17 00:00:00 2001 From: Jeroen Date: Wed, 31 Aug 2022 20:08:39 +0200 Subject: [PATCH 122/172] Add Dutch translations (Nederlands) (#25327) * Add Dutch translations (Nederlands) * Dutch translation improvements * Use Qt's plurals * Improvements to translations Thanks for the review Willem! Co-authored-by: Willem Melching * Shortened a translation to fit screen Shortened 'Show map on left side when in split screen view.' translation * update translations * Shortened 2 translations * Fix test * Changed 'CONTROLEREN' to 'CONTROLEER' * Merge remote-tracking branch 'upstream/master' into dutch-translations (#3) * Rename KIA_NIRO_HEV to KIA_NIRO_PHEV (#24216) * Add car port: Kia Niro Plug-In Hybrid 2018 * Add additional FW version * Low speed lockout 32 MPH * Add test route * min_steer_speed in CarInfo * Remove min_steer_speed from CarInfo * Add to CARS.md * run generator * update min enable speed and regen * update ci routes * these are the same car * i think we only add a note if it's a new platform * fix HEV -> PHEV * Add test route * dup fw * haha we already support this car in #25187 Co-authored-by: Shane Smiskol * GM pcmCruise: cancel more reliably (#25454) * Cancel more reliably * Apply suggestions from code review * Try sending multiple * Apply suggestions from code review * Apply suggestions from code review * Update selfdrive/car/gm/carcontroller.py * lower rate a bit * try this * Update selfdrive/car/gm/carcontroller.py * bump panda * Car docs: add more videos (#25494) * Add Civic video * add mazda cx-9 2022 video link * GM Bolt EUV: update supported packages (#25496) * Update values.py * Update selfdrive/car/gm/values.py Co-authored-by: Adeeb Shihadeh * update docs Co-authored-by: Adeeb Shihadeh * Hyundai: common CAN-FD gear signal (#25498) * Hyundai: common CAN-FD gear signal * bump opendbc * GM: Chevy Silverado 2020-21 support (#25429) * Silverado support Co-authored-by: Jason Shuler * Update docs * Try 2 m/s/s * Should be good torque values * Add Silverado test route * Add to releases * Send counter * can't send multiple or it faults * Send at 33hz, no counter * try 25hz, don't line up exactly with car's buttons * never tried 10hz with same counter * Update selfdrive/car/gm/gmcan.py * Make same as pcmCruise branch * update year and package (different packages needed per-trim) * Update year in releases * Revert to 21 * We can use this package name again * wrong one! Co-authored-by: Shane Smiskol * Show CAN error if message counters are invalid (#25497) * counter check affects can valid * Apply suggestions from code review * bump to master * Hyundai: Car Port for Tucson Hybrid 2022 (#25276) * Hyundai: Car Port for Tucson Hybrid 2022 * Update RELEASES.md * Init gear_msg at the top * FW versions from script * Button send attempt * start with some cleanup * Send button fixed bits * Define all bytes and only send PAUSE/RESUME * Use CRUISE_INFO to cancel cruise and resume * 8-bit counter * Cleanup ish * 8 bit counter * Send at 20ms * Disengage bits * Revert bump submodules * Allow tx on 0x1a0 * Fix byte counts * Send LFA and HDA icons based on engageability * Send cruise buttons only on HDA2 cars for now * Add comments * Add FLAG_HYUNDAI_CANFD_HDA2 flag * Update interface.py * Update carstate.py * Update carstate.py * Update carstate.py * Bump submodules * Bump panda * Bump opendbc * Allow tx with CRUISE_INACTIVE * GEAR has 24 bytes only * Generate car docs * Fix CRUISE_INFO copy * Remove unused class * Add CAN-FD busses to unit test * Bump opendbc * Revert "Add CAN-FD busses to unit test" This reverts commit 2f751640408a7f73a9100947cbd95ea13fbb8a48. * Remove duplicate * New tune based on data * Panda safety cleanup * Include bus 0 in rx checks * Missed one * bus 6 check * Remove redundant check * Add comments * Bump opendbc * Sync with DBC * Hide LFA icon when disengaged * Little endian * fix comment * more conditions in carcontroller * update pedal signal * update tuning * cleanup carcontroller * bump panda * fix mismatch * alt buttons * little more cleanup * update refs for EV6 new safety param * bump panda Co-authored-by: Adeeb Shihadeh * remove old boardd stuff * Ford: add CADS radar interface (#24296) * Ford: use FORD_CADS radar dbc * Ford: CADS radar interface impl Co-authored-by: ReFil <31960031+ReFil@users.noreply.github.com> * fixup radar interface for FORD_CADS dbc * CADS treat different scan indexes as separate points * Ford: support both Fusion and CADS radars * Ford: rename radars to DELPHI_ESR and DELPHI_MRR Co-authored-by: ReFil <31960031+ReFil@users.noreply.github.com> * 0.8.16 release notes * test_models: no CAN invalid tolerance (#25501) * don't use end of route segment * no can invalid cnt tolerance * start checking can valid immediately once available * we check counter violations * README.md: update grammar (#25488) * first paragraph * second section * second section pt2 * third section * fifth section * fifth section pt2 * sixth section * Apply suggestions from code review Co-authored-by: Adeeb Shihadeh * setup: perform all pyenv setup in a single place (#23408) * consolidate pyenv setup * cleanup openpilot_env.sh * undo openpilot_env.sh changes * needed on mac * add that back Co-authored-by: Adeeb Shihadeh * v4l_encoder: free buf_out in destructor (#25044) * test onroad: update dmonitoringd cpu usage * CI: Actions cleanup + speedup (#25514) * actions cache cleanup * release build cleanup * fetch dpeth * sim: fix gps message (#25521) fix gps timestamp field renamed bug introduced in https://github.com/commaai/cereal/pull/341 * GMC: Sierra 2020-21 support (#25523) * Add Sierra * actually this package works * add to releases * credit * GM: add Silverado 2021 High Country FP (#25499) * Add FP from 61c6258cac78af08 * add to dict * Update Silverado release note (#25526) * Translations badges: concatenate into one badge (#25522) * add badge done correctly works Update translation_badge.svg Update translation_badge.svg Update translation_badge.svg Update README.md Update translation_badge.svg Update translation_badge.svg Update translation_badge.svg Update badge Update README.md test this try this finalize remove badges fixup readme add to test fix fix rm * clean up * no formats * Fix badge workflow * user event flagging (#25517) * setup home_btn in sidebar * create UserFlag msg * replay: show and skip to user flags * update translations * bump to cereal master * remove comment Co-authored-by: Adeeb Shihadeh * Update translations * Toyota: add missing engine and esp FW for Corolla Cross Hybrid (#25532) add missing engine and esp FW for CorollaCross Hybrid DongleId 147613502316e718 * HKG: Add FW for 2018 Kia Stinger (#25531) * HKG: Add FW for 2008 Kia Stinger * 2018 in disguise Co-authored-by: Shane Smiskol * test_models: pass carFw into car interface (#25535) pass carFw into get_params * Add Thai translations (#25189) * Add Thai translations * update to add plurals remove * Update translations * Update Thai translation to match English source. * Add to badges * use shorter km/h * Add test for correct format specifier for plural translations * pass new test * Update some sentences to make it clear. Change short form of some words. * Hide from the UI Co-authored-by: Shane Smiskol * update car candidate docs (#25536) * update car candidate docs * little more * that's a nice wikipedia * quotes * Silence a PytestCollectionWarning (#25537) Silence PytestCollectionWarning: cannot collect test class 'TestRoute' because it has a __new__ constructor (from: test_models.py) * bump version to 0.8.17 * Toyota: log stockAeb on non-TSS2 cars (#25489) * check PRE_COLLISION * need to make sure this is right * revert * temp, stash * fixes * uncomment that * it's not really cruise/pcm, but acc remove improt * revert * Fix CI * revert exception * Revert "revert exception" This reverts commit 7e2f39097651f17cf3d2ac9f442fab5071e1b9d0. * this tested enableDsu, but we have other routes that do that * use segment from db * remove exception again Co-authored-by: Jason Wen <47793918+sunnyhaibin@users.noreply.github.com> Co-authored-by: Shane Smiskol Co-authored-by: Adeeb Shihadeh Co-authored-by: Jason Shuler Co-authored-by: Cameron Clough Co-authored-by: ReFil <31960031+ReFil@users.noreply.github.com> Co-authored-by: Joseph Wagner <68037585+wjoseph0@users.noreply.github.com> Co-authored-by: Greg Hogan Co-authored-by: Dean Lee Co-authored-by: AlexandreSato <66435071+AlexandreSato@users.noreply.github.com> Co-authored-by: Rewat S <76684800+taperec@users.noreply.github.com> * Update translations * Update selfdrive/ui/translations/languages.json Co-authored-by: Shane Smiskol Co-authored-by: Shane Smiskol Co-authored-by: Willem Melching Co-authored-by: Jason Wen <47793918+sunnyhaibin@users.noreply.github.com> Co-authored-by: Adeeb Shihadeh Co-authored-by: Jason Shuler Co-authored-by: Cameron Clough Co-authored-by: ReFil <31960031+ReFil@users.noreply.github.com> Co-authored-by: Joseph Wagner <68037585+wjoseph0@users.noreply.github.com> Co-authored-by: Greg Hogan Co-authored-by: Dean Lee Co-authored-by: AlexandreSato <66435071+AlexandreSato@users.noreply.github.com> Co-authored-by: Rewat S <76684800+taperec@users.noreply.github.com> --- selfdrive/ui/translations/main_nl.ts | 1307 ++++++++++++++++++++++++++ 1 file changed, 1307 insertions(+) create mode 100644 selfdrive/ui/translations/main_nl.ts diff --git a/selfdrive/ui/translations/main_nl.ts b/selfdrive/ui/translations/main_nl.ts new file mode 100644 index 000000000..99646ed74 --- /dev/null +++ b/selfdrive/ui/translations/main_nl.ts @@ -0,0 +1,1307 @@ + + + + + AbstractAlert + + + Close + Sluit + + + + Snooze Update + Update uitstellen + + + + Reboot and Update + Opnieuw Opstarten en Updaten + + + + AdvancedNetworking + + + Back + Terug + + + + Enable Tethering + Tethering Inschakelen + + + + Tethering Password + Tethering Wachtwoord + + + + + EDIT + AANPASSEN + + + + Enter new tethering password + Voer nieuw tethering wachtwoord in + + + + IP Address + IP Adres + + + + Enable Roaming + Roaming Inschakelen + + + + APN Setting + APN Instelling + + + + Enter APN + Voer APN in + + + + leave blank for automatic configuration + laat leeg voor automatische configuratie + + + + ConfirmationDialog + + + + Ok + Ok + + + + Cancel + Annuleren + + + + DeclinePage + + + You must accept the Terms and Conditions in order to use openpilot. + U moet de Algemene Voorwaarden accepteren om openpilot te gebruiken. + + + + Back + Terug + + + + Decline, uninstall %1 + Afwijzen, verwijder %1 + + + + DevicePanel + + + Dongle ID + Dongle ID + + + + N/A + Nvt + + + + Serial + Serienummer + + + + Driver Camera + Bestuurders Camera + + + + PREVIEW + BEKIJKEN + + + + Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off) + Bekijk de naar de bestuurder gerichte camera om ervoor te zorgen dat het monitoren van de bestuurder goed zicht heeft. (Voertuig moet uitgschakeld zijn) + + + + Reset Calibration + Kalibratie Resetten + + + + RESET + RESET + + + + Are you sure you want to reset calibration? + Weet u zeker dat u de kalibratie wilt resetten? + + + + Review Training Guide + Doorloop de Training Opnieuw + + + + REVIEW + BEKIJKEN + + + + Review the rules, features, and limitations of openpilot + Bekijk de regels, functies en beperkingen van openpilot + + + + Are you sure you want to review the training guide? + Weet u zeker dat u de training opnieuw wilt doorlopen? + + + + Regulatory + Regelgeving + + + + VIEW + BEKIJKEN + + + + Change Language + Taal Wijzigen + + + + CHANGE + WIJZIGEN + + + + Select a language + Selecteer een taal + + + + Reboot + Opnieuw Opstarten + + + + Power Off + Uitschakelen + + + + 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 vereist dat het apparaat binnen 4° links of rechts en binnen 5° omhoog of 8° omlaag wordt gemonteerd. openpilot kalibreert continu, resetten is zelden nodig. + + + + Your device is pointed %1° %2 and %3° %4. + Uw apparaat is gericht op %1° %2 en %3° %4. + + + + down + omlaag + + + + up + omhoog + + + + left + links + + + + right + rechts + + + + Are you sure you want to reboot? + Weet u zeker dat u opnieuw wilt opstarten? + + + + Disengage to Reboot + Deactiveer openpilot om opnieuw op te starten + + + + Are you sure you want to power off? + Weet u zeker dat u wilt uitschakelen? + + + + Disengage to Power Off + Deactiveer openpilot om uit te schakelen + + + + DriveStats + + + Drives + Ritten + + + + Hours + Uren + + + + ALL TIME + TOTAAL + + + + PAST WEEK + AFGELOPEN WEEK + + + + KM + Km + + + + Miles + Mijl + + + + DriverViewScene + + + camera starting + Camera wordt gestart + + + + InputDialog + + + Cancel + Annuleren + + + + Need at least %n character(s)! + + Heeft minstens %n karakter nodig! + Heeft minstens %n karakters nodig! + + + + + Installer + + + Installing... + Installeren... + + + + Receiving objects: + Objecten ontvangen: + + + + Resolving deltas: + Deltas verwerken: + + + + Updating files: + Bestanden bijwerken: + + + + MapETA + + + eta + eta + + + + min + min + + + + hr + uur + + + + km + km + + + + mi + mi + + + + MapInstructions + + + km + km + + + + m + m + + + + mi + mi + + + + ft + ft + + + + MapPanel + + + Current Destination + Huidige Bestemming + + + + CLEAR + LEEGMAKEN + + + + Recent Destinations + Recente Bestemmingen + + + + Try the Navigation Beta + Probeer de Navigatie Bèta + + + + Get turn-by-turn directions displayed and more with a comma +prime subscription. Sign up now: https://connect.comma.ai + Krijg stapsgewijze routebeschrijving en meer met een comma +prime abonnement. Meld u nu aan: https://connect.comma.ai + + + + No home +location set + Geen thuislocatie +ingesteld + + + + No work +location set + Geen werklocatie +ingesteld + + + + no recent destinations + geen recente bestemmingen + + + + MapWindow + + + Map Loading + Kaart wordt geladen + + + + Waiting for GPS + Wachten op GPS + + + + MultiOptionDialog + + + Select + Selecteer + + + + Cancel + Annuleren + + + + Networking + + + Advanced + Geavanceerd + + + + Enter password + Voer wachtwoord in + + + + + for "%1" + voor "%1" + + + + Wrong password + Verkeerd wachtwoord + + + + NvgWindow + + + km/h + km/u + + + + mph + mph + + + + + MAX + MAX + + + + + SPEED + SPEED + + + + + LIMIT + LIMIT + + + + OffroadHome + + + UPDATE + UPDATE + + + + ALERTS + WAARSCHUWINGEN + + + + ALERT + WAARSCHUWING + + + + PairingPopup + + + Pair your device to your comma account + Koppel uw apparaat aan uw comma-account + + + + Go to https://connect.comma.ai on your phone + Ga naar https://connect.comma.ai op uw telefoon + + + + Click "add new device" and scan the QR code on the right + Klik op "add new device" en scan de QR-code aan de rechterkant + + + + Bookmark connect.comma.ai to your home screen to use it like an app + Voeg connect.comma.ai toe op uw startscherm om het als een app te gebruiken + + + + PrimeAdWidget + + + Upgrade Now + Upgrade nu + + + + Become a comma prime member at connect.comma.ai + Word een comma prime lid op connect.comma.ai + + + + PRIME FEATURES: + PRIME BEVAT: + + + + Remote access + Toegang op afstand + + + + 1 year of storage + 1 jaar lang opslag + + + + Developer perks + Voordelen voor ontwikkelaars + + + + PrimeUserWidget + + + ✓ SUBSCRIBED + ✓ GEABONNEERD + + + + comma prime + comma prime + + + + CONNECT.COMMA.AI + CONNECT.COMMA.AI + + + + COMMA POINTS + COMMA PUNTEN + + + + QObject + + + Reboot + Opnieuw Opstarten + + + + Exit + Afsluiten + + + + dashcam + dashcam + + + + openpilot + openpilot + + + + %n minute(s) ago + + %n minuut geleden + %n minuten geleden + + + + + %n hour(s) ago + + %n uur geleden + %n uur geleden + + + + + %n day(s) ago + + %n dag geleden + %n dagen geleden + + + + + Reset + + + Reset failed. Reboot to try again. + Opnieuw instellen mislukt. Start opnieuw op om opnieuw te proberen. + + + + Are you sure you want to reset your device? + Weet u zeker dat u uw apparaat opnieuw wilt instellen? + + + + Resetting device... + Apparaat opnieuw instellen... + + + + System Reset + Systeemreset + + + + System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot. + Systeemreset geactiveerd. Druk op bevestigen om alle inhoud en instellingen te wissen. Druk op Annuleren om het opstarten te hervatten. + + + + Cancel + Annuleren + + + + Reboot + Opnieuw Opstarten + + + + Confirm + Bevestigen + + + + Unable to mount data partition. Press confirm to reset your device. + Kan gegevenspartitie niet koppelen. Druk op bevestigen om uw apparaat te resetten. + + + + RichTextDialog + + + Ok + Ok + + + + SettingsWindow + + + × + × + + + + Device + Apparaat + + + + + Network + Netwerk + + + + Toggles + Opties + + + + Software + Software + + + + Navigation + Navigatie + + + + Setup + + + WARNING: Low Voltage + WAARCHUWING: Lage Spanning + + + + Power your device in a car with a harness or proceed at your own risk. + Voorzie uw apparaat van stroom in een auto met een harnas (car harness) of ga op eigen risico verder. + + + + Power off + Uitschakelen + + + + + + Continue + Doorgaan + + + + Getting Started + Aan de slag + + + + Before we get on the road, let’s finish installation and cover some details. + Laten we, voordat we op pad gaan, de installatie afronden en enkele details bespreken. + + + + Connect to Wi-Fi + Maak verbinding met Wi-Fi + + + + + Back + Terug + + + + Continue without Wi-Fi + Doorgaan zonder Wi-Fi + + + + Waiting for internet + Wachten op internet + + + + Choose Software to Install + Kies Software om te Installeren + + + + Dashcam + Dashcam + + + + Custom Software + Andere Software + + + + Enter URL + Voer URL in + + + + for Custom Software + voor Andere Software + + + + Downloading... + Downloaden... + + + + Download Failed + Downloaden Mislukt + + + + Ensure the entered URL is valid, and the device’s internet connection is good. + Zorg ervoor dat de ingevoerde URL geldig is en dat de internetverbinding van het apparaat goed is. + + + + Reboot device + Apparaat opnieuw opstarten + + + + Start over + Begin opnieuw + + + + SetupWidget + + + Finish Setup + Installatie voltooien + + + + Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer. + Koppel uw apparaat met comma connect (connect.comma.ai) en claim uw comma prime-aanbieding. + + + + Pair device + Apparaat koppelen + + + + Sidebar + + + + CONNECT + VERBINDING + + + + OFFLINE + OFFLINE + + + + + ONLINE + ONLINE + + + + ERROR + FOUT + + + + + + TEMP + TEMP + + + + HIGH + HOOG + + + + GOOD + GOED + + + + OK + OK + + + + VEHICLE + VOERTUIG + + + + NO + GEEN + + + + PANDA + PANDA + + + + GPS + GPS + + + + SEARCH + ZOEKEN + + + + -- + -- + + + + Wi-Fi + Wi-Fi + + + + ETH + ETH + + + + 2G + 2G + + + + 3G + 3G + + + + LTE + 4G + + + + 5G + 5G + + + + SoftwarePanel + + + Git Branch + Git Branch + + + + Git Commit + Git Commit + + + + OS Version + OS Versie + + + + Version + Versie + + + + Last Update Check + Laatste Updatecontrole + + + + The last time openpilot successfully checked for an update. The updater only runs while the car is off. + De laatste keer dat openpilot met succes heeft gecontroleerd op een update. De updater werkt alleen als de auto is uitgeschakeld. + + + + Check for Update + Controleer op Updates + + + + CHECKING + CONTROLEER + + + + Switch Branch + Branch Verwisselen + + + + ENTER + INVOEREN + + + + + The new branch will be pulled the next time the updater runs. + Tijdens de volgende update wordt de nieuwe branch opgehaald. + + + + Enter branch name + Voer branch naam in + + + + Uninstall %1 + Verwijder %1 + + + + UNINSTALL + VERWIJDER + + + + Are you sure you want to uninstall? + Weet u zeker dat u de installatie ongedaan wilt maken? + + + + failed to fetch update + ophalen van update mislukt + + + + + CHECK + CONTROLEER + + + + SshControl + + + SSH Keys + SSH Sleutels + + + + 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. + Waarschuwing: dit geeft SSH toegang tot alle openbare sleutels in uw GitHub-instellingen. Voer nooit een andere GitHub-gebruikersnaam in dan die van uzelf. Een medewerker van comma zal u NOOIT vragen om zijn GitHub-gebruikersnaam toe te voegen. + + + + + ADD + TOEVOEGEN + + + + Enter your GitHub username + Voer uw GitHub gebruikersnaam in + + + + LOADING + LADEN + + + + REMOVE + VERWIJDEREN + + + + Username '%1' has no keys on GitHub + Gebruikersnaam '%1' heeft geen SSH sleutels op GitHub + + + + Request timed out + Time-out van aanvraag + + + + Username '%1' doesn't exist on GitHub + Gebruikersnaam '%1' bestaat niet op GitHub + + + + SshToggle + + + Enable SSH + SSH Inschakelen + + + + TermsPage + + + Terms & Conditions + Algemene Voorwaarden + + + + Decline + Afwijzen + + + + Scroll to accept + Scroll om te accepteren + + + + Agree + Akkoord + + + + TogglesPanel + + + Enable openpilot + openpilot Inschakelen + + + + 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. + Gebruik het openpilot-systeem voor adaptieve cruisecontrol en rijstrookassistentie. Uw aandacht is te allen tijde vereist om deze functie te gebruiken. Het wijzigen van deze instelling wordt van kracht wanneer de auto wordt uitgeschakeld. + + + + Enable Lane Departure Warnings + Waarschuwingen bij Verlaten Rijstrook Inschakelen + + + + 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). + Ontvang waarschuwingen om terug naar de rijstrook te sturen wanneer uw voertuig over een gedetecteerde rijstrookstreep drijft zonder dat de richtingaanwijzer wordt geactiveerd terwijl u harder rijdt dan 50 km/u (31 mph). + + + + Use Metric System + Gebruik Metrisch Systeem + + + + Display speed in km/h instead of mph. + Geef snelheid weer in km/u in plaats van mph. + + + + Record and Upload Driver Camera + Opnemen en Uploaden van de Bestuurders Camera + + + + Upload data from the driver facing camera and help improve the driver monitoring algorithm. + Upload gegevens van de bestuurders camera en help het algoritme voor het monitoren van de bestuurder te verbeteren. + + + + Disengage On Accelerator Pedal + Deactiveren Met Gaspedaal + + + + When enabled, pressing the accelerator pedal will disengage openpilot. + Indien ingeschakeld, zal het indrukken van het gaspedaal openpilot deactiveren. + + + + Show ETA in 24h Format + Toon verwachte aankomsttijd in 24-uurs formaat + + + + Use 24h format instead of am/pm + Gebruik 24-uurs formaat in plaats van AM en PM + + + + Show Map on Left Side of UI + Toon kaart aan linkerkant van het scherm + + + + Show map on left side when in split screen view. + Toon kaart links in gesplitste schermweergave. + + + + openpilot Longitudinal Control + openpilot Longitudinale Controle + + + + openpilot will disable the car's radar and will take over control of gas and brakes. Warning: this disables AEB! + openpilot zal de radar van de auto uitschakelen en de controle over gas en remmen overnemen. Waarschuwing: hierdoor wordt AEB (automatische noodrem) uitgeschakeld! + + + + Updater + + + Update Required + Update Vereist + + + + An operating system update is required. Connect your device to Wi-Fi for the fastest update experience. The download size is approximately 1GB. + Een update van het besturingssysteem is vereist. Verbind je apparaat met Wi-Fi voor de snelste update-ervaring. De downloadgrootte is ongeveer 1 GB. + + + + Connect to Wi-Fi + Maak verbinding met Wi-Fi + + + + Install + Installeer + + + + Back + Terug + + + + Loading... + Aan het laden... + + + + Reboot + Opnieuw Opstarten + + + + Update failed + Update mislukt + + + + WifiUI + + + + Scanning for networks... + Scannen naar netwerken... + + + + CONNECTING... + VERBINDEN... + + + + FORGET + VERGETEN + + + + Forget Wi-Fi Network "%1"? + Vergeet Wi-Fi Netwerk "%1"? + + + From b34fe711b05d444300a9b8ed9cbb70ee35932699 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Wed, 31 Aug 2022 13:51:10 -0700 Subject: [PATCH 123/172] Toyota: same standstill check as panda (#25570) * Same standstill check as panda * test honda in the same place * bump panda * bump panda * bump panda * bump to master * bump panda --- panda | 2 +- selfdrive/car/tests/test_models.py | 5 +++-- selfdrive/car/toyota/carstate.py | 2 +- 3 files changed, 5 insertions(+), 4 deletions(-) diff --git a/panda b/panda index 1776165a3..6d2e2bde8 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 1776165a3d902d6320965b6b6b1715bb9a25915b +Subproject commit 6d2e2bde861a237593740526b466d17d43849a17 diff --git a/selfdrive/car/tests/test_models.py b/selfdrive/car/tests/test_models.py index edfa07a8c..cc7d3da87 100755 --- a/selfdrive/car/tests/test_models.py +++ b/selfdrive/car/tests/test_models.py @@ -234,6 +234,9 @@ class TestCarModelBase(unittest.TestCase): checks['gasPressed'] += CS.gasPressed != self.safety.get_gas_pressed_prev() checks['cruiseState'] += CS.cruiseState.enabled and not CS.cruiseState.available + if self.CP.carName in ("honda", "toyota"): + # TODO: fix standstill mismatches for other makes + checks['standstill'] += CS.standstill == self.safety.get_vehicle_moving() # TODO: remove this exception once this mismatch is resolved brake_pressed = CS.brakePressed @@ -263,8 +266,6 @@ class TestCarModelBase(unittest.TestCase): if self.CP.carName == "honda": checks['mainOn'] += CS.cruiseState.available != self.safety.get_acc_main_on() - # TODO: fix standstill mismatches for other makes - checks['standstill'] += CS.standstill == self.safety.get_vehicle_moving() CS_prev = CS diff --git a/selfdrive/car/toyota/carstate.py b/selfdrive/car/toyota/carstate.py index 843e7806d..70ba690aa 100644 --- a/selfdrive/car/toyota/carstate.py +++ b/selfdrive/car/toyota/carstate.py @@ -53,7 +53,7 @@ class CarState(CarStateBase): ret.vEgoRaw = mean([ret.wheelSpeeds.fl, ret.wheelSpeeds.fr, ret.wheelSpeeds.rl, ret.wheelSpeeds.rr]) ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) - ret.standstill = ret.vEgoRaw < 0.001 + ret.standstill = ret.vEgoRaw == 0 ret.steeringAngleDeg = cp.vl["STEER_ANGLE_SENSOR"]["STEER_ANGLE"] + cp.vl["STEER_ANGLE_SENSOR"]["STEER_FRACTION"] torque_sensor_angle_deg = cp.vl["STEER_TORQUE_SENSOR"]["STEER_ANGLE"] From 02bf3399956fa6cba84ba3c578771761b8d31c8e Mon Sep 17 00:00:00 2001 From: AlexandreSato <66435071+AlexandreSato@users.noreply.github.com> Date: Wed, 31 Aug 2022 19:50:56 -0300 Subject: [PATCH 124/172] Multilang: improve pt-BR translation (#25623) * fix and improve pt-BR translation * Shorter phrase for Finish Setup * Concluir are better than Encerrar bacause means sucessfuly * improve pt-BR, DEVbrazilians use english as default * fix "atualizador" text cutoff * miss mark as finish on qt linguist --- selfdrive/ui/translations/main_pt-BR.ts | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/selfdrive/ui/translations/main_pt-BR.ts b/selfdrive/ui/translations/main_pt-BR.ts index c6c7ca26d..e0d6a3c04 100644 --- a/selfdrive/ui/translations/main_pt-BR.ts +++ b/selfdrive/ui/translations/main_pt-BR.ts @@ -185,7 +185,7 @@ Change Language - Mudar Língua + Mudar Linguagem @@ -1029,7 +1029,7 @@ trabalho definido Switch Branch - Trocar Ramo + Trocar Branch @@ -1040,12 +1040,12 @@ trabalho definido The new branch will be pulled the next time the updater runs. - O novo ramo será aplicado na próxima execução do atualizador. + A nova branch será aplicada ao verificar atualizações. Enter branch name - Inserir o nome do ramo + Inserir o nome da branch @@ -1055,7 +1055,7 @@ trabalho definido Uninstall %1 - Desintalando %1 + Desintalar o %1 From e9258cccbed66dd69781b5184e34760fb8cfeb0a Mon Sep 17 00:00:00 2001 From: ZwX1616 Date: Wed, 31 Aug 2022 16:40:25 -0700 Subject: [PATCH 125/172] camerad: optional exposure params overrides (#25616) * add params override * speedup * put in param list * clean up names Co-authored-by: Comma Device --- common/params.cc | 2 + system/camerad/cameras/camera_common.h | 1 + system/camerad/cameras/camera_qcom2.cc | 58 ++++++++++++++++---------- system/camerad/cameras/camera_qcom2.h | 1 + 4 files changed, 39 insertions(+), 23 deletions(-) diff --git a/common/params.cc b/common/params.cc index a25cd278a..e5071268b 100644 --- a/common/params.cc +++ b/common/params.cc @@ -88,6 +88,8 @@ std::unordered_map keys = { {"AthenadPid", PERSISTENT}, {"AthenadUploadQueue", PERSISTENT}, {"CalibrationParams", PERSISTENT}, + {"CameraDebugExpGain", CLEAR_ON_MANAGER_START}, + {"CameraDebugExpTime", CLEAR_ON_MANAGER_START}, {"CarBatteryCapacity", PERSISTENT}, {"CarParams", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_ON}, {"CarParamsCache", CLEAR_ON_MANAGER_START}, diff --git a/system/camerad/cameras/camera_common.h b/system/camerad/cameras/camera_common.h index 198efca0b..e87eaf4b9 100644 --- a/system/camerad/cameras/camera_common.h +++ b/system/camerad/cameras/camera_common.h @@ -40,6 +40,7 @@ const bool env_disable_wide_road = getenv("DISABLE_WIDE_ROAD") != NULL; const bool env_disable_driver = getenv("DISABLE_DRIVER") != NULL; const bool env_debug_frames = getenv("DEBUG_FRAMES") != NULL; const bool env_log_raw_frames = getenv("LOG_RAW_FRAMES") != NULL; +const bool env_ctrl_exp_from_params = getenv("CTRL_EXP_FROM_PARAMS") != NULL; typedef struct CameraInfo { uint32_t frame_width, frame_height; diff --git a/system/camerad/cameras/camera_qcom2.cc b/system/camerad/cameras/camera_qcom2.cc index b6a156445..c06aeb436 100644 --- a/system/camerad/cameras/camera_qcom2.cc +++ b/system/camerad/cameras/camera_qcom2.cc @@ -1101,36 +1101,48 @@ void CameraState::set_camera_exposure(float grey_frac) { } else if (enable_dc_gain && target_grey > 0.3) { enable_dc_gain = false; } + if (env_ctrl_exp_from_params) { + // Override gain and exposure time + if (buf.cur_frame_data.frame_id % 5 == 0) { + std::string gain_bytes = Params().get("CameraDebugExpGain"); + std::string time_bytes = Params().get("CameraDebugExpTime"); + gain_idx = std::stoi(gain_bytes); + exposure_time = std::stoi(time_bytes); + } + new_g = gain_idx; + new_t = exposure_time; + enable_dc_gain = false; + } else { + // Simple brute force optimizer to choose sensor parameters + // to reach desired EV + for (int g = std::max((int)ANALOG_GAIN_MIN_IDX, gain_idx - 1); g <= std::min((int)ANALOG_GAIN_MAX_IDX, gain_idx + 1); g++) { + float gain = sensor_analog_gains[g] * (enable_dc_gain ? DC_GAIN : 1); - // Simple brute force optimizer to choose sensor parameters - // to reach desired EV - for (int g = std::max((int)ANALOG_GAIN_MIN_IDX, gain_idx - 1); g <= std::min((int)ANALOG_GAIN_MAX_IDX, gain_idx + 1); g++) { - float gain = sensor_analog_gains[g] * (enable_dc_gain ? DC_GAIN : 1); - - // Compute optimal time for given gain - int t = std::clamp(int(std::round(desired_ev / gain)), EXPOSURE_TIME_MIN, EXPOSURE_TIME_MAX); + // Compute optimal time for given gain + int t = std::clamp(int(std::round(desired_ev / gain)), EXPOSURE_TIME_MIN, EXPOSURE_TIME_MAX); - // Only go below recommended gain when absolutely necessary to not overexpose - if (g < ANALOG_GAIN_REC_IDX && t > 20 && g < gain_idx) { - continue; - } + // Only go below recommended gain when absolutely necessary to not overexpose + if (g < ANALOG_GAIN_REC_IDX && t > 20 && g < gain_idx) { + continue; + } - // Compute error to desired ev - float score = std::abs(desired_ev - (t * gain)) * 10; + // Compute error to desired ev + float score = std::abs(desired_ev - (t * gain)) * 10; - // Going below recommended gain needs lower penalty to not overexpose - float m = g > ANALOG_GAIN_REC_IDX ? 5.0 : 0.1; - score += std::abs(g - (int)ANALOG_GAIN_REC_IDX) * m; + // Going below recommended gain needs lower penalty to not overexpose + float m = g > ANALOG_GAIN_REC_IDX ? 5.0 : 0.1; + score += std::abs(g - (int)ANALOG_GAIN_REC_IDX) * m; - // LOGE("cam: %d - gain: %d, t: %d (%.2f), score %.2f, score + gain %.2f, %.3f, %.3f", camera_num, g, t, desired_ev / gain, score, score + std::abs(g - gain_idx) * (score + 1.0) / 10.0, desired_ev, min_ev); + // LOGE("cam: %d - gain: %d, t: %d (%.2f), score %.2f, score + gain %.2f, %.3f, %.3f", camera_num, g, t, desired_ev / gain, score, score + std::abs(g - gain_idx) * (score + 1.0) / 10.0, desired_ev, min_ev); - // Small penalty on changing gain - score += std::abs(g - gain_idx) * (score + 1.0) / 10.0; + // Small penalty on changing gain + score += std::abs(g - gain_idx) * (score + 1.0) / 10.0; - if (score < best_ev_score) { - new_t = t; - new_g = g; - best_ev_score = score; + if (score < best_ev_score) { + new_t = t; + new_g = g; + best_ev_score = score; + } } } diff --git a/system/camerad/cameras/camera_qcom2.h b/system/camerad/cameras/camera_qcom2.h index 03d3d1a82..e75e7e586 100644 --- a/system/camerad/cameras/camera_qcom2.h +++ b/system/camerad/cameras/camera_qcom2.h @@ -7,6 +7,7 @@ #include #include "system/camerad/cameras/camera_common.h" +#include "common/params.h" #include "common/util.h" #define FRAME_BUF_COUNT 4 From bd9966c4777a7b4393d65cc0f62d726a9fdf1ff1 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Wed, 31 Aug 2022 17:54:21 -0700 Subject: [PATCH 126/172] test_fw_query_on_routes: find first non-none path (#25628) find first non-none path --- selfdrive/debug/test_fw_query_on_routes.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/debug/test_fw_query_on_routes.py b/selfdrive/debug/test_fw_query_on_routes.py index 6cc7da5f1..595e25e8c 100755 --- a/selfdrive/debug/test_fw_query_on_routes.py +++ b/selfdrive/debug/test_fw_query_on_routes.py @@ -56,7 +56,7 @@ if __name__ == "__main__": qlog_path = f"cd:/{dongle_id}/{time}/0/qlog.bz2" else: route = Route(route) - qlog_path = route.qlog_paths()[0] + qlog_path = next((p for p in route.qlog_paths() if p is not None), None) if qlog_path is None: continue From 28cb1897cb8be80b35b1ce7573066fb36b01d2d7 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 31 Aug 2022 21:13:53 -0700 Subject: [PATCH 127/172] USB power mode cleanup (#25619) * first pass at usb power mode cleanup * fix build * a sneaky one * little more * fix build * bump pnada * remove that * power monitoring cleanup * fix tests * bump submodules --- cereal | 2 +- panda | 2 +- selfdrive/boardd/boardd.cc | 32 ++----------------- selfdrive/boardd/panda.cc | 4 --- selfdrive/boardd/panda.h | 1 - selfdrive/thermald/power_monitoring.py | 29 +++++------------ .../thermald/tests/test_power_monitoring.py | 20 ++++++------ selfdrive/thermald/thermald.py | 9 +----- system/hardware/base.py | 4 --- system/hardware/pc/hardware.py | 5 +-- system/hardware/tici/hardware.py | 1 - 11 files changed, 24 insertions(+), 85 deletions(-) diff --git a/cereal b/cereal index d05d3cbd0..d3a943ef6 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit d05d3cbd0e1243c3fef63c58ab15aeb7508159a7 +Subproject commit d3a943ef660dd29f73700806ee0baf1d5aff6834 diff --git a/panda b/panda index 6d2e2bde8..13d64d4cc 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 6d2e2bde861a237593740526b466d17d43849a17 +Subproject commit 13d64d4cc38295401ff1ffcf6a233a4b9625fd9f diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index 59579a7fc..47bff1c5b 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -197,12 +197,6 @@ Panda *usb_connect(std::string serial="", uint32_t index=0) { } //panda->enable_deepsleep(); - // power on charging, only the first time. Panda can also change mode and it causes a brief disconneciton -#ifndef __x86_64__ - static std::once_flag connected_once; - std::call_once(connected_once, &Panda::set_usb_power_mode, panda, cereal::PeripheralState::UsbPowerMode::CDP); -#endif - sync_time(panda.get(), SyncTimeDir::FROM_PANDA); return panda.release(); } @@ -391,13 +385,6 @@ std::optional send_panda_states(PubMaster *pm, const std::vector } void send_peripheral_state(PubMaster *pm, Panda *panda) { - auto pandaState_opt = panda->get_state(); - if (!pandaState_opt) { - return; - } - - health_t pandaState = *pandaState_opt; - // build msg MessageBuilder msg; auto evt = msg.initEvent(); @@ -415,7 +402,6 @@ void send_peripheral_state(PubMaster *pm, Panda *panda) { } uint16_t fan_speed_rpm = panda->get_fan_speed(); - ps.setUsbPowerMode(cereal::PeripheralState::UsbPowerMode(pandaState.usb_power_mode_pkt)); ps.setFanSpeedRpm(fan_speed_rpm); pm->send("peripheralState", msg); @@ -491,7 +477,6 @@ void peripheral_control_thread(Panda *panda) { uint16_t prev_fan_speed = 999; uint16_t ir_pwr = 0; uint16_t prev_ir_pwr = 999; - bool prev_charging_disabled = false; unsigned int cnt = 0; FirstOrderFilter integ_lines_filter(0, 30.0, 0.05); @@ -500,23 +485,9 @@ void peripheral_control_thread(Panda *panda) { cnt++; sm.update(1000); // TODO: what happens if EINTR is sent while in sm.update? - if (!Hardware::PC() && sm.updated("deviceState")) { - // Charging mode - bool charging_disabled = sm["deviceState"].getDeviceState().getChargingDisabled(); - if (charging_disabled != prev_charging_disabled) { - if (charging_disabled) { - panda->set_usb_power_mode(cereal::PeripheralState::UsbPowerMode::CLIENT); - LOGW("TURN OFF CHARGING!\n"); - } else { - panda->set_usb_power_mode(cereal::PeripheralState::UsbPowerMode::CDP); - LOGW("TURN ON CHARGING!\n"); - } - prev_charging_disabled = charging_disabled; - } - } - // Other pandas don't have fan/IR to control if (panda->hw_type != cereal::PandaState::PandaType::UNO && panda->hw_type != cereal::PandaState::PandaType::DOS) continue; + if (sm.updated("deviceState")) { // Fan speed uint16_t fan_speed = sm["deviceState"].getDeviceState().getFanSpeedPercentDesired(); @@ -541,6 +512,7 @@ void peripheral_control_thread(Panda *panda) { ir_pwr = 100.0 * (MIN_IR_POWER + ((cur_integ_lines - CUTOFF_IL) * (MAX_IR_POWER - MIN_IR_POWER) / (SATURATE_IL - CUTOFF_IL))); } } + // Disable ir_pwr on front frame timeout uint64_t cur_t = nanos_since_boot(); if (cur_t - last_front_frame_t > 1e9) { diff --git a/selfdrive/boardd/panda.cc b/selfdrive/boardd/panda.cc index d90c4cdab..685dabd87 100644 --- a/selfdrive/boardd/panda.cc +++ b/selfdrive/boardd/panda.cc @@ -342,10 +342,6 @@ void Panda::enable_deepsleep() { usb_write(0xfb, 0, 0); } -void Panda::set_usb_power_mode(cereal::PeripheralState::UsbPowerMode power_mode) { - usb_write(0xe6, (uint16_t)power_mode, 0); -} - void Panda::send_heartbeat(bool engaged) { usb_write(0xf3, engaged, 0); } diff --git a/selfdrive/boardd/panda.h b/selfdrive/boardd/panda.h index 23a10d585..1cefc3cb4 100644 --- a/selfdrive/boardd/panda.h +++ b/selfdrive/boardd/panda.h @@ -86,7 +86,6 @@ class Panda { std::optional get_serial(); void set_power_saving(bool power_saving); void enable_deepsleep(); - void set_usb_power_mode(cereal::PeripheralState::UsbPowerMode power_mode); void send_heartbeat(bool engaged); void set_can_speed_kbps(uint16_t bus, uint16_t speed); void set_data_speed_kbps(uint16_t bus, uint16_t speed); diff --git a/selfdrive/thermald/power_monitoring.py b/selfdrive/thermald/power_monitoring.py index 9f009d326..783456908 100644 --- a/selfdrive/thermald/power_monitoring.py +++ b/selfdrive/thermald/power_monitoring.py @@ -108,32 +108,19 @@ class PowerMonitoring: def get_car_battery_capacity(self) -> int: return int(self.car_battery_capacity_uWh) - # See if we need to disable charging - def should_disable_charging(self, ignition: bool, in_car: bool, offroad_timestamp: Optional[float]) -> bool: - if offroad_timestamp is None: - return False - - now = sec_since_boot() - disable_charging = False - disable_charging |= (now - offroad_timestamp) > MAX_TIME_OFFROAD_S - disable_charging |= (self.car_voltage_mV < (VBATT_PAUSE_CHARGING * 1e3)) and (self.car_voltage_instant_mV > (VBATT_INSTANT_PAUSE_CHARGING * 1e3)) - disable_charging |= (self.car_battery_capacity_uWh <= 0) - disable_charging &= not ignition - disable_charging &= (not self.params.get_bool("DisablePowerDown")) - disable_charging &= in_car - disable_charging |= self.params.get_bool("ForcePowerDown") - return disable_charging - # See if we need to shutdown - def should_shutdown(self, peripheralState, ignition, in_car, offroad_timestamp, started_seen): + def should_shutdown(self, ignition: bool, in_car: bool, offroad_timestamp: Optional[float], started_seen: bool): if offroad_timestamp is None: return False now = sec_since_boot() - panda_charging = (peripheralState.usbPowerMode != log.PeripheralState.UsbPowerMode.client) - should_shutdown = False - # Wait until we have shut down charging before powering down - should_shutdown |= (not panda_charging and self.should_disable_charging(ignition, in_car, offroad_timestamp)) + should_shutdown |= (now - offroad_timestamp) > MAX_TIME_OFFROAD_S + should_shutdown |= (self.car_voltage_mV < (VBATT_PAUSE_CHARGING * 1e3)) and (self.car_voltage_instant_mV > (VBATT_INSTANT_PAUSE_CHARGING * 1e3)) + should_shutdown |= (self.car_battery_capacity_uWh <= 0) + should_shutdown &= not ignition + should_shutdown &= (not self.params.get_bool("DisablePowerDown")) + should_shutdown &= in_car + should_shutdown |= self.params.get_bool("ForcePowerDown") should_shutdown &= started_seen or (now > MIN_ON_TIME_S) return should_shutdown diff --git a/selfdrive/thermald/tests/test_power_monitoring.py b/selfdrive/thermald/tests/test_power_monitoring.py index adcdaf427..5d7463d45 100755 --- a/selfdrive/thermald/tests/test_power_monitoring.py +++ b/selfdrive/thermald/tests/test_power_monitoring.py @@ -129,8 +129,8 @@ class TestPowerMonitoring(unittest.TestCase): while ssb <= start_time + MOCKED_MAX_OFFROAD_TIME: pm.calculate(peripheralState, ignition) if (ssb - start_time) % 1000 == 0 and ssb < start_time + MOCKED_MAX_OFFROAD_TIME: - self.assertFalse(pm.should_disable_charging(ignition, True, start_time)) - self.assertTrue(pm.should_disable_charging(ignition, True, start_time)) + self.assertFalse(pm.should_shutdown(ignition, True, start_time, False)) + self.assertTrue(pm.should_shutdown(ignition, True, start_time, False)) # Test to check policy of stopping charging when the car voltage is too low @parameterized.expand(ALL_PANDA_TYPES) @@ -145,8 +145,8 @@ class TestPowerMonitoring(unittest.TestCase): for i in range(TEST_TIME): pm.calculate(peripheralState, ignition) if i % 10 == 0: - self.assertEqual(pm.should_disable_charging(ignition, True, ssb), (pm.car_voltage_mV < VBATT_PAUSE_CHARGING*1e3)) - self.assertTrue(pm.should_disable_charging(ignition, True, ssb)) + self.assertEqual(pm.should_shutdown(ignition, True, ssb, True), (pm.car_voltage_mV < VBATT_PAUSE_CHARGING*1e3)) + self.assertTrue(pm.should_shutdown(ignition, True, ssb, True)) # Test to check policy of not stopping charging when DisablePowerDown is set def test_disable_power_down(self): @@ -161,8 +161,8 @@ class TestPowerMonitoring(unittest.TestCase): for i in range(TEST_TIME): pm.calculate(peripheralState, ignition) if i % 10 == 0: - self.assertFalse(pm.should_disable_charging(ignition, True, ssb)) - self.assertFalse(pm.should_disable_charging(ignition, True, ssb)) + self.assertFalse(pm.should_shutdown(ignition, True, ssb, False)) + self.assertFalse(pm.should_shutdown(ignition, True, ssb, False)) # Test to check policy of not stopping charging when ignition def test_ignition(self): @@ -176,8 +176,8 @@ class TestPowerMonitoring(unittest.TestCase): for i in range(TEST_TIME): pm.calculate(peripheralState, ignition) if i % 10 == 0: - self.assertFalse(pm.should_disable_charging(ignition, True, ssb)) - self.assertFalse(pm.should_disable_charging(ignition, True, ssb)) + self.assertFalse(pm.should_shutdown(ignition, True, ssb, False)) + self.assertFalse(pm.should_shutdown(ignition, True, ssb, False)) # Test to check policy of not stopping charging when harness is not connected def test_harness_connection(self): @@ -192,8 +192,8 @@ class TestPowerMonitoring(unittest.TestCase): for i in range(TEST_TIME): pm.calculate(peripheralState, ignition) if i % 10 == 0: - self.assertFalse(pm.should_disable_charging(ignition, False,ssb)) - self.assertFalse(pm.should_disable_charging(ignition, False, ssb)) + self.assertFalse(pm.should_shutdown(ignition, False, ssb, False)) + self.assertFalse(pm.should_shutdown(ignition, False, ssb, False)) if __name__ == "__main__": unittest.main() diff --git a/selfdrive/thermald/thermald.py b/selfdrive/thermald/thermald.py index c765af664..5c2fbd682 100755 --- a/selfdrive/thermald/thermald.py +++ b/selfdrive/thermald/thermald.py @@ -177,7 +177,6 @@ def thermald_thread(end_event, hw_queue): modem_temps=[], ) - current_filter = FirstOrderFilter(0., CURRENT_TAU, DT_TRML) temp_filter = FirstOrderFilter(0., TEMP_TAU, DT_TRML) should_start_prev = False in_car = False @@ -239,8 +238,6 @@ def thermald_thread(end_event, hw_queue): msg.deviceState.modemTempC = last_hw_state.modem_temps msg.deviceState.screenBrightnessPercent = HARDWARE.get_screen_brightness() - msg.deviceState.usbOnline = HARDWARE.get_usb_present() - current_filter.update(msg.deviceState.batteryCurrent / 1e6) max_comp_temp = temp_filter.update( max(max(msg.deviceState.cpuTempC), msg.deviceState.memoryTempC, max(msg.deviceState.gpuTempC)) @@ -350,15 +347,11 @@ def thermald_thread(end_event, hw_queue): statlog.sample("som_power_draw", som_power_draw) msg.deviceState.somPowerDrawW = som_power_draw - # Check if we need to disable charging (handled by boardd) - msg.deviceState.chargingDisabled = power_monitor.should_disable_charging(onroad_conditions["ignition"], in_car, off_ts) - # Check if we need to shut down - if power_monitor.should_shutdown(peripheralState, onroad_conditions["ignition"], in_car, off_ts, started_seen): + if power_monitor.should_shutdown(onroad_conditions["ignition"], in_car, off_ts, started_seen): cloudlog.warning(f"shutting device down, offroad since {off_ts}") params.put_bool("DoShutdown", True) - msg.deviceState.chargingError = current_filter.x > 0. and msg.deviceState.batteryPercent < 90 # if current is positive, then battery is being discharged msg.deviceState.started = started_ts is not None msg.deviceState.startedMonoTime = int(1e9*(started_ts or 0)) diff --git a/system/hardware/base.py b/system/hardware/base.py index c9c02f3a5..31df1babe 100644 --- a/system/hardware/base.py +++ b/system/hardware/base.py @@ -78,10 +78,6 @@ class HardwareBase(ABC): def set_bandwidth_limit(upload_speed_kbps: int, download_speed_kbps: int) -> None: pass - @abstractmethod - def get_usb_present(self): - pass - @abstractmethod def get_current_power_draw(self): pass diff --git a/system/hardware/pc/hardware.py b/system/hardware/pc/hardware.py index 60d14e4a6..564f9e483 100644 --- a/system/hardware/pc/hardware.py +++ b/system/hardware/pc/hardware.py @@ -50,12 +50,9 @@ class Pc(HardwareBase): def get_network_strength(self, network_type): return NetworkStrength.unknown - def get_usb_present(self): - return False - def get_current_power_draw(self): return 0 - + def get_som_power_draw(self): return 0 diff --git a/system/hardware/tici/hardware.py b/system/hardware/tici/hardware.py index 14a7101c6..340093b60 100644 --- a/system/hardware/tici/hardware.py +++ b/system/hardware/tici/hardware.py @@ -372,7 +372,6 @@ class Tici(HardwareBase): return (self.read_param_file("/sys/class/power_supply/bms/voltage_now", int) * self.read_param_file("/sys/class/power_supply/bms/current_now", int) / 1e12) def shutdown(self): - # Note that for this to work and have the device stay powered off, the panda needs to be in UsbPowerMode::CLIENT! os.system("sudo poweroff") def get_thermal_config(self): From 4bb399ba3c13953680522707bba662527fa771b7 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 31 Aug 2022 23:12:26 -0700 Subject: [PATCH 128/172] pigeond tests (#25630) * start pigeond tests * sm checks * add some types * little more Co-authored-by: Comma Device --- Jenkinsfile | 3 +- common/gpio.py | 13 +++- selfdrive/sensord/{test => }/__init__.py | 0 selfdrive/sensord/pigeond.py | 59 ++++++++--------- selfdrive/sensord/tests/__init__.py | 0 selfdrive/sensord/tests/test_pigeond.py | 63 +++++++++++++++++++ .../sensord/{test => tests}/test_sensord.py | 0 .../sensord/{test => tests}/ttff_test.py | 0 8 files changed, 107 insertions(+), 31 deletions(-) rename selfdrive/sensord/{test => }/__init__.py (100%) create mode 100644 selfdrive/sensord/tests/__init__.py create mode 100755 selfdrive/sensord/tests/test_pigeond.py rename selfdrive/sensord/{test => tests}/test_sensord.py (100%) rename selfdrive/sensord/{test => tests}/ttff_test.py (100%) diff --git a/Jenkinsfile b/Jenkinsfile index 6b05e81d7..c4038090e 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -131,7 +131,8 @@ pipeline { ["test boardd loopback", "python selfdrive/boardd/tests/test_boardd_loopback.py"], ["test loggerd", "python selfdrive/loggerd/tests/test_loggerd.py"], ["test encoder", "LD_LIBRARY_PATH=/usr/local/lib python selfdrive/loggerd/tests/test_encoder.py"], - ["test sensord", "python selfdrive/sensord/test/test_sensord.py"], + ["test sensord", "python selfdrive/sensord/tests/test_sensord.py"], + ["test pigeond", "python selfdrive/sensord/tests/test_pigeond.py"], ]) } } diff --git a/common/gpio.py b/common/gpio.py index 32e5ca86c..260f8898a 100644 --- a/common/gpio.py +++ b/common/gpio.py @@ -1,3 +1,5 @@ +from typing import Optional + def gpio_init(pin: int, output: bool) -> None: try: with open(f"/sys/class/gpio/gpio{pin}/direction", 'wb') as f: @@ -5,10 +7,19 @@ def gpio_init(pin: int, output: bool) -> None: except Exception as e: print(f"Failed to set gpio {pin} direction: {e}") - def gpio_set(pin: int, high: bool) -> None: try: with open(f"/sys/class/gpio/gpio{pin}/value", 'wb') as f: f.write(b"1" if high else b"0") except Exception as e: print(f"Failed to set gpio {pin} value: {e}") + +def gpio_read(pin: int) -> Optional[bool]: + val = None + try: + with open(f"/sys/class/gpio/gpio{pin}/value", 'rb') as f: + val = bool(int(f.read().strip())) + except Exception as e: + print(f"Failed to set gpio {pin} value: {e}") + + return val diff --git a/selfdrive/sensord/test/__init__.py b/selfdrive/sensord/__init__.py similarity index 100% rename from selfdrive/sensord/test/__init__.py rename to selfdrive/sensord/__init__.py diff --git a/selfdrive/sensord/pigeond.py b/selfdrive/sensord/pigeond.py index 95a27189d..e38e2d4c3 100755 --- a/selfdrive/sensord/pigeond.py +++ b/selfdrive/sensord/pigeond.py @@ -1,5 +1,4 @@ #!/usr/bin/env python3 - import sys import time import signal @@ -8,6 +7,7 @@ import struct import requests import urllib.parse from datetime import datetime +from typing import List, Optional from cereal import messaging from common.params import Params @@ -25,7 +25,7 @@ UBLOX_SOS_NACK = b"\xb5\x62\x09\x14\x08\x00\x02\x00\x00\x00\x00\x00\x00\x00" UBLOX_BACKUP_RESTORE_MSG = b"\xb5\x62\x09\x14\x08\x00\x03" UBLOX_ASSIST_ACK = b"\xb5\x62\x13\x60\x08\x00" -def set_power(enabled): +def set_power(enabled: bool) -> None: gpio_init(GPIO.UBLOX_SAFEBOOT_N, True) gpio_init(GPIO.UBLOX_PWR_EN, True) gpio_init(GPIO.UBLOX_RST_N, True) @@ -35,14 +35,14 @@ def set_power(enabled): gpio_set(GPIO.UBLOX_RST_N, enabled) -def add_ubx_checksum(msg): +def add_ubx_checksum(msg: bytes) -> bytes: A = B = 0 for b in msg[2:]: A = (A + b) % 256 B = (B + A) % 256 return msg + bytes([A, B]) -def get_assistnow_messages(token): +def get_assistnow_messages(token: bytes) -> List[bytes]: # make request # TODO: implement adding the last known location r = requests.get("https://online-live2.services.u-blox.com/GetOnlineData.ashx", params=urllib.parse.urlencode({ @@ -64,14 +64,13 @@ def get_assistnow_messages(token): class TTYPigeon(): - def __init__(self, path): - self.path = path + def __init__(self): self.tty = serial.VTIMESerial(UBLOX_TTY, baudrate=9600, timeout=0) - def send(self, dat): + def send(self, dat: bytes) -> None: self.tty.write(dat) - def receive(self): + def receive(self) -> bytes: dat = b'' while len(dat) < 0x1000: d = self.tty.read(0x40) @@ -80,10 +79,10 @@ class TTYPigeon(): break return dat - def set_baud(self, baud): + def set_baud(self, baud: int) -> None: self.tty.baudrate = baud - def wait_for_ack(self, ack=UBLOX_ACK, nack=UBLOX_NACK, timeout=0.5): + def wait_for_ack(self, ack: bytes = UBLOX_ACK, nack: bytes = UBLOX_NACK, timeout: float = 0.5) -> bool: dat = b'' st = time.monotonic() while True: @@ -99,11 +98,11 @@ class TTYPigeon(): raise TimeoutError('No response from ublox') time.sleep(0.001) - def send_with_ack(self, dat, ack=UBLOX_ACK, nack=UBLOX_NACK): + def send_with_ack(self, dat: bytes, ack: bytes = UBLOX_ACK, nack: bytes = UBLOX_NACK) -> None: self.send(dat) self.wait_for_ack(ack, nack) - def wait_for_backup_restore_status(self, timeout=1): + def wait_for_backup_restore_status(self, timeout: float = 1.) -> int: dat = b'' st = time.monotonic() while True: @@ -117,7 +116,7 @@ class TTYPigeon(): time.sleep(0.001) -def initialize_pigeon(pigeon): +def initialize_pigeon(pigeon: TTYPigeon) -> None: # try initializing a few times for _ in range(10): try: @@ -200,21 +199,22 @@ def initialize_pigeon(pigeon): except TimeoutError: cloudlog.warning("Initialization failed, trying again!") -def deinitialize_and_exit(pigeon): +def deinitialize_and_exit(pigeon: Optional[TTYPigeon]): cloudlog.warning("Storing almanac in ublox flash") - # controlled GNSS stop - pigeon.send(b"\xB5\x62\x06\x04\x04\x00\x00\x00\x08\x00\x16\x74") + if pigeon is not None: + # 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 pigeon.wait_for_ack(ack=UBLOX_SOS_ACK, nack=UBLOX_SOS_NACK): - cloudlog.warning("Done storing almanac") - else: - cloudlog.error("Error storing almanac") - except TimeoutError: - pass + # store almanac in flash + pigeon.send(b"\xB5\x62\x09\x14\x04\x00\x00\x00\x00\x00\x21\xEC") + try: + if pigeon.wait_for_ack(ack=UBLOX_SOS_ACK, nack=UBLOX_SOS_NACK): + cloudlog.warning("Done storing almanac") + else: + cloudlog.error("Error storing almanac") + except TimeoutError: + pass # turn off power and exit cleanly set_power(False) @@ -223,6 +223,10 @@ def deinitialize_and_exit(pigeon): def main(): assert TICI, "unsupported hardware for pigeond" + # register exit handler + pigeon = None + signal.signal(signal.SIGINT, lambda sig, frame: deinitialize_and_exit(pigeon)) + pm = messaging.PubMaster(['ubloxRaw']) # power cycle ublox @@ -231,12 +235,9 @@ def main(): set_power(True) time.sleep(0.5) - pigeon = TTYPigeon(UBLOX_TTY) + pigeon = TTYPigeon() initialize_pigeon(pigeon) - # register exit handler - signal.signal(signal.SIGINT, lambda sig, frame: deinitialize_and_exit(pigeon)) - # start receiving data while True: dat = pigeon.receive() diff --git a/selfdrive/sensord/tests/__init__.py b/selfdrive/sensord/tests/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/selfdrive/sensord/tests/test_pigeond.py b/selfdrive/sensord/tests/test_pigeond.py new file mode 100755 index 000000000..d15b731d0 --- /dev/null +++ b/selfdrive/sensord/tests/test_pigeond.py @@ -0,0 +1,63 @@ +#!/usr/bin/env python3 +import time +import unittest + +import cereal.messaging as messaging +from cereal.services import service_list +from common.gpio import gpio_read +from selfdrive.test.helpers import with_processes +from selfdrive.manager.process_config import managed_processes +from system.hardware import TICI +from system.hardware.tici.pins import GPIO + + +# TODO: test TTFF when we have good A-GNSS +class TestPigeond(unittest.TestCase): + @classmethod + def setUpClass(cls): + if not TICI: + raise unittest.SkipTest + + def tearDown(self): + managed_processes['pigeond'].stop() + + @with_processes(['pigeond']) + def test_frequency(self): + sm = messaging.SubMaster(['ubloxRaw']) + + # setup time + time.sleep(2) + sm.update() + + for _ in range(int(10 * service_list['ubloxRaw'].frequency)): + sm.update() + assert sm.all_checks() + + def test_startup_time(self): + for _ in range(5): + sm = messaging.SubMaster(['ubloxRaw']) + managed_processes['pigeond'].start() + + start_time = time.monotonic() + for __ in range(10): + sm.update(1 * 1000) + if sm.updated['ubloxRaw']: + break + assert sm.rcv_frame['ubloxRaw'] > 0, "pigeond didn't start outputting messages in time" + + et = time.monotonic() - start_time + assert et < 5, f"pigeond took {et:.1f}s to start" + managed_processes['pigeond'].stop() + + def test_turns_off_ublox(self): + for s in (0.1, 0.5, 1, 5): + managed_processes['pigeond'].start() + time.sleep(s) + managed_processes['pigeond'].stop() + + assert gpio_read(GPIO.UBLOX_RST_N) == 0 + assert gpio_read(GPIO.UBLOX_PWR_EN) == 0 + + +if __name__ == "__main__": + unittest.main() diff --git a/selfdrive/sensord/test/test_sensord.py b/selfdrive/sensord/tests/test_sensord.py similarity index 100% rename from selfdrive/sensord/test/test_sensord.py rename to selfdrive/sensord/tests/test_sensord.py diff --git a/selfdrive/sensord/test/ttff_test.py b/selfdrive/sensord/tests/ttff_test.py similarity index 100% rename from selfdrive/sensord/test/ttff_test.py rename to selfdrive/sensord/tests/ttff_test.py From 40d6f4b65c3776ffd78b3c3285dc5532a802c423 Mon Sep 17 00:00:00 2001 From: George Hotz <72895+geohot@users.noreply.github.com> Date: Thu, 1 Sep 2022 10:31:14 -0700 Subject: [PATCH 129/172] modeld: Move from SNPE to tinygrad (#25207) * compiling, won't work yet * running with inputs and outputs * there's some magic chance this works * no more dlc, include onnx * yolo tests plz * bump tinygrad * files_common + delete dlc * tinygrad_repo -> tinygrad * pre commit config * llops needed * extra in files_common * bump tinygrad * fix indent * tinygrad/nn/__init__ * tinygrad_repo * bump tinygrad repo * bump tinygrad * bump with native_exp, match maybe * native_explog is argument * pyopencl no cache * 5% chance this matches * work in float32? * bump tinygrad * fix build * no __init__ * fix recip * dumb hack * adding thneed PC support * fix pc segfault * pc thneed is working * to_image * prints stuff with debug=2 * it sort of works * copy host ptr is simpler * bug fix * build on c3 * this correct? * reenable float16 * fix private, fixup copy_inputs internal * bump tinygrad and update ref commit * fix OPTWG on PC * maybe fix non determinism * revert model replay ref commit * comments, init zeroed out buffers * upd ref commit * bump tinygrad to fix initial image * try this ref Co-authored-by: Comma Device --- .gitignore | 1 + .gitmodules | 3 + .pre-commit-config.yaml | 6 +- SConstruct | 5 ++ common/clutil.cc | 5 +- release/build_release.sh | 2 +- release/files_common | 15 +++- selfdrive/modeld/SConscript | 68 +++++++++++++++---- selfdrive/modeld/models/supercombo.dlc | 3 - selfdrive/modeld/thneed/serialize.cc | 7 +- selfdrive/modeld/thneed/thneed.h | 2 +- selfdrive/modeld/thneed/thneed_common.cc | 19 +++--- selfdrive/modeld/thneed/thneed_pc.cc | 40 +++++++++++ selfdrive/modeld/thneed/thneed_qcom2.cc | 2 +- .../process_replay/model_replay_ref_commit | 2 +- tinygrad | 1 + tinygrad_repo | 1 + 17 files changed, 143 insertions(+), 39 deletions(-) delete mode 100644 selfdrive/modeld/models/supercombo.dlc create mode 100644 selfdrive/modeld/thneed/thneed_pc.cc create mode 120000 tinygrad create mode 160000 tinygrad_repo diff --git a/.gitignore b/.gitignore index 6aee0ed8e..062358ef2 100644 --- a/.gitignore +++ b/.gitignore @@ -36,6 +36,7 @@ a.out config.json clcache compile_commands.json +compare_runtime*.html persist board/obj/ diff --git a/.gitmodules b/.gitmodules index bc439b451..26f93ef16 100644 --- a/.gitmodules +++ b/.gitmodules @@ -16,3 +16,6 @@ [submodule "body"] path = body url = ../../commaai/body.git +[submodule "tinygrad"] + path = tinygrad_repo + url = https://github.com/geohot/tinygrad.git diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 50554acce..347216f2f 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -28,7 +28,7 @@ repos: rev: v0.931 hooks: - id: mypy - exclude: '^(pyextra/)|(cereal/)|(rednose/)|(panda/)|(laika/)|(opendbc/)|(laika_repo/)|(rednose_repo/)/' + exclude: '^(pyextra/)|(cereal/)|(rednose/)|(panda/)|(laika/)|(opendbc/)|(laika_repo/)|(rednose_repo/)/|(tinygrad/)|(tinygrad_repo/)' additional_dependencies: ['types-PyYAML', 'lxml', 'numpy', 'types-atomicwrites', 'types-pycurl', 'types-requests', 'types-certifi'] args: - --warn-redundant-casts @@ -40,7 +40,7 @@ repos: rev: 4.0.1 hooks: - id: flake8 - exclude: '^(pyextra/)|(cereal/)|(rednose/)|(panda/)|(laika/)|(opendbc/)|(laika_repo/)|(rednose_repo/)|(selfdrive/debug/)/' + exclude: '^(pyextra/)|(cereal/)|(rednose/)|(panda/)|(laika/)|(opendbc/)|(laika_repo/)|(rednose_repo/)|(tinygrad/)|(tinygrad_repo/)|(selfdrive/debug/)/' additional_dependencies: ['flake8-no-implicit-concat'] args: - --indent-size=2 @@ -55,7 +55,7 @@ repos: entry: pylint language: system types: [python] - exclude: '^(pyextra/)|(cereal/)|(rednose/)|(panda/)|(laika/)|(laika_repo/)|(rednose_repo/)' + exclude: '^(pyextra/)|(cereal/)|(rednose/)|(panda/)|(laika/)|(laika_repo/)|(rednose_repo/)|(tinygrad/)|(tinygrad_repo/)' args: - -rn - -sn diff --git a/SConstruct b/SConstruct index d4155f4f8..66a94f9b1 100644 --- a/SConstruct +++ b/SConstruct @@ -49,6 +49,11 @@ AddOption('--no-thneed', dest='no_thneed', help='avoid using thneed') +AddOption('--pc-thneed', + action='store_true', + dest='pc_thneed', + help='use thneed on pc') + AddOption('--no-test', action='store_false', dest='test', diff --git a/common/clutil.cc b/common/clutil.cc index b8f9fde4c..9d3447d80 100644 --- a/common/clutil.cc +++ b/common/clutil.cc @@ -78,7 +78,8 @@ cl_program cl_program_from_file(cl_context ctx, cl_device_id device_id, const ch } cl_program cl_program_from_source(cl_context ctx, cl_device_id device_id, const std::string& src, const char* args) { - cl_program prg = CL_CHECK_ERR(clCreateProgramWithSource(ctx, 1, (const char*[]){src.c_str()}, NULL, &err)); + const char *csrc = src.c_str(); + cl_program prg = CL_CHECK_ERR(clCreateProgramWithSource(ctx, 1, &csrc, NULL, &err)); if (int err = clBuildProgram(prg, 1, &device_id, args, NULL, NULL); err != 0) { cl_print_build_errors(prg, device_id); assert(0); @@ -87,7 +88,7 @@ cl_program cl_program_from_source(cl_context ctx, cl_device_id device_id, const } cl_program cl_program_from_binary(cl_context ctx, cl_device_id device_id, const uint8_t* binary, size_t length, const char* args) { - cl_program prg = CL_CHECK_ERR(clCreateProgramWithBinary(ctx, 1, &device_id, &length, (const uint8_t*[]){binary}, NULL, &err)); + cl_program prg = CL_CHECK_ERR(clCreateProgramWithBinary(ctx, 1, &device_id, &length, &binary, NULL, &err)); if (int err = clBuildProgram(prg, 1, &device_id, args, NULL, NULL); err != 0) { cl_print_build_errors(prg, device_id); assert(0); diff --git a/release/build_release.sh b/release/build_release.sh index 1000e607f..80106eefb 100755 --- a/release/build_release.sh +++ b/release/build_release.sh @@ -78,7 +78,7 @@ find . -name 'moc_*' -delete find . -name '__pycache__' -delete rm -rf panda/board panda/certs panda/crypto rm -rf .sconsign.dblite Jenkinsfile release/ -rm selfdrive/modeld/models/supercombo.dlc +rm selfdrive/modeld/models/supercombo.onnx # Move back signed panda fw mkdir -p panda/board/obj diff --git a/release/files_common b/release/files_common index ca6e91fb6..5be07b1c7 100644 --- a/release/files_common +++ b/release/files_common @@ -352,7 +352,7 @@ selfdrive/modeld/models/driving.cc selfdrive/modeld/models/driving.h selfdrive/modeld/models/dmonitoring.cc selfdrive/modeld/models/dmonitoring.h -selfdrive/modeld/models/supercombo.dlc +selfdrive/modeld/models/supercombo.onnx selfdrive/modeld/models/dmonitoring_model_q.dlc selfdrive/modeld/transforms/loadyuv.cc @@ -561,3 +561,16 @@ opendbc/vw_mqb_2010.dbc opendbc/tesla_can.dbc opendbc/tesla_radar.dbc opendbc/tesla_powertrain.dbc + +tinygrad_repo/openpilot/compile.py +tinygrad_repo/accel/opencl/* +tinygrad_repo/extra/onnx.py +tinygrad_repo/extra/utils.py +tinygrad_repo/tinygrad/llops/ops_gpu.py +tinygrad_repo/tinygrad/llops/ops_opencl.py +tinygrad_repo/tinygrad/helpers.py +tinygrad_repo/tinygrad/mlops.py +tinygrad_repo/tinygrad/ops.py +tinygrad_repo/tinygrad/shapetracker.py +tinygrad_repo/tinygrad/tensor.py +tinygrad_repo/tinygrad/nn/__init__.py diff --git a/selfdrive/modeld/SConscript b/selfdrive/modeld/SConscript index 4feb17f23..2544607aa 100644 --- a/selfdrive/modeld/SConscript +++ b/selfdrive/modeld/SConscript @@ -62,25 +62,65 @@ else: common_model = lenv.Object(common_src) -# build thneed model -if use_thneed and arch == "larch64": - fn = File("models/supercombo").abspath - compiler = lenv.Program('thneed/compile', ["thneed/compile.cc"]+common_model, LIBS=libs) - cmd = f"cd {Dir('.').abspath} && {compiler[0].abspath} --in {fn}.dlc --out {fn}.thneed --binary --optimize" - - lib_paths = ':'.join(Dir(p).abspath for p in lenv["LIBPATH"]) - kernel_path = os.path.join(Dir('.').abspath, "thneed", "kernels") - cenv = Environment(ENV={'LD_LIBRARY_PATH': f"{lib_paths}:{lenv['ENV']['LD_LIBRARY_PATH']}", 'KERNEL_PATH': kernel_path}) - - kernels = [os.path.join(kernel_path, x) for x in os.listdir(kernel_path) if x.endswith(".cl")] - cenv.Command(fn + ".thneed", [fn + ".dlc", kernels, compiler], cmd) - lenv.Program('_dmonitoringmodeld', [ "dmonitoringmodeld.cc", "models/dmonitoring.cc", ]+common_model, LIBS=libs) -lenv.Program('_modeld', [ +# build thneed model +if use_thneed and arch == "larch64" or GetOption('pc_thneed'): + fn = File("models/supercombo").abspath + + if GetOption('pc_thneed'): + cmd = f"cd {Dir('#').abspath}/tinygrad_repo && NATIVE_EXPLOG=1 OPTWG=1 UNSAFE_FLOAT4=1 DEBUGCL=1 python3 openpilot/compile.py {fn}.onnx {fn}.thneed" + else: + cmd = f"cd {Dir('#').abspath}/tinygrad_repo && FLOAT16=1 PYOPENCL_NO_CACHE=1 MATMUL=1 NATIVE_EXPLOG=1 OPTWG=1 UNSAFE_FLOAT4=1 DEBUGCL=1 python3 openpilot/compile.py {fn}.onnx {fn}.thneed" + + # is there a better way then listing all of tinygrad? + lenv.Command(fn + ".thneed", [fn + ".onnx", + "#tinygrad_repo/openpilot/compile.py", + "#tinygrad_repo/accel/opencl/conv.cl", + "#tinygrad_repo/accel/opencl/matmul.cl", + "#tinygrad_repo/accel/opencl/ops_opencl.py", + "#tinygrad_repo/accel/opencl/preprocessing.py", + "#tinygrad_repo/extra/onnx.py", + "#tinygrad_repo/extra/utils.py", + "#tinygrad_repo/tinygrad/llops/ops_gpu.py", + "#tinygrad_repo/tinygrad/llops/ops_opencl.py", + "#tinygrad_repo/tinygrad/helpers.py", + "#tinygrad_repo/tinygrad/mlops.py", + "#tinygrad_repo/tinygrad/ops.py", + "#tinygrad_repo/tinygrad/shapetracker.py", + "#tinygrad_repo/tinygrad/tensor.py", + "#tinygrad_repo/tinygrad/nn/__init__.py" + ], cmd) + + # old thneed compiler. TODO: remove this once tinygrad stuff is stable + + #compiler = lenv.Program('thneed/compile', ["thneed/compile.cc"]+common_model, LIBS=libs) + #cmd = f"cd {Dir('.').abspath} && {compiler[0].abspath} --in {fn}.dlc --out {fn}.thneed --binary --optimize" + + #lib_paths = ':'.join(Dir(p).abspath for p in lenv["LIBPATH"]) + #kernel_path = os.path.join(Dir('.').abspath, "thneed", "kernels") + #cenv = Environment(ENV={'LD_LIBRARY_PATH': f"{lib_paths}:{lenv['ENV']['LD_LIBRARY_PATH']}", 'KERNEL_PATH': kernel_path}) + + #kernels = [os.path.join(kernel_path, x) for x in os.listdir(kernel_path) if x.endswith(".cl")] + #cenv.Command(fn + ".thneed", [fn + ".dlc", kernels, compiler], cmd) + +llenv = lenv.Clone() +if GetOption('pc_thneed'): + pc_thneed_src = [ + "thneed/thneed_common.cc", + "thneed/thneed_pc.cc", + "thneed/serialize.cc", + "runners/thneedmodel.cc", + ] + llenv['CFLAGS'].append("-DUSE_THNEED") + llenv['CXXFLAGS'].append("-DUSE_THNEED") + common_model += llenv.Object(pc_thneed_src) + libs += ['dl'] + +llenv.Program('_modeld', [ "modeld.cc", "models/driving.cc", ]+common_model, LIBS=libs + transformations) diff --git a/selfdrive/modeld/models/supercombo.dlc b/selfdrive/modeld/models/supercombo.dlc deleted file mode 100644 index fe133523f..000000000 --- a/selfdrive/modeld/models/supercombo.dlc +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:93d265fc88f05746ce47257e15fc2afe43b250b44715313049f829e8aa30a9d6 -size 94302331 diff --git a/selfdrive/modeld/thneed/serialize.cc b/selfdrive/modeld/thneed/serialize.cc index 0b8b02c6a..afc84ee76 100644 --- a/selfdrive/modeld/thneed/serialize.cc +++ b/selfdrive/modeld/thneed/serialize.cc @@ -33,11 +33,14 @@ void Thneed::load(const char *filename) { assert(mobj["needs_load"].bool_value() == false); } else { if (mobj["needs_load"].bool_value()) { - //printf("loading %p %d @ 0x%X\n", clbuf, sz, ptr); clbuf = clCreateBuffer(context, CL_MEM_COPY_HOST_PTR | CL_MEM_READ_WRITE, sz, &buf[ptr], NULL); + if (debug >= 1) printf("loading %p %d @ 0x%X\n", clbuf, sz, ptr); ptr += sz; } else { - clbuf = clCreateBuffer(context, CL_MEM_READ_WRITE, sz, NULL, NULL); + // TODO: is there a faster way to init zeroed out buffers? + void *host_zeros = calloc(sz, 1); + clbuf = clCreateBuffer(context, CL_MEM_COPY_HOST_PTR | CL_MEM_READ_WRITE, sz, host_zeros, NULL); + free(host_zeros); } } assert(clbuf != NULL); diff --git a/selfdrive/modeld/thneed/thneed.h b/selfdrive/modeld/thneed/thneed.h index 19dc46e8f..2a5800f30 100644 --- a/selfdrive/modeld/thneed/thneed.h +++ b/selfdrive/modeld/thneed/thneed.h @@ -122,7 +122,7 @@ class Thneed { // all CL kernels void find_inputs_outputs(); - void copy_inputs(float **finputs); + void copy_inputs(float **finputs, bool internal=false); void copy_output(float *foutput); cl_int clexec(); vector > kq; diff --git a/selfdrive/modeld/thneed/thneed_common.cc b/selfdrive/modeld/thneed/thneed_common.cc index b751cdf66..a3f5c908f 100644 --- a/selfdrive/modeld/thneed/thneed_common.cc +++ b/selfdrive/modeld/thneed/thneed_common.cc @@ -30,17 +30,16 @@ cl_int Thneed::clexec() { return clFinish(command_queue); } -void Thneed::copy_inputs(float **finputs) { - //cl_int ret; +void Thneed::copy_inputs(float **finputs, bool internal) { for (int idx = 0; idx < inputs.size(); ++idx) { if (debug >= 1) printf("copying %lu -- %p -> %p (cl %p)\n", input_sizes[idx], finputs[idx], inputs[idx], input_clmem[idx]); - // TODO: fix thneed caching - if (finputs[idx] != NULL) memcpy(inputs[idx], finputs[idx], input_sizes[idx]); - //if (finputs[idx] != NULL) CL_CHECK(clEnqueueWriteBuffer(command_queue, input_clmem[idx], CL_TRUE, 0, input_sizes[idx], finputs[idx], 0, NULL, NULL)); - - // HACK - //if (input_sizes[idx] == 16) memset((char*)inputs[idx] + 8, 0, 8); + if (internal) { + // if it's internal, using memcpy is fine since the buffer sync is cached in the ioctl layer + if (finputs[idx] != NULL) memcpy(inputs[idx], finputs[idx], input_sizes[idx]); + } else { + if (finputs[idx] != NULL) CL_CHECK(clEnqueueWriteBuffer(command_queue, input_clmem[idx], CL_TRUE, 0, input_sizes[idx], finputs[idx], 0, NULL, NULL)); + } } } @@ -202,8 +201,8 @@ void CLQueuedKernel::debug_print(bool verbose) { assert(slice_pitch == 0); clGetImageInfo(val, CL_IMAGE_BUFFER, sizeof(buf), &buf, NULL); - size_t sz; - clGetMemObjectInfo(buf, CL_MEM_SIZE, sizeof(sz), &sz, NULL); + size_t sz = 0; + if (buf != NULL) clGetMemObjectInfo(buf, CL_MEM_SIZE, sizeof(sz), &sz, NULL); printf(" image %zu x %zu rp %zu @ %p buffer %zu", width, height, row_pitch, buf, sz); } else { size_t sz; diff --git a/selfdrive/modeld/thneed/thneed_pc.cc b/selfdrive/modeld/thneed/thneed_pc.cc new file mode 100644 index 000000000..e32dd289e --- /dev/null +++ b/selfdrive/modeld/thneed/thneed_pc.cc @@ -0,0 +1,40 @@ +#include "selfdrive/modeld/thneed/thneed.h" + +#include + +#include "common/clutil.h" +#include "common/timing.h" + +Thneed::Thneed(bool do_clinit, cl_context _context) { + context = _context; + if (do_clinit) clinit(); + char *thneed_debug_env = getenv("THNEED_DEBUG"); + debug = (thneed_debug_env != NULL) ? atoi(thneed_debug_env) : 0; +} + +void Thneed::execute(float **finputs, float *foutput, bool slow) { + uint64_t tb, te; + if (debug >= 1) tb = nanos_since_boot(); + + // ****** copy inputs + copy_inputs(finputs); + + // ****** run commands + clexec(); + + // ****** copy outputs + copy_output(foutput); + + if (debug >= 1) { + te = nanos_since_boot(); + printf("model exec in %lu us\n", (te-tb)/1000); + } +} + +void Thneed::stop() { +} + +void Thneed::find_inputs_outputs() { + // thneed on PC doesn't work on old style inputs/outputs +} + diff --git a/selfdrive/modeld/thneed/thneed_qcom2.cc b/selfdrive/modeld/thneed/thneed_qcom2.cc index e79bb77ed..f35317d2a 100644 --- a/selfdrive/modeld/thneed/thneed_qcom2.cc +++ b/selfdrive/modeld/thneed/thneed_qcom2.cc @@ -269,7 +269,7 @@ void Thneed::execute(float **finputs, float *foutput, bool slow) { if (debug >= 1) tb = nanos_since_boot(); // ****** copy inputs - copy_inputs(finputs); + copy_inputs(finputs, true); // ****** set power constraint int ret; diff --git a/selfdrive/test/process_replay/model_replay_ref_commit b/selfdrive/test/process_replay/model_replay_ref_commit index 80be9b464..e2ee2e7bb 100644 --- a/selfdrive/test/process_replay/model_replay_ref_commit +++ b/selfdrive/test/process_replay/model_replay_ref_commit @@ -1 +1 @@ -ca90e11f8d59902af38d3785ddd91a27d0fbb411 +cffb4e720b0379bedd4ff802912d998ace775c37 diff --git a/tinygrad b/tinygrad new file mode 120000 index 000000000..cb003823c --- /dev/null +++ b/tinygrad @@ -0,0 +1 @@ +tinygrad_repo/tinygrad \ No newline at end of file diff --git a/tinygrad_repo b/tinygrad_repo new file mode 160000 index 000000000..2e9b7637b --- /dev/null +++ b/tinygrad_repo @@ -0,0 +1 @@ +Subproject commit 2e9b7637b3c3c8895fda9f964215db3a35fe3441 From cbe1c89698a20d7eb26897c1e202bcc7d48ee1cd Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 1 Sep 2022 13:39:00 -0700 Subject: [PATCH 130/172] Update total scons nodes --- selfdrive/manager/build.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/manager/build.py b/selfdrive/manager/build.py index 12f894061..c8a7d4153 100755 --- a/selfdrive/manager/build.py +++ b/selfdrive/manager/build.py @@ -15,7 +15,7 @@ from system.version import is_dirty MAX_CACHE_SIZE = 4e9 if "CI" in os.environ else 2e9 CACHE_DIR = Path("/data/scons_cache" if AGNOS else "/tmp/scons_cache") -TOTAL_SCONS_NODES = 2035 +TOTAL_SCONS_NODES = 2395 MAX_BUILD_PROGRESS = 100 PREBUILT = os.path.exists(os.path.join(BASEDIR, 'prebuilt')) From e1b7a37a1f6a341bdc729c186ca5b4d3fb8af9ee Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Thu, 1 Sep 2022 15:40:25 -0700 Subject: [PATCH 131/172] Support e2e long in longitudinal planner (#25636) * refactor * Add planer modes to support offline, acc, and blended * add acceleration * Fix index * Update model ref * Read in model outputs * Add model msg * Add e2e logic * Add source --- .../lib/longitudinal_mpc_lib/long_mpc.py | 117 +++++++++++------- .../controls/lib/longitudinal_planner.py | 22 +++- selfdrive/modeld/models/driving.cc | 5 + .../test/longitudinal_maneuvers/plant.py | 4 +- .../process_replay/model_replay_ref_commit | 2 +- 5 files changed, 103 insertions(+), 47 deletions(-) diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py b/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py index 94efd7a87..eaecb63a6 100644 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py @@ -3,7 +3,7 @@ import os import numpy as np from common.realtime import sec_since_boot -from common.numpy_fast import clip, interp +from common.numpy_fast import clip from system.swaglog import cloudlog from selfdrive.modeld.constants import index_function from selfdrive.controls.lib.radar_helpers import _LEAD_ACCEL_TAU @@ -20,7 +20,7 @@ LONG_MPC_DIR = os.path.dirname(os.path.abspath(__file__)) EXPORT_DIR = os.path.join(LONG_MPC_DIR, "c_generated_code") JSON_FILE = os.path.join(LONG_MPC_DIR, "acados_ocp_long.json") -SOURCES = ['lead0', 'lead1', 'cruise'] +SOURCES = ['lead0', 'lead1', 'cruise', 'e2e'] X_DIM = 3 U_DIM = 1 @@ -50,6 +50,7 @@ T_IDXS_LST = [index_function(idx, max_val=MAX_T, max_idx=N) for idx in range(N+1 T_IDXS = np.array(T_IDXS_LST) T_DIFFS = np.diff(T_IDXS, prepend=[0.]) MIN_ACCEL = -3.5 +MAX_ACCEL = 2.0 T_FOLLOW = 1.45 COMFORT_BRAKE = 2.5 STOP_DISTANCE = 6.0 @@ -190,8 +191,8 @@ def gen_long_ocp(): class LongitudinalMpc: - def __init__(self, e2e=False): - self.e2e = e2e + def __init__(self, mode='acc'): + self.mode = mode self.solver = AcadosOcpSolverCython(MODEL_NAME, ACADOS_SOLVER_TYPE, N) self.reset() self.source = SOURCES[2] @@ -225,49 +226,42 @@ class LongitudinalMpc: self.x0 = np.zeros(X_DIM) self.set_weights() - def set_weights(self, prev_accel_constraint=True): - if self.e2e: - self.set_weights_for_xva_policy() - self.params[:,0] = -10. - self.params[:,1] = 10. - self.params[:,2] = 1e5 - else: - self.set_weights_for_lead_policy(prev_accel_constraint) - - def set_weights_for_lead_policy(self, prev_accel_constraint=True): - a_change_cost = A_CHANGE_COST if prev_accel_constraint else 0 - W = np.asfortranarray(np.diag([X_EGO_OBSTACLE_COST, X_EGO_COST, V_EGO_COST, A_EGO_COST, a_change_cost, J_EGO_COST])) + def set_cost_weights(self, cost_weights, constraint_cost_weights): + W = np.asfortranarray(np.diag(cost_weights)) for i in range(N): + # TODO don't hardcode A_CHANGE_COST idx # reduce the cost on (a-a_prev) later in the horizon. - W[4,4] = a_change_cost * np.interp(T_IDXS[i], [0.0, 1.0, 2.0], [1.0, 1.0, 0.0]) + W[4,4] = cost_weights[4] * np.interp(T_IDXS[i], [0.0, 1.0, 2.0], [1.0, 1.0, 0.0]) self.solver.cost_set(i, 'W', W) # Setting the slice without the copy make the array not contiguous, # causing issues with the C interface. self.solver.cost_set(N, 'W', np.copy(W[:COST_E_DIM, :COST_E_DIM])) # Set L2 slack cost on lower bound constraints - Zl = np.array([LIMIT_COST, LIMIT_COST, LIMIT_COST, DANGER_ZONE_COST]) + Zl = np.array(constraint_cost_weights) for i in range(N): self.solver.cost_set(i, 'Zl', Zl) - def set_weights_for_xva_policy(self): - W = np.asfortranarray(np.diag([0., 0.2, 0.25, 1., 0.0, .1])) - for i in range(N): - self.solver.cost_set(i, 'W', W) - # Setting the slice without the copy make the array not contiguous, - # causing issues with the C interface. - self.solver.cost_set(N, 'W', np.copy(W[:COST_E_DIM, :COST_E_DIM])) - - # Set L2 slack cost on lower bound constraints - Zl = np.array([LIMIT_COST, LIMIT_COST, LIMIT_COST, 0.0]) - for i in range(N): - self.solver.cost_set(i, 'Zl', Zl) + def set_weights(self, prev_accel_constraint=True): + if self.mode == 'acc': + a_change_cost = A_CHANGE_COST if prev_accel_constraint else 0 + 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., 1.0, 0.0, 0.0, 0.0, 1.0] + constraint_cost_weights = [LIMIT_COST, LIMIT_COST, LIMIT_COST, 0.0] + elif self.mode == 'e2e': + cost_weights = [0., 0.2, 0.25, 1., 0.0, .1] + constraint_cost_weights = [LIMIT_COST, LIMIT_COST, LIMIT_COST, 0.0] + else: + raise NotImplementedError(f'Planner mode {self.mode} not recognized') + self.set_cost_weights(cost_weights, constraint_cost_weights) def set_cur_state(self, v, a): v_prev = self.x0[1] self.x0[1] = v self.x0[2] = a - if abs(v_prev - v) > 2.: # probably only helps if v < v_prev + if abs(v_prev - v) > 2.: # probably only helps if v < v_prev for i in range(0, N+1): self.solver.set(i, 'x', self.x0) @@ -306,31 +300,62 @@ class LongitudinalMpc: self.cruise_min_a = min_a self.cruise_max_a = max_a - def update(self, carstate, radarstate, v_cruise): + def update(self, carstate, radarstate, v_cruise, x, v, a, j): v_ego = self.x0[1] self.status = radarstate.leadOne.status or radarstate.leadTwo.status lead_xv_0 = self.process_lead(radarstate.leadOne) lead_xv_1 = self.process_lead(radarstate.leadTwo) - # set accel limits in params - self.params[:,0] = interp(float(self.status), [0.0, 1.0], [self.cruise_min_a, MIN_ACCEL]) - self.params[:,1] = self.cruise_max_a - # To estimate a safe distance from a moving lead, we calculate how much stopping # distance that lead needs as a minimum. We can add that to the current distance # and then treat that as a stopped car/obstacle at this new distance. lead_0_obstacle = lead_xv_0[:,0] + get_stopped_equivalence_factor(lead_xv_0[:,1]) lead_1_obstacle = lead_xv_1[:,0] + get_stopped_equivalence_factor(lead_xv_1[:,1]) - # Fake an obstacle for cruise, this ensures smooth acceleration to set speed - # when the leads are no factor. - v_lower = v_ego + (T_IDXS * self.cruise_min_a * 1.05) - v_upper = v_ego + (T_IDXS * self.cruise_max_a * 1.05) - v_cruise_clipped = np.clip(v_cruise * np.ones(N+1), - v_lower, - v_upper) - cruise_obstacle = np.cumsum(T_DIFFS * v_cruise_clipped) + get_safe_obstacle_distance(v_cruise_clipped) + # Update in ACC mode or ACC/e2e blend + if self.mode == 'acc': + self.params[:,0] = MIN_ACCEL if self.status else self.cruise_min_a + self.params[:,1] = self.cruise_max_a + + # Fake an obstacle for cruise, this ensures smooth acceleration to set speed + # when the leads are no factor. + v_lower = v_ego + (T_IDXS * self.cruise_min_a * 1.05) + v_upper = v_ego + (T_IDXS * self.cruise_max_a * 1.05) + v_cruise_clipped = np.clip(v_cruise * np.ones(N+1), + v_lower, + v_upper) + cruise_obstacle = np.cumsum(T_DIFFS * v_cruise_clipped) + get_safe_obstacle_distance(v_cruise_clipped) + x_obstacles = np.column_stack([lead_0_obstacle, lead_1_obstacle, cruise_obstacle]) + self.source = SOURCES[np.argmin(x_obstacles[0])] + + # These are not used in ACC mode + x[:], v[:], a[:], j[:] = 0.0, 0.0, 0.0, 0.0 + + elif self.mode == 'blended': + self.params[:,0] = MIN_ACCEL + self.params[:,1] = MAX_ACCEL + + x_obstacles = np.column_stack([lead_0_obstacle, + lead_1_obstacle]) + cruise_target = T_IDXS * v_cruise + x[0] + xforward = ((v[1:] + v[:-1]) / 2) * (T_IDXS[1:] - T_IDXS[:-1]) + x = np.cumsum(np.insert(xforward, 0, x[0])) + + x_and_cruise = np.column_stack([x, cruise_target]) + x = np.min(x_and_cruise, axis=1) + self.source = 'e2e' + + else: + raise NotImplementedError(f'Planner mode {self.mode} not recognized') + + self.yref[:,1] = x + self.yref[:,2] = v + self.yref[:,3] = a + self.yref[:,5] = j + for i in range(N): + self.solver.set(i, "yref", self.yref[i]) + self.solver.set(N, "yref", self.yref[N][:COST_E_DIM]) x_obstacles = np.column_stack([lead_0_obstacle, lead_1_obstacle, cruise_obstacle]) self.source = SOURCES[np.argmin(x_obstacles[0])] @@ -345,6 +370,10 @@ class LongitudinalMpc: self.crash_cnt = 0 def update_with_xva(self, x, v, a): + self.params[:,0] = -10. + self.params[:,1] = 10. + self.params[:,2] = 1e5 + # v, and a are in local frame, but x is wrt the x[0] position # In >90degree turns, x goes to 0 (and may even be -ve) # So, we use integral(v) + x[0] to obtain the forward-distance diff --git a/selfdrive/controls/lib/longitudinal_planner.py b/selfdrive/controls/lib/longitudinal_planner.py index cf5113677..42ce2bd0e 100755 --- a/selfdrive/controls/lib/longitudinal_planner.py +++ b/selfdrive/controls/lib/longitudinal_planner.py @@ -53,12 +53,31 @@ class Planner: self.a_desired = init_a self.v_desired_filter = FirstOrderFilter(init_v, 2.0, DT_MDL) + self.t_uniform = np.arange(0.0, T_IDXS_MPC[-1] + 0.5, 0.5) self.v_desired_trajectory = np.zeros(CONTROL_N) self.a_desired_trajectory = np.zeros(CONTROL_N) self.j_desired_trajectory = np.zeros(CONTROL_N) self.solverExecutionTime = 0.0 + def parse_model(self, model_msg): + if (len(model_msg.position.x) == 33 and + len(model_msg.velocity.x) == 33 and + len(model_msg.acceleration.x) == 33): + x = np.interp(T_IDXS_MPC, T_IDXS, model_msg.position.x) + v = np.interp(T_IDXS_MPC, T_IDXS, model_msg.velocity.x) + a = np.interp(T_IDXS_MPC, T_IDXS, model_msg.acceleration.x) + # Uniform interp so gradient is less noisy + a_sparse = np.interp(self.t_uniform, T_IDXS, model_msg.acceleration.x) + j_sparse = np.gradient(a_sparse, self.t_uniform) + j = np.interp(T_IDXS_MPC, self.t_uniform, j_sparse) + else: + x = np.zeros(len(T_IDXS_MPC)) + v = np.zeros(len(T_IDXS_MPC)) + a = np.zeros(len(T_IDXS_MPC)) + j = np.zeros(len(T_IDXS_MPC)) + return x, v, a, j + def update(self, sm): v_ego = sm['carState'].vEgo @@ -95,7 +114,8 @@ class Planner: self.mpc.set_weights(prev_accel_constraint) self.mpc.set_accel_limits(accel_limits_turns[0], accel_limits_turns[1]) self.mpc.set_cur_state(self.v_desired_filter.x, self.a_desired) - self.mpc.update(sm['carState'], sm['radarState'], v_cruise) + x, v, a, j = self.parse_model(sm['modelV2']) + self.mpc.update(sm['carState'], sm['radarState'], v_cruise, x, v, a, j) self.v_desired_trajectory = np.interp(T_IDXS[:CONTROL_N], T_IDXS_MPC, self.mpc.v_solution) self.a_desired_trajectory = np.interp(T_IDXS[:CONTROL_N], T_IDXS_MPC, self.mpc.a_solution) diff --git a/selfdrive/modeld/models/driving.cc b/selfdrive/modeld/models/driving.cc index 7a7a6ff6e..8d02eb6b2 100644 --- a/selfdrive/modeld/models/driving.cc +++ b/selfdrive/modeld/models/driving.cc @@ -203,6 +203,7 @@ void fill_plan(cereal::ModelDataV2::Builder &framed, const ModelOutputPlanPredic std::array pos_x_std, pos_y_std, pos_z_std; std::array vel_x, vel_y, vel_z; std::array rot_x, rot_y, rot_z; + std::array acc_x, acc_y, acc_z; std::array rot_rate_x, rot_rate_y, rot_rate_z; for(int i=0; i Date: Thu, 1 Sep 2022 16:19:21 -0700 Subject: [PATCH 132/172] Optima 2019: set LKAS icon correctly (#25637) * are we sure? * add params * should work should work * fix * fix * clean up * comment * comment * Update selfdrive/car/hyundai/hyundaican.py --- selfdrive/car/hyundai/carcontroller.py | 1 + selfdrive/car/hyundai/hyundaican.py | 18 ++++++++++++++++-- 2 files changed, 17 insertions(+), 2 deletions(-) diff --git a/selfdrive/car/hyundai/carcontroller.py b/selfdrive/car/hyundai/carcontroller.py index 971330a33..586d215ff 100644 --- a/selfdrive/car/hyundai/carcontroller.py +++ b/selfdrive/car/hyundai/carcontroller.py @@ -15,6 +15,7 @@ def process_hud_alert(enabled, fingerprint, hud_control): sys_warning = (hud_control.visualAlert in (VisualAlert.steerRequired, VisualAlert.ldw)) # initialize to no line visible + # TODO: this is not accurate for all cars sys_state = 1 if hud_control.leftLaneVisible and hud_control.rightLaneVisible or sys_warning: # HUD alert only display when LKAS status is active sys_state = 3 if enabled or sys_warning else 4 diff --git a/selfdrive/car/hyundai/hyundaican.py b/selfdrive/car/hyundai/hyundaican.py index 8a5e33f11..f94cc508a 100644 --- a/selfdrive/car/hyundai/hyundaican.py +++ b/selfdrive/car/hyundai/hyundaican.py @@ -37,12 +37,26 @@ def create_lkas11(packer, frame, car_fingerprint, apply_steer, steer_req, # Note: the warning is hidden while the blinkers are on values["CF_Lkas_SysWarning"] = 4 if sys_warning else 0 + # Likely cars lacking the ability to show individual lane lines in the dash + elif car_fingerprint in (CAR.KIA_OPTIMA,): + # SysWarning 4 = keep hands on wheel + beep + values["CF_Lkas_SysWarning"] = 4 if sys_warning else 0 + + # SysState 0 = no icons + # SysState 1-2 = white car + lanes + # SysState 3 = green car + lanes, green steering wheel + # SysState 4 = green car + lanes + values["CF_Lkas_LdwsSysState"] = 3 if enabled else 1 + values["CF_Lkas_LdwsOpt_USM"] = 2 # non-2 changes above SysState definition + + # these have no effect + values["CF_Lkas_LdwsActivemode"] = 0 + values["CF_Lkas_FcwOpt_USM"] = 0 + elif car_fingerprint == CAR.HYUNDAI_GENESIS: # This field is actually LdwsActivemode # Genesis and Optima fault when forwarding while engaged values["CF_Lkas_LdwsActivemode"] = 2 - elif car_fingerprint == CAR.KIA_OPTIMA: - values["CF_Lkas_LdwsActivemode"] = 0 dat = packer.make_can_msg("LKAS11", 0, values)[2] From 6c39382d71978d20f00286678b2f13e00134bb0a Mon Sep 17 00:00:00 2001 From: George Hotz <72895+geohot@users.noreply.github.com> Date: Thu, 1 Sep 2022 18:28:20 -0700 Subject: [PATCH 133/172] modeld: delete unused SNPE stuff after move to tinygrad (#25635) * delete unused stuff * remove CL interceptor from thneed since we don't use SNPE anymore * remove dead files from release * that's removed * oops, didn't save --- release/files_common | 3 - selfdrive/modeld/SConscript | 13 - selfdrive/modeld/runners/snpemodel.cc | 77 +---- selfdrive/modeld/runners/thneedmodel.cc | 1 - selfdrive/modeld/thneed/compile.cc | 81 ------ .../modeld/thneed/kernels/convolution_.cl | 272 ------------------ .../convolution_horizontal_reduced_reads.cl | 3 - ...onvolution_horizontal_reduced_reads_1x1.cl | 4 - ...tion_horizontal_reduced_reads_5_outputs.cl | 3 - ...tion_horizontal_reduced_reads_depthwise.cl | 4 - ...zontal_reduced_reads_depthwise_stride_1.cl | 3 - selfdrive/modeld/thneed/optimizer.cc | 261 ----------------- selfdrive/modeld/thneed/serialize.cc | 152 ---------- selfdrive/modeld/thneed/thneed.h | 8 +- selfdrive/modeld/thneed/thneed_common.cc | 29 +- selfdrive/modeld/thneed/thneed_pc.cc | 8 - selfdrive/modeld/thneed/thneed_qcom2.cc | 104 ------- selfdrive/modeld/thneed/weights_fixup.py | 146 ---------- 18 files changed, 14 insertions(+), 1158 deletions(-) delete mode 100644 selfdrive/modeld/thneed/compile.cc delete mode 100644 selfdrive/modeld/thneed/kernels/convolution_.cl delete mode 100644 selfdrive/modeld/thneed/kernels/convolution_horizontal_reduced_reads.cl delete mode 100644 selfdrive/modeld/thneed/kernels/convolution_horizontal_reduced_reads_1x1.cl delete mode 100644 selfdrive/modeld/thneed/kernels/convolution_horizontal_reduced_reads_5_outputs.cl delete mode 100644 selfdrive/modeld/thneed/kernels/convolution_horizontal_reduced_reads_depthwise.cl delete mode 100644 selfdrive/modeld/thneed/kernels/convolution_horizontal_reduced_reads_depthwise_stride_1.cl delete mode 100644 selfdrive/modeld/thneed/optimizer.cc delete mode 100755 selfdrive/modeld/thneed/weights_fixup.py diff --git a/release/files_common b/release/files_common index 5be07b1c7..10c66a896 100644 --- a/release/files_common +++ b/release/files_common @@ -367,10 +367,7 @@ selfdrive/modeld/thneed/thneed.h selfdrive/modeld/thneed/thneed_common.cc selfdrive/modeld/thneed/thneed_qcom2.cc selfdrive/modeld/thneed/serialize.cc -selfdrive/modeld/thneed/compile.cc -selfdrive/modeld/thneed/optimizer.cc selfdrive/modeld/thneed/include/* -selfdrive/modeld/thneed/kernels/*.cl selfdrive/modeld/runners/snpemodel.cc selfdrive/modeld/runners/snpemodel.h diff --git a/selfdrive/modeld/SConscript b/selfdrive/modeld/SConscript index 2544607aa..246f8c294 100644 --- a/selfdrive/modeld/SConscript +++ b/selfdrive/modeld/SConscript @@ -26,7 +26,6 @@ thneed_src = [ "thneed/thneed_common.cc", "thneed/thneed_qcom2.cc", "thneed/serialize.cc", - "thneed/optimizer.cc", "runners/thneedmodel.cc", ] @@ -95,18 +94,6 @@ if use_thneed and arch == "larch64" or GetOption('pc_thneed'): "#tinygrad_repo/tinygrad/nn/__init__.py" ], cmd) - # old thneed compiler. TODO: remove this once tinygrad stuff is stable - - #compiler = lenv.Program('thneed/compile', ["thneed/compile.cc"]+common_model, LIBS=libs) - #cmd = f"cd {Dir('.').abspath} && {compiler[0].abspath} --in {fn}.dlc --out {fn}.thneed --binary --optimize" - - #lib_paths = ':'.join(Dir(p).abspath for p in lenv["LIBPATH"]) - #kernel_path = os.path.join(Dir('.').abspath, "thneed", "kernels") - #cenv = Environment(ENV={'LD_LIBRARY_PATH': f"{lib_paths}:{lenv['ENV']['LD_LIBRARY_PATH']}", 'KERNEL_PATH': kernel_path}) - - #kernels = [os.path.join(kernel_path, x) for x in os.listdir(kernel_path) if x.endswith(".cl")] - #cenv.Command(fn + ".thneed", [fn + ".dlc", kernels, compiler], cmd) - llenv = lenv.Clone() if GetOption('pc_thneed'): pc_thneed_src = [ diff --git a/selfdrive/modeld/runners/snpemodel.cc b/selfdrive/modeld/runners/snpemodel.cc index 95ee5fe82..ff4adcd8d 100644 --- a/selfdrive/modeld/runners/snpemodel.cc +++ b/selfdrive/modeld/runners/snpemodel.cc @@ -186,75 +186,14 @@ std::unique_ptr SNPEModel::addExtra(float *state, in } void SNPEModel::execute() { -#ifdef USE_THNEED - if (Runtime == zdl::DlSystem::Runtime_t::GPU) { - if (!thneed_recorded) { - bool ret = inputBuffer->setBufferAddress(input); - assert(ret == true); - if (use_extra) { - assert(extra != NULL); - bool extra_ret = extraBuffer->setBufferAddress(extra); - assert(extra_ret == true); - } - if (!snpe->execute(inputMap, outputMap)) { - PrintErrorStringAndExit(); - } - memset(recurrent, 0, recurrent_size*sizeof(float)); - thneed->record = true; - if (!snpe->execute(inputMap, outputMap)) { - PrintErrorStringAndExit(); - } - thneed->stop(); - printf("thneed cached\n"); - - // doing self test - float *outputs_golden = (float *)malloc(output_size*sizeof(float)); - memcpy(outputs_golden, output, output_size*sizeof(float)); - memset(output, 0, output_size*sizeof(float)); - memset(recurrent, 0, recurrent_size*sizeof(float)); - uint64_t start_time = nanos_since_boot(); - if (extra != NULL) { - float *inputs[5] = {recurrent, trafficConvention, desire, extra, input}; - thneed->execute(inputs, output); - } else { - float *inputs[4] = {recurrent, trafficConvention, desire, input}; - thneed->execute(inputs, output); - } - uint64_t elapsed_time = nanos_since_boot() - start_time; - printf("ran model in %.2f ms\n", float(elapsed_time)/1e6); - - if (memcmp(output, outputs_golden, output_size*sizeof(float)) == 0) { - printf("thneed selftest passed\n"); - } else { - for (int i = 0; i < output_size; i++) { - printf("mismatch %3d: %f %f\n", i, output[i], outputs_golden[i]); - } - assert(false); - } - free(outputs_golden); - thneed_recorded = true; - } else { - if (use_extra) { - float *inputs[5] = {recurrent, trafficConvention, desire, extra, input}; - thneed->execute(inputs, output); - } else { - float *inputs[4] = {recurrent, trafficConvention, desire, input}; - thneed->execute(inputs, output); - } - } - } else { -#endif - bool ret = inputBuffer->setBufferAddress(input); - assert(ret == true); - if (use_extra) { - bool extra_ret = extraBuffer->setBufferAddress(extra); - assert(extra_ret == true); - } - if (!snpe->execute(inputMap, outputMap)) { - PrintErrorStringAndExit(); - } -#ifdef USE_THNEED + bool ret = inputBuffer->setBufferAddress(input); + assert(ret == true); + if (use_extra) { + bool extra_ret = extraBuffer->setBufferAddress(extra); + assert(extra_ret == true); + } + if (!snpe->execute(inputMap, outputMap)) { + PrintErrorStringAndExit(); } -#endif } diff --git a/selfdrive/modeld/runners/thneedmodel.cc b/selfdrive/modeld/runners/thneedmodel.cc index d55a8104e..67db01bb9 100644 --- a/selfdrive/modeld/runners/thneedmodel.cc +++ b/selfdrive/modeld/runners/thneedmodel.cc @@ -6,7 +6,6 @@ ThneedModel::ThneedModel(const char *path, float *loutput, size_t loutput_size, thneed = new Thneed(true, context); thneed->load(path); thneed->clexec(); - thneed->find_inputs_outputs(); recorded = false; output = loutput; diff --git a/selfdrive/modeld/thneed/compile.cc b/selfdrive/modeld/thneed/compile.cc deleted file mode 100644 index f76c63b2b..000000000 --- a/selfdrive/modeld/thneed/compile.cc +++ /dev/null @@ -1,81 +0,0 @@ -#include -#include - -#include "selfdrive/modeld/runners/snpemodel.h" -#include "selfdrive/modeld/thneed/thneed.h" -#include "system/hardware/hw.h" - -#define TEMPORAL_SIZE 512 -#define DESIRE_LEN 8 -#define TRAFFIC_CONVENTION_LEN 2 - -// TODO: This should probably use SNPE directly. -int main(int argc, char* argv[]) { - bool run_optimizer = false, save_binaries = false; - const char *input_file = NULL, *output_file = NULL; - static struct option long_options[] = { - {"in", required_argument, 0, 'i' }, - {"out", required_argument, 0, 'o' }, - {"binary", no_argument, 0, 'b' }, - {"optimize", no_argument, 0, 'f' }, - {0, 0, 0, 0 } - }; - int long_index = 0, opt = 0; - while ((opt = getopt_long_only(argc, argv,"", long_options, &long_index)) != -1) { - switch (opt) { - case 'i': input_file = optarg; break; - case 'o': output_file = optarg; break; - case 'b': save_binaries = true; break; - case 'f': run_optimizer = true; break; - } - } - - // no input? - if (!input_file) { - printf("usage: -i -o --binary --optimize\n"); - return -1; - } - - #define OUTPUT_SIZE 0x10000 - - float *output = (float*)calloc(OUTPUT_SIZE, sizeof(float)); - SNPEModel mdl(input_file, output, 0, USE_GPU_RUNTIME, true); - mdl.thneed->run_optimizer = run_optimizer; - - float state[TEMPORAL_SIZE] = {0}; - float desire[DESIRE_LEN] = {0}; - float traffic_convention[TRAFFIC_CONVENTION_LEN] = {0}; - float *input = (float*)calloc(0x1000000, sizeof(float)); - float *extra = (float*)calloc(0x1000000, sizeof(float)); - - mdl.addRecurrent(state, TEMPORAL_SIZE); - mdl.addDesire(desire, DESIRE_LEN); - mdl.addTrafficConvention(traffic_convention, TRAFFIC_CONVENTION_LEN); - mdl.addImage(input, 0); - mdl.addExtra(extra, 0); - - // first run - printf("************** execute 1 **************\n"); - memset(output, 0, OUTPUT_SIZE * sizeof(float)); - mdl.execute(); - - // don't save? - if (!output_file) { - printf("no output file, exiting\n"); - return 0; - } - - // save model - printf("saving %s with binary %d\n", output_file, save_binaries); - mdl.thneed->save(output_file, save_binaries); - - // test model - auto thneed = new Thneed(true); - thneed->record = false; - thneed->load(output_file); - thneed->clexec(); - thneed->find_inputs_outputs(); - - return 0; -} - diff --git a/selfdrive/modeld/thneed/kernels/convolution_.cl b/selfdrive/modeld/thneed/kernels/convolution_.cl deleted file mode 100644 index 1b9d74b83..000000000 --- a/selfdrive/modeld/thneed/kernels/convolution_.cl +++ /dev/null @@ -1,272 +0,0 @@ - read_only image2d_t input, -#ifndef DEPTHWISE - short startPackedInputChannel, - short numPackedInputChannelsForGroup, short totalNumPackedInputChannels, - // typo required for API compatibility - short packedOuputChannelOffset, short totalNumPackedOutputChannels, -#else - short totalNumPackedChannels, -#endif - read_only image2d_t weights, __constant float *biases, - short filterSizeX, short filterSizeY, - write_only image2d_t output, - short paddingX, short paddingY, short strideX, short strideY, -#ifdef SUPPORT_DILATION - short dilationX, short dilationY, -#endif - short neuron, float a, float b, float min_clamp, float max_clamp, -#ifndef DEPTHWISE - // note: these are not supported - __constant float *parameters, __constant float *batchNormBiases, -#endif - short numOutputColumns -#ifdef SUPPORT_ACCUMULATION - , short doAccumulate, read_only image2d_t accumulator -#endif - ) { - -#ifndef NUM_OUTPUTS - #define NUM_OUTPUTS 4 -#endif - - // init - const sampler_t smp = CLK_NORMALIZED_COORDS_FALSE | CLK_ADDRESS_CLAMP | CLK_FILTER_NEAREST; - short packedOutputChannel = get_global_id(0); - short startOutputColumn = mul24((short)get_global_id(1), NUM_OUTPUTS); - short outputRow = get_global_id(2); - -#ifdef DEPTHWISE - short totalNumPackedInputChannels = totalNumPackedChannels; - short totalNumPackedOutputChannels = totalNumPackedChannels; - short startPackedInputChannel = packedOutputChannel; -#endif - - short startX = mad24(mad24(startOutputColumn, strideX, -paddingX), totalNumPackedInputChannels, startPackedInputChannel); - short strideWithChannels = mul24(strideX, totalNumPackedInputChannels); - - float4 outputValues[NUM_OUTPUTS]; - for (short i = 0; i < NUM_OUTPUTS; ++i) { - outputValues[i] = (float4)(0, 0, 0, 0); - } - - int2 inputLocation; - inputLocation.y = mad24(outputRow, strideY, -paddingY); - - int2 weightLocation; - weightLocation.x = 0; - weightLocation.y = packedOutputChannel; - -#ifdef DEPTHWISE - -#ifdef SUPPORT_DILATION - - // depthwise convolution - for (short rfRow = 0; rfRow < filterSizeY; ++rfRow) { - for (short rfColumn = 0; rfColumn < filterSizeX; ++rfColumn) { - short dilatedStepX = mul24(totalNumPackedChannels, dilationX); - inputLocation.x = mad24(rfColumn, dilatedStepX, startX); - float4 inputValues[4]; - for (short i = 0; i < 4; ++i) { - inputValues[i] = read_imagef(input, smp, inputLocation); - inputLocation.x += strideWithChannels; - } - float4 weightValues = read_imagef(weights, smp, weightLocation); - ++weightLocation.x; - outputValues[0] += inputValues[0] * weightValues; - outputValues[1] += inputValues[1] * weightValues; - outputValues[2] += inputValues[2] * weightValues; - outputValues[3] += inputValues[3] * weightValues; - } - inputLocation.y += dilationY; - } - -#else - - // depthwise unstrided convolution - for (short rfRow = 0; rfRow < filterSizeY; ++rfRow) { - float4 inputValues[4]; - inputLocation.x = startX; - for (short i = 1; i < 4; ++i) { - inputValues[i] = read_imagef(input, smp, inputLocation); - inputLocation.x += totalNumPackedOutputChannels; - } - for (short rfColumn = 0; rfColumn < filterSizeX; ++rfColumn) { - inputValues[0] = inputValues[1]; - inputValues[1] = inputValues[2]; - inputValues[2] = inputValues[3]; - inputValues[3] = read_imagef(input, smp, inputLocation); - inputLocation.x += totalNumPackedChannels; - float4 weightValues = read_imagef(weights, smp, weightLocation); - ++weightLocation.x; - outputValues[0] += inputValues[0] * weightValues; - outputValues[1] += inputValues[1] * weightValues; - outputValues[2] += inputValues[2] * weightValues; - outputValues[3] += inputValues[3] * weightValues; - } - ++inputLocation.y; - } - -#endif - -#elif defined(ONLY_1X1_CONV) - - // 1x1 convolution - short endPackedInputChannel = startPackedInputChannel + numPackedInputChannelsForGroup; - for (short packedInputChannel = startPackedInputChannel; packedInputChannel < endPackedInputChannel; ++packedInputChannel) { - float4 weightValues[4]; - for (short outChIdx = 0; outChIdx < 4; ++outChIdx) { - weightValues[outChIdx] = read_imagef(weights, smp, weightLocation); - ++weightLocation.x; - } - - inputLocation.x = startX + packedInputChannel; - float4 inputValues[NUM_OUTPUTS]; - for (short i = 0; i < NUM_OUTPUTS; ++i) { - inputValues[i] = read_imagef(input, smp, inputLocation); - inputLocation.x += strideWithChannels; - } - - for (short i = 0; i < NUM_OUTPUTS; ++i) { - float4 curOutputValues = outputValues[i]; - curOutputValues.x += inputValues[i].x * weightValues[0].x; - curOutputValues.x += inputValues[i].y * weightValues[0].y; - curOutputValues.x += inputValues[i].z * weightValues[0].z; - curOutputValues.x += inputValues[i].w * weightValues[0].w; - curOutputValues.y += inputValues[i].x * weightValues[1].x; - curOutputValues.y += inputValues[i].y * weightValues[1].y; - curOutputValues.y += inputValues[i].z * weightValues[1].z; - curOutputValues.y += inputValues[i].w * weightValues[1].w; - curOutputValues.z += inputValues[i].x * weightValues[2].x; - curOutputValues.z += inputValues[i].y * weightValues[2].y; - curOutputValues.z += inputValues[i].z * weightValues[2].z; - curOutputValues.z += inputValues[i].w * weightValues[2].w; - curOutputValues.w += inputValues[i].x * weightValues[3].x; - curOutputValues.w += inputValues[i].y * weightValues[3].y; - curOutputValues.w += inputValues[i].z * weightValues[3].z; - curOutputValues.w += inputValues[i].w * weightValues[3].w; - outputValues[i] = curOutputValues; - } - } - packedOutputChannel += packedOuputChannelOffset; - -#else - - // normal convolution - for (short rfRow = 0; rfRow < filterSizeY; ++rfRow) { - for (short packedInputChannel = 0; packedInputChannel < numPackedInputChannelsForGroup; ++packedInputChannel) { - short startXForChannel = startX + packedInputChannel; - for (short rfColumn = 0; rfColumn < filterSizeX; ++rfColumn) { - - float4 weightValues[4]; - for (short outChIdx = 0; outChIdx < 4; ++outChIdx) { - weightValues[outChIdx] = read_imagef(weights, smp, weightLocation); - ++weightLocation.x; - } - -#ifdef SUPPORT_DILATION - short dilatedStepX = mul24(totalNumPackedInputChannels, dilationX); - inputLocation.x = mad24(rfColumn, dilatedStepX, startXForChannel); -#else - inputLocation.x = mad24(rfColumn, totalNumPackedInputChannels, startXForChannel); -#endif - float4 inputValues[NUM_OUTPUTS]; - for (short i = 0; i < NUM_OUTPUTS; ++i) { - inputValues[i] = read_imagef(input, smp, inputLocation); - inputLocation.x += strideWithChannels; - } - for (short i = 0; i < NUM_OUTPUTS; ++i) { - float4 curOutputValues = outputValues[i]; - curOutputValues.x += inputValues[i].x * weightValues[0].x; - curOutputValues.x += inputValues[i].y * weightValues[0].y; - curOutputValues.x += inputValues[i].z * weightValues[0].z; - curOutputValues.x += inputValues[i].w * weightValues[0].w; - curOutputValues.y += inputValues[i].x * weightValues[1].x; - curOutputValues.y += inputValues[i].y * weightValues[1].y; - curOutputValues.y += inputValues[i].z * weightValues[1].z; - curOutputValues.y += inputValues[i].w * weightValues[1].w; - curOutputValues.z += inputValues[i].x * weightValues[2].x; - curOutputValues.z += inputValues[i].y * weightValues[2].y; - curOutputValues.z += inputValues[i].z * weightValues[2].z; - curOutputValues.z += inputValues[i].w * weightValues[2].w; - curOutputValues.w += inputValues[i].x * weightValues[3].x; - curOutputValues.w += inputValues[i].y * weightValues[3].y; - curOutputValues.w += inputValues[i].z * weightValues[3].z; - curOutputValues.w += inputValues[i].w * weightValues[3].w; - outputValues[i] = curOutputValues; - } - } - } -#ifdef SUPPORT_DILATION - inputLocation.y += dilationY; -#else - ++inputLocation.y; -#endif - } - packedOutputChannel += packedOuputChannelOffset; -#endif - - // bias - short outputChannel = mul24(packedOutputChannel, 4); - float4 biasValues = vload4(0, biases + outputChannel); - for (short i = 0; i < NUM_OUTPUTS; ++i) { - outputValues[i] += biasValues; - } - -#ifdef SUPPORT_ACCUMULATION - // accumulate - if (doAccumulate) { - int2 outputLocation; - short outputColumn = startOutputColumn; - outputLocation.y = outputRow; - for (short i = 0; i < NUM_OUTPUTS; ++i) { - outputLocation.x = mad24(outputColumn, totalNumPackedOutputChannels, packedOutputChannel); - if (outputColumn < numOutputColumns) { - outputValues[i] += read_imagef(accumulator, smp, outputLocation); - } - ++outputColumn; - } - } -#endif - - // activation - switch (neuron) { - case 1: - for (short i = 0; i < NUM_OUTPUTS; ++i) { - outputValues[i] = max(outputValues[i], 0.0f); - } - break; - case 2: - for (short i = 0; i < NUM_OUTPUTS; ++i) { - outputValues[i] = a * tanh(b * outputValues[i]); - } - break; - case 3: - for (short i = 0; i < NUM_OUTPUTS; ++i) { - outputValues[i] = native_recip(1.0f + native_exp(-a * outputValues[i] + b)); - } - break; - case 4: - for (short i = 0; i < NUM_OUTPUTS; ++i) { - outputValues[i] = max(outputValues[i], min_clamp); - outputValues[i] = min(outputValues[i], max_clamp); - } - break; - case 5: - for (short i = 0; i < NUM_OUTPUTS; ++i) { - outputValues[i] = max(outputValues[i], 0.0f) + a * (native_exp(min(outputValues[i], 0.0f)) - 1.0f); - } - break; - } - - // output - int2 outputLocation; - short outputColumn = startOutputColumn; - outputLocation.y = outputRow; - for (short i = 0; i < NUM_OUTPUTS; ++i) { - outputLocation.x = mad24(outputColumn, totalNumPackedOutputChannels, packedOutputChannel); - if (outputColumn < numOutputColumns) { - write_imagef(output, outputLocation, outputValues[i]); - } - ++outputColumn; - } -} diff --git a/selfdrive/modeld/thneed/kernels/convolution_horizontal_reduced_reads.cl b/selfdrive/modeld/thneed/kernels/convolution_horizontal_reduced_reads.cl deleted file mode 100644 index fcea88ce9..000000000 --- a/selfdrive/modeld/thneed/kernels/convolution_horizontal_reduced_reads.cl +++ /dev/null @@ -1,3 +0,0 @@ -#define SUPPORT_DILATION - -__kernel void convolution_horizontal_reduced_reads( diff --git a/selfdrive/modeld/thneed/kernels/convolution_horizontal_reduced_reads_1x1.cl b/selfdrive/modeld/thneed/kernels/convolution_horizontal_reduced_reads_1x1.cl deleted file mode 100644 index 0d15d8058..000000000 --- a/selfdrive/modeld/thneed/kernels/convolution_horizontal_reduced_reads_1x1.cl +++ /dev/null @@ -1,4 +0,0 @@ -#define ONLY_1X1_CONV -#define SUPPORT_ACCUMULATION - -__kernel void convolution_horizontal_reduced_reads_1x1( diff --git a/selfdrive/modeld/thneed/kernels/convolution_horizontal_reduced_reads_5_outputs.cl b/selfdrive/modeld/thneed/kernels/convolution_horizontal_reduced_reads_5_outputs.cl deleted file mode 100644 index 69421fc2a..000000000 --- a/selfdrive/modeld/thneed/kernels/convolution_horizontal_reduced_reads_5_outputs.cl +++ /dev/null @@ -1,3 +0,0 @@ -#define NUM_OUTPUTS 5 - -__kernel void convolution_horizontal_reduced_reads_5_outputs( diff --git a/selfdrive/modeld/thneed/kernels/convolution_horizontal_reduced_reads_depthwise.cl b/selfdrive/modeld/thneed/kernels/convolution_horizontal_reduced_reads_depthwise.cl deleted file mode 100644 index 50e39941d..000000000 --- a/selfdrive/modeld/thneed/kernels/convolution_horizontal_reduced_reads_depthwise.cl +++ /dev/null @@ -1,4 +0,0 @@ -#define DEPTHWISE -#define SUPPORT_DILATION - -__kernel void convolution_horizontal_reduced_reads_depthwise( diff --git a/selfdrive/modeld/thneed/kernels/convolution_horizontal_reduced_reads_depthwise_stride_1.cl b/selfdrive/modeld/thneed/kernels/convolution_horizontal_reduced_reads_depthwise_stride_1.cl deleted file mode 100644 index b347cb6c7..000000000 --- a/selfdrive/modeld/thneed/kernels/convolution_horizontal_reduced_reads_depthwise_stride_1.cl +++ /dev/null @@ -1,3 +0,0 @@ -#define DEPTHWISE - -__kernel void convolution_horizontal_reduced_reads_depthwise_stride_1( diff --git a/selfdrive/modeld/thneed/optimizer.cc b/selfdrive/modeld/thneed/optimizer.cc deleted file mode 100644 index 39737d3d7..000000000 --- a/selfdrive/modeld/thneed/optimizer.cc +++ /dev/null @@ -1,261 +0,0 @@ -#include -#include -#include -#include -#include "thneed.h" - -#include "common/util.h" -#include "common/clutil.h" - -extern map g_program_source; - -/*static int is_same_size_image(cl_mem a, cl_mem b) { - size_t a_width, a_height, a_depth, a_array_size, a_row_pitch, a_slice_pitch; - clGetImageInfo(a, CL_IMAGE_WIDTH, sizeof(a_width), &a_width, NULL); - clGetImageInfo(a, CL_IMAGE_HEIGHT, sizeof(a_height), &a_height, NULL); - clGetImageInfo(a, CL_IMAGE_DEPTH, sizeof(a_depth), &a_depth, NULL); - clGetImageInfo(a, CL_IMAGE_ARRAY_SIZE, sizeof(a_array_size), &a_array_size, NULL); - clGetImageInfo(a, CL_IMAGE_ROW_PITCH, sizeof(a_row_pitch), &a_row_pitch, NULL); - clGetImageInfo(a, CL_IMAGE_SLICE_PITCH, sizeof(a_slice_pitch), &a_slice_pitch, NULL); - - size_t b_width, b_height, b_depth, b_array_size, b_row_pitch, b_slice_pitch; - clGetImageInfo(b, CL_IMAGE_WIDTH, sizeof(b_width), &b_width, NULL); - clGetImageInfo(b, CL_IMAGE_HEIGHT, sizeof(b_height), &b_height, NULL); - clGetImageInfo(b, CL_IMAGE_DEPTH, sizeof(b_depth), &b_depth, NULL); - clGetImageInfo(b, CL_IMAGE_ARRAY_SIZE, sizeof(b_array_size), &b_array_size, NULL); - clGetImageInfo(b, CL_IMAGE_ROW_PITCH, sizeof(b_row_pitch), &b_row_pitch, NULL); - clGetImageInfo(b, CL_IMAGE_SLICE_PITCH, sizeof(b_slice_pitch), &b_slice_pitch, NULL); - - return (a_width == b_width) && (a_height == b_height) && - (a_depth == b_depth) && (a_array_size == b_array_size) && - (a_row_pitch == b_row_pitch) && (a_slice_pitch == b_slice_pitch); -}*/ - -static cl_mem make_image_like(cl_context context, cl_mem val) { - cl_image_format format; - size_t width, height, row_pitch; - clGetImageInfo(val, CL_IMAGE_FORMAT, sizeof(format), &format, NULL); - assert(format.image_channel_order == CL_RGBA); - assert(format.image_channel_data_type == CL_HALF_FLOAT); - clGetImageInfo(val, CL_IMAGE_WIDTH, sizeof(width), &width, NULL); - clGetImageInfo(val, CL_IMAGE_HEIGHT, sizeof(height), &height, NULL); - clGetImageInfo(val, CL_IMAGE_ROW_PITCH, sizeof(row_pitch), &row_pitch, NULL); - - cl_image_desc desc = {0}; - desc.image_type = CL_MEM_OBJECT_IMAGE2D; - desc.image_width = width; - desc.image_height = height; - desc.image_row_pitch = row_pitch; - - cl_mem buf = clCreateBuffer(context, CL_MEM_READ_WRITE, row_pitch*height, NULL, NULL); - assert(buf != NULL); - desc.buffer = buf; - - cl_int err; - cl_mem tmp = clCreateImage(context, CL_MEM_READ_WRITE, &format, &desc, NULL, &err); - //printf("got %d for image %zux%zu %zu\n", err, width, height, row_pitch); - assert(tmp != NULL); - - return tmp; -} - -// convolution_horizontal_reduced_reads_1x1 is 66% of the model runtime -// make that faster and the model gets faster - -// this cuts ~2 ms off the model runtime right now -int Thneed::optimize() { - const char *kernel_path = getenv("KERNEL_PATH"); - if (!kernel_path) { kernel_path = "/data/openpilot/selfdrive/modeld/thneed/kernels"; printf("no KERNEL_PATH set, defaulting to %s\n", kernel_path); } - - string convolution_; - { - char fn[0x100]; - snprintf(fn, sizeof(fn), "%s/%s.cl", kernel_path, "convolution_"); - convolution_ = util::read_file(fn); - } - - // load custom kernels - map g_programs; - for (auto &k : kq) { - // replace program? - if (g_programs.find(k->name) == g_programs.end()) { - char fn[0x100]; - snprintf(fn, sizeof(fn), "%s/%s.cl", kernel_path, k->name.c_str()); - if (util::file_exists(fn)) { - string kernel_src = util::read_file(fn); - if (k->name.rfind("convolution_", 0) == 0) { - kernel_src += convolution_; - } - printf("building kernel %s with len %lu\n", k->name.c_str(), kernel_src.length()); - k->program = cl_program_from_source(context, device_id, kernel_src); - - // save in cache - g_programs[k->name] = k->program; - g_program_source[k->program] = kernel_src; - } else { - g_programs[k->name] = NULL; - } - } else { - // cached replacement - if (g_programs[k->name] != NULL) { - k->program = g_programs[k->name]; - } - } - - // hack in accumulator to convolution_horizontal_reduced_reads_1x1 - if (k->name == "convolution_horizontal_reduced_reads_1x1") { - k->arg_names.push_back("doAccumulate"); - short doAccumulate = 0; - k->args.push_back(string((char *)&doAccumulate, sizeof(doAccumulate))); - k->args_size.push_back(2); - k->arg_names.push_back("accumulator"); - k->args.push_back(k->args[k->get_arg_num("output")]); - k->args_size.push_back(8); - k->num_args += 2; - } - - // assert that parameters + batchNormBiases are not used - // since they aren't supported in custom replacement kernels - if (k->name == "convolution_horizontal_reduced_reads_1x1" || - k->name == "convolution_horizontal_reduced_reads" || - k->name == "convolution_horizontal_reduced_reads_5_outputs") { - string p1 = k->args[k->get_arg_num("parameters")]; - string p2 = k->args[k->get_arg_num("batchNormBiases")]; - assert(p1.length() == 8 && *((uint64_t*)p1.data()) == 0); - assert(p2.length() == 8 && *((uint64_t*)p2.data()) == 0); - } - } - - // optimizer - size_t start_size; - do { - start_size = kq.size(); - - // get optimizations - map replacements; - for (int i = 0; i < kq.size(); i++) { - // fusing elementwise_sum + activate_image will save 3 enqueues - - // delete useless copy layers - // saves ~0.7 ms - /*if (kq[i]->name == "concatenation" || kq[i]->name == "flatten") { - string in = kq[i]->args[kq[i]->get_arg_num("input")]; - string out = kq[i]->args[kq[i]->get_arg_num("output")]; - if (is_same_size_image(*(cl_mem*)in.data(), *(cl_mem*)out.data())) { - cl_mem tmp = make_image_like(context, *(cl_mem *)in.data()); - replacements[in] = string((char *)&tmp, sizeof(tmp)); - replacements[out] = string((char *)&tmp, sizeof(tmp)); - - kq.erase(kq.begin()+i); --i; - } - }*/ - - // NOTE: if activations/accumulation are done in the wrong order, this will be wrong - - // fuse activations into convs and fc_Wtx - // saves ~1.5 ms - // NOTE: this changes the outputs because of rounding, should be better now! - if (i != 0 && kq[i]->name == "activate_image") { - if (kq[i-1]->name == "convolution_horizontal_reduced_reads_1x1" || - kq[i-1]->name == "convolution_horizontal_reduced_reads_5_outputs" || - kq[i-1]->name == "convolution_horizontal_reduced_reads" || - kq[i-1]->name == "convolution_horizontal_reduced_reads_depthwise" || - kq[i-1]->name == "convolution_horizontal_reduced_reads_depthwise_stride_1" || - kq[i-1]->name == "fc_Wtx") { - string lastout = kq[i-1]->args[kq[i-1]->get_arg_num("output")]; - string in = kq[i]->args[kq[i]->get_arg_num("input")]; - string out = kq[i]->args[kq[i]->get_arg_num("output")]; - - if (lastout == in) { - short neuron = *(int*)kq[i]->args[kq[i]->get_arg_num("neuron")].data(); - assert(neuron <= 5); - - // ELU isn't supported in fc_Wtx - assert(!(kq[i-1]->name == "fc_Wtx" && neuron == 5)); - - kq[i-1]->args[kq[i-1]->get_arg_num("neuron")] = string((char *)&neuron, sizeof(neuron)); - - cl_mem tmp = make_image_like(context, *(cl_mem *)lastout.data()); - replacements[in] = string((char *)&tmp, sizeof(tmp)); - replacements[out] = string((char *)&tmp, sizeof(tmp)); - - kq.erase(kq.begin()+i); --i; - } - } - } - - // fuse accumulation into convs and fc_Wtx - if (i != 0 && kq[i]->name == "elementwise_sum") { - if (kq[i-1]->name == "convolution_horizontal_reduced_reads_1x1" || - kq[i-1]->name == "fc_Wtx") { - string lastout = kq[i-1]->args[kq[i-1]->get_arg_num("output")]; - string a = kq[i]->args[kq[i]->get_arg_num("a")]; - string b = kq[i]->args[kq[i]->get_arg_num("b")]; - string out = kq[i]->args[kq[i]->get_arg_num("output")]; - - if (lastout == a) { - kq[i-1]->args[kq[i-1]->get_arg_num("accumulator")] = b; - } else if (lastout == b) { - kq[i-1]->args[kq[i-1]->get_arg_num("accumulator")] = a; - } else { - continue; - } - - cl_mem tmp = make_image_like(context, *(cl_mem *)lastout.data()); - replacements[lastout] = string((char *)&tmp, sizeof(tmp)); - replacements[out] = string((char *)&tmp, sizeof(tmp)); - - short doAccumulate = 1; - kq[i-1]->args[kq[i-1]->get_arg_num("doAccumulate")] = string((char *)&doAccumulate, sizeof(doAccumulate)); - - kq.erase(kq.begin()+i); --i; - } - } - } - - // remap inputs and outputs, and clear the kernels - for (int i = 0; i < kq.size(); i++) { - kq[i]->kernel = NULL; - for (int j = 0; j < kq[i]->num_args; j++) { - if (replacements.find(kq[i]->args[j]) != replacements.end()) { - kq[i]->args[j] = replacements[kq[i]->args[j]]; - } - } - } - - printf("optimize %lu -> %lu\n", start_size, kq.size()); - } while (kq.size() != start_size); - - size_t work_group_size = 0; - clGetDeviceInfo(device_id, CL_DEVICE_MAX_WORK_GROUP_SIZE, sizeof(work_group_size), &work_group_size, NULL); - printf("max work group size %lu\n", work_group_size); - - // local work group optimizer - for (auto &k : kq) { - // only do it for convs, since others might share memory - if (k->name.rfind("convolution_", 0) == 0) { - int best = -1; - if (k->local_work_size[0] * k->local_work_size[1] * k->local_work_size[2] < work_group_size/2) { - uint64_t base_time = k->benchmark(); - uint64_t best_time = base_time; - for (int i = 0; i < 3; i++) { - k->local_work_size[i] *= 2; - uint64_t this_time = k->benchmark(); - if (this_time < best_time) { - best = i; - best_time = this_time; - } - k->local_work_size[i] /= 2; - } - if (best != -1) { - k->local_work_size[best] *= 2; - //printf("%s %.2f ms doubled %d to %.2f ms\n", k->name.c_str(), base_time/1e6, best, best_time/1e6); - } - } - - } - } - - return 0; -} - diff --git a/selfdrive/modeld/thneed/serialize.cc b/selfdrive/modeld/thneed/serialize.cc index afc84ee76..f789e5bf5 100644 --- a/selfdrive/modeld/thneed/serialize.cc +++ b/selfdrive/modeld/thneed/serialize.cc @@ -152,155 +152,3 @@ void Thneed::load(const char *filename) { clFinish(command_queue); } - -void Thneed::save(const char *filename, bool save_binaries) { - printf("Thneed::save: saving to %s\n", filename); - - // get kernels - std::vector kernels; - std::set saved_objects; - std::vector objects; - std::map programs; - std::map binaries; - - for (auto &k : kq) { - kernels.push_back(k->to_json()); - - // check args for objects - int i = 0; - for (auto &a : k->args) { - if (a.size() == 8) { - if (saved_objects.find(a) == saved_objects.end()) { - saved_objects.insert(a); - cl_mem val = *(cl_mem*)(a.data()); - if (val != NULL) { - bool needs_load = k->arg_names[i] == "weights" || k->arg_names[i] == "biases"; - - auto jj = Json::object({ - {"id", a}, - {"arg_type", k->arg_types[i]}, - }); - - if (k->arg_types[i] == "image2d_t" || k->arg_types[i] == "image1d_t") { - cl_mem buf = NULL; - clGetImageInfo(val, CL_IMAGE_BUFFER, sizeof(buf), &buf, NULL); - string aa = string((char *)&buf, sizeof(buf)); - jj["buffer_id"] = aa; - - size_t width, height, row_pitch; - clGetImageInfo(val, CL_IMAGE_WIDTH, sizeof(width), &width, NULL); - clGetImageInfo(val, CL_IMAGE_HEIGHT, sizeof(height), &height, NULL); - clGetImageInfo(val, CL_IMAGE_ROW_PITCH, sizeof(row_pitch), &row_pitch, NULL); - jj["width"] = (int)width; - jj["height"] = (int)height; - jj["row_pitch"] = (int)row_pitch; - jj["size"] = (int)(height * row_pitch); - jj["needs_load"] = false; - jj["float32"] = false; - - if (saved_objects.find(aa) == saved_objects.end()) { - saved_objects.insert(aa); - size_t sz; - clGetMemObjectInfo(buf, CL_MEM_SIZE, sizeof(sz), &sz, NULL); - // save the buffer - objects.push_back(Json::object({ - {"id", aa}, - {"arg_type", ""}, - {"needs_load", needs_load}, - {"size", (int)sz} - })); - if (needs_load) assert(sz == height * row_pitch); - } - } else { - size_t sz = 0; - clGetMemObjectInfo(val, CL_MEM_SIZE, sizeof(sz), &sz, NULL); - jj["size"] = (int)sz; - jj["needs_load"] = needs_load; - } - - objects.push_back(jj); - } - } - } - i++; - } - - if (save_binaries) { - int err; - size_t binary_size = 0; - err = clGetProgramInfo(k->program, CL_PROGRAM_BINARY_SIZES, sizeof(binary_size), &binary_size, NULL); - assert(err == 0); - assert(binary_size > 0); - string sv(binary_size, '\x00'); - - uint8_t* bufs[1] = { (uint8_t*)sv.data(), }; - err = clGetProgramInfo(k->program, CL_PROGRAM_BINARIES, sizeof(bufs), &bufs, NULL); - assert(err == 0); - - binaries[k->name] = sv; - } else { - programs[k->name] = g_program_source[k->program]; - } - } - - vector saved_buffers; - for (auto &obj : objects) { - auto mobj = obj.object_items(); - cl_mem val = *(cl_mem*)(mobj["id"].string_value().data()); - int sz = mobj["size"].int_value(); - if (mobj["needs_load"].bool_value()) { - char *buf = (char *)malloc(sz); - if (mobj["arg_type"] == "image2d_t" || mobj["arg_type"] == "image1d_t") { - assert(false); - } else { - // buffers allocated with CL_MEM_HOST_WRITE_ONLY, hence this hack - //hexdump((uint32_t*)val, 0x100); - - // the worst hack in thneed, the flags are at 0x14 - ((uint32_t*)val)[0x14] &= ~CL_MEM_HOST_WRITE_ONLY; - cl_int ret = clEnqueueReadBuffer(command_queue, val, CL_TRUE, 0, sz, buf, 0, NULL, NULL); - assert(ret == CL_SUCCESS); - } - //printf("saving buffer: %d %p %s\n", sz, buf, mobj["arg_type"].string_value().c_str()); - saved_buffers.push_back(string(buf, sz)); - free(buf); - } - } - - std::vector jbinaries; - for (auto &obj : binaries) { - jbinaries.push_back(Json::object({{"name", obj.first}, {"length", (int)obj.second.size()}})); - saved_buffers.push_back(obj.second); - } - - Json jdat = Json::object({ - {"kernels", kernels}, - {"objects", objects}, - {"programs", programs}, - {"binaries", jbinaries}, - }); - - string str = jdat.dump(); - int jsz = str.length(); - - FILE *f = fopen(filename, "wb"); - fwrite(&jsz, 1, sizeof(jsz), f); - fwrite(str.data(), 1, jsz, f); - for (auto &s : saved_buffers) { - fwrite(s.data(), 1, s.length(), f); - } - fclose(f); -} - -Json CLQueuedKernel::to_json() const { - return Json::object { - { "name", name }, - { "work_dim", (int)work_dim }, - { "global_work_size", Json::array { (int)global_work_size[0], (int)global_work_size[1], (int)global_work_size[2] } }, - { "local_work_size", Json::array { (int)local_work_size[0], (int)local_work_size[1], (int)local_work_size[2] } }, - { "num_args", (int)num_args }, - { "args", args }, - { "args_size", args_size }, - }; -} - diff --git a/selfdrive/modeld/thneed/thneed.h b/selfdrive/modeld/thneed/thneed.h index 2a5800f30..65475ccf7 100644 --- a/selfdrive/modeld/thneed/thneed.h +++ b/selfdrive/modeld/thneed/thneed.h @@ -17,7 +17,6 @@ using namespace std; cl_int thneed_clSetKernelArg(cl_kernel kernel, cl_uint arg_index, size_t arg_size, const void *arg_value); -cl_program thneed_clCreateProgramWithSource(cl_context context, cl_uint count, const char **strings, const size_t *lengths, cl_int *errcode_ret); namespace json11 { class Json; @@ -43,7 +42,6 @@ class CLQueuedKernel { const size_t *_global_work_size, const size_t *_local_work_size); cl_int exec(); - uint64_t benchmark(); void debug_print(bool verbose); int get_arg_num(const char *search_arg_name); cl_program program; @@ -96,8 +94,6 @@ class Thneed { void stop(); void execute(float **finputs, float *foutput, bool slow=false); void wait(); - int optimize(); - bool run_optimizer = false; vector input_clmem; vector inputs; @@ -121,7 +117,6 @@ class Thneed { #endif // all CL kernels - void find_inputs_outputs(); void copy_inputs(float **finputs, bool internal=false); void copy_output(float *foutput); cl_int clexec(); @@ -130,9 +125,8 @@ class Thneed { // pending CL kernels vector > ckq; - // loading and saving + // loading void load(const char *filename); - void save(const char *filename, bool save_binaries=false); private: void clinit(); }; diff --git a/selfdrive/modeld/thneed/thneed_common.cc b/selfdrive/modeld/thneed/thneed_common.cc index a3f5c908f..21170b13a 100644 --- a/selfdrive/modeld/thneed/thneed_common.cc +++ b/selfdrive/modeld/thneed/thneed_common.cc @@ -11,6 +11,11 @@ map, string> g_args; map, int> g_args_size; map g_program_source; +void Thneed::stop() { + printf("Thneed::stop: recorded %lu commands\n", cmds.size()); + record = false; +} + void Thneed::clinit() { device_id = cl_get_device_id(CL_DEVICE_TYPE_DEFAULT); if (context == NULL) context = CL_CHECK_ERR(clCreateContext(NULL, 1, &device_id, NULL, NULL, &err)); @@ -131,23 +136,6 @@ cl_int CLQueuedKernel::exec() { kernel, work_dim, NULL, global_work_size, local_work_size, 0, NULL, NULL); } -uint64_t CLQueuedKernel::benchmark() { - uint64_t ret = 0; - int old_record = thneed->record; - thneed->record = 0; - clFinish(thneed->command_queue); - // TODO: benchmarking at a lower level will make this more accurate - for (int i = 0; i < 10; i++) { - uint64_t sb = nanos_since_boot(); - exec(); - clFinish(thneed->command_queue); - uint64_t et = nanos_since_boot() - sb; - if (ret == 0 || et < ret) ret = et; - } - thneed->record = old_record; - return ret; -} - void CLQueuedKernel::debug_print(bool verbose) { printf("%p %56s -- ", kernel, name.c_str()); for (int i = 0; i < work_dim; i++) { @@ -226,10 +214,3 @@ cl_int thneed_clSetKernelArg(cl_kernel kernel, cl_uint arg_index, size_t arg_siz cl_int ret = clSetKernelArg(kernel, arg_index, arg_size, arg_value); return ret; } - -cl_program thneed_clCreateProgramWithSource(cl_context context, cl_uint count, const char **strings, const size_t *lengths, cl_int *errcode_ret) { - assert(count == 1); - cl_program ret = clCreateProgramWithSource(context, count, strings, lengths, errcode_ret); - g_program_source[ret] = strings[0]; - return ret; -} \ No newline at end of file diff --git a/selfdrive/modeld/thneed/thneed_pc.cc b/selfdrive/modeld/thneed/thneed_pc.cc index e32dd289e..8d0037628 100644 --- a/selfdrive/modeld/thneed/thneed_pc.cc +++ b/selfdrive/modeld/thneed/thneed_pc.cc @@ -30,11 +30,3 @@ void Thneed::execute(float **finputs, float *foutput, bool slow) { printf("model exec in %lu us\n", (te-tb)/1000); } } - -void Thneed::stop() { -} - -void Thneed::find_inputs_outputs() { - // thneed on PC doesn't work on old style inputs/outputs -} - diff --git a/selfdrive/modeld/thneed/thneed_qcom2.cc b/selfdrive/modeld/thneed/thneed_qcom2.cc index f35317d2a..a29a82c8c 100644 --- a/selfdrive/modeld/thneed/thneed_qcom2.cc +++ b/selfdrive/modeld/thneed/thneed_qcom2.cc @@ -218,39 +218,6 @@ Thneed::Thneed(bool do_clinit, cl_context _context) { debug = (thneed_debug_env != NULL) ? atoi(thneed_debug_env) : 0; } -void Thneed::stop() { - find_inputs_outputs(); - printf("Thneed::stop: recorded %lu commands\n", cmds.size()); - record = false; -} - -void Thneed::find_inputs_outputs() { - cl_int err; - if (inputs.size() > 0) return; - - // save the global inputs/outputs - for (auto &k : kq) { - for (int i = 0; i < k->num_args; i++) { - if (k->name == "zero_pad_image_float" && k->arg_names[i] == "input") { - cl_mem aa = *(cl_mem*)(k->args[i].data()); - input_clmem.push_back(aa); - - size_t sz; - clGetMemObjectInfo(aa, CL_MEM_SIZE, sizeof(sz), &sz, NULL); - input_sizes.push_back(sz); - - void *ret = clEnqueueMapBuffer(command_queue, aa, CL_TRUE, CL_MAP_WRITE, 0, sz, 0, NULL, NULL, &err); - assert(err == CL_SUCCESS); - inputs.push_back(ret); - } - - if (k->name == "image2d_to_buffer_float" && k->arg_names[i] == "output") { - output = *(cl_mem*)(k->args[i].data()); - } - } - } -} - void Thneed::wait() { struct kgsl_device_waittimestamp_ctxtid wait; wait.context_id = context_id; @@ -314,74 +281,3 @@ void Thneed::execute(float **finputs, float *foutput, bool slow) { printf("model exec in %lu us\n", (te-tb)/1000); } } - -// *********** OpenCL interceptor *********** - -cl_int thneed_clEnqueueNDRangeKernel(cl_command_queue command_queue, - cl_kernel kernel, - cl_uint work_dim, - const size_t *global_work_offset, - const size_t *global_work_size, - const size_t *local_work_size, - cl_uint num_events_in_wait_list, - const cl_event *event_wait_list, - cl_event *event) { - - Thneed *thneed = g_thneed; - - // SNPE doesn't use these - assert(num_events_in_wait_list == 0); - assert(global_work_offset == NULL); - assert(event_wait_list == NULL); - - cl_int ret = 0; - if (thneed != NULL && thneed->record) { - if (thneed->context == NULL) { - thneed->command_queue = command_queue; - clGetKernelInfo(kernel, CL_KERNEL_CONTEXT, sizeof(thneed->context), &thneed->context, NULL); - clGetContextInfo(thneed->context, CL_CONTEXT_DEVICES, sizeof(thneed->device_id), &thneed->device_id, NULL); - } - - // if we are recording, we don't actually enqueue the kernel - thneed->kq.push_back(unique_ptr(new CLQueuedKernel(thneed, kernel, work_dim, global_work_size, local_work_size))); - *event = NULL; - } else { - ret = clEnqueueNDRangeKernel(command_queue, kernel, work_dim, - global_work_offset, global_work_size, local_work_size, - num_events_in_wait_list, event_wait_list, event); - } - - return ret; -} - -cl_int thneed_clFinish(cl_command_queue command_queue) { - Thneed *thneed = g_thneed; - - if (thneed != NULL && thneed->record) { - if (thneed->run_optimizer) thneed->optimize(); - return thneed->clexec(); - } else { - return clFinish(command_queue); - } -} - -void *dlsym(void *handle, const char *symbol) { -#ifdef QCOM2 - void *(*my_dlsym)(void *handle, const char *symbol) = (void *(*)(void *handle, const char *symbol))((uintptr_t)dlopen + DLSYM_OFFSET); -#else - #error "Unsupported platform for thneed" -#endif - if (memcmp("REAL_", symbol, 5) == 0) { - return my_dlsym(handle, symbol+5); - } else if (strcmp("clFinish", symbol) == 0) { - return (void*)thneed_clFinish; - } else if (strcmp("clEnqueueNDRangeKernel", symbol) == 0) { - return (void*)thneed_clEnqueueNDRangeKernel; - } else if (strcmp("clSetKernelArg", symbol) == 0) { - return (void*)thneed_clSetKernelArg; - } else if (strcmp("clCreateProgramWithSource", symbol) == 0) { - return (void*)thneed_clCreateProgramWithSource; - } else { - return my_dlsym(handle, symbol); - } -} diff --git a/selfdrive/modeld/thneed/weights_fixup.py b/selfdrive/modeld/thneed/weights_fixup.py deleted file mode 100755 index 539b1b5d3..000000000 --- a/selfdrive/modeld/thneed/weights_fixup.py +++ /dev/null @@ -1,146 +0,0 @@ -#!/usr/bin/env python3 -import os -import struct -import zipfile -import numpy as np -from tqdm import tqdm - -from common.basedir import BASEDIR -from selfdrive.modeld.thneed.lib import load_thneed, save_thneed - -# this is junk code, but it doesn't have deps -def load_dlc_weights(fn): - archive = zipfile.ZipFile(fn, 'r') - dlc_params = archive.read("model.params") - - def extract(rdat): - idx = rdat.find(b"\x00\x00\x00\x09\x04\x00\x00\x00") - rdat = rdat[idx+8:] - ll = struct.unpack("I", rdat[0:4])[0] - buf = np.frombuffer(rdat[4:4+ll*4], dtype=np.float32) - rdat = rdat[4+ll*4:] - dims = struct.unpack("I", rdat[0:4])[0] - buf = buf.reshape(struct.unpack("I"*dims, rdat[4:4+dims*4])) - if len(buf.shape) == 4: - buf = np.transpose(buf, (3,2,0,1)) - return buf - - def parse(tdat): - ll = struct.unpack("I", tdat[0:4])[0] + 4 - return (None, [extract(tdat[0:]), extract(tdat[ll:])]) - - ptr = 0x20 - def r4(): - nonlocal ptr - ret = struct.unpack("I", dlc_params[ptr:ptr+4])[0] - ptr += 4 - return ret - ranges = [] - cnt = r4() - for _ in range(cnt): - o = r4() + ptr - # the header is 0xC - plen, is_4, is_2 = struct.unpack("III", dlc_params[o:o+0xC]) - assert is_4 == 4 and is_2 == 2 - ranges.append((o+0xC, o+plen+0xC)) - ranges = sorted(ranges, reverse=True) - - return [parse(dlc_params[s:e]) for s,e in ranges] - -# this won't run on device without onnx -def load_onnx_weights(fn): - import onnx - from onnx import numpy_helper - - model = onnx.load(fn) - graph = model.graph # pylint: disable=maybe-no-member - init = {x.name:x for x in graph.initializer} - - onnx_layers = [] - for node in graph.node: - #print(node.name, node.op_type, node.input, node.output) - vals = [] - for inp in node.input: - if inp in init: - vals.append(numpy_helper.to_array(init[inp])) - if len(vals) > 0: - onnx_layers.append((node.name, vals)) - return onnx_layers - -def weights_fixup(target, source_thneed, dlc): - #onnx_layers = load_onnx_weights(os.path.join(BASEDIR, "models/supercombo.onnx")) - onnx_layers = load_dlc_weights(dlc) - jdat = load_thneed(source_thneed) - - bufs = {} - for o in jdat['objects']: - bufs[o['id']] = o - - thneed_layers = [] - for k in jdat['kernels']: - #print(k['name']) - vals = [] - for a in k['args']: - if a in bufs: - o = bufs[a] - if o['needs_load'] or ('buffer_id' in o and bufs[o['buffer_id']]['needs_load']): - #print(" ", o['arg_type']) - vals.append(o) - if len(vals) > 0: - thneed_layers.append((k['name'], vals)) - - assert len(thneed_layers) == len(onnx_layers) - - # fix up weights - for tl, ol in tqdm(zip(thneed_layers, onnx_layers), total=len(thneed_layers)): - #print(tl[0], ol[0]) - assert len(tl[1]) == len(ol[1]) - for o, onnx_weight in zip(tl[1], ol[1]): - if o['arg_type'] == "image2d_t": - obuf = bufs[o['buffer_id']] - saved_weights = np.frombuffer(obuf['data'], dtype=np.float16).reshape(o['height'], o['row_pitch']//2) - - if len(onnx_weight.shape) == 4: - # convolution - oc,ic,ch,cw = onnx_weight.shape - - if 'depthwise' in tl[0]: - assert ic == 1 - weights = np.transpose(onnx_weight.reshape(oc//4,4,ch,cw), (0,2,3,1)).reshape(o['height'], o['width']*4) - else: - weights = np.transpose(onnx_weight.reshape(oc//4,4,ic//4,4,ch,cw), (0,4,2,5,1,3)).reshape(o['height'], o['width']*4) - else: - # fc_Wtx - weights = onnx_weight - - new_weights = np.zeros((o['height'], o['row_pitch']//2), dtype=np.float32) - new_weights[:, :weights.shape[1]] = weights - - # weights shouldn't be too far off - err = np.mean((saved_weights.astype(np.float32) - new_weights)**2) - assert err < 1e-3 - rerr = np.mean(np.abs((saved_weights.astype(np.float32) - new_weights)/(new_weights+1e-12))) - assert rerr < 0.5 - - # fix should improve things - fixed_err = np.mean((new_weights.astype(np.float16).astype(np.float32) - new_weights)**2) - assert (err/fixed_err) >= 1 - - #print(" ", o['size'], onnx_weight.shape, o['row_pitch'], o['width'], o['height'], "err %.2fx better" % (err/fixed_err)) - - obuf['data'] = new_weights.astype(np.float16).tobytes() - - elif o['arg_type'] == "float*": - # unconverted floats are correct - new_weights = np.zeros(o['size']//4, dtype=np.float32) - new_weights[:onnx_weight.shape[0]] = onnx_weight - assert new_weights.tobytes() == o['data'] - #print(" ", o['size'], onnx_weight.shape) - - save_thneed(jdat, target) - -if __name__ == "__main__": - model_dir = os.path.join(BASEDIR, "selfdrive/modeld/models/") - weights_fixup(os.path.join(model_dir, "supercombo_fixed.thneed"), - os.path.join(model_dir, "supercombo.thneed"), - os.path.join(model_dir, "supercombo.dlc")) From 502a39219932172d52ee0f280c5200ba11bca0c9 Mon Sep 17 00:00:00 2001 From: Jeroen Date: Fri, 2 Sep 2022 04:05:15 +0200 Subject: [PATCH 134/172] bootlog: only do nvme checks on tici (#25634) --- selfdrive/loggerd/bootlog.cc | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/selfdrive/loggerd/bootlog.cc b/selfdrive/loggerd/bootlog.cc index 90ba487ff..6ff052655 100644 --- a/selfdrive/loggerd/bootlog.cc +++ b/selfdrive/loggerd/bootlog.cc @@ -26,10 +26,13 @@ static kj::Array build_boot_log() { // Gather output of commands std::vector bootlog_commands = { - "[ -e /dev/nvme0 ] && sudo nvme smart-log --output-format=json /dev/nvme0", "[ -x \"$(command -v journalctl)\" ] && journalctl", }; + if (Hardware::TICI()) { + bootlog_commands.push_back("[ -e /dev/nvme0 ] && sudo nvme smart-log --output-format=json /dev/nvme0"); + } + auto commands = boot.initCommands().initEntries(bootlog_commands.size()); for (int j = 0; j < bootlog_commands.size(); j++) { auto lentry = commands[j]; From 6b236b4edd2028521e0a36fe59547ee0115751f0 Mon Sep 17 00:00:00 2001 From: Alex Ye <49353607+FeistyFinn@users.noreply.github.com> Date: Thu, 1 Sep 2022 22:23:49 -0400 Subject: [PATCH 135/172] Toyota: Add missing engine FW 2020 Corolla (#25626) * Toyota: Add missing engine FW 2020 Corolla 2020 Corolla LE (2ZR-FAE) Dongle/route: 73fed27d198f6a7d|2022-08-31--17-41-34 * Made entry alphabetical --- 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 5649e7d65..42a67ec96 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -718,6 +718,7 @@ FW_VERSIONS = { b'\x03312N6000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', b'\x03312N6100\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', b'\x03312N6100\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', + b'\x03312N6200\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', b'\x02312K4000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', b'\x02312U5000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', ], From fd7525d806eb6fb6bd397db0dd95325d4175b979 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 1 Sep 2022 21:51:48 -0700 Subject: [PATCH 136/172] Chrysler: support convenience blinkers (#25644) Co-authored-by: Comma Device --- selfdrive/car/chrysler/carstate.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/car/chrysler/carstate.py b/selfdrive/car/chrysler/carstate.py index fefd351a2..0f0d30782 100644 --- a/selfdrive/car/chrysler/carstate.py +++ b/selfdrive/car/chrysler/carstate.py @@ -58,8 +58,8 @@ class CarState(CarStateBase): ) # button presses - ret.leftBlinker = cp.vl["STEERING_LEVERS"]["TURN_SIGNALS"] == 1 - ret.rightBlinker = cp.vl["STEERING_LEVERS"]["TURN_SIGNALS"] == 2 + ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_stalk(200, cp.vl["STEERING_LEVERS"]["TURN_SIGNALS"] == 1, + cp.vl["STEERING_LEVERS"]["TURN_SIGNALS"] == 2) ret.genericToggle = cp.vl["STEERING_LEVERS"]["HIGH_BEAM_PRESSED"] == 1 # steering wheel From 7ecc0409bd767392074a37cdd0b7e44ed9953296 Mon Sep 17 00:00:00 2001 From: Robbe Derks Date: Fri, 2 Sep 2022 07:18:44 +0200 Subject: [PATCH 137/172] camerad: read param to see if we want manual gain (#25642) * also read params to determine if we want manual gains * check for larger than 0 Co-authored-by: Comma Device --- system/camerad/cameras/camera_qcom2.cc | 16 ++++++++++------ 1 file changed, 10 insertions(+), 6 deletions(-) diff --git a/system/camerad/cameras/camera_qcom2.cc b/system/camerad/cameras/camera_qcom2.cc index c06aeb436..a86218c06 100644 --- a/system/camerad/cameras/camera_qcom2.cc +++ b/system/camerad/cameras/camera_qcom2.cc @@ -1101,14 +1101,18 @@ void CameraState::set_camera_exposure(float grey_frac) { } else if (enable_dc_gain && target_grey > 0.3) { enable_dc_gain = false; } + + std::string gain_bytes, time_bytes; if (env_ctrl_exp_from_params) { + gain_bytes = Params().get("CameraDebugExpGain"); + time_bytes = Params().get("CameraDebugExpTime"); + } + + if (gain_bytes.size() > 0 && time_bytes.size() > 0) { // Override gain and exposure time - if (buf.cur_frame_data.frame_id % 5 == 0) { - std::string gain_bytes = Params().get("CameraDebugExpGain"); - std::string time_bytes = Params().get("CameraDebugExpTime"); - gain_idx = std::stoi(gain_bytes); - exposure_time = std::stoi(time_bytes); - } + gain_idx = std::stoi(gain_bytes); + exposure_time = std::stoi(time_bytes); + new_g = gain_idx; new_t = exposure_time; enable_dc_gain = false; From faff2b8950c3ae0b0dff69c871381416ce2be416 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Fri, 2 Sep 2022 00:24:53 -0700 Subject: [PATCH 138/172] Add e2e long toggle (#25638) * Add toggle * Misc fixes * Update translations * pre alpha not great --- common/params.cc | 1 + .../lib/longitudinal_mpc_lib/long_mpc.py | 10 +- .../controls/lib/longitudinal_planner.py | 9 +- selfdrive/ui/qt/offroad/settings.cc | 6 + selfdrive/ui/translations/main_ja.ts | 136 ++++++++++-------- selfdrive/ui/translations/main_ko.ts | 136 ++++++++++-------- selfdrive/ui/translations/main_pt-BR.ts | 136 ++++++++++-------- selfdrive/ui/translations/main_zh-CHS.ts | 136 ++++++++++-------- selfdrive/ui/translations/main_zh-CHT.ts | 136 ++++++++++-------- 9 files changed, 383 insertions(+), 323 deletions(-) diff --git a/common/params.cc b/common/params.cc index e5071268b..5c8002dfb 100644 --- a/common/params.cc +++ b/common/params.cc @@ -100,6 +100,7 @@ std::unordered_map keys = { {"DashcamOverride", PERSISTENT}, {"DisableLogging", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_ON}, {"DisablePowerDown", PERSISTENT}, + {"EndToEndLong", PERSISTENT}, {"DisableRadar_Allow", PERSISTENT}, {"DisableRadar", PERSISTENT}, // WARNING: THIS DISABLES AEB {"DisableUpdates", PERSISTENT}, diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py b/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py index eaecb63a6..405ef8191 100644 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py @@ -248,13 +248,13 @@ 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., 1.0, 0.0, 0.0, 0.0, 1.0] - constraint_cost_weights = [LIMIT_COST, LIMIT_COST, LIMIT_COST, 0.0] + cost_weights = [0., 0.2, 0.25, 1.0, 0.0, 1.0] + constraint_cost_weights = [LIMIT_COST, LIMIT_COST, LIMIT_COST, 5.0] elif self.mode == 'e2e': cost_weights = [0., 0.2, 0.25, 1., 0.0, .1] constraint_cost_weights = [LIMIT_COST, LIMIT_COST, LIMIT_COST, 0.0] else: - raise NotImplementedError(f'Planner mode {self.mode} not recognized') + raise NotImplementedError(f'Planner mode {self.mode} not recognized in planner cost set') self.set_cost_weights(cost_weights, constraint_cost_weights) def set_cur_state(self, v, a): @@ -347,7 +347,7 @@ class LongitudinalMpc: self.source = 'e2e' else: - raise NotImplementedError(f'Planner mode {self.mode} not recognized') + raise NotImplementedError(f'Planner mode {self.mode} not recognized in planner update') self.yref[:,1] = x self.yref[:,2] = v @@ -357,8 +357,6 @@ class LongitudinalMpc: self.solver.set(i, "yref", self.yref[i]) self.solver.set(N, "yref", self.yref[N][:COST_E_DIM]) - x_obstacles = np.column_stack([lead_0_obstacle, lead_1_obstacle, cruise_obstacle]) - self.source = SOURCES[np.argmin(x_obstacles[0])] self.params[:,2] = np.min(x_obstacles, axis=1) self.params[:,3] = np.copy(self.prev_a) diff --git a/selfdrive/controls/lib/longitudinal_planner.py b/selfdrive/controls/lib/longitudinal_planner.py index 42ce2bd0e..b6120d245 100755 --- a/selfdrive/controls/lib/longitudinal_planner.py +++ b/selfdrive/controls/lib/longitudinal_planner.py @@ -6,6 +6,7 @@ from common.numpy_fast import interp import cereal.messaging as messaging from common.conversions import Conversions as CV from common.filter_simple import FirstOrderFilter +from common.params import Params from common.realtime import DT_MDL from selfdrive.modeld.constants import T_IDXS from selfdrive.controls.lib.longcontrol import LongCtrlState @@ -47,7 +48,10 @@ def limit_accel_in_turns(v_ego, angle_steers, a_target, CP): class Planner: def __init__(self, CP, init_v=0.0, init_a=0.0): self.CP = CP - self.mpc = LongitudinalMpc() + params = Params() + # TODO read param in the loop for live toggling + mode = 'blended' if params.get_bool('EndToEndLong') else 'acc' + self.mpc = LongitudinalMpc(mode=mode) self.fcw = False @@ -122,7 +126,8 @@ class Planner: self.j_desired_trajectory = np.interp(T_IDXS[:CONTROL_N], T_IDXS_MPC[:-1], self.mpc.j_solution) # TODO counter is only needed because radar is glitchy, remove once radar is gone - self.fcw = self.mpc.crash_cnt > 5 + # TODO write fcw in e2e_long mode + self.fcw = self.mpc.mode == 'acc' and self.mpc.crash_cnt > 5 if self.fcw: cloudlog.info("FCW triggered") diff --git a/selfdrive/ui/qt/offroad/settings.cc b/selfdrive/ui/qt/offroad/settings.cc index 5e0e87e64..09ff0eed9 100644 --- a/selfdrive/ui/qt/offroad/settings.cc +++ b/selfdrive/ui/qt/offroad/settings.cc @@ -53,6 +53,12 @@ TogglesPanel::TogglesPanel(SettingsWindow *parent) : ListWidget(parent) { tr("Upload data from the driver facing camera and help improve the driver monitoring algorithm."), "../assets/offroad/icon_monitoring.png", }, + { + "EndToEndLong", + tr("🌮 End-to-end longitudinal (extremely alpha) 🌮"), + tr("Let the driving model control the gas and brakes, openpilot will drive as it thinks a human would. Super experimental."), + "../assets/offroad/icon_road.png", + }, { "DisengageOnAccelerator", tr("Disengage On Accelerator Pedal"), diff --git a/selfdrive/ui/translations/main_ja.ts b/selfdrive/ui/translations/main_ja.ts index dd9f933dc..d56f4e846 100644 --- a/selfdrive/ui/translations/main_ja.ts +++ b/selfdrive/ui/translations/main_ja.ts @@ -108,152 +108,152 @@ DevicePanel - + Dongle ID ドングル番号 (Dongle ID) - + N/A N/A - + Serial シリアル番号 - + Driver Camera 車内カメラ - + PREVIEW 見る - + Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off) 車内カメラをプレビューして、ドライバー監視システムの視界を確認ができます。(車両の電源を切る必要があります) - + Reset Calibration キャリブレーションをリセット - + RESET リセット - + Are you sure you want to reset calibration? キャリブレーションをリセットしてもよろしいですか? - + Review Training Guide 入門書を見る - + REVIEW 見る - + Review the rules, features, and limitations of openpilot openpilot の特徴を見る - + Are you sure you want to review the training guide? 入門書を見てもよろしいですか? - + Regulatory 認証情報 - + VIEW 見る - + Change Language 言語を変更 - + CHANGE 変更 - + Select a language 言語を選択 - + Reboot 再起動 - + Power Off 電源を切る - + 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°以内にデバイスを取付ける必要があります。キャリブレーションを引き続きます、リセットはほとんど必要ありません。 - + Your device is pointed %1° %2 and %3° %4. このデバイスは%2の%1°、%4の%3°に向けます。 - + down - + up - + left - + right - + Are you sure you want to reboot? 再起動してもよろしいですか? - + Disengage to Reboot openpilot をキャンセルして再起動ができます - + Are you sure you want to power off? シャットダウンしてもよろしいですか? - + Disengage to Power Off openpilot をキャンセルしてシャットダウンができます @@ -718,33 +718,33 @@ location set SettingsWindow - + × × - + Device デバイス - - + + Network ネットワーク - + Toggles 切り替え - + Software ソフトウェア - + Navigation ナビゲーション @@ -983,89 +983,89 @@ location set SoftwarePanel - + Git Branch Git ブランチ - + Git Commit Git コミット - + OS Version OS バージョン - + 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 ブランチの切り替え - + ENTER 切替 - - + + The new branch will be pulled the next time the updater runs. updater を実行する時にブランチを切り替えます。 - + Enter branch name ブランチ名を入力 - + UNINSTALL アンインストール - + Uninstall %1 %1をアンインストール - + Are you sure you want to uninstall? アンインストールしてもよろしいですか? - + failed to fetch update 更新のダウンロードにエラーが発生しました - - + + CHECK 確認 @@ -1194,41 +1194,51 @@ location set + 🌮 End-to-end longitudinal (extremely alpha) 🌮 + + + + + Let the driving model control the gas and brakes, openpilot will drive as it thinks a human would. Super experimental. + + + + Disengage On Accelerator Pedal アクセル踏むと openpilot をキャンセル - + When enabled, pressing the accelerator pedal will disengage openpilot. 有効な場合は、アクセルを踏むと openpilot をキャンセルします。 - + Show ETA in 24h Format 24時間表示 - + Use 24h format instead of am/pm AM/PM の代わりに24時間形式を使用します - + Show Map on Left Side of UI ディスプレイの左側にマップを表示 - + 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 を無効化にします! diff --git a/selfdrive/ui/translations/main_ko.ts b/selfdrive/ui/translations/main_ko.ts index d4abe8619..bb4f884aa 100644 --- a/selfdrive/ui/translations/main_ko.ts +++ b/selfdrive/ui/translations/main_ko.ts @@ -108,152 +108,152 @@ DevicePanel - + Dongle ID Dongle ID - + N/A N/A - + Serial Serial - + Driver Camera 운전자 카메라 - + PREVIEW 미리보기 - + Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off) 운전자 모니터링이 좋은 가시성을 갖도록 운전자를 향한 카메라를 미리 봅니다. (차량연결은 해제되어있어야 합니다) - + Reset Calibration 캘리브레이션 재설정 - + RESET 재설정 - + Are you sure you want to reset calibration? 캘리브레이션을 재설정하시겠습니까? - + Review Training Guide 트레이닝 가이드 다시보기 - + REVIEW 다시보기 - + Review the rules, features, and limitations of openpilot openpilot의 규칙, 기능 및 제한 다시보기 - + Are you sure you want to review the training guide? 트레이닝 가이드를 다시보시겠습니까? - + Regulatory 규제 - + VIEW 보기 - + Change Language 언어 변경 - + CHANGE 변경 - + Select a language 언어를 선택하세요 - + Reboot 재부팅 - + Power Off 전원 종료 - + 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은 지속적으로 보정되므로 리셋이 거의 필요하지 않습니다. - + Your device is pointed %1° %2 and %3° %4. 사용자의 장치가 %1° %2 및 %3° %4를 가리키고 있습니다. - + down 아래로 - + up 위로 - + left 좌측으로 - + right 우측으로 - + Are you sure you want to reboot? 재부팅 하시겠습니까? - + Disengage to Reboot 재부팅 하려면 해제하세요 - + Are you sure you want to power off? 전원을 종료하시겠습니까? - + Disengage to Power Off 전원을 종료하려면 해제하세요 @@ -718,33 +718,33 @@ location set SettingsWindow - + × × - + Device 장치 - - + + Network 네트워크 - + Toggles 토글 - + Software 소프트웨어 - + Navigation 네비게이션 @@ -983,89 +983,89 @@ location set SoftwarePanel - + Git Branch Git 브렌치 - + Git Commit Git 커밋 - + OS Version OS 버전 - + 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 브랜치 변경 - + ENTER 입력하세요 - - + + The new branch will be pulled the next time the updater runs. 다음 업데이트 프로그램이 실행될 때 새 브랜치가 적용됩니다. - + Enter branch name 브랜치명 입력 - + UNINSTALL 제거 - + Uninstall %1 %1 제거 - + Are you sure you want to uninstall? 제거하시겠습니까? - + failed to fetch update 업데이트를 가져올수없습니다 - - + + CHECK 확인 @@ -1194,41 +1194,51 @@ location set + 🌮 End-to-end longitudinal (extremely alpha) 🌮 + + + + + Let the driving model control the gas and brakes, openpilot will drive as it thinks a human would. Super experimental. + + + + Disengage On Accelerator Pedal 가속페달 조작시 해제 - + When enabled, pressing the accelerator pedal will disengage openpilot. 활성화된 경우 가속 페달을 누르면 openpilot이 해제됩니다. - + Show ETA in 24h Format 24시간 형식으로 도착예정시간 표시 - + Use 24h format instead of am/pm 오전/오후 대신 24시간 형식 사용 - + Show Map on Left Side of UI UI 왼쪽에 지도 표시 - + Show map on left side when in split screen view. 분할 화면 보기에서 지도를 왼쪽에 표시합니다. - + openpilot Longitudinal Control openpilot Longitudinal Control - + openpilot will disable the car's radar and will take over control of gas and brakes. Warning: this disables AEB! openpilot은 차량'의 레이더를 무력화시키고 가속페달과 브레이크의 제어를 인계받을 것이다. 경고: AEB를 비활성화합니다! diff --git a/selfdrive/ui/translations/main_pt-BR.ts b/selfdrive/ui/translations/main_pt-BR.ts index e0d6a3c04..c0ef5c88f 100644 --- a/selfdrive/ui/translations/main_pt-BR.ts +++ b/selfdrive/ui/translations/main_pt-BR.ts @@ -108,152 +108,152 @@ DevicePanel - + Dongle ID Dongle ID - + N/A N/A - + Serial Serial - + Driver Camera Câmera voltada para o Motorista - + PREVIEW PREVISUAL - + Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off) Pré-visualizar a câmera voltada para o motorista para garantir que monitor tem uma boa visibilidade (veículo precisa estar desligado) - + Reset Calibration Resetar Calibragem - + RESET RESET - + Are you sure you want to reset calibration? Tem certeza que quer resetar a calibragem? - + Review Training Guide Revisar o Treinamento - + REVIEW REVISAR - + Review the rules, features, and limitations of openpilot Revisar regras, aprimoramentos e limitações do openpilot - + Are you sure you want to review the training guide? Tem certeza que quer rever o treinamento? - + Regulatory Regulatório - + VIEW VER - + Change Language Mudar Linguagem - + CHANGE MUDAR - + Select a language Selecione uma linguagem - + Reboot Reiniciar - + Power Off Desligar - + 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. o openpilot requer que o dispositivo seja montado dentro de 4° esquerda ou direita e dentro de 5° para cima ou 8° para baixo. o openpilot está continuamente calibrando, resetar raramente é necessário. - + Your device is pointed %1° %2 and %3° %4. Seu dispositivo está montado %1° %2 e %3° %4. - + down baixo - + up cima - + left esquerda - + right direita - + Are you sure you want to reboot? Tem certeza que quer reiniciar? - + Disengage to Reboot Desacione para Reiniciar - + Are you sure you want to power off? Tem certeza que quer desligar? - + Disengage to Power Off Desacione para Desligar @@ -722,33 +722,33 @@ trabalho definido SettingsWindow - + × × - + Device Dispositivo - - + + Network Rede - + Toggles Ajustes - + Software Software - + Navigation Navegação @@ -987,89 +987,89 @@ trabalho definido SoftwarePanel - + Git Branch Ramo Git - + Git Commit Commit Git - + OS Version Versão do Sistema - + Version Versão - + Last Update Check Verificação da última atualização - + The last time openpilot successfully checked for an update. The updater only runs while the car is off. A última vez que o openpilot verificou com sucesso uma atualização. O atualizador só funciona com o carro desligado. - + Check for Update Verifique atualizações - + CHECKING VERIFICANDO - + Switch Branch Trocar Branch - + ENTER INSERIR - - + + The new branch will be pulled the next time the updater runs. A nova branch será aplicada ao verificar atualizações. - + Enter branch name Inserir o nome da branch - + UNINSTALL DESINSTALAR - + Uninstall %1 Desintalar o %1 - + Are you sure you want to uninstall? Tem certeza que quer desinstalar? - + failed to fetch update falha ao buscar atualização - - + + CHECK VERIFICAR @@ -1198,41 +1198,51 @@ trabalho definido + 🌮 End-to-end longitudinal (extremely alpha) 🌮 + + + + + Let the driving model control the gas and brakes, openpilot will drive as it thinks a human would. Super experimental. + + + + Disengage On Accelerator Pedal Desacionar Com Pedal Do Acelerador - + When enabled, pressing the accelerator pedal will disengage openpilot. Quando ativado, pressionar o pedal do acelerador desacionará o openpilot. - + Show ETA in 24h Format Mostrar ETA em formato 24h - + Use 24h format instead of am/pm Use o formato 24h em vez de am/pm - + Show Map on Left Side of UI Exibir Mapa no Lado Esquerdo - + Show map on left side when in split screen view. Exibir mapa do lado esquerdo quando a tela for dividida. - + openpilot Longitudinal Control openpilot Controle Longitudinal - + openpilot will disable the car's radar and will take over control of gas and brakes. Warning: this disables AEB! openpilot desativará o radar do carro e assumirá o controle do acelerador e freios. Atenção: isso desativa AEB! diff --git a/selfdrive/ui/translations/main_zh-CHS.ts b/selfdrive/ui/translations/main_zh-CHS.ts index a26cddc0c..e8c9b8ec5 100644 --- a/selfdrive/ui/translations/main_zh-CHS.ts +++ b/selfdrive/ui/translations/main_zh-CHS.ts @@ -108,152 +108,152 @@ DevicePanel - + Dongle ID 设备ID(Dongle ID) - + N/A N/A - + Serial 序列号 - + Driver Camera 驾驶员摄像头 - + PREVIEW 预览 - + Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off) 打开并预览驾驶员摄像头,以确保驾驶员监控具有良好视野。仅熄火时可用。 - + Reset Calibration 重置设备校准 - + RESET 重置 - + Are you sure you want to reset calibration? 您确定要重置设备校准吗? - + Review Training Guide 新手指南 - + REVIEW 查看 - + Review the rules, features, and limitations of openpilot 查看openpilot的使用规则,以及其功能和限制。 - + Are you sure you want to review the training guide? 您确定要查看新手指南吗? - + Regulatory 监管信息 - + VIEW 查看 - + Change Language 切换语言 - + CHANGE 切换 - + Select a language 选择语言 - + Reboot 重启 - + Power Off 关机 - + 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°和右4°之间,俯仰角在上5°和下8°之间。一般来说,openpilot会持续更新校准,很少需要重置。 - + Your device is pointed %1° %2 and %3° %4. 您的设备校准为%1° %2、%3° %4。 - + down 朝下 - + up 朝上 - + left 朝左 - + right 朝右 - + Are you sure you want to reboot? 您确定要重新启动吗? - + Disengage to Reboot 取消openpilot以重新启动 - + Are you sure you want to power off? 您确定要关机吗? - + Disengage to Power Off 取消openpilot以关机 @@ -716,33 +716,33 @@ location set SettingsWindow - + × × - + Device 设备 - - + + Network 网络 - + Toggles 设定 - + Software 软件 - + Navigation 导航 @@ -981,89 +981,89 @@ 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. 上一次成功检查更新的时间。更新程序仅在汽车熄火时运行。 - + Check for Update 检查更新 - + CHECKING 正在检查更新 - + Switch Branch 切换分支 - + ENTER 输入 - - + + The new branch will be pulled the next time the updater runs. 分支将在更新服务下次启动时自动切换。 - + Enter branch name 输入分支名称 - + UNINSTALL 卸载 - + Uninstall %1 卸载 %1 - + Are you sure you want to uninstall? 您确定要卸载吗? - + failed to fetch update 获取更新失败 - - + + CHECK 查看 @@ -1192,41 +1192,51 @@ location set
+ 🌮 End-to-end longitudinal (extremely alpha) 🌮 + + + + + Let the driving model control the gas and brakes, openpilot will drive as it thinks a human would. Super experimental. + + + + Disengage On Accelerator Pedal 踩油门时取消控制 - + When enabled, pressing the accelerator pedal will disengage openpilot. 启用后,踩下油门踏板将取消openpilot。 - + Show ETA in 24h Format 以24小时格式显示预计到达时间 - + Use 24h format instead of am/pm 使用24小时制代替am/pm - + Show Map on Left Side of UI 在介面左侧显示地图 - + 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将被禁用! diff --git a/selfdrive/ui/translations/main_zh-CHT.ts b/selfdrive/ui/translations/main_zh-CHT.ts index f4681f85d..9b792e6df 100644 --- a/selfdrive/ui/translations/main_zh-CHT.ts +++ b/selfdrive/ui/translations/main_zh-CHT.ts @@ -108,152 +108,152 @@ DevicePanel - + Dongle ID Dongle ID - + N/A 無法使用 - + Serial 序號 - + Driver Camera 駕駛員攝像頭 - + PREVIEW 預覽 - + Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off) 預覽駕駛員監控鏡頭畫面,以確保其具有良好視野。(僅在熄火時可用) - + Reset Calibration 重置校準 - + RESET 重置 - + Are you sure you want to reset calibration? 您確定要重置校準嗎? - + Review Training Guide 觀看使用教學 - + REVIEW 觀看 - + Review the rules, features, and limitations of openpilot 觀看 openpilot 的使用規則、功能和限制 - + Are you sure you want to review the training guide? 您確定要觀看使用教學嗎? - + Regulatory 法規/監管 - + VIEW 觀看 - + Change Language 更改語言 - + CHANGE 更改 - + Select a language 選擇語言 - + Reboot 重新啟動 - + Power Off 關機 - + 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° 以内。鏡頭在後台會持續自動校準,很少有需要重置的情况。 - + Your device is pointed %1° %2 and %3° %4. 你的設備目前朝%2 %1° 以及朝%4 %3° 。 - + down - + up - + left - + right - + Are you sure you want to reboot? 您確定要重新啟動嗎? - + Disengage to Reboot 請先取消控車才能重新啟動 - + Are you sure you want to power off? 您確定您要關機嗎? - + Disengage to Power Off 請先取消控車才能關機 @@ -718,33 +718,33 @@ location set SettingsWindow - + × × - + Device 設備 - - + + Network 網路 - + Toggles 設定 - + Software 軟體 - + Navigation 導航 @@ -983,89 +983,89 @@ location set SoftwarePanel - + Git Branch Git 分支 - + Git Commit Git 提交 - + OS Version 系統版本 - + Version 版本 - + Last Update Check 上次檢查時間 - + The last time openpilot successfully checked for an update. The updater only runs while the car is off. 上次成功檢查更新的時間。更新系統只會在車子熄火時執行。 - + Check for Update 檢查更新 - + CHECKING 檢查中 - + Switch Branch 切換分支 - + ENTER 切換 - - + + The new branch will be pulled the next time the updater runs. 新的分支將會在下次檢查更新時切換過去。 - + Enter branch name 輸入分支名稱 - + UNINSTALL 卸載 - + Uninstall %1 卸載 %1 - + Are you sure you want to uninstall? 您確定您要卸載嗎? - + failed to fetch update 下載更新失敗 - - + + CHECK 檢查 @@ -1194,41 +1194,51 @@ location set
+ 🌮 End-to-end longitudinal (extremely alpha) 🌮 + + + + + Let the driving model control the gas and brakes, openpilot will drive as it thinks a human would. Super experimental. + + + + Disengage On Accelerator Pedal 油門取消控車 - + When enabled, pressing the accelerator pedal will disengage openpilot. 啟用後,踩踏油門將會取消 openpilot 控制。 - + Show ETA in 24h Format 預計到達時間單位改用 24 小時制 - + Use 24h format instead of am/pm 使用 24 小時制。(預設值為 12 小時制) - + Show Map on Left Side of UI 將地圖顯示在畫面的左側 - + 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) 系統! From b805b138453e175e560df60cba9d83e330f1db8d Mon Sep 17 00:00:00 2001 From: Jason Young <46612682+jyoung8607@users.noreply.github.com> Date: Fri, 2 Sep 2022 14:57:09 -0500 Subject: [PATCH 139/172] VW MQB: Add FW for 2023 Volkswagen Atlas (#25648) --- docs/CARS.md | 2 +- selfdrive/car/volkswagen/values.py | 6 +++++- 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/docs/CARS.md b/docs/CARS.md index aa7b5ecc5..1bea3f868 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -185,7 +185,7 @@ A supported vehicle is one that just works when you install a comma three. All s |Volkswagen|Arteon 2018-22[7,8](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| |Volkswagen|Arteon eHybrid 2020-22[7,8](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| |Volkswagen|Arteon R 2020-22[7,8](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| -|Volkswagen|Atlas 2018-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| +|Volkswagen|Atlas 2018-23[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| |Volkswagen|Atlas Cross Sport 2021-22[7](#footnotes)|Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| |Volkswagen|California 2021[7](#footnotes)|Driver Assistance|Stock|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| |Volkswagen|Caravelle 2020[7](#footnotes)|Driver Assistance|Stock|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533| diff --git a/selfdrive/car/volkswagen/values.py b/selfdrive/car/volkswagen/values.py index 7b1b0c876..278f4bc66 100755 --- a/selfdrive/car/volkswagen/values.py +++ b/selfdrive/car/volkswagen/values.py @@ -174,7 +174,7 @@ CAR_INFO: Dict[str, Union[VWCarInfo, List[VWCarInfo]]] = { VWCarInfo("Volkswagen CC 2018-22", footnotes=[Footnote.VW_HARNESS, Footnote.VW_VARIANT], harness=Harness.j533, video_link="https://youtu.be/FAomFKPFlDA"), ], CAR.ATLAS_MK1: [ - VWCarInfo("Volkswagen Atlas 2018-22", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533), + VWCarInfo("Volkswagen Atlas 2018-23", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533), VWCarInfo("Volkswagen Atlas Cross Sport 2021-22", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533), VWCarInfo("Volkswagen Teramont 2018-22", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533), VWCarInfo("Volkswagen Teramont Cross Sport 2021-22", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533), @@ -275,6 +275,7 @@ FW_VERSIONS = { b'\xf1\x8703H906026AA\xf1\x899970', b'\xf1\x8703H906026AJ\xf1\x890638', b'\xf1\x8703H906026AT\xf1\x891922', + b'\xf1\x8703H906026BC\xf1\x892664', b'\xf1\x8703H906026F \xf1\x896696', b'\xf1\x8703H906026F \xf1\x899970', b'\xf1\x8703H906026J \xf1\x896026', @@ -287,12 +288,14 @@ FW_VERSIONS = { b'\xf1\x8709G927158DR\xf1\x893536', b'\xf1\x8709G927158DR\xf1\x893742', b'\xf1\x8709G927158FT\xf1\x893835', + b'\xf1\x8709G927158GL\xf1\x893939', ], (Ecu.srs, 0x715, None): [ b'\xf1\x873Q0959655BC\xf1\x890503\xf1\x82\0161914151912001103111122031200', b'\xf1\x873Q0959655BN\xf1\x890713\xf1\x82\0162214152212001105141122052900', b'\xf1\x873Q0959655DB\xf1\x890720\xf1\x82\0162214152212001105141122052900', b'\xf1\x873Q0959655DM\xf1\x890732\xf1\x82\x0e1114151112001105161122052J00', + b'\xf1\x873Q0959655DM\xf1\x890732\xf1\x82\x0e1115151112001105171122052J00', ], (Ecu.eps, 0x712, None): [ b'\xf1\x873QF909144B \xf1\x891582\xf1\x82\00571B60924A1', @@ -300,6 +303,7 @@ FW_VERSIONS = { b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820528B6090105', ], (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', b'\xf1\x872Q0907572R \xf1\x890372', b'\xf1\x872Q0907572T \xf1\x890383', b'\xf1\x875Q0907572H \xf1\x890620', From 3b602e28443263c043daec4bfa2ca6bc7a13eb56 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Fri, 2 Sep 2022 13:41:58 -0700 Subject: [PATCH 140/172] GM: update minimum steer speed (#25618) * EUV is 10 kph * Update ref_commit * temp * Revert "temp" This reverts commit 90ce28b06ba623e7bd1252798af3c285b465e0ec. --- docs/CARS.md | 12 ++++++------ selfdrive/car/gm/interface.py | 2 +- selfdrive/test/process_replay/ref_commit | 2 +- 3 files changed, 8 insertions(+), 8 deletions(-) diff --git a/docs/CARS.md b/docs/CARS.md index 1bea3f868..097a5c577 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -17,10 +17,10 @@ A supported vehicle is one that just works when you install a comma three. All s |Audi|Q3 2020-21|ACC + Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| |Audi|RS3 2018|ACC + Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| |Audi|S3 2015-17|ACC + Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW| -|Cadillac|Escalade ESV 2016[1](#footnotes)|Adaptive Cruise Control (ACC) & LKAS|openpilot|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|OBD-II| -|Chevrolet|Bolt EUV 2022-23|Premier or Premier Redline Trim without Super Cruise Package|Stock|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|GM| -|Chevrolet|Silverado 1500 2020-21|Safety Package II|Stock|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|GM| -|Chevrolet|Volt 2017-18[1](#footnotes)|Adaptive Cruise Control|openpilot|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|OBD-II| +|Cadillac|Escalade ESV 2016[1](#footnotes)|Adaptive Cruise Control (ACC) & LKAS|openpilot|0 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|OBD-II| +|Chevrolet|Bolt EUV 2022-23|Premier or Premier Redline Trim without Super Cruise Package|Stock|0 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|GM| +|Chevrolet|Silverado 1500 2020-21|Safety Package II|Stock|0 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|GM| +|Chevrolet|Volt 2017-18[1](#footnotes)|Adaptive Cruise Control|openpilot|0 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|OBD-II| |Chrysler|Pacifica 2017-18|Adaptive Cruise Control|Stock|0 mph|9 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|FCA| |Chrysler|Pacifica 2019-20|Adaptive Cruise Control|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|FCA| |Chrysler|Pacifica 2021|All|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|FCA| @@ -31,8 +31,8 @@ A supported vehicle is one that just works when you install a comma three. All s |Genesis|G70 2020|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai F| |Genesis|G80 2017-19|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai H| |Genesis|G90 2017-18|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C| -|GMC|Acadia 2018[1](#footnotes)|Adaptive Cruise Control|openpilot|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|OBD-II| -|GMC|Sierra 1500 2020-21|Driver Alert Package II|Stock|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|GM| +|GMC|Acadia 2018[1](#footnotes)|Adaptive Cruise Control|openpilot|0 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|OBD-II| +|GMC|Sierra 1500 2020-21|Driver Alert Package II|Stock|0 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|GM| |Honda|Accord 2018-22|All|Stock|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch A| |Honda|Accord Hybrid 2018-22|All|Stock|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch A| |Honda|Civic 2016-18|Honda Sensing|openpilot|0 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Nidec| diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py index 118e54aa0..ac8bc4580 100755 --- a/selfdrive/car/gm/interface.py +++ b/selfdrive/car/gm/interface.py @@ -74,7 +74,7 @@ class CarInterface(CarInterfaceBase): ret.dashcamOnly = candidate in {CAR.CADILLAC_ATS, CAR.HOLDEN_ASTRA, CAR.MALIBU, CAR.BUICK_REGAL} # Start with a baseline tuning for all GM vehicles. Override tuning as needed in each model section below. - ret.minSteerSpeed = 7 * CV.MPH_TO_MS + ret.minSteerSpeed = 10 * CV.KPH_TO_MS ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2], [0.00]] ret.lateralTuning.pid.kf = 0.00004 # full torque for 20 deg at 80mph means 0.00007818594 diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 591acc2f1..2f93b7587 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -af74c25e869d1128c0277f789e8f88bb95c5be1b +cad0c6a23a9baea9853fe2117ff9127a83f9e884 From 593dfd0aed6f3bbb37b05ef7c331df08781327d9 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Fri, 2 Sep 2022 16:19:06 -0700 Subject: [PATCH 141/172] Faster a_ego filter (#25646) * Faster a_ego filter * :x Update ref * typo * update ref --- selfdrive/car/interfaces.py | 6 +++--- selfdrive/test/process_replay/ref_commit | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/selfdrive/car/interfaces.py b/selfdrive/car/interfaces.py index 401b243ba..1e14aca8c 100644 --- a/selfdrive/car/interfaces.py +++ b/selfdrive/car/interfaces.py @@ -271,12 +271,12 @@ class CarStateBase(ABC): self.left_blinker_prev = False self.right_blinker_prev = False - # Q = np.matrix([[10.0, 0.0], [0.0, 100.0]]) - # R = 1e3 + # Q = np.matrix([[0.0, 0.0], [0.0, 100.0]]) + # R = 0.3 self.v_ego_kf = KF1D(x0=[[0.0], [0.0]], A=[[1.0, DT_CTRL], [0.0, 1.0]], C=[1.0, 0.0], - K=[[0.12287673], [0.29666309]]) + K=[[0.17406039], [1.65925647]]) def update_speed_kf(self, v_ego_raw): if abs(v_ego_raw - self.v_ego_kf.x[0][0]) > 2.0: # Prevent large accelerations when car starts at non zero speed diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 2f93b7587..672763461 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -cad0c6a23a9baea9853fe2117ff9127a83f9e884 +5cb8e7ea92f333bdb49682b0593ab2ae5a5f3824 From 3183b00ff265602da9f852e23a4230c7e12a475b Mon Sep 17 00:00:00 2001 From: AlexandreSato <66435071+AlexandreSato@users.noreply.github.com> Date: Fri, 2 Sep 2022 20:34:28 -0300 Subject: [PATCH 142/172] Portuguese: add e2e long translations (#25650) * fix and improve pt-BR translation * Shorter phrase for Finish Setup * Concluir are better than Encerrar bacause means sucessfuly * improve pt-BR, DEVbrazilians use english as default * fix "atualizador" text cutoff * miss mark as finish on qt linguist * translate to pt-BR the e2e_long toggle --- selfdrive/ui/translations/main_pt-BR.ts | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/ui/translations/main_pt-BR.ts b/selfdrive/ui/translations/main_pt-BR.ts index c0ef5c88f..e4df8f36b 100644 --- a/selfdrive/ui/translations/main_pt-BR.ts +++ b/selfdrive/ui/translations/main_pt-BR.ts @@ -1199,12 +1199,12 @@ trabalho definido 🌮 End-to-end longitudinal (extremely alpha) 🌮 - + 🌮 End-to-end longitudinal (experimental) 🌮 Let the driving model control the gas and brakes, openpilot will drive as it thinks a human would. Super experimental. - + Deixe o modelo de direção controlar o acelerador e o freio, o openpilot dirigirá da maneira como ele entende que um humano o faria. Super experimental. From 1d86c431ee7a63616e5f0b927280bf82f34c7969 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Fri, 2 Sep 2022 17:02:54 -0700 Subject: [PATCH 143/172] Kia: update Forte supported package (#25652) * Not standard * https://cdn.dealereprocess.org/cdn/brochures/hyundai/2020-ioniqhybrid.pdf * revert --- docs/CARS.md | 2 +- selfdrive/car/hyundai/values.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/CARS.md b/docs/CARS.md index 097a5c577..1f0e24865 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -85,7 +85,7 @@ A supported vehicle is one that just works when you install a comma three. All s |Kia|Ceed 2019|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai E| |Kia|EV6 2022|Highway Driving Assist II|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai P| |Kia|Forte 2018|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai B| -|Kia|Forte 2019-21|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai G| +|Kia|Forte 2019-21|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai G| |Kia|K5 2021-22|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai A| |Kia|Niro Electric 2019|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai H| |Kia|Niro Electric 2020|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai F| diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index aa1823522..79e3ea419 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -140,7 +140,7 @@ CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = { # Kia CAR.KIA_FORTE: [ HyundaiCarInfo("Kia Forte 2018", harness=Harness.hyundai_b), - HyundaiCarInfo("Kia Forte 2019-21", "All", harness=Harness.hyundai_g), + HyundaiCarInfo("Kia Forte 2019-21", harness=Harness.hyundai_g), ], CAR.KIA_K5_2021: HyundaiCarInfo("Kia K5 2021-22", "Smart Cruise Control (SCC)", harness=Harness.hyundai_a), CAR.KIA_NIRO_EV: [ From 01a73b14d8b23c17bc6c7b314a266d594e88eb55 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Sun, 4 Sep 2022 12:04:28 -0700 Subject: [PATCH 144/172] Toggles must be alphabetical (#25654) toggles must be alphabetical --- selfdrive/ui/qt/offroad/settings.cc | 12 ++++++------ selfdrive/ui/translations/main_ja.ts | 8 ++++---- selfdrive/ui/translations/main_ko.ts | 8 ++++---- selfdrive/ui/translations/main_pt-BR.ts | 8 ++++---- selfdrive/ui/translations/main_zh-CHS.ts | 8 ++++---- selfdrive/ui/translations/main_zh-CHT.ts | 8 ++++---- 6 files changed, 26 insertions(+), 26 deletions(-) diff --git a/selfdrive/ui/qt/offroad/settings.cc b/selfdrive/ui/qt/offroad/settings.cc index 09ff0eed9..d44f4c75f 100644 --- a/selfdrive/ui/qt/offroad/settings.cc +++ b/selfdrive/ui/qt/offroad/settings.cc @@ -53,18 +53,18 @@ TogglesPanel::TogglesPanel(SettingsWindow *parent) : ListWidget(parent) { tr("Upload data from the driver facing camera and help improve the driver monitoring algorithm."), "../assets/offroad/icon_monitoring.png", }, - { - "EndToEndLong", - tr("🌮 End-to-end longitudinal (extremely alpha) 🌮"), - tr("Let the driving model control the gas and brakes, openpilot will drive as it thinks a human would. Super experimental."), - "../assets/offroad/icon_road.png", - }, { "DisengageOnAccelerator", tr("Disengage On Accelerator Pedal"), tr("When enabled, pressing the accelerator pedal will disengage openpilot."), "../assets/offroad/icon_disengage_on_accelerator.svg", }, + { + "EndToEndLong", + tr("🌮 End-to-end longitudinal (extremely alpha) 🌮"), + tr("Let the driving model control the gas and brakes, openpilot will drive as it thinks a human would. Super experimental."), + "../assets/offroad/icon_road.png", + }, #ifdef ENABLE_MAPS { "NavSettingTime24h", diff --git a/selfdrive/ui/translations/main_ja.ts b/selfdrive/ui/translations/main_ja.ts index d56f4e846..13697ce52 100644 --- a/selfdrive/ui/translations/main_ja.ts +++ b/selfdrive/ui/translations/main_ja.ts @@ -1193,22 +1193,22 @@ location set 車内カメラの映像をアップロードし、ドライバー監視システムのアルゴリズムの向上に役立てます。 - + 🌮 End-to-end longitudinal (extremely alpha) 🌮 - + Let the driving model control the gas and brakes, openpilot will drive as it thinks a human would. Super experimental. - + Disengage On Accelerator Pedal アクセル踏むと openpilot をキャンセル - + When enabled, pressing the accelerator pedal will disengage openpilot. 有効な場合は、アクセルを踏むと openpilot をキャンセルします。 diff --git a/selfdrive/ui/translations/main_ko.ts b/selfdrive/ui/translations/main_ko.ts index bb4f884aa..918cd29e2 100644 --- a/selfdrive/ui/translations/main_ko.ts +++ b/selfdrive/ui/translations/main_ko.ts @@ -1193,22 +1193,22 @@ location set 운전자 카메라에서 데이터를 업로드하고 운전자 모니터링 알고리즘을 개선합니다.
- + 🌮 End-to-end longitudinal (extremely alpha) 🌮 - + Let the driving model control the gas and brakes, openpilot will drive as it thinks a human would. Super experimental. - + Disengage On Accelerator Pedal 가속페달 조작시 해제 - + When enabled, pressing the accelerator pedal will disengage openpilot. 활성화된 경우 가속 페달을 누르면 openpilot이 해제됩니다. diff --git a/selfdrive/ui/translations/main_pt-BR.ts b/selfdrive/ui/translations/main_pt-BR.ts index e4df8f36b..f5aa386e5 100644 --- a/selfdrive/ui/translations/main_pt-BR.ts +++ b/selfdrive/ui/translations/main_pt-BR.ts @@ -1197,22 +1197,22 @@ trabalho definido Upload dados da câmera voltada para o motorista e ajude a melhorar o algoritmo de monitoramentor. - + 🌮 End-to-end longitudinal (extremely alpha) 🌮 🌮 End-to-end longitudinal (experimental) 🌮 - + Let the driving model control the gas and brakes, openpilot will drive as it thinks a human would. Super experimental. Deixe o modelo de direção controlar o acelerador e o freio, o openpilot dirigirá da maneira como ele entende que um humano o faria. Super experimental. - + Disengage On Accelerator Pedal Desacionar Com Pedal Do Acelerador - + When enabled, pressing the accelerator pedal will disengage openpilot. Quando ativado, pressionar o pedal do acelerador desacionará o openpilot. diff --git a/selfdrive/ui/translations/main_zh-CHS.ts b/selfdrive/ui/translations/main_zh-CHS.ts index e8c9b8ec5..e405dc902 100644 --- a/selfdrive/ui/translations/main_zh-CHS.ts +++ b/selfdrive/ui/translations/main_zh-CHS.ts @@ -1191,22 +1191,22 @@ location set 上传驾驶员摄像头的数据,帮助改进驾驶员监控算法。 - + 🌮 End-to-end longitudinal (extremely alpha) 🌮 - + Let the driving model control the gas and brakes, openpilot will drive as it thinks a human would. Super experimental. - + Disengage On Accelerator Pedal 踩油门时取消控制 - + When enabled, pressing the accelerator pedal will disengage openpilot. 启用后,踩下油门踏板将取消openpilot。 diff --git a/selfdrive/ui/translations/main_zh-CHT.ts b/selfdrive/ui/translations/main_zh-CHT.ts index 9b792e6df..71893218f 100644 --- a/selfdrive/ui/translations/main_zh-CHT.ts +++ b/selfdrive/ui/translations/main_zh-CHT.ts @@ -1193,22 +1193,22 @@ location set 上傳駕駛監控的錄像來協助我們提升駕駛監控的準確率。 - + 🌮 End-to-end longitudinal (extremely alpha) 🌮 - + Let the driving model control the gas and brakes, openpilot will drive as it thinks a human would. Super experimental. - + Disengage On Accelerator Pedal 油門取消控車 - + When enabled, pressing the accelerator pedal will disengage openpilot. 啟用後,踩踏油門將會取消 openpilot 控制。 From 2eff6d0ebd20b95b10726f979b04df028f50d303 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Sun, 4 Sep 2022 13:07:51 -0700 Subject: [PATCH 145/172] Remove lane planning code (#25651) * Remove all lane planning logic * Revert "Update ref" This reverts commit 8dcb08ebccbb5641443459ac40601a95cf605682. * bump cereal * Update ref --- cereal | 2 +- release/files_common | 1 - selfdrive/controls/controlsd.py | 2 +- selfdrive/controls/lib/lane_planner.py | 97 ----------------------- selfdrive/controls/lib/lateral_planner.py | 38 +++------ selfdrive/controls/plannerd.py | 7 +- selfdrive/test/process_replay/ref_commit | 2 +- 7 files changed, 17 insertions(+), 132 deletions(-) delete mode 100644 selfdrive/controls/lib/lane_planner.py diff --git a/cereal b/cereal index d3a943ef6..632395010 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit d3a943ef660dd29f73700806ee0baf1d5aff6834 +Subproject commit 632395010102aabdd0ed87aba50d25042cdcb70e diff --git a/release/files_common b/release/files_common index 10c66a896..ad99af752 100644 --- a/release/files_common +++ b/release/files_common @@ -173,7 +173,6 @@ selfdrive/controls/lib/alerts_offroad.json selfdrive/controls/lib/desire_helper.py selfdrive/controls/lib/drive_helpers.py selfdrive/controls/lib/events.py -selfdrive/controls/lib/lane_planner.py selfdrive/controls/lib/latcontrol_angle.py selfdrive/controls/lib/latcontrol_indi.py selfdrive/controls/lib/latcontrol_torque.py diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index b8b66a567..f2b2ddc98 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -15,7 +15,7 @@ from system.swaglog import cloudlog from system.version import get_short_branch from selfdrive.boardd.boardd import can_list_to_can_capnp from selfdrive.car.car_helpers import get_car, get_startup_event, get_one_can -from selfdrive.controls.lib.lane_planner import CAMERA_OFFSET +from selfdrive.controls.lib.lateral_planner import CAMERA_OFFSET from selfdrive.controls.lib.drive_helpers import V_CRUISE_INITIAL, update_v_cruise, initialize_v_cruise from selfdrive.controls.lib.drive_helpers import get_lag_adjusted_curvature from selfdrive.controls.lib.latcontrol import LatControl diff --git a/selfdrive/controls/lib/lane_planner.py b/selfdrive/controls/lib/lane_planner.py deleted file mode 100644 index 1facb66d6..000000000 --- a/selfdrive/controls/lib/lane_planner.py +++ /dev/null @@ -1,97 +0,0 @@ -import numpy as np -from cereal import log -from common.filter_simple import FirstOrderFilter -from common.numpy_fast import interp -from common.realtime import DT_MDL -from system.swaglog import cloudlog - - -TRAJECTORY_SIZE = 33 -# camera offset is meters from center car to camera -# model path is in the frame of the camera -PATH_OFFSET = 0.00 -CAMERA_OFFSET = 0.04 - - -class LanePlanner: - def __init__(self, wide_camera=False): - self.ll_t = np.zeros((TRAJECTORY_SIZE,)) - self.ll_x = np.zeros((TRAJECTORY_SIZE,)) - self.lll_y = np.zeros((TRAJECTORY_SIZE,)) - self.rll_y = np.zeros((TRAJECTORY_SIZE,)) - self.lane_width_estimate = FirstOrderFilter(3.7, 9.95, DT_MDL) - self.lane_width_certainty = FirstOrderFilter(1.0, 0.95, DT_MDL) - self.lane_width = 3.7 - - self.lll_prob = 0. - self.rll_prob = 0. - self.d_prob = 0. - - self.lll_std = 0. - self.rll_std = 0. - - self.l_lane_change_prob = 0. - self.r_lane_change_prob = 0. - - self.camera_offset = -CAMERA_OFFSET if wide_camera else CAMERA_OFFSET - self.path_offset = -PATH_OFFSET if wide_camera else PATH_OFFSET - - def parse_model(self, md): - lane_lines = md.laneLines - if len(lane_lines) == 4 and len(lane_lines[0].t) == TRAJECTORY_SIZE: - self.ll_t = (np.array(lane_lines[1].t) + np.array(lane_lines[2].t))/2 - # left and right ll x is the same - self.ll_x = lane_lines[1].x - self.lll_y = np.array(lane_lines[1].y) + self.camera_offset - self.rll_y = np.array(lane_lines[2].y) + self.camera_offset - self.lll_prob = md.laneLineProbs[1] - self.rll_prob = md.laneLineProbs[2] - self.lll_std = md.laneLineStds[1] - self.rll_std = md.laneLineStds[2] - - desire_state = md.meta.desireState - if len(desire_state): - self.l_lane_change_prob = desire_state[log.LateralPlan.Desire.laneChangeLeft] - self.r_lane_change_prob = desire_state[log.LateralPlan.Desire.laneChangeRight] - - def get_d_path(self, v_ego, path_t, path_xyz): - # Reduce reliance on lanelines that are too far apart or - # will be in a few seconds - path_xyz[:, 1] += self.path_offset - l_prob, r_prob = self.lll_prob, self.rll_prob - width_pts = self.rll_y - self.lll_y - prob_mods = [] - for t_check in (0.0, 1.5, 3.0): - width_at_t = interp(t_check * (v_ego + 7), self.ll_x, width_pts) - prob_mods.append(interp(width_at_t, [4.0, 5.0], [1.0, 0.0])) - mod = min(prob_mods) - l_prob *= mod - r_prob *= mod - - # Reduce reliance on uncertain lanelines - l_std_mod = interp(self.lll_std, [.15, .3], [1.0, 0.0]) - r_std_mod = interp(self.rll_std, [.15, .3], [1.0, 0.0]) - l_prob *= l_std_mod - r_prob *= r_std_mod - - # Find current lanewidth - self.lane_width_certainty.update(l_prob * r_prob) - current_lane_width = abs(self.rll_y[0] - self.lll_y[0]) - self.lane_width_estimate.update(current_lane_width) - speed_lane_width = interp(v_ego, [0., 31.], [2.8, 3.5]) - self.lane_width = self.lane_width_certainty.x * self.lane_width_estimate.x + \ - (1 - self.lane_width_certainty.x) * speed_lane_width - - clipped_lane_width = min(4.0, self.lane_width) - path_from_left_lane = self.lll_y + clipped_lane_width / 2.0 - path_from_right_lane = self.rll_y - clipped_lane_width / 2.0 - - self.d_prob = l_prob + r_prob - l_prob * r_prob - lane_path_y = (l_prob * path_from_left_lane + r_prob * path_from_right_lane) / (l_prob + r_prob + 0.0001) - safe_idxs = np.isfinite(self.ll_t) - if safe_idxs[0]: - lane_path_y_interp = np.interp(path_t, self.ll_t[safe_idxs], lane_path_y[safe_idxs]) - path_xyz[:,1] = self.d_prob * lane_path_y_interp + (1.0 - self.d_prob) * path_xyz[:,1] - else: - cloudlog.warning("Lateral mpc - NaNs in laneline times, ignoring") - return path_xyz diff --git a/selfdrive/controls/lib/lateral_planner.py b/selfdrive/controls/lib/lateral_planner.py index 29dfc7711..3470754bc 100644 --- a/selfdrive/controls/lib/lateral_planner.py +++ b/selfdrive/controls/lib/lateral_planner.py @@ -4,16 +4,15 @@ from common.numpy_fast import interp from system.swaglog import cloudlog from selfdrive.controls.lib.lateral_mpc_lib.lat_mpc import LateralMpc from selfdrive.controls.lib.drive_helpers import CONTROL_N, MPC_COST_LAT, LAT_MPC_N -from selfdrive.controls.lib.lane_planner import LanePlanner, TRAJECTORY_SIZE from selfdrive.controls.lib.desire_helper import DesireHelper import cereal.messaging as messaging from cereal import log +TRAJECTORY_SIZE = 33 +CAMERA_OFFSET = 0.04 class LateralPlanner: - def __init__(self, CP, use_lanelines=True, wide_camera=False): - self.use_lanelines = use_lanelines - self.LP = LanePlanner(wide_camera) + def __init__(self, CP): self.DH = DesireHelper() # Vehicle model parameters used to calculate lateral movement of car @@ -42,7 +41,6 @@ class LateralPlanner: # Parse model predictions md = sm['modelV2'] - self.LP.parse_model(md) if len(md.position.x) == TRAJECTORY_SIZE and len(md.orientation.x) == TRAJECTORY_SIZE: self.path_xyz = np.column_stack([md.position.x, md.position.y, md.position.z]) self.t_idxs = np.array(md.position.t) @@ -51,23 +49,17 @@ class LateralPlanner: self.path_xyz_stds = np.column_stack([md.position.xStd, md.position.yStd, md.position.zStd]) # Lane change logic - lane_change_prob = self.LP.l_lane_change_prob + self.LP.r_lane_change_prob + desire_state = md.meta.desireState + if len(desire_state): + self.l_lane_change_prob = desire_state[log.LateralPlan.Desire.laneChangeLeft] + self.r_lane_change_prob = desire_state[log.LateralPlan.Desire.laneChangeRight] + lane_change_prob = self.l_lane_change_prob + self.r_lane_change_prob self.DH.update(sm['carState'], sm['carControl'].latActive, lane_change_prob) - # Turn off lanes during lane change - if self.DH.desire == log.LateralPlan.Desire.laneChangeRight or self.DH.desire == log.LateralPlan.Desire.laneChangeLeft: - self.LP.lll_prob *= self.DH.lane_change_ll_prob - self.LP.rll_prob *= self.DH.lane_change_ll_prob - - # Calculate final driving path and set MPC costs - if self.use_lanelines: - d_path_xyz = self.LP.get_d_path(v_ego, self.t_idxs, self.path_xyz) - self.lat_mpc.set_weights(MPC_COST_LAT.PATH, MPC_COST_LAT.HEADING, MPC_COST_LAT.STEER_RATE) - else: - d_path_xyz = self.path_xyz - # Heading cost is useful at low speed, otherwise end of plan can be off-heading - heading_cost = interp(v_ego, [5.0, 10.0], [MPC_COST_LAT.HEADING, 0.15]) - self.lat_mpc.set_weights(MPC_COST_LAT.PATH, heading_cost, MPC_COST_LAT.STEER_RATE) + d_path_xyz = self.path_xyz + # Heading cost is useful at low speed, otherwise end of plan can be off-heading + heading_cost = interp(v_ego, [5.0, 10.0], [MPC_COST_LAT.HEADING, 0.15]) + self.lat_mpc.set_weights(MPC_COST_LAT.PATH, heading_cost, MPC_COST_LAT.STEER_RATE) y_pts = np.interp(v_ego * self.t_idxs[:LAT_MPC_N + 1], np.linalg.norm(d_path_xyz, axis=1), d_path_xyz[:, 1]) heading_pts = np.interp(v_ego * self.t_idxs[:LAT_MPC_N + 1], np.linalg.norm(self.path_xyz, axis=1), self.plan_yaw) @@ -112,20 +104,16 @@ class LateralPlanner: lateralPlan = plan_send.lateralPlan lateralPlan.modelMonoTime = sm.logMonoTime['modelV2'] - lateralPlan.laneWidth = float(self.LP.lane_width) lateralPlan.dPathPoints = self.y_pts.tolist() lateralPlan.psis = self.lat_mpc.x_sol[0:CONTROL_N, 2].tolist() lateralPlan.curvatures = self.lat_mpc.x_sol[0:CONTROL_N, 3].tolist() lateralPlan.curvatureRates = [float(x) for x in self.lat_mpc.u_sol[0:CONTROL_N - 1]] + [0.0] - lateralPlan.lProb = float(self.LP.lll_prob) - lateralPlan.rProb = float(self.LP.rll_prob) - lateralPlan.dProb = float(self.LP.d_prob) lateralPlan.mpcSolutionValid = bool(plan_solution_valid) lateralPlan.solverExecutionTime = self.lat_mpc.solve_time lateralPlan.desire = self.DH.desire - lateralPlan.useLaneLines = self.use_lanelines + lateralPlan.useLaneLines = False lateralPlan.laneChangeState = self.DH.lane_change_state lateralPlan.laneChangeDirection = self.DH.lane_change_direction diff --git a/selfdrive/controls/plannerd.py b/selfdrive/controls/plannerd.py index ca7523f2e..513131a33 100755 --- a/selfdrive/controls/plannerd.py +++ b/selfdrive/controls/plannerd.py @@ -16,13 +16,8 @@ def plannerd_thread(sm=None, pm=None): CP = car.CarParams.from_bytes(params.get("CarParams", block=True)) cloudlog.info("plannerd got CarParams: %s", CP.carName) - use_lanelines = False - wide_camera = params.get_bool('WideCameraOnly') - - cloudlog.event("e2e mode", on=use_lanelines) - longitudinal_planner = Planner(CP) - lateral_planner = LateralPlanner(CP, use_lanelines=use_lanelines, wide_camera=wide_camera) + lateral_planner = LateralPlanner(CP) if sm is None: sm = messaging.SubMaster(['carControl', 'carState', 'controlsState', 'radarState', 'modelV2'], diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 672763461..cf3eb89f9 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -5cb8e7ea92f333bdb49682b0593ab2ae5a5f3824 +e1c189b002a179763fa34f24e5d96f2b2d0c4c49 From 4c05c88c10f24d771c76bd8b078426a06a82b4f8 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Sun, 4 Sep 2022 13:29:13 -0700 Subject: [PATCH 146/172] Radard: ignore leads without model confirmation wider than 1.0m (#25664) Dont stop for cars next to you without model confirmation --- selfdrive/controls/lib/radar_helpers.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/controls/lib/radar_helpers.py b/selfdrive/controls/lib/radar_helpers.py index 85699866b..0e2b96668 100644 --- a/selfdrive/controls/lib/radar_helpers.py +++ b/selfdrive/controls/lib/radar_helpers.py @@ -152,7 +152,7 @@ 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.5 and (v_ego < v_ego_stationary) and self.dRel < 25 + return abs(self.yRel) < 1.0 and (v_ego < v_ego_stationary) and self.dRel < 25 def is_potential_fcw(self, model_prob): return model_prob > .9 From f44ebb9f1ed37b2c3add981bf493e4d7cc7d0ee0 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Tue, 6 Sep 2022 04:20:05 +0800 Subject: [PATCH 147/172] ui/sidebar: remove unused variable params (#25667) * remove params * update translations Co-authored-by: Adeeb Shihadeh --- selfdrive/ui/qt/sidebar.h | 2 -- selfdrive/ui/translations/main_ja.ts | 14 +++++++------- selfdrive/ui/translations/main_ko.ts | 14 +++++++------- selfdrive/ui/translations/main_pt-BR.ts | 14 +++++++------- selfdrive/ui/translations/main_zh-CHS.ts | 14 +++++++------- selfdrive/ui/translations/main_zh-CHT.ts | 14 +++++++------- 6 files changed, 35 insertions(+), 37 deletions(-) diff --git a/selfdrive/ui/qt/sidebar.h b/selfdrive/ui/qt/sidebar.h index 0140673aa..621a21444 100644 --- a/selfdrive/ui/qt/sidebar.h +++ b/selfdrive/ui/qt/sidebar.h @@ -3,7 +3,6 @@ #include #include -#include "common/params.h" #include "selfdrive/ui/ui.h" typedef QPair, QColor> ItemStatus; @@ -49,7 +48,6 @@ protected: const QColor warning_color = QColor(218, 202, 37); const QColor danger_color = QColor(201, 34, 49); - Params params; ItemStatus connect_status, panda_status, temp_status; QString net_type; int net_strength = 0; diff --git a/selfdrive/ui/translations/main_ja.ts b/selfdrive/ui/translations/main_ja.ts index 13697ce52..43327f8ef 100644 --- a/selfdrive/ui/translations/main_ja.ts +++ b/selfdrive/ui/translations/main_ja.ts @@ -945,37 +945,37 @@ location set 検索 - + -- -- - + Wi-Fi Wi-Fi - + ETH ETH - + 2G 2G - + 3G 3G - + LTE LTE - + 5G 5G diff --git a/selfdrive/ui/translations/main_ko.ts b/selfdrive/ui/translations/main_ko.ts index 918cd29e2..1d7ddbe6e 100644 --- a/selfdrive/ui/translations/main_ko.ts +++ b/selfdrive/ui/translations/main_ko.ts @@ -945,37 +945,37 @@ location set 검색중 - + -- -- - + Wi-Fi Wi-Fi - + ETH 이더넷 - + 2G 2G - + 3G 3G - + LTE LTE - + 5G 5G diff --git a/selfdrive/ui/translations/main_pt-BR.ts b/selfdrive/ui/translations/main_pt-BR.ts index f5aa386e5..f50cf65e1 100644 --- a/selfdrive/ui/translations/main_pt-BR.ts +++ b/selfdrive/ui/translations/main_pt-BR.ts @@ -949,37 +949,37 @@ trabalho definido PROCURA - + -- -- - + Wi-Fi Wi-Fi - + ETH ETH - + 2G 2G - + 3G 3G - + LTE LTE - + 5G 5G diff --git a/selfdrive/ui/translations/main_zh-CHS.ts b/selfdrive/ui/translations/main_zh-CHS.ts index e405dc902..1a384482d 100644 --- a/selfdrive/ui/translations/main_zh-CHS.ts +++ b/selfdrive/ui/translations/main_zh-CHS.ts @@ -943,37 +943,37 @@ location set 搜索中 - + -- -- - + Wi-Fi Wi-Fi - + ETH 以太网 - + 2G 2G - + 3G 3G - + LTE LTE - + 5G 5G diff --git a/selfdrive/ui/translations/main_zh-CHT.ts b/selfdrive/ui/translations/main_zh-CHT.ts index 71893218f..d7dd5cb56 100644 --- a/selfdrive/ui/translations/main_zh-CHT.ts +++ b/selfdrive/ui/translations/main_zh-CHT.ts @@ -945,37 +945,37 @@ location set 車輛通訊 - + -- -- - + Wi-Fi - + ETH - + 2G - + 3G - + LTE - + 5G From 23254b454e927a5813f8beb00a4579150a5a7fab Mon Sep 17 00:00:00 2001 From: Erich Moraga <33645296+ErichMoraga@users.noreply.github.com> Date: Mon, 5 Sep 2022 15:20:56 -0500 Subject: [PATCH 148/172] Add missing HIGHLANDER_TSS2 engine f/w (#25657) --- 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 42a67ec96..9635fe2e7 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -948,6 +948,7 @@ FW_VERSIONS = { b'\x01896630EC4000\x00\x00\x00\x00', b'\x01896630ED9000\x00\x00\x00\x00', b'\x01896630EE1000\x00\x00\x00\x00', + b'\x01896630EE1100\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 0xf): [ b'\x018821F3301400\x00\x00\x00\x00', From 98484697cb66aa7863f509ef36bef0e51dd96b32 Mon Sep 17 00:00:00 2001 From: Justin Newberry Date: Mon, 5 Sep 2022 16:24:17 -0400 Subject: [PATCH 149/172] Subaru Legacy 22 fingerprint (#25665) --- selfdrive/car/subaru/values.py | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/selfdrive/car/subaru/values.py b/selfdrive/car/subaru/values.py index 7d8365a11..d04e5f2cc 100644 --- a/selfdrive/car/subaru/values.py +++ b/selfdrive/car/subaru/values.py @@ -106,18 +106,23 @@ FW_VERSIONS = { CAR.LEGACY: { (Ecu.esp, 0x7b0, None): [ b'\xa1\\ x04\x01', + b'\xa1 \x03\x03' ], (Ecu.eps, 0x746, None): [ b'\x9b\xc0\x11\x00', + b'\x9b\xc0\x11\x02' ], (Ecu.fwdCamera, 0x787, None): [ b'\x00\x00e\x80\x00\x1f@ \x19\x00', + b'\x00\x00e\x9a\x00\x00\x00\x00\x00\x00' ], (Ecu.engine, 0x7e0, None): [ b'\xde\"a0\x07', + b'\xe2"aq\x07' ], (Ecu.transmission, 0x7e1, None): [ b'\xa5\xf6\x05@\x00', + b'\xa7\xf6\x04@\x00' ], }, CAR.IMPREZA: { From d804b945e2a161a2a53923d70c2ee45c0a3493ce Mon Sep 17 00:00:00 2001 From: vanillagorillaa <31773928+vanillagorillaa@users.noreply.github.com> Date: Mon, 5 Sep 2022 13:25:24 -0700 Subject: [PATCH 150/172] small nissan cleanup (#25663) --- selfdrive/car/nissan/interface.py | 4 +--- selfdrive/car/nissan/nissancan.py | 5 +---- 2 files changed, 2 insertions(+), 7 deletions(-) diff --git a/selfdrive/car/nissan/interface.py b/selfdrive/car/nissan/interface.py index fe567468b..494573f49 100644 --- a/selfdrive/car/nissan/interface.py +++ b/selfdrive/car/nissan/interface.py @@ -18,24 +18,22 @@ class CarInterface(CarInterfaceBase): ret.steerLimitTimer = 1.0 ret.steerActuatorDelay = 0.1 + ret.steerRatio = 17 if candidate in (CAR.ROGUE, CAR.XTRAIL): ret.mass = 1610 + STD_CARGO_KG ret.wheelbase = 2.705 ret.centerToFront = ret.wheelbase * 0.44 - ret.steerRatio = 17 elif candidate in (CAR.LEAF, CAR.LEAF_IC): ret.mass = 1610 + STD_CARGO_KG ret.wheelbase = 2.705 ret.centerToFront = ret.wheelbase * 0.44 - ret.steerRatio = 17 elif candidate == CAR.ALTIMA: # Altima has EPS on C-CAN unlike the others that have it on V-CAN ret.safetyConfigs[0].safetyParam = 1 # EPS is on alternate bus ret.mass = 1492 + STD_CARGO_KG ret.wheelbase = 2.824 ret.centerToFront = ret.wheelbase * 0.44 - ret.steerRatio = 17 ret.steerControlType = car.CarParams.SteerControlType.angle ret.radarOffCan = True diff --git a/selfdrive/car/nissan/nissancan.py b/selfdrive/car/nissan/nissancan.py index f59714b8d..01fb3463a 100644 --- a/selfdrive/car/nissan/nissancan.py +++ b/selfdrive/car/nissan/nissancan.py @@ -24,10 +24,7 @@ def create_steering_control(packer, apply_steer, frame, steer_on, lkas_max_torqu def create_acc_cancel_cmd(packer, car_fingerprint, cruise_throttle_msg): values = copy.copy(cruise_throttle_msg) - can_bus = 2 - - if car_fingerprint == CAR.ALTIMA: - can_bus = 1 + can_bus = 1 if car_fingerprint == CAR.ALTIMA else 2 values["CANCEL_BUTTON"] = 1 values["NO_BUTTON_PRESSED"] = 0 From 71d152bf518f4e2866d6f2cd8c84e1916310d6f2 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Tue, 6 Sep 2022 04:25:46 +0800 Subject: [PATCH 151/172] manager.py: set default lang to main_en (#25666) * default main_en * update transaltions * set default language in manager.py * after h --- selfdrive/manager/manager.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/manager/manager.py b/selfdrive/manager/manager.py index a065242bb..772dd9488 100755 --- a/selfdrive/manager/manager.py +++ b/selfdrive/manager/manager.py @@ -40,6 +40,7 @@ def manager_init() -> None: ("CompletedTrainingVersion", "0"), ("DisengageOnAccelerator", "1"), ("HasAcceptedTerms", "0"), + ("LanguageSetting", "main_en"), ("OpenpilotEnabledToggle", "1"), ] if not PC: From 80533d6c0368b6b2fd797ec0388ed75d74dee80f Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 5 Sep 2022 13:57:07 -0700 Subject: [PATCH 152/172] Toyota: match dash set speed (#25649) * toyota: match set speed from dash * Use unit bit * Use RSA2 * flip this * Universal unit signal, set vEgoCluster * remove this and bump opendbc * detect if car interface sets cluster fields * revert * needs to be cp * UI_SPEED is actually always in kph? * forgot to actually convert it * same in onroad * try conv factor only for imperial * Seems like UI_SPEED is not the UI speed at all * the dash might floor it * same openpilot behavior * bump * ego speed factor is dynamic across speeds, handle Lexus exceptions with diff msg * remove test, bump opendbc * secret formula * secret formula v2 * 1.03 is sufficient * try short press * bump opendbc * surely this can be cleaned up surely this can be cleaned up * use filter * redo factors * try UI_SPEED again with a factor try UI_SPEED again with a factor * dash applies hysteresis to speed. this matches pretty well, but not exactly * match only set speed * clean up * clean up clean up * Update ref_commit * update refs Co-authored-by: Willem Melching Co-authored-by: Adeeb Shihadeh --- opendbc | 2 +- selfdrive/car/toyota/carstate.py | 14 ++++++++++++++ selfdrive/test/process_replay/ref_commit | 2 +- 3 files changed, 16 insertions(+), 2 deletions(-) diff --git a/opendbc b/opendbc index 8c634615c..83d4cb9fd 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit 8c634615c5b6eb05ebdecc097bdc72f5403a3afa +Subproject commit 83d4cb9fd871a563f4a0af0102992c0b52c94310 diff --git a/selfdrive/car/toyota/carstate.py b/selfdrive/car/toyota/carstate.py index 70ba690aa..0cfba2b09 100644 --- a/selfdrive/car/toyota/carstate.py +++ b/selfdrive/car/toyota/carstate.py @@ -90,9 +90,17 @@ class CarState(CarStateBase): if self.CP.carFingerprint in (CAR.LEXUS_IS, CAR.LEXUS_RC): ret.cruiseState.available = cp.vl["DSU_CRUISE"]["MAIN_ON"] != 0 ret.cruiseState.speed = cp.vl["DSU_CRUISE"]["SET_SPEED"] * CV.KPH_TO_MS + cluster_set_speed = cp.vl["PCM_CRUISE_ALT"]["UI_SET_SPEED"] else: ret.cruiseState.available = cp.vl["PCM_CRUISE_2"]["MAIN_ON"] != 0 ret.cruiseState.speed = cp.vl["PCM_CRUISE_2"]["SET_SPEED"] * CV.KPH_TO_MS + cluster_set_speed = cp.vl["PCM_CRUISE_SM"]["UI_SET_SPEED"] + + # UI_SET_SPEED is always non-zero when main is on, hide until first enable + if ret.cruiseState.speed != 0: + is_metric = cp.vl["BODY_CONTROL_STATE_2"]["UNITS"] in (1, 2) + conversion_factor = CV.KPH_TO_MS if is_metric else CV.MPH_TO_MS + ret.cruiseState.speedCluster = cluster_set_speed * conversion_factor cp_acc = cp_cam if self.CP.carFingerprint in (TSS2_CAR - RADAR_ACC_CAR) else cp @@ -147,6 +155,7 @@ class CarState(CarStateBase): ("DOOR_OPEN_RR", "BODY_CONTROL_STATE"), ("SEATBELT_DRIVER_UNLATCHED", "BODY_CONTROL_STATE"), ("PARKING_BRAKE", "BODY_CONTROL_STATE"), + ("UNITS", "BODY_CONTROL_STATE_2"), ("TC_DISABLED", "ESP_CONTROL"), ("BRAKE_HOLD_ACTIVE", "ESP_CONTROL"), ("STEER_FRACTION", "STEER_ANGLE_SENSOR"), @@ -154,6 +163,7 @@ class CarState(CarStateBase): ("CRUISE_ACTIVE", "PCM_CRUISE"), ("CRUISE_STATE", "PCM_CRUISE"), ("GAS_RELEASED", "PCM_CRUISE"), + ("UI_SET_SPEED", "PCM_CRUISE_SM"), ("STEER_TORQUE_DRIVER", "STEER_TORQUE_SENSOR"), ("STEER_TORQUE_EPS", "STEER_TORQUE_SENSOR"), ("STEER_ANGLE", "STEER_TORQUE_SENSOR"), @@ -168,12 +178,14 @@ class CarState(CarStateBase): ("LIGHT_STALK", 1), ("BLINKERS_STATE", 0.15), ("BODY_CONTROL_STATE", 3), + ("BODY_CONTROL_STATE_2", 2), ("ESP_CONTROL", 3), ("EPS_STATUS", 25), ("BRAKE_MODULE", 40), ("WHEEL_SPEEDS", 80), ("STEER_ANGLE_SENSOR", 80), ("PCM_CRUISE", 33), + ("PCM_CRUISE_SM", 1), ("STEER_TORQUE_SENSOR", 50), ] @@ -187,7 +199,9 @@ class CarState(CarStateBase): if CP.carFingerprint in (CAR.LEXUS_IS, CAR.LEXUS_RC): signals.append(("MAIN_ON", "DSU_CRUISE")) signals.append(("SET_SPEED", "DSU_CRUISE")) + signals.append(("UI_SET_SPEED", "PCM_CRUISE_ALT")) checks.append(("DSU_CRUISE", 5)) + checks.append(("PCM_CRUISE_ALT", 1)) else: signals.append(("MAIN_ON", "PCM_CRUISE_2")) signals.append(("SET_SPEED", "PCM_CRUISE_2")) diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index cf3eb89f9..20bb4c82f 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -e1c189b002a179763fa34f24e5d96f2b2d0c4c49 +915309019fef256512ee30cf92cfae2e479dd04e \ No newline at end of file From a3bc906b113bbe6a5726c2fef4f64f3304cdaf1a Mon Sep 17 00:00:00 2001 From: cydia2020 <12470297+cydia2020@users.noreply.github.com> Date: Tue, 6 Sep 2022 07:07:47 +1000 Subject: [PATCH 153/172] Toyota: add missing HIGHLANDER_TSS2 engine f/w (#25659) --- 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 9635fe2e7..18b6db0db 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -947,6 +947,7 @@ FW_VERSIONS = { b'\x01896630EB2200\x00\x00\x00\x00', b'\x01896630EC4000\x00\x00\x00\x00', b'\x01896630ED9000\x00\x00\x00\x00', + b'\x01896630ED9100\x00\x00\x00\x00', b'\x01896630EE1000\x00\x00\x00\x00', b'\x01896630EE1100\x00\x00\x00\x00', ], From 75c434bde708b15f392cea68f897a1450d4d8b78 Mon Sep 17 00:00:00 2001 From: Dean Lee Date: Tue, 6 Sep 2022 05:11:32 +0800 Subject: [PATCH 154/172] replay: add shortcuts for seeking to the next info, warning, and critical alerts (#25576) --- tools/replay/consoleui.cc | 11 ++++++++++- tools/replay/replay.cc | 7 +++++-- tools/replay/replay.h | 3 +++ 3 files changed, 18 insertions(+), 3 deletions(-) diff --git a/tools/replay/consoleui.cc b/tools/replay/consoleui.cc index 6b419ca9d..5f165ac31 100644 --- a/tools/replay/consoleui.cc +++ b/tools/replay/consoleui.cc @@ -18,7 +18,10 @@ const std::initializer_list> keyboard_shortc {"space", "Pause/Resume"}, {"e", "Next Engagement"}, {"d", "Next Disengagement"}, - {"t", "Next User Tag"} + {"t", "Next User Tag"}, + {"i", "Next Info"}, + {"w", "Next Warning"}, + {"c", "Next Critical"}, }, { {"enter", "Enter seek request"}, @@ -344,6 +347,12 @@ void ConsoleUI::handleKey(char c) { replay->seekToFlag(FindFlag::nextDisEngagement); } else if (c == 't') { replay->seekToFlag(FindFlag::nextUserFlag); + } else if (c == 'i') { + replay->seekToFlag(FindFlag::nextInfo); + } else if (c == 'w') { + replay->seekToFlag(FindFlag::nextWarning); + } else if (c == 'c') { + replay->seekToFlag(FindFlag::nextCritical); } else if (c == 'm') { replay->seekTo(+60, true); } else if (c == 'M') { diff --git a/tools/replay/replay.cc b/tools/replay/replay.cc index ed8dea612..3e482b547 100644 --- a/tools/replay/replay.cc +++ b/tools/replay/replay.cc @@ -166,8 +166,11 @@ std::optional Replay::find(FindFlag flag) { } else if (flag == FindFlag::nextDisEngagement && end_ts > cur_ts) { return end_ts; } - } else if (type == TimelineType::UserFlag) { - if (flag == FindFlag::nextUserFlag && start_ts > cur_ts) { + } else if (start_ts > cur_ts) { + if ((flag == FindFlag::nextUserFlag && type == TimelineType::UserFlag) || + (flag == FindFlag::nextInfo && type == TimelineType::AlertInfo) || + (flag == FindFlag::nextWarning && type == TimelineType::AlertWarning) || + (flag == FindFlag::nextCritical && type == TimelineType::AlertCritical)) { return start_ts; } } diff --git a/tools/replay/replay.h b/tools/replay/replay.h index e4217736d..e86c453f7 100644 --- a/tools/replay/replay.h +++ b/tools/replay/replay.h @@ -26,6 +26,9 @@ enum class FindFlag { nextEngagement, nextDisEngagement, nextUserFlag, + nextInfo, + nextWarning, + nextCritical }; enum class TimelineType { None, Engaged, AlertInfo, AlertWarning, AlertCritical, UserFlag }; From 19a33a4845da5c99c8ccd9b5f860f7eaf98d611c Mon Sep 17 00:00:00 2001 From: ogiechogie <48487836+ogiechogie@users.noreply.github.com> Date: Mon, 5 Sep 2022 14:33:43 -0700 Subject: [PATCH 155/172] VW: Add fingerprint for 2015 Audi A3 MK3 (US) (#25639) --- selfdrive/car/volkswagen/values.py | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/selfdrive/car/volkswagen/values.py b/selfdrive/car/volkswagen/values.py index 278f4bc66..62d6dcdda 100755 --- a/selfdrive/car/volkswagen/values.py +++ b/selfdrive/car/volkswagen/values.py @@ -744,6 +744,7 @@ FW_VERSIONS = { b'\xf1\x8704E906023BL\xf1\x895190', b'\xf1\x8704E906027CJ\xf1\x897798', b'\xf1\x8704L997022N \xf1\x899459', + b'\xf1\x875G0906259A \xf1\x890004', b'\xf1\x875G0906259L \xf1\x890002', b'\xf1\x875G0906259Q \xf1\x890002', b'\xf1\x878V0906259F \xf1\x890002', @@ -756,6 +757,7 @@ FW_VERSIONS = { b'\xf1\x870CW300044T \xf1\x895245', b'\xf1\x870CW300048 \xf1\x895201', b'\xf1\x870D9300012 \xf1\x894912', + b'\xf1\x870D9300012K \xf1\x894513', b'\xf1\x870D9300013B \xf1\x894931', b'\xf1\x870D9300041N \xf1\x894512', b'\xf1\x870D9300043T \xf1\x899699', @@ -772,6 +774,7 @@ FW_VERSIONS = { b'\xf1\x875Q0959655AM\xf1\x890315\xf1\x82\x1311111111111111311411011231129321212100', b'\xf1\x875Q0959655AM\xf1\x890318\xf1\x82\x1311111111111112311411011531159321212100', b'\xf1\x875Q0959655BJ\xf1\x890339\xf1\x82\x1311110011131100311111011731179321342100', + b'\xf1\x875Q0959655J \xf1\x890825\xf1\x82\x13111112111111--241115141112221291163221', b'\xf1\x875Q0959655J \xf1\x890825\xf1\x82\023111112111111--171115141112221291163221', b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\023121111111211--261117141112231291163221', b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13121111111111--341117141212231291163221', @@ -785,6 +788,7 @@ FW_VERSIONS = { b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\00521G0G809A1', b'\xf1\x875Q0909144P \xf1\x891043\xf1\x82\00503G00303A0', b'\xf1\x875Q0909144P \xf1\x891043\xf1\x82\00503G00803A0', + b'\xf1\x875Q0909144P \xf1\x891043\xf1\x82\x0503G0G803A0', b'\xf1\x875Q0909144R \xf1\x891061\xf1\x82\00516G00804A1', b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\00521G00807A1', ], From 1632c2aa62a2501783b7c4b3aa5b0b7dae7d00f3 Mon Sep 17 00:00:00 2001 From: Lee Jong Mun <43285072+crwusiz@users.noreply.github.com> Date: Tue, 6 Sep 2022 08:11:22 +0900 Subject: [PATCH 156/172] Korean: add missing translations (#25647) * kor translate update * more translation fix * better * this pr e2e long only Co-authored-by: sshane --- selfdrive/ui/translations/main_ko.ts | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/ui/translations/main_ko.ts b/selfdrive/ui/translations/main_ko.ts index 1d7ddbe6e..73a5da5ad 100644 --- a/selfdrive/ui/translations/main_ko.ts +++ b/selfdrive/ui/translations/main_ko.ts @@ -1195,12 +1195,12 @@ location set 🌮 End-to-end longitudinal (extremely alpha) 🌮 - + 🌮 e2e long 사용 (매우 실험적) 🌮 Let the driving model control the gas and brakes, openpilot will drive as it thinks a human would. Super experimental. - + 주행모델이 가속과 감속을 제어하도록 하면 openpilot은 운전자가 생각하는것처럼 운전합니다. (매우 실험적) From 7cdb538043c40f4c30c83863fa52a1fba8c6f621 Mon Sep 17 00:00:00 2001 From: Inoichan <37664066+Ino-Ichan@users.noreply.github.com> Date: Tue, 6 Sep 2022 09:52:12 +0900 Subject: [PATCH 157/172] modeld: bug fix in single camera mode of modeld (#25658) --- selfdrive/modeld/modeld.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/modeld/modeld.cc b/selfdrive/modeld/modeld.cc index 653661a3a..d08075ff2 100644 --- a/selfdrive/modeld/modeld.cc +++ b/selfdrive/modeld/modeld.cc @@ -109,7 +109,7 @@ void run_model(ModelState &model, VisionIpcClient &vipc_client_main, VisionIpcCl } } else { // Use single camera - buf_extra = buf_main; + buf_extra = nullptr; meta_extra = meta_main; } From 2e013c9d46119412571b8fa5f2d255663b4b22be Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 5 Sep 2022 18:07:45 -0700 Subject: [PATCH 158/172] fix intel mac build, from #25500 --- SConstruct | 11 +++++++++-- third_party/acados/build.sh | 9 +++++++-- 2 files changed, 16 insertions(+), 4 deletions(-) diff --git a/SConstruct b/SConstruct index 66a94f9b1..8b32eba4a 100644 --- a/SConstruct +++ b/SConstruct @@ -75,7 +75,7 @@ lenv = { "ACADOS_SOURCE_DIR": Dir("#third_party/acados/include/acados").abspath, "ACADOS_PYTHON_INTERFACE_PATH": Dir("#pyextra/acados_template").abspath, - "TERA_PATH": Dir("#").abspath + f"/third_party/acados/{arch}/t_renderer", + "TERA_PATH": Dir("#").abspath + f"/third_party/acados/{arch}/t_renderer" } rpath = lenv["LD_LIBRARY_PATH"].copy() @@ -112,6 +112,9 @@ else: # MacOS if arch == "Darwin": + if real_arch == "x86_64": + lenv["TERA_PATH"] = Dir("#").abspath + f"/third_party/acados/Darwin_x86_64/t_renderer" + brew_prefix = subprocess.check_output(['brew', '--prefix'], encoding='utf8').strip() yuv_dir = "mac" if real_arch != "arm64" else "mac_arm64" libpath = [ @@ -120,9 +123,13 @@ else: f"{brew_prefix}/Library", f"{brew_prefix}/opt/openssl/lib", f"{brew_prefix}/Cellar", - f"#third_party/acados/{arch}/lib", "/System/Library/Frameworks/OpenGL.framework/Libraries", ] + if real_arch == "x86_64": + libpath.append(f"#third_party/acados/Darwin_x86_64/lib") + else: + libpath.append(f"#third_party/acados/{arch}/lib") + cflags += ["-DGL_SILENCE_DEPRECATION"] cxxflags += ["-DGL_SILENCE_DEPRECATION"] cpppath += [ diff --git a/third_party/acados/build.sh b/third_party/acados/build.sh index a4246fbda..0481e8159 100755 --- a/third_party/acados/build.sh +++ b/third_party/acados/build.sh @@ -13,8 +13,13 @@ fi ACADOS_FLAGS="-DACADOS_WITH_QPOASES=ON -UBLASFEO_TARGET -DBLASFEO_TARGET=$BLAS_TARGET" if [[ "$OSTYPE" == "darwin"* ]]; then - ACADOS_FLAGS="$ACADOS_FLAGS -DCMAKE_OSX_ARCHITECTURES=arm64;x86_64" - ARCHNAME="Darwin" + if [[ $(uname -m) == "x86_64" ]]; then + ACADOS_FLAGS="$ACADOS_FLAGS -DCMAKE_OSX_ARCHITECTURES=x86_64" + ARCHNAME="Darwin_x86_64" + else + ACADOS_FLAGS="$ACADOS_FLAGS -DCMAKE_OSX_ARCHITECTURES=arm64;x86_64" + ARCHNAME="Darwin" + fi fi if [ ! -d acados_repo/ ]; then From bc9b862d271e20540cb996c7ad3bbfded37508fc Mon Sep 17 00:00:00 2001 From: Rewat S <76684800+taperec@users.noreply.github.com> Date: Wed, 7 Sep 2022 01:47:11 +0700 Subject: [PATCH 159/172] Thai: update translations (#25682) * Add Thai translations * update to add plurals remove * Update translations * Update Thai translation to match English source. * Add to badges * use shorter km/h * Add test for correct format specifier for plural translations * pass new test * Update some sentences to make it clear. Change short form of some words. * Hide from the UI * Thai: Update translations Update Low voltage alert for better understanding. Co-authored-by: Shane Smiskol --- selfdrive/ui/translations/main_th.ts | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/ui/translations/main_th.ts b/selfdrive/ui/translations/main_th.ts index 3277f5374..7e7fcf278 100644 --- a/selfdrive/ui/translations/main_th.ts +++ b/selfdrive/ui/translations/main_th.ts @@ -754,7 +754,7 @@ location set WARNING: Low Voltage - คำเตือน: แรงดันไฟฟ้าต่ำ + คำเตือน: แรงดันแบตเตอรี่ต่ำ From 48efd8374bf7e484ab0580f344407ab57dcff6c8 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 6 Sep 2022 13:00:49 -0700 Subject: [PATCH 160/172] Revert "modeld: bug fix in single camera mode of modeld (#25658)" This reverts commit 7cdb538043c40f4c30c83863fa52a1fba8c6f621. --- selfdrive/modeld/modeld.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/modeld/modeld.cc b/selfdrive/modeld/modeld.cc index d08075ff2..653661a3a 100644 --- a/selfdrive/modeld/modeld.cc +++ b/selfdrive/modeld/modeld.cc @@ -109,7 +109,7 @@ void run_model(ModelState &model, VisionIpcClient &vipc_client_main, VisionIpcCl } } else { // Use single camera - buf_extra = nullptr; + buf_extra = buf_main; meta_extra = meta_main; } From d222461a3e630690d05fbd07ed0d80feadfae944 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 6 Sep 2022 13:05:47 -0700 Subject: [PATCH 161/172] LDW: fix deprecated ll prob reference (#25681) * fix crash when ldw is turned on * in lane change * Revert "in lane change" This reverts commit 98e7224f81d2036689339779e582e2085c9c4d3e. --- selfdrive/controls/controlsd.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index f2b2ddc98..370438930 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -709,8 +709,8 @@ class Controls: model_v2 = self.sm['modelV2'] desire_prediction = model_v2.meta.desirePrediction if len(desire_prediction) and ldw_allowed: - right_lane_visible = self.sm['lateralPlan'].rProb > 0.5 - left_lane_visible = self.sm['lateralPlan'].lProb > 0.5 + right_lane_visible = model_v2.laneLineProbs[2] > 0.5 + left_lane_visible = model_v2.laneLineProbs[1] > 0.5 l_lane_change_prob = desire_prediction[Desire.laneChangeLeft - 1] r_lane_change_prob = desire_prediction[Desire.laneChangeRight - 1] From 719d5f78560c393732df240f1b6e053113aef2f8 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 6 Sep 2022 13:23:41 -0700 Subject: [PATCH 162/172] translations tests: ignore line numbers (#25675) * no line numbers * remove locations * test * ignore line numbers * revert revert * fix that * use relative * non bytes, global * clean up --- selfdrive/ui/tests/test_translations.py | 13 +- selfdrive/ui/translations/main_en.ts | 4 + selfdrive/ui/translations/main_ja.ts | 506 +++++++++++------------ selfdrive/ui/translations/main_ko.ts | 506 +++++++++++------------ selfdrive/ui/translations/main_pt-BR.ts | 506 +++++++++++------------ selfdrive/ui/translations/main_zh-CHS.ts | 506 +++++++++++------------ selfdrive/ui/translations/main_zh-CHT.ts | 506 +++++++++++------------ selfdrive/ui/update_translations.py | 2 +- 8 files changed, 1278 insertions(+), 1271 deletions(-) diff --git a/selfdrive/ui/tests/test_translations.py b/selfdrive/ui/tests/test_translations.py index fead288df..d8609f110 100755 --- a/selfdrive/ui/tests/test_translations.py +++ b/selfdrive/ui/tests/test_translations.py @@ -9,6 +9,7 @@ import xml.etree.ElementTree as ET from selfdrive.ui.update_translations import TRANSLATIONS_DIR, LANGUAGES_FILE, update_translations TMP_TRANSLATIONS_DIR = os.path.join(TRANSLATIONS_DIR, "tmp") +LOCATION_TAG = "" not in cur_translations, + self.assertTrue("" not in cur_translations, f"{file} ({name}) translation file has unfinished translations. Finish translations or mark them as completed in Qt Linguist") def test_vanished_translations(self): for name, file in self.translation_files.items(): with self.subTest(name=name, file=file): cur_translations = self._read_translation_file(TRANSLATIONS_DIR, file) - self.assertTrue(b"" not in cur_translations, + self.assertTrue("" not in cur_translations, f"{file} ({name}) translation file has obsolete translations. Run selfdrive/ui/update_translations.py --vanish to remove them") def test_plural_translations(self): diff --git a/selfdrive/ui/translations/main_en.ts b/selfdrive/ui/translations/main_en.ts index 3f9692e5f..42e30a59a 100644 --- a/selfdrive/ui/translations/main_en.ts +++ b/selfdrive/ui/translations/main_en.ts @@ -4,6 +4,7 @@ InputDialog + Need at least %n character(s)! Need at least %n character! @@ -14,6 +15,7 @@ QObject + %n minute(s) ago %n minute ago @@ -21,6 +23,7 @@ + %n hour(s) ago %n hour ago @@ -28,6 +31,7 @@ + %n day(s) ago %n day ago diff --git a/selfdrive/ui/translations/main_ja.ts b/selfdrive/ui/translations/main_ja.ts index 43327f8ef..7d0203dae 100644 --- a/selfdrive/ui/translations/main_ja.ts +++ b/selfdrive/ui/translations/main_ja.ts @@ -4,17 +4,17 @@ AbstractAlert - + Close 閉じる - + Snooze Update 更新の一時停止 - + Reboot and Update 再起動してアップデート @@ -22,53 +22,53 @@ AdvancedNetworking - + Back 戻る - + Enable Tethering テザリングを有効化 - + Tethering Password テザリングパスワード - - + + EDIT 編集 - + Enter new tethering password 新しいテザリングパスワードを入力 - + IP Address IP アドレス - + Enable Roaming ローミングを有効化 - + APN Setting APN 設定 - + Enter APN APN を入力 - + leave blank for automatic configuration 空白のままにして、自動設定にします @@ -76,13 +76,13 @@ ConfirmationDialog - - + + Ok OK - + Cancel キャンセル @@ -90,17 +90,17 @@ DeclinePage - + You must accept the Terms and Conditions in order to use openpilot. openpilot をご利用される前に、利用規約に同意する必要があります。 - + Back 戻る - + Decline, uninstall %1 拒否して %1 をアンインストール @@ -108,152 +108,152 @@ DevicePanel - + Dongle ID ドングル番号 (Dongle ID) - + N/A N/A - + Serial シリアル番号 - + Driver Camera 車内カメラ - + PREVIEW 見る - + Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off) 車内カメラをプレビューして、ドライバー監視システムの視界を確認ができます。(車両の電源を切る必要があります) - + Reset Calibration キャリブレーションをリセット - + RESET リセット - + Are you sure you want to reset calibration? キャリブレーションをリセットしてもよろしいですか? - + Review Training Guide 入門書を見る - + REVIEW 見る - + Review the rules, features, and limitations of openpilot openpilot の特徴を見る - + Are you sure you want to review the training guide? 入門書を見てもよろしいですか? - + Regulatory 認証情報 - + VIEW 見る - + Change Language 言語を変更 - + CHANGE 変更 - + Select a language 言語を選択 - + Reboot 再起動 - + Power Off 電源を切る - + 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°以内にデバイスを取付ける必要があります。キャリブレーションを引き続きます、リセットはほとんど必要ありません。 - + Your device is pointed %1° %2 and %3° %4. このデバイスは%2の%1°、%4の%3°に向けます。 - + down - + up - + left - + right - + Are you sure you want to reboot? 再起動してもよろしいですか? - + Disengage to Reboot openpilot をキャンセルして再起動ができます - + Are you sure you want to power off? シャットダウンしてもよろしいですか? - + Disengage to Power Off openpilot をキャンセルしてシャットダウンができます @@ -261,32 +261,32 @@ DriveStats - + Drives 運転履歴 - + Hours 時間 - + ALL TIME 累計 - + PAST WEEK 先週 - + KM km - + Miles マイル @@ -294,7 +294,7 @@ DriverViewScene - + camera starting カメラを起動しています @@ -302,12 +302,12 @@ InputDialog - + Cancel キャンセル - + Need at least %n character(s)! %n文字以上でお願いします! @@ -317,22 +317,22 @@ Installer - + Installing... インストールしています... - + Receiving objects: オブジェクトをダウンロードしています: - + Resolving deltas: デルタを解決しています: - + Updating files: ファイルを更新しています: @@ -340,27 +340,27 @@ MapETA - + eta 予定到着時間 - + min - + hr 時間 - + km キロメートル - + mi マイル @@ -368,22 +368,22 @@ MapInstructions - + km キロメートル - + m メートル - + mi マイル - + ft フィート @@ -391,48 +391,48 @@ MapPanel - + Current Destination 現在の目的地 - + CLEAR 削除 - + Recent Destinations 最近の目的地 - + Try the Navigation Beta β版ナビゲーションを試す - + Get turn-by-turn directions displayed and more with a comma prime subscription. Sign up now: https://connect.comma.ai より詳細な案内情報を得ることができます。 詳しくはこちら:https://connect.comma.ai - + No home location set 自宅の住所はまだ 設定されていません - + No work location set 職場の住所はまだ 設定されていません - + no recent destinations 最近の目的地履歴がありません @@ -440,12 +440,12 @@ location set MapWindow - + Map Loading マップを読み込んでいます - + Waiting for GPS GPS信号を探しています @@ -453,12 +453,12 @@ location set MultiOptionDialog - + Select 選択 - + Cancel キャンセル @@ -466,23 +466,23 @@ location set Networking - + Advanced 詳細 - + Enter password パスワードを入力 - - + + for "%1" ネットワーク名:%1 - + Wrong password パスワードが間違っています @@ -490,30 +490,30 @@ location set NvgWindow - + km/h km/h - + mph mph - - + + MAX 最高速度 - - + + SPEED 速度 - - + + LIMIT 制限速度 @@ -521,17 +521,17 @@ location set OffroadHome - + UPDATE 更新 - + ALERTS 警告 - + ALERT 警告 @@ -539,22 +539,22 @@ location set PairingPopup - + Pair your device to your comma account デバイスと comma アカウントを連携する - + Go to https://connect.comma.ai on your phone モバイルデバイスで「connect.comma.ai」にアクセスして - + Click "add new device" and scan the QR code on the right 「新しいデバイスを追加」を押すと、右側のQRコードをスキャンしてください - + Bookmark connect.comma.ai to your home screen to use it like an app 「connect.comma.ai」をホーム画面に追加して、アプリのように使うことができます @@ -562,32 +562,32 @@ location set PrimeAdWidget - + Upgrade Now 今すぐアップグレート - + Become a comma prime member at connect.comma.ai connect.comma.ai でプライム会員に登録できます - + PRIME FEATURES: 特典: - + Remote access リモートアクセス - + 1 year of storage 一年間の保存期間 - + Developer perks 開発者向け特典 @@ -595,22 +595,22 @@ location set PrimeUserWidget - + ✓ SUBSCRIBED ✓ 入会しました - + comma prime comma prime - + CONNECT.COMMA.AI CONNECT.COMMA.AI - + COMMA POINTS COMMA POINTS @@ -618,41 +618,41 @@ location set QObject - + Reboot 再起動 - + Exit 閉じる - + dashcam ドライブレコーダー - + openpilot openpilot - + %n minute(s) ago %n 分前 - + %n hour(s) ago %n 時間前 - + %n day(s) ago %n 日前 @@ -662,47 +662,47 @@ location set Reset - + Reset failed. Reboot to try again. 初期化に失敗しました。再起動後に再試行してください。 - + Are you sure you want to reset your device? 初期化してもよろしいですか? - + Resetting device... デバイスが初期化されます... - + System Reset システムを初期化 - + System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot. システムの初期化をリクエストしました。「確認」ボタンを押すとデバイスが初期化されます。「キャンセル」ボタンを押すと起動を続行します。 - + Cancel キャンセル - + Reboot 再起動 - + Confirm 確認 - + Unable to mount data partition. Press confirm to reset your device. 「data」パーティションをマウントできません。「確認」ボタンを押すとデバイスが初期化されます。 @@ -710,7 +710,7 @@ location set RichTextDialog - + Ok OK @@ -718,33 +718,33 @@ location set SettingsWindow - + × × - + Device デバイス - - + + Network ネットワーク - + Toggles 切り替え - + Software ソフトウェア - + Navigation ナビゲーション @@ -752,105 +752,105 @@ location set Setup - + WARNING: Low Voltage 警告:低電圧 - + Power your device in a car with a harness or proceed at your own risk. 自己責任でハーネスから電源を供給してください。 - + Power off 電源を切る - - - + + + Continue 続ける - + Getting Started はじめに - + Before we get on the road, let’s finish installation and cover some details. その前に、インストールを完了し、いくつかの詳細を説明します。 - + Connect to Wi-Fi Wi-Fi に接続 - - + + Back 戻る - + Continue without Wi-Fi Wi-Fi に未接続で続行 - + Waiting for internet インターネット接続を待機中 - + Choose Software to Install インストールするソフトウェアを選びます - + Dashcam ドライブレコーダー - + Custom Software カスタムソフトウェア - + Enter URL URL を入力 - + for Custom Software カスタムソフトウェア - + Downloading... ダウンロード中... - + Download Failed ダウンロード失敗 - + Ensure the entered URL is valid, and the device’s internet connection is good. 入力された URL を確認し、デバイスがインターネットに接続されていることを確認してください。 - + Reboot device デバイスを再起動 - + Start over 最初からやり直す @@ -858,17 +858,17 @@ location set SetupWidget - + Finish Setup セットアップ完了 - + Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer. デバイスを comma connect (connect.comma.ai)でペアリングし comma prime 特典を申請してください。 - + Pair device デバイスをペアリング @@ -876,106 +876,106 @@ location set Sidebar - - + + CONNECT 接続 - + OFFLINE オフライン - - + + ONLINE オンライン - + ERROR エラー - - - + + + TEMP 温度 - + HIGH 高温 - + GOOD 最適 - + OK OK - + VEHICLE 車両 - + NO NO - + PANDA PANDA - + GPS GPS - + SEARCH 検索 - + -- -- - + Wi-Fi Wi-Fi - + ETH ETH - + 2G 2G - + 3G 3G - + LTE LTE - + 5G 5G @@ -983,89 +983,89 @@ location set SoftwarePanel - + Git Branch Git ブランチ - + Git Commit Git コミット - + OS Version OS バージョン - + 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 ブランチの切り替え - + ENTER 切替 - - + + The new branch will be pulled the next time the updater runs. updater を実行する時にブランチを切り替えます。 - + Enter branch name ブランチ名を入力 - + UNINSTALL アンインストール - + Uninstall %1 %1をアンインストール - + Are you sure you want to uninstall? アンインストールしてもよろしいですか? - + failed to fetch update 更新のダウンロードにエラーが発生しました - - + + CHECK 確認 @@ -1073,48 +1073,48 @@ location set SshControl - + SSH Keys SSH 鍵 - + 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 のユーザー名を追加するようお願いすることはありません。 - - + + ADD 追加 - + Enter your GitHub username GitHub のユーザー名を入力してください - + LOADING ローディング - + REMOVE 削除 - + Username '%1' has no keys on GitHub ユーザー名 “%1” は GitHub に鍵がありません - + Request timed out リクエストタイムアウト - + Username '%1' doesn't exist on GitHub ユーザー名 '%1' は GitHub に存在しません @@ -1122,7 +1122,7 @@ location set SshToggle - + Enable SSH SSH を有効化 @@ -1130,22 +1130,22 @@ location set TermsPage - + Terms & Conditions 利用規約 - + Decline 拒否 - + Scroll to accept スクロールして同意 - + Agree 同意 @@ -1153,92 +1153,92 @@ location set TogglesPanel - + Enable openpilot openpilot を有効化 - + Use the openpilot system for adaptive cruise control and lane keep driver assistance. Your attention is required at all times to use this feature. Changing this setting takes effect when the car is powered off. アダプティブクルーズコントロールとレーンキーピングドライバーアシスト(openpilotシステム)。この機能を使用するには、常に注意が必要です。この設定を変更すると、車の電源が切れたときに有効になります。 - + Enable Lane Departure Warnings 車線逸脱警報機能を有効化 - + Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31 mph (50 km/h). 時速31マイル(50km)を超えるスピードで走行中、方向指示器を作動させずに検出された車線ライン上に車両が触れた場合、車線に戻るアラートを受信します。 - + Use Metric System メートル法を有効化 - + Display speed in km/h instead of mph. 速度は mph ではなく km/h で表示されます。 - + Record and Upload Driver Camera 車内カメラの録画とアップロード - + Upload data from the driver facing camera and help improve the driver monitoring algorithm. 車内カメラの映像をアップロードし、ドライバー監視システムのアルゴリズムの向上に役立てます。 - + 🌮 End-to-end longitudinal (extremely alpha) 🌮 - + Let the driving model control the gas and brakes, openpilot will drive as it thinks a human would. Super experimental. - + Disengage On Accelerator Pedal アクセル踏むと openpilot をキャンセル - + When enabled, pressing the accelerator pedal will disengage openpilot. 有効な場合は、アクセルを踏むと openpilot をキャンセルします。 - + Show ETA in 24h Format 24時間表示 - + Use 24h format instead of am/pm AM/PM の代わりに24時間形式を使用します - + Show Map on Left Side of UI ディスプレイの左側にマップを表示 - + 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 を無効化にします! @@ -1246,42 +1246,42 @@ 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 です。 - + Connect to Wi-Fi Wi-Fi に接続 - + Install インストール - + Back 戻る - + Loading... 読み込み中... - + Reboot 再起動 - + Update failed 更新失敗 @@ -1289,23 +1289,23 @@ location set WifiUI - - + + Scanning for networks... ネットワークをスキャン中... - + CONNECTING... 接続中... - + FORGET 削除 - + Forget Wi-Fi Network "%1"? Wi-Fiネットワーク%1を削除してもよろしいですか? diff --git a/selfdrive/ui/translations/main_ko.ts b/selfdrive/ui/translations/main_ko.ts index 73a5da5ad..ff83057a9 100644 --- a/selfdrive/ui/translations/main_ko.ts +++ b/selfdrive/ui/translations/main_ko.ts @@ -4,17 +4,17 @@ AbstractAlert - + Close 닫기 - + Snooze Update 업데이트 일시중지 - + Reboot and Update 업데이트 및 재부팅 @@ -22,53 +22,53 @@ AdvancedNetworking - + Back 뒤로 - + Enable Tethering 테더링 사용 - + Tethering Password 테더링 비밀번호 - - + + EDIT 편집 - + Enter new tethering password 새 테더링 비밀번호를 입력하세요 - + IP Address IP 주소 - + Enable Roaming 로밍 사용 - + APN Setting APN 설정 - + Enter APN APN 입력 - + leave blank for automatic configuration 자동설정을 하려면 공백으로 두세요 @@ -76,13 +76,13 @@ ConfirmationDialog - - + + Ok 확인 - + Cancel 취소 @@ -90,17 +90,17 @@ DeclinePage - + You must accept the Terms and Conditions in order to use openpilot. openpilot을 사용하려면 이용 약관에 동의해야 합니다. - + Back 뒤로 - + Decline, uninstall %1 거절, %1 제거 @@ -108,152 +108,152 @@ DevicePanel - + Dongle ID Dongle ID - + N/A N/A - + Serial Serial - + Driver Camera 운전자 카메라 - + PREVIEW 미리보기 - + Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off) 운전자 모니터링이 좋은 가시성을 갖도록 운전자를 향한 카메라를 미리 봅니다. (차량연결은 해제되어있어야 합니다) - + Reset Calibration 캘리브레이션 재설정 - + RESET 재설정 - + Are you sure you want to reset calibration? 캘리브레이션을 재설정하시겠습니까? - + Review Training Guide 트레이닝 가이드 다시보기 - + REVIEW 다시보기 - + Review the rules, features, and limitations of openpilot openpilot의 규칙, 기능 및 제한 다시보기 - + Are you sure you want to review the training guide? 트레이닝 가이드를 다시보시겠습니까? - + Regulatory 규제 - + VIEW 보기 - + Change Language 언어 변경 - + CHANGE 변경 - + Select a language 언어를 선택하세요 - + Reboot 재부팅 - + Power Off 전원 종료 - + 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은 지속적으로 보정되므로 리셋이 거의 필요하지 않습니다. - + Your device is pointed %1° %2 and %3° %4. 사용자의 장치가 %1° %2 및 %3° %4를 가리키고 있습니다. - + down 아래로 - + up 위로 - + left 좌측으로 - + right 우측으로 - + Are you sure you want to reboot? 재부팅 하시겠습니까? - + Disengage to Reboot 재부팅 하려면 해제하세요 - + Are you sure you want to power off? 전원을 종료하시겠습니까? - + Disengage to Power Off 전원을 종료하려면 해제하세요 @@ -261,32 +261,32 @@ DriveStats - + Drives 주행 - + Hours 시간 - + ALL TIME 전체 - + PAST WEEK 지난주 - + KM Km - + Miles Miles @@ -294,7 +294,7 @@ DriverViewScene - + camera starting 카메라 시작중 @@ -302,12 +302,12 @@ InputDialog - + Cancel 취소 - + Need at least %n character(s)! 최소 %n 자가 필요합니다! @@ -317,22 +317,22 @@ Installer - + Installing... 설치중... - + Receiving objects: 수신중: - + Resolving deltas: 델타병합: - + Updating files: 파일갱신: @@ -340,27 +340,27 @@ MapETA - + eta 도착 - + min - + hr 시간 - + km km - + mi mi @@ -368,22 +368,22 @@ MapInstructions - + km km - + m m - + mi mi - + ft ft @@ -391,48 +391,48 @@ MapPanel - + Current Destination 현재 목적지 - + CLEAR 삭제 - + Recent Destinations 최근 목적지 - + Try the Navigation Beta 네비게이션(베타)를 사용해보세요 - + Get turn-by-turn directions displayed and more with a comma prime subscription. Sign up now: https://connect.comma.ai 자세한 경로안내를 원하시면 comma prime을 구독하세요. 등록:https://connect.comma.ai - + No home location set 집 설정되지않음 - + No work location set 회사 설정되지않음 - + no recent destinations 최근 목적지 없음 @@ -440,12 +440,12 @@ location set MapWindow - + Map Loading 지도 로딩 - + Waiting for GPS GPS를 기다리는 중 @@ -453,12 +453,12 @@ location set MultiOptionDialog - + Select 선택 - + Cancel 취소 @@ -466,23 +466,23 @@ location set Networking - + Advanced 고급 설정 - + Enter password 비밀번호를 입력하세요 - - + + for "%1" 하기위한 "%1" - + Wrong password 비밀번호가 틀렸습니다 @@ -490,30 +490,30 @@ location set NvgWindow - + km/h km/h - + mph mph - - + + MAX MAX - - + + SPEED SPEED - - + + LIMIT LIMIT @@ -521,17 +521,17 @@ location set OffroadHome - + UPDATE 업데이트 - + ALERTS 알림 - + ALERT 알림 @@ -539,22 +539,22 @@ location set PairingPopup - + Pair your device to your comma account 장치를 콤마 계정과 페어링합니다 - + Go to https://connect.comma.ai on your phone https://connect.comma.ai에 접속하세요 - + Click "add new device" and scan the QR code on the right "새 장치 추가"를 클릭하고 오른쪽 QR 코드를 검색합니다 - + Bookmark connect.comma.ai to your home screen to use it like an app connect.comma.ai을 앱처럼 사용하려면 홈 화면에 바로가기를 만드십시오 @@ -562,32 +562,32 @@ location set PrimeAdWidget - + Upgrade Now 지금 업그레이드 - + Become a comma prime member at connect.comma.ai connect.comma.ai에서 comma prime에 가입합니다 - + PRIME FEATURES: PRIME 기능: - + Remote access 원격 접속 - + 1 year of storage 1년간 저장 - + Developer perks 개발자 혜택 @@ -595,22 +595,22 @@ location set PrimeUserWidget - + ✓ SUBSCRIBED ✓ 구독함 - + comma prime comma prime - + CONNECT.COMMA.AI CONNECT.COMMA.AI - + COMMA POINTS COMMA POINTS @@ -618,41 +618,41 @@ location set QObject - + Reboot 재부팅 - + Exit 종료 - + dashcam dashcam - + openpilot openpilot - + %n minute(s) ago %n 분전 - + %n hour(s) ago %n 시간전 - + %n day(s) ago %n 일전 @@ -662,47 +662,47 @@ location set Reset - + Reset failed. Reboot to try again. 초기화 실패. 재부팅후 다시 시도하세요. - + Are you sure you want to reset your device? 장치를 초기화 하시겠습니까? - + Resetting device... 장치 초기화중... - + System Reset 장치 초기화 - + System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot. 장치를 초기화 합니다. 확인버튼을 누르면 모든 내용과 설정이 초기화됩니다. 취소를 누르면 다시 부팅합니다. - + Cancel 취소 - + Reboot 재부팅 - + Confirm 확인 - + Unable to mount data partition. Press confirm to reset your device. 데이터 파티션을 마운트할 수 없습니다. 확인 버튼을 눌러 장치를 리셋합니다. @@ -710,7 +710,7 @@ location set RichTextDialog - + Ok 확인 @@ -718,33 +718,33 @@ location set SettingsWindow - + × × - + Device 장치 - - + + Network 네트워크 - + Toggles 토글 - + Software 소프트웨어 - + Navigation 네비게이션 @@ -752,105 +752,105 @@ location set Setup - + WARNING: Low Voltage 경고: 전압이 낮습니다 - + Power your device in a car with a harness or proceed at your own risk. 하네스 보드에 차량의 전원을 연결하세요. - + Power off 전원 종료 - - - + + + Continue 계속 - + Getting Started 설정 시작 - + Before we get on the road, let’s finish installation and cover some details. 출발하기 전에 설정을 완료하고 몇 가지 세부 사항을 살펴보겠습니다. - + Connect to Wi-Fi wifi 연결 - - + + Back 뒤로 - + Continue without Wi-Fi wifi 없이 계속 - + Waiting for internet 네트워크 접속을 기다립니다 - + Choose Software to Install 설치할 소프트웨어를 선택하세요 - + Dashcam Dashcam - + Custom Software Custom Software - + Enter URL URL 입력 - + for Custom Software for Custom Software - + Downloading... 다운로드중... - + Download Failed 다운로드 실패 - + Ensure the entered URL is valid, and the device’s internet connection is good. 입력된 URL이 유효하고 장치의 인터넷 연결이 잘 되어 있는지 확인합니다. - + Reboot device 재부팅 - + Start over 다시 시작 @@ -858,17 +858,17 @@ location set SetupWidget - + Finish Setup 설정 완료 - + Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer. 장치를 (connect.comma.ai)에서 페어링하고 comma prime 오퍼를 청구합니다. - + Pair device 장치 페어링 @@ -876,106 +876,106 @@ location set Sidebar - - + + CONNECT 연결 - + OFFLINE 오프라인 - - + + ONLINE 온라인 - + ERROR 오류 - - - + + + TEMP 온도 - + HIGH 높음 - + GOOD 좋음 - + OK 경고 - + VEHICLE 차량 - + NO NO - + PANDA PANDA - + GPS GPS - + SEARCH 검색중 - + -- -- - + Wi-Fi Wi-Fi - + ETH 이더넷 - + 2G 2G - + 3G 3G - + LTE LTE - + 5G 5G @@ -983,89 +983,89 @@ location set SoftwarePanel - + Git Branch Git 브렌치 - + Git Commit Git 커밋 - + OS Version OS 버전 - + 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 브랜치 변경 - + ENTER 입력하세요 - - + + The new branch will be pulled the next time the updater runs. 다음 업데이트 프로그램이 실행될 때 새 브랜치가 적용됩니다. - + Enter branch name 브랜치명 입력 - + UNINSTALL 제거 - + Uninstall %1 %1 제거 - + Are you sure you want to uninstall? 제거하시겠습니까? - + failed to fetch update 업데이트를 가져올수없습니다 - - + + CHECK 확인 @@ -1073,48 +1073,48 @@ location set SshControl - + SSH Keys SSH 키 - + 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 사용자 이름을 입력하지 마십시오. comma 직원은 GitHub 사용자 이름을 추가하도록 요청하지 않습니다. - - + + ADD 추가 - + Enter your GitHub username GitHub 사용자 ID - + LOADING 로딩 - + REMOVE 제거 - + Username '%1' has no keys on GitHub '%1'의 키가 GitHub에 없습니다 - + Request timed out 요청 시간 초과 - + Username '%1' doesn't exist on GitHub '%1'은 GitHub에 없습니다 @@ -1122,7 +1122,7 @@ location set SshToggle - + Enable SSH SSH 사용 @@ -1130,22 +1130,22 @@ location set TermsPage - + Terms & Conditions 약관 - + Decline 거절 - + Scroll to accept 허용하려면 아래로 스크롤하세요 - + Agree 동의 @@ -1153,92 +1153,92 @@ location set TogglesPanel - + Enable openpilot openpilot 사용 - + Use the openpilot system for adaptive cruise control and lane keep driver assistance. Your attention is required at all times to use this feature. Changing this setting takes effect when the car is powered off. 어댑티브 크루즈 컨트롤 및 차선 유지 운전자 보조를 위해 openpilot 시스템을 사용하십시오. 이 기능을 사용하려면 항상 주의를 기울여야 합니다. 이 설정을 변경하면 차량 전원이 꺼질 때 적용됩니다. - + Enable Lane Departure Warnings 차선 이탈 경고 사용 - + Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31 mph (50 km/h). 차량이 50km/h(31mph) 이상의 속도로 주행하는 동안 방향 지시등이 활성화되지 않은 상태에서 감지된 차선 위를 주행할 경우 차선이탈 경고를 사용합니다. - + Use Metric System 미터법 사용 - + Display speed in km/h instead of mph. mph 대신 km/h로 속도를 표시합니다. - + Record and Upload Driver Camera 운전자 카메라 녹화 및 업로드 - + Upload data from the driver facing camera and help improve the driver monitoring algorithm. 운전자 카메라에서 데이터를 업로드하고 운전자 모니터링 알고리즘을 개선합니다. - + 🌮 End-to-end longitudinal (extremely alpha) 🌮 🌮 e2e long 사용 (매우 실험적) 🌮 - + Let the driving model control the gas and brakes, openpilot will drive as it thinks a human would. Super experimental. 주행모델이 가속과 감속을 제어하도록 하면 openpilot은 운전자가 생각하는것처럼 운전합니다. (매우 실험적) - + Disengage On Accelerator Pedal 가속페달 조작시 해제 - + When enabled, pressing the accelerator pedal will disengage openpilot. 활성화된 경우 가속 페달을 누르면 openpilot이 해제됩니다. - + Show ETA in 24h Format 24시간 형식으로 도착예정시간 표시 - + Use 24h format instead of am/pm 오전/오후 대신 24시간 형식 사용 - + Show Map on Left Side of UI UI 왼쪽에 지도 표시 - + Show map on left side when in split screen view. 분할 화면 보기에서 지도를 왼쪽에 표시합니다. - + openpilot Longitudinal Control openpilot Longitudinal Control - + openpilot will disable the car's radar and will take over control of gas and brakes. Warning: this disables AEB! openpilot은 차량'의 레이더를 무력화시키고 가속페달과 브레이크의 제어를 인계받을 것이다. 경고: AEB를 비활성화합니다! @@ -1246,42 +1246,42 @@ 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. OS 업데이트가 필요합니다. 장치를 wifi에 연결하여 가장 빠른 업데이트 경험을 제공합니다. 다운로드 크기는 약 1GB입니다. - + Connect to Wi-Fi wifi 연결 - + Install 설치 - + Back 뒤로 - + Loading... 로딩중... - + Reboot 재부팅 - + Update failed 업데이트 실패 @@ -1289,23 +1289,23 @@ location set WifiUI - - + + Scanning for networks... 네트워크 검색 중... - + CONNECTING... 연결중... - + FORGET 저장안함 - + Forget Wi-Fi Network "%1"? wifi 네트워크 저장안함 "%1"? diff --git a/selfdrive/ui/translations/main_pt-BR.ts b/selfdrive/ui/translations/main_pt-BR.ts index f50cf65e1..622d8ee44 100644 --- a/selfdrive/ui/translations/main_pt-BR.ts +++ b/selfdrive/ui/translations/main_pt-BR.ts @@ -4,17 +4,17 @@ AbstractAlert - + Close Fechar - + Snooze Update Adiar Atualização - + Reboot and Update Reiniciar e Atualizar @@ -22,53 +22,53 @@ AdvancedNetworking - + Back Voltar - + Enable Tethering Ativar Tether - + Tethering Password Senha Tethering - - + + EDIT EDITAR - + Enter new tethering password Insira nova senha tethering - + IP Address Endereço IP - + Enable Roaming Ativar Roaming - + APN Setting APN Config - + Enter APN Insira APN - + leave blank for automatic configuration deixe em branco para configuração automática @@ -76,13 +76,13 @@ ConfirmationDialog - - + + Ok OK - + Cancel Cancelar @@ -90,17 +90,17 @@ DeclinePage - + You must accept the Terms and Conditions in order to use openpilot. Você precisa aceitar os Termos e Condições para utilizar openpilot. - + Back Voltar - + Decline, uninstall %1 Rejeitar, desintalar %1 @@ -108,152 +108,152 @@ DevicePanel - + Dongle ID Dongle ID - + N/A N/A - + Serial Serial - + Driver Camera Câmera voltada para o Motorista - + PREVIEW PREVISUAL - + Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off) Pré-visualizar a câmera voltada para o motorista para garantir que monitor tem uma boa visibilidade (veículo precisa estar desligado) - + Reset Calibration Resetar Calibragem - + RESET RESET - + Are you sure you want to reset calibration? Tem certeza que quer resetar a calibragem? - + Review Training Guide Revisar o Treinamento - + REVIEW REVISAR - + Review the rules, features, and limitations of openpilot Revisar regras, aprimoramentos e limitações do openpilot - + Are you sure you want to review the training guide? Tem certeza que quer rever o treinamento? - + Regulatory Regulatório - + VIEW VER - + Change Language Mudar Linguagem - + CHANGE MUDAR - + Select a language Selecione uma linguagem - + Reboot Reiniciar - + Power Off Desligar - + 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. o openpilot requer que o dispositivo seja montado dentro de 4° esquerda ou direita e dentro de 5° para cima ou 8° para baixo. o openpilot está continuamente calibrando, resetar raramente é necessário. - + Your device is pointed %1° %2 and %3° %4. Seu dispositivo está montado %1° %2 e %3° %4. - + down baixo - + up cima - + left esquerda - + right direita - + Are you sure you want to reboot? Tem certeza que quer reiniciar? - + Disengage to Reboot Desacione para Reiniciar - + Are you sure you want to power off? Tem certeza que quer desligar? - + Disengage to Power Off Desacione para Desligar @@ -261,32 +261,32 @@ DriveStats - + Drives Dirigidas - + Hours Horas - + ALL TIME TOTAL - + PAST WEEK SEMANA PASSADA - + KM KM - + Miles Milhas @@ -294,7 +294,7 @@ DriverViewScene - + camera starting câmera iniciando @@ -302,12 +302,12 @@ InputDialog - + Cancel Cancelar - + Need at least %n character(s)! Necessita no mínimo %n caractere! @@ -318,22 +318,22 @@ Installer - + Installing... Instalando... - + Receiving objects: Recebendo objetos: - + Resolving deltas: Resolvendo deltas: - + Updating files: Atualizando arquivos: @@ -341,27 +341,27 @@ MapETA - + eta eta - + min min - + hr hr - + km km - + mi mi @@ -369,22 +369,22 @@ MapInstructions - + km km - + m m - + mi milha - + ft pés @@ -392,48 +392,48 @@ MapPanel - + Current Destination Destino Atual - + CLEAR LIMPAR - + Recent Destinations Destinos Recentes - + Try the Navigation Beta Experimente a Navegação Beta - + Get turn-by-turn directions displayed and more with a comma prime subscription. Sign up now: https://connect.comma.ai Obtenha instruções passo a passo exibidas e muito mais com uma assinatura prime Inscreva-se agora: https://connect.comma.ai - + No home location set Sem local residência definido - + No work location set Sem local de trabalho definido - + no recent destinations sem destinos recentes @@ -441,12 +441,12 @@ trabalho definido MapWindow - + Map Loading Carregando Mapa - + Waiting for GPS Esperando por GPS @@ -454,12 +454,12 @@ trabalho definido MultiOptionDialog - + Select Selecione - + Cancel Cancelar @@ -467,23 +467,23 @@ trabalho definido Networking - + Advanced Avançado - + Enter password Insira a senha - - + + for "%1" para "%1" - + Wrong password Senha incorreta @@ -491,30 +491,30 @@ trabalho definido NvgWindow - + km/h km/h - + mph mph - - + + MAX LIMITE - - + + SPEED MAX - - + + LIMIT VELO @@ -522,17 +522,17 @@ trabalho definido OffroadHome - + UPDATE ATUALIZAÇÃO - + ALERTS ALERTAS - + ALERT ALERTA @@ -540,22 +540,22 @@ trabalho definido PairingPopup - + Pair your device to your comma account Pareie seu dispositivo à sua conta comma - + Go to https://connect.comma.ai on your phone navegue até https://connect.comma.ai no seu telefone - + Click "add new device" and scan the QR code on the right Clique "add new device" e escaneie o QR code a seguir - + Bookmark connect.comma.ai to your home screen to use it like an app Salve connect.comma.ai como sua página inicial para utilizar como um app @@ -563,32 +563,32 @@ trabalho definido PrimeAdWidget - + Upgrade Now Atualizar Agora - + Become a comma prime member at connect.comma.ai Torne-se um membro comma prime em connect.comma.ai - + PRIME FEATURES: APRIMORAMENTOS PRIME: - + Remote access Acesso remoto - + 1 year of storage 1 ano de armazenamento - + Developer perks Benefícios para desenvolvedor @@ -596,22 +596,22 @@ trabalho definido PrimeUserWidget - + ✓ SUBSCRIBED ✓ INSCRITO - + comma prime comma prime - + CONNECT.COMMA.AI CONNECT.COMMA.AI - + COMMA POINTS PONTOS COMMA @@ -619,27 +619,27 @@ trabalho definido QObject - + Reboot Reiniciar - + Exit Sair - + dashcam dashcam - + openpilot openpilot - + %n minute(s) ago há %n minuto @@ -647,7 +647,7 @@ trabalho definido - + %n hour(s) ago há %n hora @@ -655,7 +655,7 @@ trabalho definido - + %n day(s) ago há %n dia @@ -666,47 +666,47 @@ trabalho definido Reset - + Reset failed. Reboot to try again. Reset falhou. Reinicie para tentar novamente. - + Are you sure you want to reset your device? Tem certeza que quer resetar seu dispositivo? - + Resetting device... Resetando dispositivo... - + System Reset Resetar Sistema - + System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot. Solicitado reset do sistema. Confirme para apagar todo conteúdo e configurações. Aperte cancelar para continuar boot. - + Cancel Cancelar - + Reboot Reiniciar - + Confirm Confirmar - + Unable to mount data partition. Press confirm to reset your device. Não foi possível montar a partição de dados. Pressione confirmar para resetar seu dispositivo. @@ -714,7 +714,7 @@ trabalho definido RichTextDialog - + Ok Ok @@ -722,33 +722,33 @@ trabalho definido SettingsWindow - + × × - + Device Dispositivo - - + + Network Rede - + Toggles Ajustes - + Software Software - + Navigation Navegação @@ -756,105 +756,105 @@ trabalho definido Setup - + WARNING: Low Voltage ALERTA: Baixa Voltagem - + Power your device in a car with a harness or proceed at your own risk. Ligue seu dispositivo em um carro com um chicote ou prossiga por sua conta e risco. - + Power off Desligar - - - + + + Continue Continuar - + Getting Started Começando - + Before we get on the road, let’s finish installation and cover some details. Antes de pegarmos a estrada, vamos terminar a instalação e cobrir alguns detalhes. - + Connect to Wi-Fi Conectar ao Wi-Fi - - + + Back Voltar - + Continue without Wi-Fi Continuar sem Wi-Fi - + Waiting for internet Esperando pela internet - + Choose Software to Install Escolher Software para Instalar - + Dashcam Dashcam - + Custom Software Sofware Customizado - + Enter URL Preencher URL - + for Custom Software para o Software Customizado - + Downloading... Baixando... - + Download Failed Download Falhou - + Ensure the entered URL is valid, and the device’s internet connection is good. Garanta que a URL inserida é valida, e uma boa conexão à internet. - + Reboot device Reiniciar Dispositivo - + Start over Inicializar @@ -862,17 +862,17 @@ trabalho definido SetupWidget - + Finish Setup Concluir - + Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer. Pareie seu dispositivo com comma connect (connect.comma.ai) e reivindique sua oferta de comma prime. - + Pair device Parear dispositivo @@ -880,106 +880,106 @@ trabalho definido Sidebar - - + + CONNECT CONEXÃO - + OFFLINE DESCONEC - - + + ONLINE CONECTADO - + ERROR ERRO - - - + + + TEMP TEMP - + HIGH ALTA - + GOOD BOA - + OK OK - + VEHICLE VEÍCULO - + NO SEM - + PANDA PANDA - + GPS GPS - + SEARCH PROCURA - + -- -- - + Wi-Fi Wi-Fi - + ETH ETH - + 2G 2G - + 3G 3G - + LTE LTE - + 5G 5G @@ -987,89 +987,89 @@ trabalho definido SoftwarePanel - + Git Branch Ramo Git - + Git Commit Commit Git - + OS Version Versão do Sistema - + Version Versão - + Last Update Check Verificação da última atualização - + The last time openpilot successfully checked for an update. The updater only runs while the car is off. A última vez que o openpilot verificou com sucesso uma atualização. O atualizador só funciona com o carro desligado. - + Check for Update Verifique atualizações - + CHECKING VERIFICANDO - + Switch Branch Trocar Branch - + ENTER INSERIR - - + + The new branch will be pulled the next time the updater runs. A nova branch será aplicada ao verificar atualizações. - + Enter branch name Inserir o nome da branch - + UNINSTALL DESINSTALAR - + Uninstall %1 Desintalar o %1 - + Are you sure you want to uninstall? Tem certeza que quer desinstalar? - + failed to fetch update falha ao buscar atualização - - + + CHECK VERIFICAR @@ -1077,48 +1077,48 @@ trabalho definido SshControl - + SSH Keys Chave SSH - + 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. Aviso: isso concede acesso SSH a todas as chaves públicas nas configurações do GitHub. Nunca insira um nome de usuário do GitHub que não seja o seu. Um funcionário da comma NUNCA pedirá que você adicione seu nome de usuário do GitHub. - - + + ADD ADICIONAR - + Enter your GitHub username Insira seu nome de usuário do GitHub - + LOADING CARREGANDO - + REMOVE REMOVER - + Username '%1' has no keys on GitHub Usuário "%1” não possui chaves no GitHub - + Request timed out A solicitação expirou - + Username '%1' doesn't exist on GitHub Usuário '%1' não existe no GitHub @@ -1126,7 +1126,7 @@ trabalho definido SshToggle - + Enable SSH Habilitar SSH @@ -1134,22 +1134,22 @@ trabalho definido TermsPage - + Terms & Conditions Termos & Condições - + Decline Declinar - + Scroll to accept Role a tela para aceitar - + Agree Concordo @@ -1157,92 +1157,92 @@ trabalho definido TogglesPanel - + Enable openpilot Ativar openpilot - + Use the openpilot system for adaptive cruise control and lane keep driver assistance. Your attention is required at all times to use this feature. Changing this setting takes effect when the car is powered off. Use o sistema openpilot para controle de cruzeiro adaptativo e assistência ao motorista de manutenção de faixa. Sua atenção é necessária o tempo todo para usar esse recurso. A alteração desta configuração tem efeito quando o carro é desligado. - + Enable Lane Departure Warnings Ativar Avisos de Saída de Faixa - + 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). Receba alertas para voltar para a pista se o seu veículo sair da faixa e a seta não tiver sido acionada previamente quando em velocidades superiores a 50 km/h. - + Use Metric System Usar Sistema Métrico - + Display speed in km/h instead of mph. Exibir velocidade em km/h invés de mph. - + Record and Upload Driver Camera Gravar e Upload Câmera Motorista - + Upload data from the driver facing camera and help improve the driver monitoring algorithm. Upload dados da câmera voltada para o motorista e ajude a melhorar o algoritmo de monitoramentor. - + 🌮 End-to-end longitudinal (extremely alpha) 🌮 🌮 End-to-end longitudinal (experimental) 🌮 - + Let the driving model control the gas and brakes, openpilot will drive as it thinks a human would. Super experimental. Deixe o modelo de direção controlar o acelerador e o freio, o openpilot dirigirá da maneira como ele entende que um humano o faria. Super experimental. - + Disengage On Accelerator Pedal Desacionar Com Pedal Do Acelerador - + When enabled, pressing the accelerator pedal will disengage openpilot. Quando ativado, pressionar o pedal do acelerador desacionará o openpilot. - + Show ETA in 24h Format Mostrar ETA em formato 24h - + Use 24h format instead of am/pm Use o formato 24h em vez de am/pm - + Show Map on Left Side of UI Exibir Mapa no Lado Esquerdo - + Show map on left side when in split screen view. Exibir mapa do lado esquerdo quando a tela for dividida. - + openpilot Longitudinal Control openpilot Controle Longitudinal - + openpilot will disable the car's radar and will take over control of gas and brakes. Warning: this disables AEB! openpilot desativará o radar do carro e assumirá o controle do acelerador e freios. Atenção: isso desativa AEB! @@ -1250,42 +1250,42 @@ trabalho definido Updater - + Update Required Atualização Necessária - + An operating system update is required. Connect your device to Wi-Fi for the fastest update experience. The download size is approximately 1GB. Uma atualização do sistema operacional é necessária. Conecte seu dispositivo ao Wi-Fi para a experiência de atualização mais rápida. O tamanho do download é de aproximadamente 1GB. - + Connect to Wi-Fi Conecte-se ao Wi-Fi - + Install Instalar - + Back Voltar - + Loading... Carregando... - + Reboot Reiniciar - + Update failed Falha na atualização @@ -1293,23 +1293,23 @@ trabalho definido WifiUI - - + + Scanning for networks... Procurando redes... - + CONNECTING... CONECTANDO... - + FORGET ESQUECER - + Forget Wi-Fi Network "%1"? Esquecer Rede Wi-Fi "%1"? diff --git a/selfdrive/ui/translations/main_zh-CHS.ts b/selfdrive/ui/translations/main_zh-CHS.ts index 1a384482d..79a08899c 100644 --- a/selfdrive/ui/translations/main_zh-CHS.ts +++ b/selfdrive/ui/translations/main_zh-CHS.ts @@ -4,17 +4,17 @@ AbstractAlert - + Close 关闭 - + Snooze Update 暂停更新 - + Reboot and Update 重启并更新 @@ -22,53 +22,53 @@ AdvancedNetworking - + Back 返回 - + Enable Tethering 启用WiFi热点 - + Tethering Password WiFi热点密码 - - + + EDIT 编辑 - + Enter new tethering password 输入新的WiFi热点密码 - + IP Address IP地址 - + Enable Roaming 启用数据漫游 - + APN Setting APN设置 - + Enter APN 输入APN - + leave blank for automatic configuration 留空以自动配置 @@ -76,13 +76,13 @@ ConfirmationDialog - - + + Ok 好的 - + Cancel 取消 @@ -90,17 +90,17 @@ DeclinePage - + You must accept the Terms and Conditions in order to use openpilot. 您必须接受条款和条件以使用openpilot。 - + Back 返回 - + Decline, uninstall %1 拒绝并卸载%1 @@ -108,152 +108,152 @@ DevicePanel - + Dongle ID 设备ID(Dongle ID) - + N/A N/A - + Serial 序列号 - + Driver Camera 驾驶员摄像头 - + PREVIEW 预览 - + Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off) 打开并预览驾驶员摄像头,以确保驾驶员监控具有良好视野。仅熄火时可用。 - + Reset Calibration 重置设备校准 - + RESET 重置 - + Are you sure you want to reset calibration? 您确定要重置设备校准吗? - + Review Training Guide 新手指南 - + REVIEW 查看 - + Review the rules, features, and limitations of openpilot 查看openpilot的使用规则,以及其功能和限制。 - + Are you sure you want to review the training guide? 您确定要查看新手指南吗? - + Regulatory 监管信息 - + VIEW 查看 - + Change Language 切换语言 - + CHANGE 切换 - + Select a language 选择语言 - + Reboot 重启 - + Power Off 关机 - + 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°和右4°之间,俯仰角在上5°和下8°之间。一般来说,openpilot会持续更新校准,很少需要重置。 - + Your device is pointed %1° %2 and %3° %4. 您的设备校准为%1° %2、%3° %4。 - + down 朝下 - + up 朝上 - + left 朝左 - + right 朝右 - + Are you sure you want to reboot? 您确定要重新启动吗? - + Disengage to Reboot 取消openpilot以重新启动 - + Are you sure you want to power off? 您确定要关机吗? - + Disengage to Power Off 取消openpilot以关机 @@ -261,32 +261,32 @@ DriveStats - + Drives 旅程数 - + Hours 小时 - + ALL TIME 全部 - + PAST WEEK 过去一周 - + KM 公里 - + Miles 英里 @@ -294,7 +294,7 @@ DriverViewScene - + camera starting 正在启动相机 @@ -302,12 +302,12 @@ InputDialog - + Cancel 取消 - + Need at least %n character(s)! 至少需要 %n 个字符! @@ -317,22 +317,22 @@ Installer - + Installing... 正在安装…… - + Receiving objects: 正在接收: - + Resolving deltas: 正在处理: - + Updating files: 正在更新文件: @@ -340,27 +340,27 @@ MapETA - + eta 埃塔 - + min 分钟 - + hr 小时 - + km km - + mi mi @@ -368,22 +368,22 @@ MapInstructions - + km km - + m m - + mi mi - + ft ft @@ -391,46 +391,46 @@ MapPanel - + Current Destination 当前目的地 - + CLEAR 清空 - + Recent Destinations 最近目的地 - + Try the Navigation Beta 试用导航测试版 - + Get turn-by-turn directions displayed and more with a comma prime subscription. Sign up now: https://connect.comma.ai 订阅comma prime以获取导航。 立即注册:https://connect.comma.ai - + No home location set 家:未设定 - + No work location set 工作:未设定 - + no recent destinations 无最近目的地 @@ -438,12 +438,12 @@ location set MapWindow - + Map Loading 地图加载中 - + Waiting for GPS 等待 GPS @@ -451,12 +451,12 @@ location set MultiOptionDialog - + Select 选择 - + Cancel 取消 @@ -464,23 +464,23 @@ location set Networking - + Advanced 高级 - + Enter password 输入密码 - - + + for "%1" 网络名称:"%1" - + Wrong password 密码错误 @@ -488,30 +488,30 @@ location set NvgWindow - + km/h km/h - + mph mph - - + + MAX 最高定速 - - + + SPEED SPEED - - + + LIMIT LIMIT @@ -519,17 +519,17 @@ location set OffroadHome - + UPDATE 更新 - + ALERTS 警报 - + ALERT 警报 @@ -537,22 +537,22 @@ location set PairingPopup - + Pair your device to your comma account 将您的设备与comma账号配对 - + Go to https://connect.comma.ai on your phone 在手机上访问 https://connect.comma.ai - + Click "add new device" and scan the QR code on the right 点击“添加新设备”,扫描右侧二维码 - + Bookmark connect.comma.ai to your home screen to use it like an app 将 connect.comma.ai 收藏到您的主屏幕,以便像应用程序一样使用它 @@ -560,32 +560,32 @@ location set PrimeAdWidget - + Upgrade Now 现在升级 - + Become a comma prime member at connect.comma.ai 打开connect.comma.ai以注册comma prime会员 - + PRIME FEATURES: comma prime特权: - + Remote access 远程访问 - + 1 year of storage 1年数据存储 - + Developer perks 开发者福利 @@ -593,22 +593,22 @@ location set PrimeUserWidget - + ✓ SUBSCRIBED ✓ 已订阅 - + comma prime comma prime - + CONNECT.COMMA.AI CONNECT.COMMA.AI - + COMMA POINTS COMMA POINTS点数 @@ -616,41 +616,41 @@ location set QObject - + Reboot 重启 - + Exit 退出 - + dashcam 行车记录仪 - + openpilot openpilot - + %n minute(s) ago %n 分钟前 - + %n hour(s) ago %n 小时前 - + %n day(s) ago %n 天前 @@ -660,47 +660,47 @@ location set Reset - + Reset failed. Reboot to try again. 重置失败。 重新启动以重试。 - + Are you sure you want to reset your device? 您确定要重置您的设备吗? - + Resetting device... 正在重置设备…… - + System Reset 恢复出厂设置 - + System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot. 已触发系统重置:确认以删除所有内容和设置。取消以正常启动设备。 - + Cancel 取消 - + Reboot 重启 - + Confirm 确认 - + Unable to mount data partition. Press confirm to reset your device. 无法挂载数据分区。 确认以重置您的设备。 @@ -708,7 +708,7 @@ location set RichTextDialog - + Ok 好的 @@ -716,33 +716,33 @@ location set SettingsWindow - + × × - + Device 设备 - - + + Network 网络 - + Toggles 设定 - + Software 软件 - + Navigation 导航 @@ -750,105 +750,105 @@ location set Setup - + WARNING: Low Voltage 警告:低电压 - + Power your device in a car with a harness or proceed at your own risk. 请使用car harness线束为您的设备供电,或自行承担风险。 - + Power off 关机 - - - + + + Continue 继续 - + Getting Started 开始设置 - + Before we get on the road, let’s finish installation and cover some details. 开始旅程之前,让我们完成安装并介绍一些细节。 - + Connect to Wi-Fi 连接到WiFi - - + + Back 返回 - + Continue without Wi-Fi 不连接WiFi并继续 - + Waiting for internet 等待网络连接 - + Choose Software to Install 选择要安装的软件 - + Dashcam Dashcam(行车记录仪) - + Custom Software 自定义软件 - + Enter URL 输入网址 - + for Custom Software 以下载自定义软件 - + Downloading... 正在下载…… - + Download Failed 下载失败 - + Ensure the entered URL is valid, and the device’s internet connection is good. 请确保互联网连接良好且输入的URL有效。 - + Reboot device 重启设备 - + Start over 重来 @@ -856,17 +856,17 @@ location set SetupWidget - + Finish Setup 完成设置 - + Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer. 将您的设备与comma connect (connect.comma.ai)配对并领取您的comma prime优惠。 - + Pair device 配对设备 @@ -874,106 +874,106 @@ location set Sidebar - - + + CONNECT CONNECT - + OFFLINE 离线 - - + + ONLINE 在线 - + ERROR 连接出错 - - - + + + TEMP 设备温度 - + HIGH 过热 - + GOOD 良好 - + OK 一般 - + VEHICLE 车辆连接 - + NO - + PANDA PANDA - + GPS GPS - + SEARCH 搜索中 - + -- -- - + Wi-Fi Wi-Fi - + ETH 以太网 - + 2G 2G - + 3G 3G - + LTE LTE - + 5G 5G @@ -981,89 +981,89 @@ 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. 上一次成功检查更新的时间。更新程序仅在汽车熄火时运行。 - + Check for Update 检查更新 - + CHECKING 正在检查更新 - + Switch Branch 切换分支 - + ENTER 输入 - - + + The new branch will be pulled the next time the updater runs. 分支将在更新服务下次启动时自动切换。 - + Enter branch name 输入分支名称 - + UNINSTALL 卸载 - + Uninstall %1 卸载 %1 - + Are you sure you want to uninstall? 您确定要卸载吗? - + failed to fetch update 获取更新失败 - - + + CHECK 查看 @@ -1071,48 +1071,48 @@ location set SshControl - + SSH Keys SSH密钥 - + 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. 警告:这将授予SSH访问权限给您GitHub设置中的所有公钥。切勿输入您自己以外的GitHub用户名。comma员工永远不会要求您添加他们的GitHub用户名。 - - + + ADD 添加 - + Enter your GitHub username 输入您的GitHub用户名 - + LOADING 正在加载 - + REMOVE 删除 - + Username '%1' has no keys on GitHub 用户名“%1”在GitHub上没有密钥 - + Request timed out 请求超时 - + Username '%1' doesn't exist on GitHub GitHub上不存在用户名“%1” @@ -1120,7 +1120,7 @@ location set SshToggle - + Enable SSH 启用SSH @@ -1128,22 +1128,22 @@ location set TermsPage - + Terms & Conditions 条款和条件 - + Decline 拒绝 - + Scroll to accept 滑动以接受 - + Agree 同意 @@ -1151,92 +1151,92 @@ location set TogglesPanel - + Enable openpilot 启用openpilot - + Use the openpilot system for adaptive cruise control and lane keep driver assistance. Your attention is required at all times to use this feature. Changing this setting takes effect when the car is powered off. 使用openpilot进行自适应巡航和车道保持辅助。使用此功能时您必须时刻保持注意力。该设置的更改在熄火时生效。 - + Enable Lane Departure Warnings 启用车道偏离警告 - + Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31 mph (50 km/h). 车速超过31mph(50km/h)时,若检测到车辆越过车道线且未打转向灯,系统将发出警告以提醒您返回车道。 - + Use Metric System 使用公制单位 - + Display speed in km/h instead of mph. 显示车速时,以km/h代替mph。 - + Record and Upload Driver Camera 录制并上传驾驶员摄像头 - + Upload data from the driver facing camera and help improve the driver monitoring algorithm. 上传驾驶员摄像头的数据,帮助改进驾驶员监控算法。 - + 🌮 End-to-end longitudinal (extremely alpha) 🌮 - + Let the driving model control the gas and brakes, openpilot will drive as it thinks a human would. Super experimental. - + Disengage On Accelerator Pedal 踩油门时取消控制 - + When enabled, pressing the accelerator pedal will disengage openpilot. 启用后,踩下油门踏板将取消openpilot。 - + Show ETA in 24h Format 以24小时格式显示预计到达时间 - + Use 24h format instead of am/pm 使用24小时制代替am/pm - + Show Map on Left Side of UI 在介面左侧显示地图 - + 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将被禁用! @@ -1244,42 +1244,42 @@ 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. 操作系统需要更新。请将您的设备连接到WiFi以获取更快的更新体验。下载大小约为1GB。 - + Connect to Wi-Fi 连接到WiFi - + Install 安装 - + Back 返回 - + Loading... 正在加载…… - + Reboot 重启 - + Update failed 更新失败 @@ -1287,23 +1287,23 @@ location set WifiUI - - + + Scanning for networks... 正在扫描网络…… - + CONNECTING... 正在连接…… - + FORGET 忘记 - + Forget Wi-Fi Network "%1"? 忘记WiFi网络 "%1"? diff --git a/selfdrive/ui/translations/main_zh-CHT.ts b/selfdrive/ui/translations/main_zh-CHT.ts index d7dd5cb56..0d51e6d28 100644 --- a/selfdrive/ui/translations/main_zh-CHT.ts +++ b/selfdrive/ui/translations/main_zh-CHT.ts @@ -4,17 +4,17 @@ AbstractAlert - + Close 關閉 - + Snooze Update 暫停更新 - + Reboot and Update 重啟並更新 @@ -22,53 +22,53 @@ AdvancedNetworking - + Back 回上頁 - + Enable Tethering 啟用網路分享 - + Tethering Password 網路分享密碼 - - + + EDIT 編輯 - + Enter new tethering password 輸入新的網路分享密碼 - + IP Address IP 地址 - + Enable Roaming 啟用漫遊 - + APN Setting APN 設置 - + Enter APN 輸入 APN - + leave blank for automatic configuration 留空白將自動配置 @@ -76,13 +76,13 @@ ConfirmationDialog - - + + Ok 確定 - + Cancel 取消 @@ -90,17 +90,17 @@ DeclinePage - + You must accept the Terms and Conditions in order to use openpilot. 您必須先接受條款和條件才能使用 openpilot。 - + Back 回上頁 - + Decline, uninstall %1 拒絕並卸載 %1 @@ -108,152 +108,152 @@ DevicePanel - + Dongle ID Dongle ID - + N/A 無法使用 - + Serial 序號 - + Driver Camera 駕駛員攝像頭 - + PREVIEW 預覽 - + Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off) 預覽駕駛員監控鏡頭畫面,以確保其具有良好視野。(僅在熄火時可用) - + Reset Calibration 重置校準 - + RESET 重置 - + Are you sure you want to reset calibration? 您確定要重置校準嗎? - + Review Training Guide 觀看使用教學 - + REVIEW 觀看 - + Review the rules, features, and limitations of openpilot 觀看 openpilot 的使用規則、功能和限制 - + Are you sure you want to review the training guide? 您確定要觀看使用教學嗎? - + Regulatory 法規/監管 - + VIEW 觀看 - + Change Language 更改語言 - + CHANGE 更改 - + Select a language 選擇語言 - + Reboot 重新啟動 - + Power Off 關機 - + 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° 以内。鏡頭在後台會持續自動校準,很少有需要重置的情况。 - + Your device is pointed %1° %2 and %3° %4. 你的設備目前朝%2 %1° 以及朝%4 %3° 。 - + down - + up - + left - + right - + Are you sure you want to reboot? 您確定要重新啟動嗎? - + Disengage to Reboot 請先取消控車才能重新啟動 - + Are you sure you want to power off? 您確定您要關機嗎? - + Disengage to Power Off 請先取消控車才能關機 @@ -261,32 +261,32 @@ DriveStats - + Drives 旅程 - + Hours 小時 - + ALL TIME 總共 - + PAST WEEK 上周 - + KM 公里 - + Miles 英里 @@ -294,7 +294,7 @@ DriverViewScene - + camera starting 開啟相機中 @@ -302,12 +302,12 @@ InputDialog - + Cancel 取消 - + Need at least %n character(s)! 需要至少 %n 個字元! @@ -317,22 +317,22 @@ Installer - + Installing... 安裝中… - + Receiving objects: 接收對象: - + Resolving deltas: 分析差異: - + Updating files: 更新檔案: @@ -340,27 +340,27 @@ MapETA - + eta 抵達 - + min 分鐘 - + hr 小時 - + km km - + mi mi @@ -368,22 +368,22 @@ MapInstructions - + km km - + m m - + mi mi - + ft ft @@ -391,48 +391,48 @@ MapPanel - + Current Destination 當前目的地 - + CLEAR 清除 - + Recent Destinations 最近目的地 - + Try the Navigation Beta 試用導航功能 - + Get turn-by-turn directions displayed and more with a comma prime subscription. Sign up now: https://connect.comma.ai 成為 comma 高級會員來使用導航功能 立即註冊:https://connect.comma.ai - + No home location set 未設定 住家位置 - + No work location set 未設定 工作位置 - + no recent destinations 沒有最近的導航記錄 @@ -440,12 +440,12 @@ location set MapWindow - + Map Loading 地圖加載中 - + Waiting for GPS 等待 GPS @@ -453,12 +453,12 @@ location set MultiOptionDialog - + Select 選擇 - + Cancel 取消 @@ -466,23 +466,23 @@ location set Networking - + Advanced 進階 - + Enter password 輸入密碼 - - + + for "%1" 給 "%1" - + Wrong password 密碼錯誤 @@ -490,30 +490,30 @@ location set NvgWindow - + km/h km/h - + mph mph - - + + MAX 最高 - - + + SPEED 速度 - - + + LIMIT 速限 @@ -521,17 +521,17 @@ location set OffroadHome - + UPDATE 更新 - + ALERTS 提醒 - + ALERT 提醒 @@ -539,22 +539,22 @@ location set PairingPopup - + Pair your device to your comma account 將設備與您的 comma 帳號配對 - + Go to https://connect.comma.ai on your phone 用手機連至 https://connect.comma.ai - + Click "add new device" and scan the QR code on the right 點選 "add new device" 後掃描右邊的二維碼 - + Bookmark connect.comma.ai to your home screen to use it like an app 將 connect.comma.ai 加入您的主屏幕,以便像手機 App 一樣使用它 @@ -562,32 +562,32 @@ location set PrimeAdWidget - + Upgrade Now 馬上升級 - + Become a comma prime member at connect.comma.ai 成為 connect.comma.ai 的高級會員 - + PRIME FEATURES: 高級會員特點: - + Remote access 遠程訪問 - + 1 year of storage 一年的雲端行車記錄 - + Developer perks 開發者福利 @@ -595,22 +595,22 @@ location set PrimeUserWidget - + ✓ SUBSCRIBED ✓ 已訂閱 - + comma prime comma 高級會員 - + CONNECT.COMMA.AI CONNECT.COMMA.AI - + COMMA POINTS COMMA 積分 @@ -618,41 +618,41 @@ location set QObject - + Reboot 重新啟動 - + Exit 離開 - + dashcam 行車記錄器 - + openpilot openpilot - + %n minute(s) ago %n 分鐘前 - + %n hour(s) ago %n 小時前 - + %n day(s) ago %n 天前 @@ -662,47 +662,47 @@ location set Reset - + Reset failed. Reboot to try again. 重置失敗。請重新啟動後再試。 - + Are you sure you want to reset your device? 您確定要重置你的設備嗎? - + Resetting device... 重置設備中… - + System Reset 系統重置 - + System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot. 系統重置已觸發。請按確認刪除所有內容和設置。按取消恢復啟動。 - + Cancel 取消 - + Reboot 重新啟動 - + Confirm 確認 - + Unable to mount data partition. Press confirm to reset your device. 無法掛載數據分區。請按確認重置您的設備。 @@ -710,7 +710,7 @@ location set RichTextDialog - + Ok 確定 @@ -718,33 +718,33 @@ location set SettingsWindow - + × × - + Device 設備 - - + + Network 網路 - + Toggles 設定 - + Software 軟體 - + Navigation 導航 @@ -752,105 +752,105 @@ location set Setup - + WARNING: Low Voltage 警告:電壓過低 - + Power your device in a car with a harness or proceed at your own risk. 請使用車上 harness 提供的電源,若繼續的話您需要自擔風險。 - + Power off 關機 - - - + + + Continue 繼續 - + Getting Started 入門 - + Before we get on the road, let’s finish installation and cover some details. 在我們上路之前,讓我們完成安裝並介紹一些細節。 - + Connect to Wi-Fi 連接到無線網絡 - - + + Back 回上頁 - + Continue without Wi-Fi 在沒有 Wi-Fi 的情況下繼續 - + Waiting for internet 連接至網路中 - + Choose Software to Install 選擇要安裝的軟體 - + Dashcam 行車記錄器 - + Custom Software 定制的軟體 - + Enter URL 輸入網址 - + for Custom Software 定制的軟體 - + Downloading... 下載中… - + Download Failed 下載失敗 - + Ensure the entered URL is valid, and the device’s internet connection is good. 請確定您輸入的是有效的安裝網址,並且確定設備的網路連線狀態良好。 - + Reboot device 重新啟動 - + Start over 重新開始 @@ -858,17 +858,17 @@ location set SetupWidget - + Finish Setup 完成設置 - + Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer. 將您的設備與 comma connect (connect.comma.ai) 配對並領取您的 comma 高級會員優惠。 - + Pair device 配對設備 @@ -876,106 +876,106 @@ location set Sidebar - - + + CONNECT 雲端服務 - + OFFLINE 已離線 - - + + ONLINE 已連線 - + ERROR 錯誤 - - - + + + TEMP 溫度 - + HIGH 偏高 - + GOOD 正常 - + OK 一般 - + VEHICLE 車輛通訊 - + NO 未連線 - + PANDA 車輛通訊 - + GPS GPS - + SEARCH 車輛通訊 - + -- -- - + Wi-Fi - + ETH - + 2G - + 3G - + LTE - + 5G @@ -983,89 +983,89 @@ location set SoftwarePanel - + Git Branch Git 分支 - + Git Commit Git 提交 - + OS Version 系統版本 - + Version 版本 - + Last Update Check 上次檢查時間 - + The last time openpilot successfully checked for an update. The updater only runs while the car is off. 上次成功檢查更新的時間。更新系統只會在車子熄火時執行。 - + Check for Update 檢查更新 - + CHECKING 檢查中 - + Switch Branch 切換分支 - + ENTER 切換 - - + + The new branch will be pulled the next time the updater runs. 新的分支將會在下次檢查更新時切換過去。 - + Enter branch name 輸入分支名稱 - + UNINSTALL 卸載 - + Uninstall %1 卸載 %1 - + Are you sure you want to uninstall? 您確定您要卸載嗎? - + failed to fetch update 下載更新失敗 - - + + CHECK 檢查 @@ -1073,48 +1073,48 @@ location set SshControl - + SSH Keys SSH 密鑰 - + 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 用戶名。comma 員工「永遠不會」要求您添加他們的 GitHub 用戶名。 - - + + ADD 新增 - + Enter your GitHub username 請輸入您 GitHub 的用戶名 - + LOADING 載入中 - + REMOVE 移除 - + Username '%1' has no keys on GitHub GitHub 用戶 '%1' 沒有設定任何密鑰 - + Request timed out 請求超時 - + Username '%1' doesn't exist on GitHub GitHub 用戶 '%1' 不存在 @@ -1122,7 +1122,7 @@ location set SshToggle - + Enable SSH 啟用 SSH 服務 @@ -1130,22 +1130,22 @@ location set TermsPage - + Terms & Conditions 條款和條件 - + Decline 拒絕 - + Scroll to accept 滑動至頁尾接受條款 - + Agree 接受 @@ -1153,92 +1153,92 @@ location set TogglesPanel - + Enable openpilot 啟用 openpilot - + Use the openpilot system for adaptive cruise control and lane keep driver assistance. Your attention is required at all times to use this feature. Changing this setting takes effect when the car is powered off. 使用 openpilot 的主動式巡航和車道保持功能,開啟後您需要持續集中注意力,設定變更在重新啟動車輛後生效。 - + Enable Lane Departure Warnings 啟用車道偏離警告 - + Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31 mph (50 km/h). 車速在時速 50 公里 (31 英里) 以上且未打方向燈的情況下,如果偵測到車輛駛出目前車道線時,發出車道偏離警告。 - + Use Metric System 使用公制單位 - + Display speed in km/h instead of mph. 啟用後,速度單位顯示將從 mp/h 改為 km/h。 - + Record and Upload Driver Camera 記錄並上傳駕駛監控影像 - + Upload data from the driver facing camera and help improve the driver monitoring algorithm. 上傳駕駛監控的錄像來協助我們提升駕駛監控的準確率。 - + 🌮 End-to-end longitudinal (extremely alpha) 🌮 - + Let the driving model control the gas and brakes, openpilot will drive as it thinks a human would. Super experimental. - + Disengage On Accelerator Pedal 油門取消控車 - + When enabled, pressing the accelerator pedal will disengage openpilot. 啟用後,踩踏油門將會取消 openpilot 控制。 - + Show ETA in 24h Format 預計到達時間單位改用 24 小時制 - + Use 24h format instead of am/pm 使用 24 小時制。(預設值為 12 小時制) - + Show Map on Left Side of UI 將地圖顯示在畫面的左側 - + 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) 系統! @@ -1246,42 +1246,42 @@ 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。 - + Connect to Wi-Fi 連接到無線網絡 - + Install 安裝 - + Back 回上頁 - + Loading... 載入中… - + Reboot 重新啟動 - + Update failed 更新失敗 @@ -1289,23 +1289,23 @@ location set WifiUI - - + + Scanning for networks... 掃描無線網路中... - + CONNECTING... 連線中... - + FORGET 清除 - + Forget Wi-Fi Network "%1"? 清除 Wi-Fi 網路 "%1"? diff --git a/selfdrive/ui/update_translations.py b/selfdrive/ui/update_translations.py index e509168ad..afd42c3b3 100755 --- a/selfdrive/ui/update_translations.py +++ b/selfdrive/ui/update_translations.py @@ -19,7 +19,7 @@ def update_translations(vanish=False, plural_only=None, translations_dir=TRANSLA for file in translation_files.values(): tr_file = os.path.join(translations_dir, f"{file}.ts") - args = f"lupdate -recursive {UI_DIR} -ts {tr_file}" + args = f"lupdate -locations relative -recursive {UI_DIR} -ts {tr_file}" if vanish: args += " -no-obsolete" if file in plural_only: From 50d117ed9a0c75a7374e76ec6e42d1a603bb11b0 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 6 Sep 2022 19:30:34 -0700 Subject: [PATCH 163/172] =?UTF-8?q?Toyota:=20remove=20100=C2=B0/sec=20stee?= =?UTF-8?q?ring=20lockout=20(#24067)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * try a method to kill those faults * cut torque for 1 frame * sign doesn't seem to matter * clean up * better name * Toyota allows you to keep your apply_steer, better control * the logic was wrong entire time? * cut steer for two frames * Revert "cut steer for two frames" This reverts commit 13a68ecc568fe1c0cd1f6f0b5f7ff6560efaf9e0. * better variable names and comments better variable names and comments * should be good * add safety * actual number of frames * constant * bump panda * bump panda * bump panda * bump panda * bump panda * bump panda * bump panda * fix to use min valid frames * rm line * simplify check * bump panda * bump panda to master --- panda | 2 +- selfdrive/car/toyota/carcontroller.py | 17 +++++++++++++++-- 2 files changed, 16 insertions(+), 3 deletions(-) diff --git a/panda b/panda index 13d64d4cc..0ca23b677 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 13d64d4cc38295401ff1ffcf6a233a4b9625fd9f +Subproject commit 0ca23b67786d0fa2a3162371aadeca52d24a8958 diff --git a/selfdrive/car/toyota/carcontroller.py b/selfdrive/car/toyota/carcontroller.py index 3288bcaed..511017a55 100644 --- a/selfdrive/car/toyota/carcontroller.py +++ b/selfdrive/car/toyota/carcontroller.py @@ -10,6 +10,10 @@ from opendbc.can.packer import CANPacker VisualAlert = car.CarControl.HUDControl.VisualAlert +# constants for fault workaround +MAX_STEER_RATE = 100 # deg/s +MAX_STEER_RATE_FRAMES = 18 # control frames allowed where steering rate >= MAX_STEER_RATE + class CarController: def __init__(self, dbc_name, CP, VM): @@ -20,6 +24,7 @@ class CarController: self.alert_active = False self.last_standstill = False self.standstill_req = False + self.steer_rate_counter = 0 self.packer = CANPacker(dbc_name) self.gas = 0 @@ -52,11 +57,19 @@ class CarController: new_steer = int(round(actuators.steer * CarControllerParams.STEER_MAX)) apply_steer = apply_toyota_steer_torque_limits(new_steer, self.last_steer, CS.out.steeringTorqueEps, self.torque_rate_limits) + # Count up to MAX_STEER_RATE_FRAMES, at which point we need to cut torque to avoid a steering fault + if CC.latActive and abs(CS.out.steeringRateDeg) >= MAX_STEER_RATE: + self.steer_rate_counter += 1 + else: + self.steer_rate_counter = 0 + + apply_steer_req = 1 if not CC.latActive: apply_steer = 0 apply_steer_req = 0 - else: - apply_steer_req = 1 + elif self.steer_rate_counter > MAX_STEER_RATE_FRAMES: + apply_steer_req = 0 + self.steer_rate_counter = 0 # TODO: probably can delete this. CS.pcm_acc_status uses a different signal # than CS.cruiseState.enabled. confirm they're not meaningfully different From 210a6163ac9a8ccc425114fd722e864befa77966 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Tue, 6 Sep 2022 21:30:10 -0700 Subject: [PATCH 164/172] Let planner decide stopping state (#25643) * Let planner decide stopping * Refactor stop/start state machine * Stay stoppe condition * 1sec from target * Add starting state * Add starting state logic * Undo some changes * Update ref --- cereal | 2 +- selfdrive/car/toyota/tunes.py | 2 +- selfdrive/controls/lib/longcontrol.py | 91 ++++++++++++++---------- selfdrive/test/process_replay/ref_commit | 2 +- 4 files changed, 56 insertions(+), 41 deletions(-) diff --git a/cereal b/cereal index 632395010..3248f6658 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 632395010102aabdd0ed87aba50d25042cdcb70e +Subproject commit 3248f6658f58551ce0de9e3ea712d67896e196fd diff --git a/selfdrive/car/toyota/tunes.py b/selfdrive/car/toyota/tunes.py index a8b8758d8..fc538b969 100644 --- a/selfdrive/car/toyota/tunes.py +++ b/selfdrive/car/toyota/tunes.py @@ -38,7 +38,7 @@ def set_long_tune(tune, name): # Default longitudinal tune elif name == LongTunes.TSS: tune.deadzoneBP = [0., 9.] - tune.deadzoneV = [0., .15] + tune.deadzoneV = [.0, .15] tune.kpBP = [0., 5., 35.] tune.kiBP = [0., 35.] tune.kpV = [3.6, 2.4, 1.5] diff --git a/selfdrive/controls/lib/longcontrol.py b/selfdrive/controls/lib/longcontrol.py index e9458607d..082e7725d 100644 --- a/selfdrive/controls/lib/longcontrol.py +++ b/selfdrive/controls/lib/longcontrol.py @@ -11,16 +11,21 @@ LongCtrlState = car.CarControl.Actuators.LongControlState ACCEL_MIN_ISO = -3.5 # m/s^2 ACCEL_MAX_ISO = 2.0 # m/s^2 - def long_control_state_trans(CP, active, long_control_state, v_ego, v_target, - v_target_future, brake_pressed, cruise_standstill): - """Update longitudinal control state machine""" - accelerating = v_target_future > v_target - stopping_condition = (v_ego < 2.0 and cruise_standstill) or \ - (v_ego < CP.vEgoStopping and - ((v_target_future < CP.vEgoStopping and not accelerating) or brake_pressed)) - - starting_condition = v_target_future > CP.vEgoStarting and accelerating and not cruise_standstill + v_target_1sec, brake_pressed, cruise_standstill): + accelerating = v_target_1sec > v_target + planned_stop = (v_target < CP.vEgoStopping and + v_target_1sec < CP.vEgoStopping and + not accelerating) + stay_stopped = (v_ego < CP.vEgoStopping and + (brake_pressed or cruise_standstill)) + stopping_condition = planned_stop or stay_stopped + + starting_condition = (v_target_1sec > CP.vEgoStarting and + accelerating and + not cruise_standstill and + not brake_pressed) + started_condition = v_ego > CP.vEgoStarting if not active: long_control_state = LongCtrlState.off @@ -34,9 +39,21 @@ def long_control_state_trans(CP, active, long_control_state, v_ego, v_target, long_control_state = LongCtrlState.stopping elif long_control_state == LongCtrlState.stopping: - if starting_condition: + if starting_condition and CP.startingState: + long_control_state = LongCtrlState.starting + elif starting_condition: + long_control_state = LongCtrlState.pid + + elif long_control_state == LongCtrlState.starting: + if stopping_condition: + long_control_state = LongCtrlState.stopping + elif started_condition: long_control_state = LongCtrlState.pid + + + + return long_control_state @@ -60,64 +77,62 @@ class LongControl: # Interp control trajectory speeds = long_plan.speeds if len(speeds) == CONTROL_N: - v_target = interp(t_since_plan, T_IDXS[:CONTROL_N], speeds) - a_target = interp(t_since_plan, T_IDXS[:CONTROL_N], long_plan.accels) + v_target_now = interp(t_since_plan, T_IDXS[:CONTROL_N], speeds) + a_target_now = interp(t_since_plan, T_IDXS[:CONTROL_N], long_plan.accels) v_target_lower = interp(self.CP.longitudinalActuatorDelayLowerBound + t_since_plan, T_IDXS[:CONTROL_N], speeds) - a_target_lower = 2 * (v_target_lower - v_target) / self.CP.longitudinalActuatorDelayLowerBound - a_target + a_target_lower = 2 * (v_target_lower - v_target_now) / self.CP.longitudinalActuatorDelayLowerBound - a_target_now v_target_upper = interp(self.CP.longitudinalActuatorDelayUpperBound + t_since_plan, T_IDXS[:CONTROL_N], speeds) - a_target_upper = 2 * (v_target_upper - v_target) / self.CP.longitudinalActuatorDelayUpperBound - a_target + a_target_upper = 2 * (v_target_upper - v_target_now) / self.CP.longitudinalActuatorDelayUpperBound - a_target_now + + v_target = min(v_target_lower, v_target_upper) a_target = min(a_target_lower, a_target_upper) - v_target_future = speeds[-1] + v_target_1sec = interp(self.CP.longitudinalActuatorDelayUpperBound + t_since_plan + 1.0, T_IDXS[:CONTROL_N], speeds) else: v_target = 0.0 - v_target_future = 0.0 + v_target_1sec = 0.0 a_target = 0.0 - # TODO: This check is not complete and needs to be enforced by MPC - a_target = clip(a_target, ACCEL_MIN_ISO, ACCEL_MAX_ISO) - self.pid.neg_limit = accel_limits[0] self.pid.pos_limit = accel_limits[1] - # Update state machine output_accel = self.last_output_accel self.long_control_state = long_control_state_trans(self.CP, active, self.long_control_state, CS.vEgo, - v_target, v_target_future, CS.brakePressed, + v_target, v_target_1sec, CS.brakePressed, CS.cruiseState.standstill) if self.long_control_state == LongCtrlState.off: self.reset(CS.vEgo) output_accel = 0. - # tracking objects and driving + elif self.long_control_state == LongCtrlState.stopping: + if output_accel > self.CP.stopAccel: + output_accel -= self.CP.stoppingDecelRate * DT_CTRL + self.reset(CS.vEgo) + + elif self.long_control_state == LongCtrlState.starting: + output_accel = self.CP.startAccel + self.reset(CS.vEgo) + elif self.long_control_state == LongCtrlState.pid: - self.v_pid = v_target + self.v_pid = v_target_now # Toyota starts braking more when it thinks you want to stop # Freeze the integrator so we don't accelerate to compensate, and don't allow positive acceleration - prevent_overshoot = not self.CP.stoppingControl and CS.vEgo < 1.5 and v_target_future < 0.7 and v_target_future < self.v_pid + # TODO too complex, needs to be simplified and tested on toyotas + prevent_overshoot = not self.CP.stoppingControl and CS.vEgo < 1.5 and v_target_1sec < 0.7 and v_target_1sec < self.v_pid deadzone = interp(CS.vEgo, self.CP.longitudinalTuning.deadzoneBP, self.CP.longitudinalTuning.deadzoneV) freeze_integrator = prevent_overshoot error = self.v_pid - CS.vEgo error_deadzone = apply_deadzone(error, deadzone) - output_accel = self.pid.update(error_deadzone, speed=CS.vEgo, feedforward=a_target, freeze_integrator=freeze_integrator) - - if prevent_overshoot: - output_accel = min(output_accel, 0.0) + output_accel = self.pid.update(error_deadzone, speed=CS.vEgo, + feedforward=a_target, + freeze_integrator=freeze_integrator) - # Intention is to stop, switch to a different brake control until we stop - elif self.long_control_state == LongCtrlState.stopping: - # Keep applying brakes until the car is stopped - if not CS.standstill or output_accel > self.CP.stopAccel: - output_accel -= self.CP.stoppingDecelRate * DT_CTRL - output_accel = clip(output_accel, accel_limits[0], accel_limits[1]) - self.reset(CS.vEgo) - self.last_output_accel = output_accel - final_accel = clip(output_accel, accel_limits[0], accel_limits[1]) + self.last_output_accel = clip(output_accel, accel_limits[0], accel_limits[1]) - return final_accel + return self.last_output_accel diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 20bb4c82f..0e2a5d84e 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -915309019fef256512ee30cf92cfae2e479dd04e \ No newline at end of file +209423f468194c77443110078639ff67a8b99073 From 7899fb79c1b3c56034dea3ceb70955f94fdb5ff4 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Tue, 6 Sep 2022 21:52:34 -0700 Subject: [PATCH 165/172] More conservative lead policy in e2e long mode (#25684) * Add params for lead and danger * fix long params * E2e passes simple maneuver tests * Make tests run with e2e long mode * Slightly more error allowed in e2e mode * FCW back and populate long source field * Fix planner name * FCW still doesnt work * Slightly less aggressive * Doesn't need to simulate from stop --- .../lib/longitudinal_mpc_lib/long_mpc.py | 40 ++++++++++++++----- .../controls/lib/longitudinal_planner.py | 2 +- selfdrive/controls/plannerd.py | 4 +- selfdrive/controls/tests/test_cruise_speed.py | 20 ++++++---- .../controls/tests/test_following_distance.py | 23 ++++++----- .../test/longitudinal_maneuvers/maneuver.py | 4 +- .../test/longitudinal_maneuvers/plant.py | 21 +++++++++- .../test_longitudinal.py | 11 ++++- 8 files changed, 91 insertions(+), 34 deletions(-) diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py b/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py index 405ef8191..ea9b0683a 100644 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py @@ -24,7 +24,7 @@ SOURCES = ['lead0', 'lead1', 'cruise', 'e2e'] X_DIM = 3 U_DIM = 1 -PARAM_DIM = 4 +PARAM_DIM = 6 COST_E_DIM = 5 COST_DIM = COST_E_DIM + 1 CONSTR_DIM = 4 @@ -37,6 +37,7 @@ J_EGO_COST = 5.0 A_CHANGE_COST = 200. DANGER_ZONE_COST = 100. CRASH_DISTANCE = .5 +LEAD_DANGER_FACTOR = 0.75 LIMIT_COST = 1e6 ACADOS_SOLVER_TYPE = 'SQP_RTI' @@ -58,8 +59,8 @@ STOP_DISTANCE = 6.0 def get_stopped_equivalence_factor(v_lead): return (v_lead**2) / (2 * COMFORT_BRAKE) -def get_safe_obstacle_distance(v_ego): - return (v_ego**2) / (2 * COMFORT_BRAKE) + T_FOLLOW * v_ego + STOP_DISTANCE +def get_safe_obstacle_distance(v_ego, t_follow=T_FOLLOW): + return (v_ego**2) / (2 * COMFORT_BRAKE) + t_follow * v_ego + STOP_DISTANCE def desired_follow_distance(v_ego, v_lead): return get_safe_obstacle_distance(v_ego) - get_stopped_equivalence_factor(v_lead) @@ -90,7 +91,9 @@ def gen_long_model(): a_max = SX.sym('a_max') x_obstacle = SX.sym('x_obstacle') prev_a = SX.sym('prev_a') - model.p = vertcat(a_min, a_max, x_obstacle, prev_a) + lead_t_follow = SX.sym('lead_t_follow') + lead_danger_factor = SX.sym('lead_danger_factor') + model.p = vertcat(a_min, a_max, x_obstacle, prev_a, lead_t_follow, lead_danger_factor) # dynamics model f_expl = vertcat(v_ego, a_ego, j_ego) @@ -124,11 +127,13 @@ def gen_long_ocp(): a_min, a_max = ocp.model.p[0], ocp.model.p[1] x_obstacle = ocp.model.p[2] prev_a = ocp.model.p[3] + lead_t_follow = ocp.model.p[4] + lead_danger_factor = ocp.model.p[5] ocp.cost.yref = np.zeros((COST_DIM, )) ocp.cost.yref_e = np.zeros((COST_E_DIM, )) - desired_dist_comfort = get_safe_obstacle_distance(v_ego) + desired_dist_comfort = get_safe_obstacle_distance(v_ego, lead_t_follow) # The main cost in normal operation is how close you are to the "desired" distance # from an obstacle at every timestep. This obstacle can be a lead car @@ -149,12 +154,12 @@ def gen_long_ocp(): constraints = vertcat(v_ego, (a_ego - a_min), (a_max - a_ego), - ((x_obstacle - x_ego) - (3/4) * (desired_dist_comfort)) / (v_ego + 10.)) + ((x_obstacle - x_ego) - lead_danger_factor * (desired_dist_comfort)) / (v_ego + 10.)) ocp.model.con_h_expr = constraints x0 = np.zeros(X_DIM) ocp.constraints.x0 = x0 - ocp.parameter_values = np.array([-1.2, 1.2, 0.0, 0.0]) + ocp.parameter_values = np.array([-1.2, 1.2, 0.0, 0.0, T_FOLLOW, LEAD_DANGER_FACTOR]) # We put all constraint cost weights to 0 and only set them at runtime cost_weights = np.zeros(CONSTR_DIM) @@ -249,7 +254,7 @@ class LongitudinalMpc: constraint_cost_weights = [LIMIT_COST, LIMIT_COST, LIMIT_COST, DANGER_ZONE_COST] elif self.mode == 'blended': cost_weights = [0., 0.2, 0.25, 1.0, 0.0, 1.0] - constraint_cost_weights = [LIMIT_COST, LIMIT_COST, LIMIT_COST, 5.0] + constraint_cost_weights = [LIMIT_COST, LIMIT_COST, LIMIT_COST, 50.0] elif self.mode == 'e2e': cost_weights = [0., 0.2, 0.25, 1., 0.0, .1] constraint_cost_weights = [LIMIT_COST, LIMIT_COST, LIMIT_COST, 0.0] @@ -317,6 +322,7 @@ class LongitudinalMpc: if self.mode == 'acc': self.params[:,0] = MIN_ACCEL if self.status else self.cruise_min_a self.params[:,1] = self.cruise_max_a + self.params[:,5] = LEAD_DANGER_FACTOR # Fake an obstacle for cruise, this ensures smooth acceleration to set speed # when the leads are no factor. @@ -335,6 +341,7 @@ class LongitudinalMpc: elif self.mode == 'blended': self.params[:,0] = MIN_ACCEL self.params[:,1] = MAX_ACCEL + self.params[:,5] = 1.0 x_obstacles = np.column_stack([lead_0_obstacle, lead_1_obstacle]) @@ -344,7 +351,8 @@ class LongitudinalMpc: x_and_cruise = np.column_stack([x, cruise_target]) x = np.min(x_and_cruise, axis=1) - self.source = 'e2e' + + self.source = 'e2e' if x_and_cruise[0,0] < x_and_cruise[0,1] else 'cruise' else: raise NotImplementedError(f'Planner mode {self.mode} not recognized in planner update') @@ -359,6 +367,7 @@ class LongitudinalMpc: self.params[:,2] = np.min(x_obstacles, axis=1) self.params[:,3] = np.copy(self.prev_a) + self.params[:,4] = T_FOLLOW self.run() if (np.any(lead_xv_0[:,0] - self.x_sol[:,0] < CRASH_DISTANCE) and @@ -367,10 +376,23 @@ class LongitudinalMpc: else: self.crash_cnt = 0 + # Check if it got within lead comfort range + # TODO This should be done cleaner + if self.mode == 'blended': + if any((lead_0_obstacle - get_safe_obstacle_distance(self.x_sol[:,1], T_FOLLOW))- self.x_sol[:,0] < 0.0): + self.source = 'lead0' + if any((lead_1_obstacle - get_safe_obstacle_distance(self.x_sol[:,1], T_FOLLOW))- self.x_sol[:,0] < 0.0) and \ + (lead_1_obstacle[0] - lead_0_obstacle[0]): + self.source = 'lead1' + + + def update_with_xva(self, x, v, a): self.params[:,0] = -10. self.params[:,1] = 10. self.params[:,2] = 1e5 + self.params[:,4] = T_FOLLOW + self.params[:,5] = LEAD_DANGER_FACTOR # v, and a are in local frame, but x is wrt the x[0] position # In >90degree turns, x goes to 0 (and may even be -ve) diff --git a/selfdrive/controls/lib/longitudinal_planner.py b/selfdrive/controls/lib/longitudinal_planner.py index b6120d245..b9bf5dcbf 100755 --- a/selfdrive/controls/lib/longitudinal_planner.py +++ b/selfdrive/controls/lib/longitudinal_planner.py @@ -45,7 +45,7 @@ def limit_accel_in_turns(v_ego, angle_steers, a_target, CP): return [a_target[0], min(a_target[1], a_x_allowed)] -class Planner: +class LongitudinalPlanner: def __init__(self, CP, init_v=0.0, init_a=0.0): self.CP = CP params = Params() diff --git a/selfdrive/controls/plannerd.py b/selfdrive/controls/plannerd.py index 513131a33..93d0c80da 100755 --- a/selfdrive/controls/plannerd.py +++ b/selfdrive/controls/plannerd.py @@ -3,7 +3,7 @@ from cereal import car from common.params import Params from common.realtime import Priority, config_realtime_process from system.swaglog import cloudlog -from selfdrive.controls.lib.longitudinal_planner import Planner +from selfdrive.controls.lib.longitudinal_planner import LongitudinalPlanner from selfdrive.controls.lib.lateral_planner import LateralPlanner import cereal.messaging as messaging @@ -16,7 +16,7 @@ def plannerd_thread(sm=None, pm=None): CP = car.CarParams.from_bytes(params.get("CarParams", block=True)) cloudlog.info("plannerd got CarParams: %s", CP.carName) - longitudinal_planner = Planner(CP) + longitudinal_planner = LongitudinalPlanner(CP) lateral_planner = LateralPlanner(CP) if sm is None: diff --git a/selfdrive/controls/tests/test_cruise_speed.py b/selfdrive/controls/tests/test_cruise_speed.py index 364be8db7..a972bfb07 100644 --- a/selfdrive/controls/tests/test_cruise_speed.py +++ b/selfdrive/controls/tests/test_cruise_speed.py @@ -1,13 +1,16 @@ #!/usr/bin/env python3 import unittest import numpy as np +from common.params import Params + + from selfdrive.test.longitudinal_maneuvers.maneuver import Maneuver -def run_cruise_simulation(cruise, t_end=100.): +def run_cruise_simulation(cruise, t_end=20.): man = Maneuver( '', duration=t_end, - initial_speed=float(0.), + initial_speed=max(cruise - 1., 0.0), lead_relevancy=True, initial_distance_lead=100, cruise_values=[cruise], @@ -21,12 +24,15 @@ def run_cruise_simulation(cruise, t_end=100.): class TestCruiseSpeed(unittest.TestCase): def test_cruise_speed(self): - for speed in np.arange(5, 40, 5): - print(f'Testing {speed} m/s') - cruise_speed = float(speed) + params = Params() + for e2e in [False, True]: + params.put_bool("EndToEndLong", e2e) + for speed in np.arange(5, 40, 5): + print(f'Testing {speed} m/s') + cruise_speed = float(speed) - simulation_steady_state = run_cruise_simulation(cruise_speed) - self.assertAlmostEqual(simulation_steady_state, cruise_speed, delta=.01, msg=f'Did not reach {speed} m/s') + simulation_steady_state = run_cruise_simulation(cruise_speed) + self.assertAlmostEqual(simulation_steady_state, cruise_speed, delta=.01, msg=f'Did not reach {speed} m/s') if __name__ == "__main__": diff --git a/selfdrive/controls/tests/test_following_distance.py b/selfdrive/controls/tests/test_following_distance.py index ebe477673..3534f5823 100644 --- a/selfdrive/controls/tests/test_following_distance.py +++ b/selfdrive/controls/tests/test_following_distance.py @@ -1,11 +1,13 @@ #!/usr/bin/env python3 import unittest import numpy as np +from common.params import Params + from selfdrive.controls.lib.longitudinal_mpc_lib.long_mpc import desired_follow_distance from selfdrive.test.longitudinal_maneuvers.maneuver import Maneuver -def run_following_distance_simulation(v_lead, t_end=100.0): +def run_following_distance_simulation(v_lead, t_end=100.0, e2e=False): man = Maneuver( '', duration=t_end, @@ -14,6 +16,7 @@ def run_following_distance_simulation(v_lead, t_end=100.0): initial_distance_lead=100, speed_lead_values=[v_lead], breakpoints=[0.], + e2e=e2e ) valid, output = man.evaluate() assert valid @@ -22,14 +25,16 @@ def run_following_distance_simulation(v_lead, t_end=100.0): class TestFollowingDistance(unittest.TestCase): def test_following_distance(self): - for speed in np.arange(0, 40, 5): - print(f'Testing {speed} m/s') - v_lead = float(speed) - - simulation_steady_state = run_following_distance_simulation(v_lead) - correct_steady_state = desired_follow_distance(v_lead, v_lead) - - self.assertAlmostEqual(simulation_steady_state, correct_steady_state, delta=(correct_steady_state*.1 + .5)) + params = Params() + for e2e in [False, True]: + params.put_bool("EndToEndLong", e2e) + for speed in np.arange(0, 40, 5): + print(f'Testing {speed} m/s') + v_lead = float(speed) + simulation_steady_state = run_following_distance_simulation(v_lead) + correct_steady_state = desired_follow_distance(v_lead, v_lead) + err_ratio = 0.2 if e2e else 0.1 + self.assertAlmostEqual(simulation_steady_state, correct_steady_state, delta=(err_ratio * correct_steady_state + .5)) if __name__ == "__main__": diff --git a/selfdrive/test/longitudinal_maneuvers/maneuver.py b/selfdrive/test/longitudinal_maneuvers/maneuver.py index 0d605a5fc..dad5d8984 100644 --- a/selfdrive/test/longitudinal_maneuvers/maneuver.py +++ b/selfdrive/test/longitudinal_maneuvers/maneuver.py @@ -27,7 +27,7 @@ class Maneuver(): speed=self.speed, distance_lead=self.distance_lead, only_lead2=self.only_lead2, - only_radar=self.only_radar + only_radar=self.only_radar, ) valid = True @@ -54,7 +54,7 @@ class Maneuver(): valid = False if self.ensure_start and log['v_rel'] > 0 and log['speeds'][-1] <= 0.1: - print('Planner not starting!') + print('LongitudinalPlanner not starting!') valid = False print("maneuver end", valid) diff --git a/selfdrive/test/longitudinal_maneuvers/plant.py b/selfdrive/test/longitudinal_maneuvers/plant.py index b11f6bef3..21af1cd3b 100755 --- a/selfdrive/test/longitudinal_maneuvers/plant.py +++ b/selfdrive/test/longitudinal_maneuvers/plant.py @@ -6,7 +6,8 @@ from cereal import log import cereal.messaging as messaging from common.realtime import Ratekeeper, DT_MDL from selfdrive.controls.lib.longcontrol import LongCtrlState -from selfdrive.controls.lib.longitudinal_planner import Planner +from selfdrive.modeld.constants import T_IDXS +from selfdrive.controls.lib.longitudinal_planner import LongitudinalPlanner class Plant(): @@ -43,7 +44,8 @@ class Plant(): from selfdrive.car.honda.values import CAR from selfdrive.car.honda.interface import CarInterface - self.planner = Planner(CarInterface.get_params(CAR.CIVIC), init_v=self.speed) + + self.planner = LongitudinalPlanner(CarInterface.get_params(CAR.CIVIC), init_v=self.speed) def current_time(self): return float(self.rk.frame) / self.rate @@ -88,6 +90,21 @@ class Plant(): radar.radarState.leadOne = lead radar.radarState.leadTwo = lead + # Simulate model predicting slightly faster speed + # this is to ensure lead policy is effective when model + # does not predict slowdown in e2e mode + position = log.ModelDataV2.XYZTData.new_message() + position.x = [float(x) for x in (self.speed + 0.5) * np.array(T_IDXS)] + model.modelV2.position = position + velocity = log.ModelDataV2.XYZTData.new_message() + velocity.x = [float(x) for x in (self.speed + 0.5) * np.ones_like(T_IDXS)] + model.modelV2.velocity = velocity + acceleration = log.ModelDataV2.XYZTData.new_message() + acceleration.x = [float(x) for x in np.zeros_like(T_IDXS)] + model.modelV2.acceleration = acceleration + + + control.controlsState.longControlState = LongCtrlState.pid control.controlsState.vCruise = float(v_cruise * 3.6) car_state.carState.vEgo = float(self.speed) diff --git a/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py b/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py index ec698d88f..c7c291587 100755 --- a/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py +++ b/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py @@ -140,16 +140,23 @@ class LongitudinalControl(unittest.TestCase): def run_maneuver_worker(k): def run(self): + params = Params() + man = maneuvers[k] - print(man.title) + params.put_bool("EndToEndLong", True) + print(man.title, ' in e2e mode') + valid, _ = man.evaluate() + self.assertTrue(valid, msg=man.title) + params.put_bool("EndToEndLong", False) + print(man.title, ' in acc mode') valid, _ = man.evaluate() self.assertTrue(valid, msg=man.title) return run - for k in range(len(maneuvers)): setattr(LongitudinalControl, f"test_longitudinal_maneuvers_{k+1}", run_maneuver_worker(k)) + if __name__ == "__main__": unittest.main(failfast=True) From 285ce30996e75e80e419ff2ef2d43cdb96fcb530 Mon Sep 17 00:00:00 2001 From: Bruce Wayne Date: Tue, 6 Sep 2022 22:00:09 -0700 Subject: [PATCH 166/172] bump cereal --- cereal | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cereal b/cereal index 3248f6658..f26ee5a28 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 3248f6658f58551ce0de9e3ea712d67896e196fd +Subproject commit f26ee5a28d778bd1833e47036398fd6b6f5f44bd From c5dc10bd2f063e2233795a66e45b6f17dffbd5c1 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Wed, 7 Sep 2022 00:18:01 -0700 Subject: [PATCH 167/172] Toyota: fix permanent LKAS faults (#25620) * Fix permanent LKAS Toyota faults * comment and global variable * EPS * comments * move up * comment --- selfdrive/car/toyota/carcontroller.py | 12 ++++++++---- 1 file changed, 8 insertions(+), 4 deletions(-) diff --git a/selfdrive/car/toyota/carcontroller.py b/selfdrive/car/toyota/carcontroller.py index 511017a55..b34a31a01 100644 --- a/selfdrive/car/toyota/carcontroller.py +++ b/selfdrive/car/toyota/carcontroller.py @@ -10,9 +10,12 @@ from opendbc.can.packer import CANPacker VisualAlert = car.CarControl.HUDControl.VisualAlert -# constants for fault workaround +# EPS faults if you apply torque while the steering rate is above 100 deg/s for too long MAX_STEER_RATE = 100 # deg/s -MAX_STEER_RATE_FRAMES = 18 # control frames allowed where steering rate >= MAX_STEER_RATE +MAX_STEER_RATE_FRAMES = 18 # tx control frames needed before torque can be cut + +# EPS allows user torque above threshold for 50 frames before permanently faulting +MAX_USER_TORQUE = 500 class CarController: @@ -34,6 +37,7 @@ class CarController: actuators = CC.actuators hud_control = CC.hudControl pcm_cancel_cmd = CC.cruiseControl.cancel + lat_active = CC.latActive and abs(CS.out.steeringTorque) < MAX_USER_TORQUE # gas and brake if self.CP.enableGasInterceptor and CC.longActive: @@ -58,13 +62,13 @@ class CarController: apply_steer = apply_toyota_steer_torque_limits(new_steer, self.last_steer, CS.out.steeringTorqueEps, self.torque_rate_limits) # Count up to MAX_STEER_RATE_FRAMES, at which point we need to cut torque to avoid a steering fault - if CC.latActive and abs(CS.out.steeringRateDeg) >= MAX_STEER_RATE: + if lat_active and abs(CS.out.steeringRateDeg) >= MAX_STEER_RATE: self.steer_rate_counter += 1 else: self.steer_rate_counter = 0 apply_steer_req = 1 - if not CC.latActive: + if not lat_active: apply_steer = 0 apply_steer_req = 0 elif self.steer_rate_counter > MAX_STEER_RATE_FRAMES: From c317bb464d1daa73e870fb55ae95377a580cf7af Mon Sep 17 00:00:00 2001 From: AlexandreSato <66435071+AlexandreSato@users.noreply.github.com> Date: Wed, 7 Sep 2022 04:26:37 -0300 Subject: [PATCH 168/172] Multilang: formal pt-BR translations (#25669) * fix and improve pt-BR translation * Shorter phrase for Finish Setup * Concluir are better than Encerrar bacause means sucessfuly * improve pt-BR, DEVbrazilians use english as default * fix "atualizador" text cutoff * miss mark as finish on qt linguist * Multilang: improve pt-BR translation * Update selfdrive/ui/translations/main_pt-BR.ts looks good! Co-authored-by: Shane Smiskol Co-authored-by: Shane Smiskol --- selfdrive/ui/translations/main_pt-BR.ts | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/selfdrive/ui/translations/main_pt-BR.ts b/selfdrive/ui/translations/main_pt-BR.ts index 622d8ee44..5a2167ea8 100644 --- a/selfdrive/ui/translations/main_pt-BR.ts +++ b/selfdrive/ui/translations/main_pt-BR.ts @@ -155,7 +155,7 @@ Review Training Guide - Revisar o Treinamento + Revisar Guia de Treinamento @@ -185,17 +185,17 @@ Change Language - Mudar Linguagem + Alterar Idioma CHANGE - MUDAR + ALTERAR Select a language - Selecione uma linguagem + Selecione o Idioma @@ -989,12 +989,12 @@ trabalho definido Git Branch - Ramo Git + Git Branch Git Commit - Commit Git + Último Commit @@ -1029,7 +1029,7 @@ trabalho definido Switch Branch - Trocar Branch + Alterar Branch From a8134f226589675b2d1619bc6ed8b0d9c6a37ba7 Mon Sep 17 00:00:00 2001 From: Cameron Clough Date: Wed, 7 Sep 2022 08:58:33 -0700 Subject: [PATCH 169/172] e2e long yellow path (#25679) * yellow brick road * live toggling * path color from acceleration * more yellow --- selfdrive/ui/qt/onroad.cc | 46 +++++++++++++++++++++++++++++---------- selfdrive/ui/ui.cc | 1 + selfdrive/ui/ui.h | 2 +- 3 files changed, 36 insertions(+), 13 deletions(-) diff --git a/selfdrive/ui/qt/onroad.cc b/selfdrive/ui/qt/onroad.cc index 4414e602e..3920453a4 100644 --- a/selfdrive/ui/qt/onroad.cc +++ b/selfdrive/ui/qt/onroad.cc @@ -459,19 +459,41 @@ void NvgWindow::drawLaneLines(QPainter &painter, const UIState *s) { // paint path QLinearGradient bg(0, height(), 0, height() / 4); - const auto &orientation = (*s->sm)["modelV2"].getModelV2().getOrientation(); - float orientation_future = 0; - if (orientation.getZ().size() > 16) { - orientation_future = std::abs(orientation.getZ()[16]); // 2.5 seconds + float start_hue, end_hue; + if (scene.end_to_end_long) { + const auto &acceleration = (*s->sm)["modelV2"].getModelV2().getAcceleration(); + float acceleration_future = 0; + if (acceleration.getZ().size() > 16) { + acceleration_future = acceleration.getX()[16]; // 2.5 seconds + } + start_hue = 60; + // speed up: 120, slow down: 0 + end_hue = fmax(fmin(start_hue + acceleration_future * 30, 120), 0); + + // FIXME: painter.drawPolygon can be slow if hue is not rounded + end_hue = int(end_hue * 100 + 0.5) / 100; + + bg.setColorAt(0.0, QColor::fromHslF(start_hue / 360., 0.97, 0.56, 0.4)); + bg.setColorAt(0.5, QColor::fromHslF(end_hue / 360., 1.0, 0.68, 0.35)); + bg.setColorAt(1.0, QColor::fromHslF(end_hue / 360., 1.0, 0.68, 0.0)); + } else { + const auto &orientation = (*s->sm)["modelV2"].getModelV2().getOrientation(); + float orientation_future = 0; + if (orientation.getZ().size() > 16) { + orientation_future = std::abs(orientation.getZ()[16]); // 2.5 seconds + } + start_hue = 148; + // straight: 112, in turns: 70 + end_hue = fmax(70, 112 - (orientation_future * 420)); + + // FIXME: painter.drawPolygon can be slow if hue is not rounded + end_hue = int(end_hue * 100 + 0.5) / 100; + + bg.setColorAt(0.0, QColor::fromHslF(start_hue / 360., 0.94, 0.51, 0.4)); + bg.setColorAt(0.5, QColor::fromHslF(end_hue / 360., 1.0, 0.68, 0.35)); + bg.setColorAt(1.0, QColor::fromHslF(end_hue / 360., 1.0, 0.68, 0.0)); } - // straight: 112, in turns: 70 - float curve_hue = fmax(70, 112 - (orientation_future * 420)); - // FIXME: painter.drawPolygon can be slow if hue is not rounded - curve_hue = int(curve_hue * 100 + 0.5) / 100; - - bg.setColorAt(0.0, QColor::fromHslF(148 / 360., 0.94, 0.51, 0.4)); - bg.setColorAt(0.75 / 1.5, QColor::fromHslF(curve_hue / 360., 1.0, 0.68, 0.35)); - bg.setColorAt(1.0, QColor::fromHslF(curve_hue / 360., 1.0, 0.68, 0.0)); + painter.setBrush(bg); painter.drawPolygon(scene.track_vertices); diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index 317ef497a..b208945fe 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -195,6 +195,7 @@ void ui_update_params(UIState *s) { auto params = Params(); s->scene.is_metric = params.getBool("IsMetric"); s->scene.map_on_left = params.getBool("NavSettingLeftSide"); + s->scene.end_to_end_long = params.getBool("EndToEndLong"); } void UIState::updateStatus() { diff --git a/selfdrive/ui/ui.h b/selfdrive/ui/ui.h index 16f78cdef..08ae16ab2 100644 --- a/selfdrive/ui/ui.h +++ b/selfdrive/ui/ui.h @@ -101,7 +101,7 @@ typedef struct UIScene { QPointF lead_vertices[2]; float light_sensor, accel_sensor, gyro_sensor; - bool started, ignition, is_metric, map_on_left, longitudinal_control; + bool started, ignition, is_metric, map_on_left, longitudinal_control, end_to_end_long; uint64_t started_frame; } UIScene; From 8857e02dd4e141680476644a07fa3c9cd2ae9364 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Wed, 7 Sep 2022 11:29:19 -0700 Subject: [PATCH 170/172] Live e2e long toggling (#25685) Live toggling --- selfdrive/controls/lib/longitudinal_planner.py | 17 ++++++++++++----- 1 file changed, 12 insertions(+), 5 deletions(-) diff --git a/selfdrive/controls/lib/longitudinal_planner.py b/selfdrive/controls/lib/longitudinal_planner.py index b9bf5dcbf..8162d1007 100755 --- a/selfdrive/controls/lib/longitudinal_planner.py +++ b/selfdrive/controls/lib/longitudinal_planner.py @@ -48,10 +48,11 @@ def limit_accel_in_turns(v_ego, angle_steers, a_target, CP): class LongitudinalPlanner: def __init__(self, CP, init_v=0.0, init_a=0.0): self.CP = CP - params = Params() - # TODO read param in the loop for live toggling - mode = 'blended' if params.get_bool('EndToEndLong') else 'acc' - self.mpc = LongitudinalMpc(mode=mode) + self.params = Params() + self.param_read_counter = 0 + + self.mpc = LongitudinalMpc() + self.read_param() self.fcw = False @@ -64,6 +65,9 @@ class LongitudinalPlanner: self.j_desired_trajectory = np.zeros(CONTROL_N) self.solverExecutionTime = 0.0 + def read_param(self): + self.mpc.mode = 'blended' if self.params.get_bool('EndToEndLong') else 'acc' + def parse_model(self, model_msg): if (len(model_msg.position.x) == 33 and len(model_msg.velocity.x) == 33 and @@ -83,8 +87,11 @@ class LongitudinalPlanner: return x, v, a, j def update(self, sm): - v_ego = sm['carState'].vEgo + if self.param_read_counter % 50 == 0: + self.read_param() + self.param_read_counter += 1 + v_ego = sm['carState'].vEgo v_cruise_kph = sm['controlsState'].vCruise v_cruise_kph = min(v_cruise_kph, V_CRUISE_MAX) v_cruise = v_cruise_kph * CV.KPH_TO_MS From 9bb29240b04e979bc79d929fa526fd29bd4071a6 Mon Sep 17 00:00:00 2001 From: ioniq5-cz <111085918+ioniq5-cz@users.noreply.github.com> Date: Wed, 7 Sep 2022 22:25:48 +0200 Subject: [PATCH 171/172] Hyuyndai: add missing FW versions for 2022 Ioniq 5 (#25691) --- selfdrive/car/hyundai/values.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 79e3ea419..4354f1344 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -1290,6 +1290,8 @@ FW_VERSIONS = { (Ecu.esp, 0x7d1, None): [ b'\xf1\x00NE1 IEB \x07 106!\x11) 58520-GI010', b'\xf1\x8758520GI010\xf1\x00NE1 IEB \x07 106!\x11) 58520-GI010', + b'\xf1\x00NE1 IEB \x08 104!\x04\x05 58520-GI000', + b'\xf1\x8758520GI000\xf1\x00NE1 IEB \x08 104!\x04\x05 58520-GI000', ], (Ecu.eps, 0x7d4, None): [ b'\xf1\x00NE MDPS R 1.00 1.06 57700GI000 4NEDR106', @@ -1301,6 +1303,7 @@ FW_VERSIONS = { ], (Ecu.fwdCamera, 0x7c4, None): [ b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.02 99211-GI010 211206', + b'\xf1\x00NE1 MFC AT EUR LHD 1.00 1.06 99211-GI000 210813', ], }, CAR.TUCSON_HYBRID_4TH_GEN: { From e9c87daef6534906c728da9a191866926bbfbfe4 Mon Sep 17 00:00:00 2001 From: Cameron Clough Date: Wed, 7 Sep 2022 14:25:57 -0700 Subject: [PATCH 172/172] rename esp ECU to abs (#25640) * rename esp ecu to abs * bump cereal --- cereal | 2 +- selfdrive/car/chrysler/values.py | 6 +- selfdrive/car/ford/values.py | 4 +- selfdrive/car/fw_versions.py | 10 +-- selfdrive/car/hyundai/values.py | 38 +++++----- selfdrive/car/mazda/values.py | 12 ++-- selfdrive/car/nissan/values.py | 4 +- selfdrive/car/subaru/values.py | 20 +++--- selfdrive/car/toyota/values.py | 90 ++++++++++++------------ selfdrive/controls/tests/test_startup.py | 4 +- 10 files changed, 95 insertions(+), 95 deletions(-) diff --git a/cereal b/cereal index f26ee5a28..cea51afd6 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit f26ee5a28d778bd1833e47036398fd6b6f5f44bd +Subproject commit cea51afd67b5c56f7a18207ef91c5e45d6345526 diff --git a/selfdrive/car/chrysler/values.py b/selfdrive/car/chrysler/values.py index 0df2c1886..f495d06a1 100644 --- a/selfdrive/car/chrysler/values.py +++ b/selfdrive/car/chrysler/values.py @@ -132,7 +132,7 @@ FINGERPRINTS = { FW_VERSIONS = { CAR.PACIFICA_2019_HYBRID: { (Ecu.hcp, 0x7e2, None): [], - (Ecu.esp, 0x7e4, None): [], + (Ecu.abs, 0x7e4, None): [], }, CAR.RAM_1500: { @@ -149,7 +149,7 @@ FW_VERSIONS = { b'68428609AB', b'68500728AA', ], - (Ecu.esp, 0x747, None): [ + (Ecu.abs, 0x747, None): [ b'68432418AD', b'68432418AB', b'68436004AE', @@ -205,7 +205,7 @@ FW_VERSIONS = { b'68428503AA', b'68428505AA', ], - (Ecu.esp, 0x747, None): [ + (Ecu.abs, 0x747, None): [ b'68334977AH', b'68504022AB', b'68530686AB', diff --git a/selfdrive/car/ford/values.py b/selfdrive/car/ford/values.py index 825d515da..2624fd252 100644 --- a/selfdrive/car/ford/values.py +++ b/selfdrive/car/ford/values.py @@ -51,7 +51,7 @@ FW_VERSIONS = { (Ecu.eps, 0x730, None): [ b'LX6C-14D003-AH\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x760, None): [ + (Ecu.abs, 0x760, None): [ b'LX6C-2D053-NS\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x764, None): [ @@ -68,7 +68,7 @@ FW_VERSIONS = { (Ecu.eps, 0x730, None): [ b'JX6C-14D003-AH\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x760, None): [ + (Ecu.abs, 0x760, None): [ b'JX61-2D053-CJ\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x764, None): [ diff --git a/selfdrive/car/fw_versions.py b/selfdrive/car/fw_versions.py index 363b852eb..e6faa0e95 100755 --- a/selfdrive/car/fw_versions.py +++ b/selfdrive/car/fw_versions.py @@ -16,7 +16,7 @@ from selfdrive.car.toyota.values import CAR as TOYOTA from system.swaglog import cloudlog Ecu = car.CarParams.Ecu -ESSENTIAL_ECUS = [Ecu.engine, Ecu.eps, Ecu.esp, Ecu.fwdRadar, Ecu.fwdCamera, Ecu.vsa] +ESSENTIAL_ECUS = [Ecu.engine, Ecu.eps, Ecu.abs, Ecu.fwdRadar, Ecu.fwdCamera, Ecu.vsa] def p16(val): @@ -213,14 +213,14 @@ REQUESTS: List[Request] = [ "chrysler", [CHRYSLER_VERSION_REQUEST], [CHRYSLER_VERSION_RESPONSE], - whitelist_ecus=[Ecu.esp, Ecu.eps, Ecu.srs, Ecu.gateway, Ecu.fwdRadar, Ecu.fwdCamera, Ecu.combinationMeter], + whitelist_ecus=[Ecu.abs, Ecu.eps, Ecu.srs, Ecu.gateway, Ecu.fwdRadar, Ecu.fwdCamera, Ecu.combinationMeter], rx_offset=CHRYSLER_RX_OFFSET, ), Request( "chrysler", [CHRYSLER_VERSION_REQUEST], [CHRYSLER_VERSION_RESPONSE], - whitelist_ecus=[Ecu.esp, Ecu.hcp, Ecu.engine, Ecu.transmission], + whitelist_ecus=[Ecu.abs, Ecu.hcp, Ecu.engine, Ecu.transmission], ), Request( "chrysler", @@ -240,7 +240,7 @@ REQUESTS: List[Request] = [ [TESTER_PRESENT_REQUEST, FORD_VERSION_REQUEST], [TESTER_PRESENT_RESPONSE, FORD_VERSION_RESPONSE], bus=0, - whitelist_ecus=[Ecu.eps, Ecu.esp, Ecu.fwdRadar, Ecu.fwdCamera], + whitelist_ecus=[Ecu.eps, Ecu.abs, Ecu.fwdRadar, Ecu.fwdCamera], ), ] @@ -328,7 +328,7 @@ def match_fw_to_car_exact(fw_versions_dict): ecu_type = ecu[0] addr = ecu[1:] found_versions = fw_versions_dict.get(addr, set()) - if ecu_type == Ecu.esp and candidate in (TOYOTA.RAV4, TOYOTA.COROLLA, TOYOTA.HIGHLANDER, TOYOTA.SIENNA, TOYOTA.LEXUS_IS) and not len(found_versions): + if ecu_type == Ecu.abs and candidate in (TOYOTA.RAV4, TOYOTA.COROLLA, TOYOTA.HIGHLANDER, TOYOTA.SIENNA, TOYOTA.LEXUS_IS) and not len(found_versions): continue # On some Toyota models, the engine can show on two different addresses diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 4354f1344..e2374a1c0 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -398,7 +398,7 @@ FW_VERSIONS = { b'\xf1\x8799110L0000\xf1\x00DN8_ SCC F-CUP 1.00 1.00 99110-L0000 ', b'\xf1\x8799110L0000\xf1\x00DN8_ SCC FHCUP 1.00 1.00 99110-L0000 ', ], - (Ecu.esp, 0x7d1, None): [ + (Ecu.abs, 0x7d1, None): [ b'\xf1\x00DN ESC \x07 106 \x07\x01 58910-L0100', b'\xf1\x00DN ESC \x01 102\x19\x04\x13 58910-L1300', b'\xf1\x00DN ESC \x03 100 \x08\x01 58910-L0300', @@ -518,7 +518,7 @@ FW_VERSIONS = { (Ecu.fwdRadar, 0x7d0, None): [ b'\xf1\x00LF__ SCC F-CUP 1.00 1.00 96401-C2200 ', ], - (Ecu.esp, 0x7d1, None): [ + (Ecu.abs, 0x7d1, None): [ b'\xf1\x00LF ESC \f 11 \x17\x01\x13 58920-C2610', b'\xf1\x00LF ESC \t 11 \x17\x01\x13 58920-C2610', ], @@ -565,7 +565,7 @@ FW_VERSIONS = { b'\xf1\x00TM__ SCC F-CUP 1.00 1.02 99110-S2000 ', b'\xf1\x00TM__ SCC F-CUP 1.00 1.03 99110-S2000 ', ], - (Ecu.esp, 0x7d1, None): [ + (Ecu.abs, 0x7d1, None): [ b'\xf1\x00TM ESC \r 100\x18\x031 58910-S2650', b'\xf1\x00TM ESC \r 103\x18\x11\x08 58910-S2650', b'\xf1\x00TM ESC \r 104\x19\a\b 58910-S2650', @@ -623,7 +623,7 @@ FW_VERSIONS = { b'\xf1\x8799110S1500\xf1\x00TM__ SCC FHCUP 1.00 1.00 99110-S1500 ', b'\xf1\x00TM__ SCC FHCUP 1.00 1.00 99110-S1500 ', ], - (Ecu.esp, 0x7d1, None): [ + (Ecu.abs, 0x7d1, None): [ b'\xf1\x00TM ESC \x02 101 \x08\x04 58910-S2GA0', b'\xf1\x00TM ESC \x03 101 \x08\x02 58910-S2DA0', b'\xf1\x8758910-S2DA0\xf1\x00TM ESC \x03 101 \x08\x02 58910-S2DA0', @@ -744,7 +744,7 @@ FW_VERSIONS = { b'\xf1\x00LX2_ SCC FHCUP 1.00 1.05 99110-S8100 ', b'\xf1\x00ON__ FCA FHCUP 1.00 1.02 99110-S9100 ', ], - (Ecu.esp, 0x7d1, None): [ + (Ecu.abs, 0x7d1, None): [ b'\xf1\x00LX ESC \x01 103\x19\t\x10 58910-S8360', b'\xf1\x00LX ESC \x01 1031\t\x10 58910-S8360', b'\xf1\x00LX ESC \x0b 101\x19\x03\x17 58910-S8330', @@ -834,7 +834,7 @@ FW_VERSIONS = { b'\xf1\x00JS__ SCC H-CUP 1.00 1.02 95650-J3200 ', b'\xf1\x00JS__ SCC HNCUP 1.00 1.02 95650-J3100 ', ], - (Ecu.esp, 0x7d1, None): [ + (Ecu.abs, 0x7d1, None): [ b'\xf1\x00\x00\x00\x00\x00\x00\x00', b'\xf1\x816V8RAC00121.ELF\xf1\x00\x00\x00\x00\x00\x00\x00', ], @@ -895,7 +895,7 @@ FW_VERSIONS = { }, CAR.KONA: { (Ecu.fwdRadar, 0x7d0, None): [b'\xf1\x00OS__ SCC F-CUP 1.00 1.00 95655-J9200 ', ], - (Ecu.esp, 0x7d1, None): [b'\xf1\x816V5RAK00018.ELF\xf1\x00\x00\x00\x00\x00\x00\x00', ], + (Ecu.abs, 0x7d1, None): [b'\xf1\x816V5RAK00018.ELF\xf1\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.engine, 0x7e0, None): [b'"\x01TOS-0NU06F301J02', ], (Ecu.eps, 0x7d4, None): [b'\xf1\x00OS MDPS C 1.00 1.05 56310J9030\x00 4OSDC105', ], (Ecu.fwdCamera, 0x7c4, None): [b'\xf1\x00OS9 LKAS AT USA LHD 1.00 1.00 95740-J9300 g21', ], @@ -910,7 +910,7 @@ FW_VERSIONS = { b'\xf1\x816U2V7051\000\000\xf1\0006U2V0_C2\000\0006U2V7051\000\000DCD0T14US1\000\000\000\000', b'\xf1\x816U2V7051\x00\x00\xf1\x006U2V0_C2\x00\x006U2V7051\x00\x00DCD0T14US1U\x867Z', ], - (Ecu.esp, 0x7D1, None): [b'\xf1\000CD ESC \003 102\030\b\005 58920-J7350', ], + (Ecu.abs, 0x7D1, None): [b'\xf1\000CD ESC \003 102\030\b\005 58920-J7350', ], }, CAR.KIA_FORTE: { (Ecu.eps, 0x7D4, None): [ @@ -928,7 +928,7 @@ FW_VERSIONS = { b'\x01TBDM1NU06F200H01', b'391182B945\x00', ], - (Ecu.esp, 0x7d1, None): [ + (Ecu.abs, 0x7d1, None): [ b'\xf1\x816VGRAH00018.ELF\xf1\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.transmission, 0x7e1, None): [ @@ -952,7 +952,7 @@ FW_VERSIONS = { b'\xf1\x00DL3 MFC AT USA LHD 1.00 1.03 99210-L3000 200915', b'\xf1\x00DL3 MFC AT USA LHD 1.00 1.04 99210-L3000 210208', ], - (Ecu.esp, 0x7D1, None): [ + (Ecu.abs, 0x7D1, None): [ b'\xf1\000DL ESC \006 101 \004\002 58910-L3200', b'\xf1\x8758910-L3200\xf1\000DL ESC \006 101 \004\002 58910-L3200', b'\xf1\x8758910-L3800\xf1\x00DL ESC \t 101 \x07\x02 58910-L3800', @@ -972,7 +972,7 @@ FW_VERSIONS = { ], }, CAR.KONA_EV: { - (Ecu.esp, 0x7D1, None): [ + (Ecu.abs, 0x7D1, None): [ b'\xf1\x00OS IEB \r 105\x18\t\x18 58520-K4000', b'\xf1\x00OS IEB \x01 212 \x11\x13 58520-K4000', b'\xf1\x00OS IEB \x02 212 \x11\x13 58520-K4000', @@ -999,7 +999,7 @@ FW_VERSIONS = { ], }, CAR.KONA_EV_2022: { - (Ecu.esp, 0x7D1, None): [ + (Ecu.abs, 0x7D1, None): [ b'\xf1\x8758520-K4010\xf1\x00OS IEB \x02 101 \x11\x13 58520-K4010', b'\xf1\x8758520-K4010\xf1\x00OS IEB \x04 101 \x11\x13 58520-K4010', b'\xf1\x8758520-K4010\xf1\x00OS IEB \x03 101 \x11\x13 58520-K4010', @@ -1093,7 +1093,7 @@ FW_VERSIONS = { }, CAR.KIA_SELTOS: { (Ecu.fwdRadar, 0x7d0, None): [b'\xf1\x8799110Q5100\xf1\000SP2_ SCC FHCUP 1.01 1.05 99110-Q5100 ',], - (Ecu.esp, 0x7d1, None): [ + (Ecu.abs, 0x7d1, None): [ b'\xf1\x8758910-Q5450\xf1\000SP ESC \a 101\031\t\005 58910-Q5450', b'\xf1\x8758910-Q5450\xf1\000SP ESC \t 101\031\t\005 58910-Q5450', ], @@ -1121,7 +1121,7 @@ FW_VERSIONS = { (Ecu.fwdRadar, 0x7d0, None): [ b'\xf1\x00JF__ SCC F-CUP 1.00 1.00 96400-D4110 ', ], - (Ecu.esp, 0x7d1, None): [ + (Ecu.abs, 0x7d1, None): [ b'\xf1\x00JF ESC \x0b 11 \x18\x030 58920-D5180', ], (Ecu.engine, 0x7e0, None): [ @@ -1158,7 +1158,7 @@ FW_VERSIONS = { b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.01 99210-AB000 210205', b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.06 99210-AA000 220111', ], - (Ecu.esp, 0x7d1, None): [ + (Ecu.abs, 0x7d1, None): [ b'\xf1\x00CN ESC \t 101 \x10\x03 58910-AB800', b'\xf1\x8758910-AA800\xf1\x00CN ESC \t 104 \x08\x03 58910-AA800', b'\xf1\x8758910-AB800\xf1\x00CN ESC \t 101 \x10\x03 58910-AB800', @@ -1204,7 +1204,7 @@ FW_VERSIONS = { ] }, CAR.KONA_HEV: { - (Ecu.esp, 0x7d1, None): [ + (Ecu.abs, 0x7d1, None): [ b'\xf1\x00OS IEB \x01 104 \x11 58520-CM000', ], (Ecu.fwdRadar, 0x7d0, None): [ @@ -1258,7 +1258,7 @@ FW_VERSIONS = { (Ecu.fwdCamera, 0x7c4, None): [ b'\xf1\x00UMP LKAS AT USA LHD 1.01 1.01 95740-C6550 d01' ], - (Ecu.esp, 0x7d1, None): [ + (Ecu.abs, 0x7d1, None): [ b'\xf1\x00UM ESC \x0c 12 \x18\x05\x06 58910-C6330' ], (Ecu.fwdRadar, 0x7D0, None): [ @@ -1272,7 +1272,7 @@ FW_VERSIONS = { ], }, CAR.KIA_EV6: { - (Ecu.esp, 0x7d1, None): [ + (Ecu.abs, 0x7d1, None): [ b'\xf1\x8758520CV100\xf1\x00CV IEB \x02 101!\x10\x18 58520-CV100', ], (Ecu.eps, 0x7d4, None): [ @@ -1287,7 +1287,7 @@ FW_VERSIONS = { ], }, CAR.IONIQ_5: { - (Ecu.esp, 0x7d1, None): [ + (Ecu.abs, 0x7d1, None): [ b'\xf1\x00NE1 IEB \x07 106!\x11) 58520-GI010', b'\xf1\x8758520GI010\xf1\x00NE1 IEB \x07 106!\x11) 58520-GI010', b'\xf1\x00NE1 IEB \x08 104!\x04\x05 58520-GI000', diff --git a/selfdrive/car/mazda/values.py b/selfdrive/car/mazda/values.py index ed246f15d..95f140422 100644 --- a/selfdrive/car/mazda/values.py +++ b/selfdrive/car/mazda/values.py @@ -72,7 +72,7 @@ FW_VERSIONS = { (Ecu.fwdRadar, 0x764, None): [ b'K131-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x760, None): [ + (Ecu.abs, 0x760, None): [ b'KSD5-437K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdCamera, 0x706, None): [ @@ -116,7 +116,7 @@ FW_VERSIONS = { b'K131-67XK2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'K131-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x760, None): [ + (Ecu.abs, 0x760, None): [ b'K123-437K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'KBJ5-437K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'KL2K-437K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', @@ -173,7 +173,7 @@ FW_VERSIONS = { b'TK80-67XK2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'TK80-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x760, None): [ + (Ecu.abs, 0x760, None): [ b'TA0B-437K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'TK79-437K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'TK79-437K2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', @@ -217,7 +217,7 @@ FW_VERSIONS = { b'GHP9-67Y10---41\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'K131-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x760, None): [ + (Ecu.abs, 0x760, None): [ b'B45A-437AS-0-08\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdCamera, 0x706, None): [ @@ -248,7 +248,7 @@ FW_VERSIONS = { b'K131-67XK2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'K131-67XK2-E\000\000\000\000\000\000\000\000\000\000\000\000', ], - (Ecu.esp, 0x760, None): [ + (Ecu.abs, 0x760, None): [ b'GBVH-437K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'GDDM-437K2-A\000\000\000\000\000\000\000\000\000\000\000\000', ], @@ -275,7 +275,7 @@ FW_VERSIONS = { b'K131-67XK2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'K131-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x760, None): [ + (Ecu.abs, 0x760, None): [ b'TA0B-437K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdCamera, 0x706, None): [ diff --git a/selfdrive/car/nissan/values.py b/selfdrive/car/nissan/values.py index 2126e550e..440c68249 100644 --- a/selfdrive/car/nissan/values.py +++ b/selfdrive/car/nissan/values.py @@ -95,7 +95,7 @@ FW_VERSIONS = { b'5SH1BDB\x04\x18\x00\x00\x00\x00\x00_-?\x04\x91\xf2\x00\x00\x00\x80', b'5SK0ADB\x04\x18\x00\x00\x00\x00\x00_(5\x07\x9aQ\x00\x00\x00\x80', ], - (Ecu.esp, 0x740, None): [ + (Ecu.abs, 0x740, None): [ b'476605SH1D', b'476605SK2A', ], @@ -112,7 +112,7 @@ FW_VERSIONS = { (Ecu.fwdCamera, 0x707, None): [ b'284N86FR2A', ], - (Ecu.esp, 0x740, None): [ + (Ecu.abs, 0x740, None): [ b'6FU1BD\x11\x02\x00\x02e\x95e\x80iX#\x01\x00\x00\x00\x00\x00\x80', b'6FU0AD\x11\x02\x00\x02e\x95e\x80iQ#\x01\x00\x00\x00\x00\x00\x80', ], diff --git a/selfdrive/car/subaru/values.py b/selfdrive/car/subaru/values.py index d04e5f2cc..53dd4a763 100644 --- a/selfdrive/car/subaru/values.py +++ b/selfdrive/car/subaru/values.py @@ -74,7 +74,7 @@ CAR_INFO: Dict[str, Union[SubaruCarInfo, List[SubaruCarInfo]]] = { FW_VERSIONS = { CAR.ASCENT: { - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'\xa5 \x19\x02\x00', b'\xa5 !\002\000', b'\xf1\x82\xa5 \x19\x02\x00', @@ -104,7 +104,7 @@ FW_VERSIONS = { ], }, CAR.LEGACY: { - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'\xa1\\ x04\x01', b'\xa1 \x03\x03' ], @@ -126,7 +126,7 @@ FW_VERSIONS = { ], }, CAR.IMPREZA: { - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'\x7a\x94\x3f\x90\x00', b'\xa2 \x185\x00', b'\xa2 \x193\x00', @@ -201,7 +201,7 @@ FW_VERSIONS = { ], }, CAR.IMPREZA_2020: { - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'\xa2 \0314\000', b'\xa2 \0313\000', b'\xa2 !i\000', @@ -239,7 +239,7 @@ FW_VERSIONS = { ], }, CAR.FORESTER: { - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'\xa3 \x18\x14\x00', b'\xa3 \024\000', b'\xa3 \031\024\000', @@ -274,7 +274,7 @@ FW_VERSIONS = { ], }, CAR.FORESTER_PREGLOBAL: { - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'\x7d\x97\x14\x40', b'\xf1\x00\xbb\x0c\x04', ], @@ -303,7 +303,7 @@ FW_VERSIONS = { ], }, CAR.LEGACY_PREGLOBAL: { - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'k\x97D\x00', b'[\xba\xc4\x03', b'{\x97D\x00', @@ -333,7 +333,7 @@ FW_VERSIONS = { ], }, CAR.OUTBACK_PREGLOBAL: { - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'{\x9a\xac\x00', b'k\x97\xac\x00', b'\x5b\xf7\xbc\x03', @@ -387,7 +387,7 @@ FW_VERSIONS = { ], }, CAR.OUTBACK_PREGLOBAL_2018: { - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'\x8b\x97\xac\x00', b'\x8b\x9a\xac\x00', b'\x9b\x97\xac\x00', @@ -430,7 +430,7 @@ FW_VERSIONS = { ], }, CAR.OUTBACK: { - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'\xa1 \x06\x01', b'\xa1 \a\x00', b'\xa1 \b\001', diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 18b6db0db..af2fc9f56 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -200,7 +200,7 @@ STATIC_DSU_MSGS = [ FW_VERSIONS = { CAR.AVALON: { - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152607060\x00\x00\x00\x00\x00\x00', ], (Ecu.dsu, 0x791, None): [ @@ -225,7 +225,7 @@ FW_VERSIONS = { ], }, CAR.AVALON_2019: { - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152607140\x00\x00\x00\x00\x00\x00', b'F152607171\x00\x00\x00\x00\x00\x00', b'F152607110\x00\x00\x00\x00\x00\x00', @@ -253,7 +253,7 @@ FW_VERSIONS = { ], }, CAR.AVALONH_2019: { - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152641040\x00\x00\x00\x00\x00\x00', b'F152641061\x00\x00\x00\x00\x00\x00', b'F152641050\x00\x00\x00\x00\x00\x00', @@ -280,7 +280,7 @@ FW_VERSIONS = { ], }, CAR.AVALON_TSS2: { - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'\x01F152607240\x00\x00\x00\x00\x00\x00', b'\x01F152607280\x00\x00\x00\x00\x00\x00', ], @@ -300,7 +300,7 @@ FW_VERSIONS = { ], }, CAR.AVALONH_TSS2: { - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152641080\x00\x00\x00\x00\x00\x00', ], (Ecu.eps, 0x7a1, None): [ @@ -356,7 +356,7 @@ FW_VERSIONS = { b'8821F0608200 ', b'8821F0609100 ', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152606210\x00\x00\x00\x00\x00\x00', b'F152606230\x00\x00\x00\x00\x00\x00', b'F152606270\x00\x00\x00\x00\x00\x00', @@ -420,7 +420,7 @@ FW_VERSIONS = { b'\x028966306S0100\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', b'\x028966306S1100\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152633214\x00\x00\x00\x00\x00\x00', b'F152633660\x00\x00\x00\x00\x00\x00', b'F152633712\x00\x00\x00\x00\x00\x00', @@ -486,7 +486,7 @@ FW_VERSIONS = { (Ecu.eps, 0x7a1, None): [ b'8965B33630\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'\x01F152606370\x00\x00\x00\x00\x00\x00', b'\x01F152606390\x00\x00\x00\x00\x00\x00', b'\x01F152606400\x00\x00\x00\x00\x00\x00', @@ -512,7 +512,7 @@ FW_VERSIONS = { (Ecu.eps, 0x7a1, None): [ b'8965B33630\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152633D00\x00\x00\x00\x00\x00\x00', ], (Ecu.engine, 0x700, None): [ @@ -547,7 +547,7 @@ FW_VERSIONS = { b'8821FF406000 ', b'8821FF407100 ', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152610020\x00\x00\x00\x00\x00\x00', b'F152610153\x00\x00\x00\x00\x00\x00', b'F152610210\x00\x00\x00\x00\x00\x00', @@ -599,7 +599,7 @@ FW_VERSIONS = { b'\x0289663F431000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x0189663F438000\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152610012\x00\x00\x00\x00\x00\x00', b'F152610013\x00\x00\x00\x00\x00\x00', b'F152610014\x00\x00\x00\x00\x00\x00', @@ -658,7 +658,7 @@ FW_VERSIONS = { b'881510201100\x00\x00\x00\x00', b'881510201200\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152602190\x00\x00\x00\x00\x00\x00', b'F152602191\x00\x00\x00\x00\x00\x00', ], @@ -735,7 +735,7 @@ FW_VERSIONS = { b'\x018965B12510\x00\x00\x00\x00\x00\x00', b'\x018965B1256000\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'\x01F152602280\x00\x00\x00\x00\x00\x00', b'\x01F152602560\x00\x00\x00\x00\x00\x00', b'\x01F152602590\x00\x00\x00\x00\x00\x00', @@ -813,7 +813,7 @@ FW_VERSIONS = { b'\x018965B12520\x00\x00\x00\x00\x00\x00', b'\x018965B12530\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152612590\x00\x00\x00\x00\x00\x00', b'F152612691\x00\x00\x00\x00\x00\x00', b'F152612692\x00\x00\x00\x00\x00\x00', @@ -885,7 +885,7 @@ FW_VERSIONS = { b'8965B48150\x00\x00\x00\x00\x00\x00', b'8965B48210\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [b'F15260E011\x00\x00\x00\x00\x00\x00'], + (Ecu.abs, 0x7b0, None): [b'F15260E011\x00\x00\x00\x00\x00\x00'], (Ecu.dsu, 0x791, None): [ b'881510E01100\x00\x00\x00\x00', b'881510E01200\x00\x00\x00\x00', @@ -903,7 +903,7 @@ FW_VERSIONS = { (Ecu.eps, 0x7a1, None): [ b'8965B48160\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152648541\x00\x00\x00\x00\x00\x00', b'F152648542\x00\x00\x00\x00\x00\x00', ], @@ -928,7 +928,7 @@ FW_VERSIONS = { b'8965B48310\x00\x00\x00\x00\x00\x00', b'8965B48320\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'\x01F15260E051\x00\x00\x00\x00\x00\x00', b'\x01F15260E061\x00\x00\x00\x00\x00\x00', b'\x01F15260E110\x00\x00\x00\x00\x00\x00', @@ -967,7 +967,7 @@ FW_VERSIONS = { b'8965B48241\x00\x00\x00\x00\x00\x00', b'8965B48310\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'\x01F15264872300\x00\x00\x00\x00', b'\x01F15264872400\x00\x00\x00\x00', b'\x01F15264872500\x00\x00\x00\x00', @@ -1015,7 +1015,7 @@ FW_VERSIONS = { b'\x02353P7000\x00\x00\x00\x00\x00\x00\x00\x00530J5000\x00\x00\x00\x00\x00\x00\x00\x00', b'\x02353P9000\x00\x00\x00\x00\x00\x00\x00\x00553C1000\x00\x00\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152653300\x00\x00\x00\x00\x00\x00', b'F152653301\x00\x00\x00\x00\x00\x00', b'F152653310\x00\x00\x00\x00\x00\x00', @@ -1099,7 +1099,7 @@ FW_VERSIONS = { b'8965B47050\x00\x00\x00\x00\x00\x00', b'8965B47060\x00\x00\x00\x00\x00\x00', # This is the EPS with good angle sensor ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152647290\x00\x00\x00\x00\x00\x00', b'F152647300\x00\x00\x00\x00\x00\x00', b'F152647310\x00\x00\x00\x00\x00\x00', @@ -1140,7 +1140,7 @@ FW_VERSIONS = { ], }, CAR.PRIUS_V: { - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152647280\x00\x00\x00\x00\x00\x00', ], (Ecu.engine, 0x7e0, None): [ @@ -1173,7 +1173,7 @@ FW_VERSIONS = { b'8965B42082\x00\x00\x00\x00\x00\x00', b'8965B42083\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F15260R102\x00\x00\x00\x00\x00\x00', b'F15260R103\x00\x00\x00\x00\x00\x00', b'F152642493\x00\x00\x00\x00\x00\x00', @@ -1210,7 +1210,7 @@ FW_VERSIONS = { b'8965B42162\x00\x00\x00\x00\x00\x00', b'8965B42163\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152642090\x00\x00\x00\x00\x00\x00', b'F152642110\x00\x00\x00\x00\x00\x00', b'F152642120\x00\x00\x00\x00\x00\x00', @@ -1272,7 +1272,7 @@ FW_VERSIONS = { b'\x02896634A47000\x00\x00\x00\x00897CF4201001\x00\x00\x00\x00', b'\x028966342Z8000\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'\x01F15260R210\x00\x00\x00\x00\x00\x00', b'\x01F15260R220\x00\x00\x00\x00\x00\x00', b'\x01F15260R290\x00\x00\x00\x00\x00\x00', @@ -1313,7 +1313,7 @@ FW_VERSIONS = { ], }, CAR.RAV4_TSS2_2022: { - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'\x01F15260R350\x00\x00\x00\x00\x00\x00', b'\x01F15260R361\x00\x00\x00\x00\x00\x00', ], @@ -1353,7 +1353,7 @@ FW_VERSIONS = { b'\x02896634A14001\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', b'\x02896634A14101\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152642291\x00\x00\x00\x00\x00\x00', b'F152642290\x00\x00\x00\x00\x00\x00', b'F152642322\x00\x00\x00\x00\x00\x00', @@ -1392,7 +1392,7 @@ FW_VERSIONS = { ], }, CAR.RAV4H_TSS2_2022: { - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'\x01F15264283100\x00\x00\x00\x00', b'\x01F15264286200\x00\x00\x00\x00', b'\x01F15264286100\x00\x00\x00\x00', @@ -1440,7 +1440,7 @@ FW_VERSIONS = { b'8965B45080\x00\x00\x00\x00\x00\x00', b'8965B45082\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152608130\x00\x00\x00\x00\x00\x00', ], (Ecu.dsu, 0x791, None): [ @@ -1459,7 +1459,7 @@ FW_VERSIONS = { (Ecu.dsu, 0x791, None): [ b'881517601100\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152676144\x00\x00\x00\x00\x00\x00', ], (Ecu.engine, 0x7e0, None): [ @@ -1481,7 +1481,7 @@ FW_VERSIONS = { b'\x018966333X6000\x00\x00\x00\x00', b'\x01896633T07000\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'\x01F152606281\x00\x00\x00\x00\x00\x00', b'\x01F152606340\x00\x00\x00\x00\x00\x00', b'\x01F152606461\x00\x00\x00\x00\x00\x00', @@ -1518,7 +1518,7 @@ FW_VERSIONS = { b'\x02896633T09000\x00\x00\x00\x00897CF3307001\x00\x00\x00\x00', b'\x01896633T38000\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152633423\x00\x00\x00\x00\x00\x00', b'F152633680\x00\x00\x00\x00\x00\x00', b'F152633681\x00\x00\x00\x00\x00\x00', @@ -1551,7 +1551,7 @@ FW_VERSIONS = { (Ecu.engine, 0x7e0, None): [ b'\x02333M4200\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152633171\x00\x00\x00\x00\x00\x00', ], (Ecu.dsu, 0x791, None): [ @@ -1577,7 +1577,7 @@ FW_VERSIONS = { b'\x01896637854000\x00\x00\x00\x00', b'\x01896637878000\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152678130\x00\x00\x00\x00\x00\x00', b'F152678140\x00\x00\x00\x00\x00\x00', ], @@ -1604,7 +1604,7 @@ FW_VERSIONS = { b'\x018966378B3000\x00\x00\x00\x00', b'\x018966378G3000\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'\x01F152678221\x00\x00\x00\x00\x00\x00', ], (Ecu.eps, 0x7a1, None): [ @@ -1624,7 +1624,7 @@ FW_VERSIONS = { (Ecu.engine, 0x7e0, None): [ b'\x0237887000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152678210\x00\x00\x00\x00\x00\x00', ], (Ecu.eps, 0x7a1, None): [ @@ -1645,7 +1645,7 @@ FW_VERSIONS = { b'\x0237882000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', b'\x0237886000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152678160\x00\x00\x00\x00\x00\x00', b'F152678170\x00\x00\x00\x00\x00\x00', b'F152678171\x00\x00\x00\x00\x00\x00', @@ -1672,7 +1672,7 @@ FW_VERSIONS = { (Ecu.engine, 0x7e0, None): [ b'\x0232484000\x00\x00\x00\x00\x00\x00\x00\x0052422000\x00\x00\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152624221\x00\x00\x00\x00\x00\x00', ], (Ecu.dsu, 0x791, None): [ @@ -1708,7 +1708,7 @@ FW_VERSIONS = { b'\x018966348R8500\x00\x00\x00\x00', b'\x018966348W1300\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152648472\x00\x00\x00\x00\x00\x00', b'F152648473\x00\x00\x00\x00\x00\x00', b'F152648492\x00\x00\x00\x00\x00\x00', @@ -1755,7 +1755,7 @@ FW_VERSIONS = { b'\x02348V6000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', b'\x02348Z3000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152648361\x00\x00\x00\x00\x00\x00', b'F152648501\x00\x00\x00\x00\x00\x00', b'F152648502\x00\x00\x00\x00\x00\x00', @@ -1803,7 +1803,7 @@ FW_VERSIONS = { b'\x01896634D43000\x00\x00\x00\x00', b'\x01896634D44000\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'\x01F15260E031\x00\x00\x00\x00\x00\x00', b'\x01F15260E041\x00\x00\x00\x00\x00\x00', b'\x01F152648781\x00\x00\x00\x00\x00\x00', @@ -1833,7 +1833,7 @@ FW_VERSIONS = { b'\x0234D16000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', b'\x02348X4000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152648831\x00\x00\x00\x00\x00\x00', b'F152648891\x00\x00\x00\x00\x00\x00', b'F152648D00\x00\x00\x00\x00\x00\x00', @@ -1863,7 +1863,7 @@ FW_VERSIONS = { b'\x038966347C5000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4707101\x00\x00\x00\x00', b'\x038966347C5100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4707101\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152647500\x00\x00\x00\x00\x00\x00', b'F152647510\x00\x00\x00\x00\x00\x00', b'F152647520\x00\x00\x00\x00\x00\x00', @@ -1883,8 +1883,8 @@ FW_VERSIONS = { ], }, CAR.MIRAI: { - (Ecu.esp, 0x7D1, None): [b'\x01898A36203000\x00\x00\x00\x00',], - (Ecu.esp, 0x7B0, None): [ # a second ESP ECU + (Ecu.abs, 0x7D1, None): [b'\x01898A36203000\x00\x00\x00\x00',], + (Ecu.abs, 0x7B0, None): [ # a second ABS ECU b'\x01F15266203200\x00\x00\x00\x00', b'\x01F15266203500\x00\x00\x00\x00', ], @@ -1917,7 +1917,7 @@ FW_VERSIONS = { (Ecu.eps, 0x7a1, None): [ b'8965B58040\x00\x00\x00\x00\x00\x00', ], - (Ecu.esp, 0x7b0, None): [ + (Ecu.abs, 0x7b0, None): [ b'F152658341\x00\x00\x00\x00\x00\x00' ], (Ecu.fwdRadar, 0x750, 0xf): [ diff --git a/selfdrive/controls/tests/test_startup.py b/selfdrive/controls/tests/test_startup.py index a94311c8c..63af4c7d9 100755 --- a/selfdrive/controls/tests/test_startup.py +++ b/selfdrive/controls/tests/test_startup.py @@ -18,7 +18,7 @@ Ecu = car.CarParams.Ecu COROLLA_FW_VERSIONS = [ (Ecu.engine, 0x7e0, None, b'\x0230ZC2000\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00'), - (Ecu.esp, 0x7b0, None, b'F152602190\x00\x00\x00\x00\x00\x00'), + (Ecu.abs, 0x7b0, None, b'F152602190\x00\x00\x00\x00\x00\x00'), (Ecu.eps, 0x7a1, None, b'8965B02181\x00\x00\x00\x00\x00\x00'), (Ecu.fwdRadar, 0x750, 0xf, b'8821F4702100\x00\x00\x00\x00'), (Ecu.fwdCamera, 0x750, 0x6d, b'8646F0201101\x00\x00\x00\x00'), @@ -29,7 +29,7 @@ COROLLA_FW_VERSIONS_NO_DSU = COROLLA_FW_VERSIONS[:-1] CX5_FW_VERSIONS = [ (Ecu.engine, 0x7e0, None, b'PYNF-188K2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00'), - (Ecu.esp, 0x760, None, b'K123-437K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00'), + (Ecu.abs, 0x760, None, b'K123-437K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00'), (Ecu.eps, 0x730, None, b'KJ01-3210X-G-00\x00\x00\x00\x00\x00\x00\x00\x00\x00'), (Ecu.fwdRadar, 0x764, None, b'K123-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00'), (Ecu.fwdCamera, 0x706, None, b'B61L-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00'),