diff --git a/.gitmodules b/.gitmodules index d515d1f21d..26f93ef164 100644 --- a/.gitmodules +++ b/.gitmodules @@ -1,9 +1,9 @@ [submodule "panda"] path = panda - url = ../../jnewb1/panda.git + url = ../../commaai/panda.git [submodule "opendbc"] path = opendbc - url = ../../jnewb1/opendbc.git + url = ../../commaai/opendbc.git [submodule "laika_repo"] path = laika_repo url = ../../commaai/laika.git diff --git a/Jenkinsfile b/Jenkinsfile index 4e80b5fa3c..88f98f33e9 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -125,6 +125,21 @@ pipeline { } */ + stage('tizi-tests') { + agent { docker { image 'ghcr.io/commaai/alpine-ssh'; args '--user=root' } } + steps { + phone_steps("tizi", [ + ["build openpilot", "cd selfdrive/manager && ./build.py"], + ["test boardd loopback", "SINGLE_PANDA=1 python selfdrive/boardd/tests/test_boardd_loopback.py"], + ["test pandad", "python selfdrive/boardd/tests/test_pandad.py"], + ["test sensord", "cd system/sensord/tests && python -m unittest test_sensord.py"], + ["test camerad", "python system/camerad/test/test_camerad.py"], + ["test exposure", "python system/camerad/test/test_exposure.py"], + ["test amp", "python system/hardware/tici/tests/test_amplifier.py"], + ]) + } + } + stage('build') { agent { docker { image 'ghcr.io/commaai/alpine-ssh'; args '--user=root' } } environment { @@ -156,7 +171,7 @@ pipeline { steps { phone_steps("tici-common", [ ["build", "cd selfdrive/manager && ./build.py"], - ["test power draw", "python system/hardware/tici/test_power_draw.py"], + ["test power draw", "python system/hardware/tici/tests/test_power_draw.py"], ["test loggerd", "python system/loggerd/tests/test_loggerd.py"], ["test encoder", "LD_LIBRARY_PATH=/usr/local/lib python system/loggerd/tests/test_encoder.py"], ["test pigeond", "python system/sensord/tests/test_pigeond.py"], diff --git a/RELEASES.md b/RELEASES.md index 55edc47c27..34ca0338ed 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -2,7 +2,9 @@ Version 0.9.2 (2023-03-XX) ======================== * New driving model, trained on a new dataset * Draw MPC path instead of model predicted path, this is a more accurate representation of what the car will do. +* Chevrolet Trailblazer 2021-22 support thanks to TurboCE! * Buick LaCrosse 2017-19 support thanks to koch-cf! +* Kia Niro EV 2023 support thanks to JosselinLecocq! * Škoda Fabia 2022-23 support thanks to jyoung8607! Version 0.9.1 (2023-02-28) diff --git a/SConstruct b/SConstruct index 387d2e76f4..1c9ce74853 100644 --- a/SConstruct +++ b/SConstruct @@ -5,6 +5,8 @@ import sysconfig import platform import numpy as np +import SCons.Errors + TICI = os.path.isfile('/TICI') AGNOS = TICI @@ -311,7 +313,11 @@ else: elif arch != "Darwin": qt_libs += ["GL"] -qt_env.Tool('qt') +try: + qt_env.Tool('qt3') +except SCons.Errors.UserError: + qt_env.Tool('qt') + qt_env['CPPPATH'] += qt_dirs + ["#selfdrive/ui/qt/"] qt_flags = [ "-D_REENTRANT", @@ -434,9 +440,6 @@ SConscript(['selfdrive/navd/SConscript']) if arch in ['x86_64', 'Darwin'] or GetOption('extras'): SConscript(['tools/replay/SConscript']) - - opendbc = abspath([File('opendbc/can/libdbc.so')]) - Export('opendbc') SConscript(['tools/cabana/SConscript']) external_sconscript = GetOption('external_sconscript') diff --git a/cereal b/cereal index d70d215de6..4f5502c865 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit d70d215de6c584f671272d2de2f46a4f778e9f14 +Subproject commit 4f5502c8657813ccb538e9575ca1a7b258b17af9 diff --git a/common/gpio.py b/common/gpio.py index 260f8898a1..711fcff85d 100644 --- a/common/gpio.py +++ b/common/gpio.py @@ -1,4 +1,5 @@ -from typing import Optional +import glob +from typing import Optional, List def gpio_init(pin: int, output: bool) -> None: try: @@ -23,3 +24,13 @@ def gpio_read(pin: int) -> Optional[bool]: print(f"Failed to set gpio {pin} value: {e}") return val + +def get_irq_for_action(action: str) -> List[int]: + ret = [] + for fn in glob.glob('/sys/kernel/irq/*/actions'): + with open(fn) as f: + actions = f.read().strip().split(',') + if action in actions: + irq = int(fn.split('/')[-2]) + ret.append(irq) + return ret diff --git a/common/statlog.cc b/common/statlog.cc index 26945882d9..587f3e8620 100644 --- a/common/statlog.cc +++ b/common/statlog.cc @@ -5,6 +5,7 @@ #include "common/statlog.h" #include "common/util.h" +#include #include #include #include diff --git a/common/swaglog.cc b/common/swaglog.cc index 22682dc54c..54f1c3478a 100644 --- a/common/swaglog.cc +++ b/common/swaglog.cc @@ -5,6 +5,7 @@ #include "common/swaglog.h" #include +#include #include #include #include diff --git a/docs/CARS.md b/docs/CARS.md index 7c8170c275..96b30fcf1c 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -2,9 +2,9 @@ # Supported Cars -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. +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. Supported vehicles reference the US market unless otherwise specified. -# 239 Supported Cars +# 241 Supported Cars |Make|Model|Supported Package|ACC|No ACC accel below|No ALC below|Steering Torque|Resume from stop|Harness|Video| |---|---|---|:---:|:---:|:---:|:---:|:---:|:---:|:---:| @@ -23,6 +23,7 @@ A supported vehicle is one that just works when you install a comma three. All s |Chevrolet|Bolt EUV 2022-23|Premier or Premier Redline Trim without Super Cruise Package|openpilot available[1](#footnotes)|3 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|GM|| |Chevrolet|Bolt EV 2022-23|2LT Trim with Adaptive Cruise Control Package|openpilot available[1](#footnotes)|3 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|GM|| |Chevrolet|Silverado 1500 2020-21|Safety Package II|openpilot available[1](#footnotes)|3 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|GM|| +|Chevrolet|Trailblazer 2021-22|Adaptive Cruise Control (ACC)|openpilot available[1](#footnotes)|3 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|GM|| |Chevrolet|Volt 2017-18[3](#footnotes)|Adaptive Cruise Control (ACC)|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 (ACC)|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 (ACC)|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|FCA|| @@ -44,9 +45,9 @@ A supported vehicle is one that just works when you install a comma three. All s |Honda|Accord Hybrid 2018-22|All|openpilot available[1](#footnotes)|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|openpilot available[1](#footnotes)|0 mph|2 mph[4](#footnotes)|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch A|| -|Honda|Civic 2022|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch B|| +|Honda|Civic 2022|All|openpilot available[1](#footnotes)|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|openpilot available[1](#footnotes)|0 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch A|| -|Honda|Civic Hatchback 2022|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch B|| +|Honda|Civic Hatchback 2022|All|openpilot available[1](#footnotes)|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|openpilot available[1](#footnotes)|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|openpilot available[1](#footnotes)|0 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch A|| @@ -107,6 +108,7 @@ A supported vehicle is one that just works when you install a comma three. All s |Kia|Niro EV 2020|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai F|| |Kia|Niro EV 2021|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C|| |Kia|Niro EV 2022|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai H|| +|Kia|Niro EV 2023[5](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai A|| |Kia|Niro Hybrid 2021|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|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)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai H|| |Kia|Niro Hybrid 2023[5](#footnotes)|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai A|| @@ -237,8 +239,8 @@ A supported vehicle is one that just works when you install a comma three. All s |Volkswagen|Passat 2015-22[8](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|| |Volkswagen|Passat Alltrack 2015-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|| |Volkswagen|Passat GTE 2015-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|| -|Volkswagen|Polo 2020-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533[10](#footnotes)|| -|Volkswagen|Polo GTI 2020-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533[10](#footnotes)|| +|Volkswagen|Polo 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533[10](#footnotes)|| +|Volkswagen|Polo GTI 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533[10](#footnotes)|| |Volkswagen|T-Cross 2021|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533[10](#footnotes)|| |Volkswagen|T-Roc 2021|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533[10](#footnotes)|| |Volkswagen|Taos 2022|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|| diff --git a/opendbc b/opendbc index 14eb9de2d9..3c81860270 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit 14eb9de2d923235a485abbc9b5e8d33c03a06278 +Subproject commit 3c81860270e918d1a08f14a833522fd798aa39ca diff --git a/poetry.lock b/poetry.lock index b7554ac03a..5d60353f80 100644 --- a/poetry.lock +++ b/poetry.lock @@ -55,7 +55,7 @@ frozenlist = ">=1.1.0" name = "alabaster" version = "0.7.12" description = "A configurable sidebar-enabled Sphinx theme" -category = "dev" +category = "main" optional = false python-versions = "*" @@ -374,7 +374,7 @@ azure-nspkg = ">=2.0.0" name = "babel" version = "2.10.3" description = "Internationalization utilities" -category = "dev" +category = "main" optional = false python-versions = ">=3.6" @@ -856,7 +856,7 @@ python-versions = "*" name = "docutils" version = "0.17.1" description = "Docutils -- Python Documentation Utilities" -category = "dev" +category = "main" optional = false python-versions = ">=2.7, !=3.0.*, !=3.1.*, !=3.2.*, !=3.3.*, !=3.4.*" @@ -1390,7 +1390,7 @@ tifffile = ["tifffile"] name = "imagesize" version = "1.4.1" description = "Getting image size from png/jpeg/jpeg2000/gif file" -category = "dev" +category = "main" optional = false python-versions = ">=2.7, !=3.0.*, !=3.1.*, !=3.2.*, !=3.3.*" @@ -2519,6 +2519,33 @@ category = "main" optional = false python-versions = ">=3.8" +[[package]] +name = "nvidia-cublas-cu12" +version = "12.1.0.26" +description = "CUBLAS native runtime libraries" +category = "dev" +optional = false +python-versions = ">=3" + +[[package]] +name = "nvidia-cuda-runtime-cu12" +version = "12.1.55" +description = "CUDA Runtime native Libraries" +category = "dev" +optional = false +python-versions = ">=3" + +[[package]] +name = "nvidia-cudnn-cu12" +version = "8.9.0.131" +description = "cuDNN runtime libraries" +category = "dev" +optional = false +python-versions = ">=3" + +[package.dependencies] +nvidia-cublas-cu12 = "*" + [[package]] name = "nvidia-ml-py3" version = "7.352.0" @@ -2703,6 +2730,23 @@ category = "dev" optional = false python-versions = ">=2.7, !=3.0.*, !=3.1.*, !=3.2.*, !=3.3.*" +[[package]] +name = "panflute" +version = "2.3.0" +description = "Pythonic Pandoc filters" +category = "main" +optional = false +python-versions = ">=3.6" + +[package.dependencies] +click = ">=6,<9" +pyyaml = ">=3,<7" + +[package.extras] +dev = ["configparser", "coverage", "flake8", "pandocfilters", "pytest", "pytest-cov", "requests"] +extras = ["yamlloader (>=1,<2)"] +pypi = ["Pygments", "docutils", "twine", "wheel"] + [[package]] name = "parameterized" version = "0.8.1" @@ -3115,7 +3159,7 @@ python-versions = ">=3.6" name = "pygments" version = "2.13.0" description = "Pygments is a syntax highlighting package written in Python." -category = "dev" +category = "main" optional = false python-versions = ">=3.6" @@ -3426,7 +3470,7 @@ numpy = ["numpy (>=1.6.0)"] name = "pytz" version = "2022.5" description = "World timezone definitions, modern and historical" -category = "dev" +category = "main" optional = false python-versions = "*" @@ -3714,6 +3758,27 @@ python-versions = ">=3.6" [package.dependencies] setuptools = "*" +[[package]] +name = "sconscontrib" +version = "1.0" +description = "" +category = "main" +optional = false +python-versions = ">=3.6, <4" +develop = false + +[package.dependencies] +docutils = "*" +panflute = "*" +SCons = ">=4" +sphinx = "*" + +[package.source] +type = "git" +url = "https://github.com/SCons/scons-contrib.git" +reference = "HEAD" +resolved_reference = "f3b0100d3a628e4d18f496815903660a99489bae" + [[package]] name = "secretstorage" version = "3.3.3" @@ -3892,7 +3957,7 @@ python-versions = ">=3.7" name = "snowballstemmer" version = "2.2.0" description = "This package provides 29 stemmers for 28 languages generated from Snowball algorithms." -category = "dev" +category = "main" optional = false python-versions = "*" @@ -3930,7 +3995,7 @@ python-versions = ">=3.6" name = "sphinx" version = "5.3.0" description = "Python documentation generator" -category = "dev" +category = "main" optional = false python-versions = ">=3.6" @@ -3989,7 +4054,7 @@ sphinx = ">=1.2" name = "sphinxcontrib-applehelp" version = "1.0.2" description = "sphinxcontrib-applehelp is a sphinx extension which outputs Apple help books" -category = "dev" +category = "main" optional = false python-versions = ">=3.5" @@ -4001,7 +4066,7 @@ test = ["pytest"] name = "sphinxcontrib-devhelp" version = "1.0.2" description = "sphinxcontrib-devhelp is a sphinx extension which outputs Devhelp document." -category = "dev" +category = "main" optional = false python-versions = ">=3.5" @@ -4013,7 +4078,7 @@ test = ["pytest"] name = "sphinxcontrib-htmlhelp" version = "2.0.0" description = "sphinxcontrib-htmlhelp is a sphinx extension which renders HTML help files" -category = "dev" +category = "main" optional = false python-versions = ">=3.6" @@ -4025,7 +4090,7 @@ test = ["html5lib", "pytest"] name = "sphinxcontrib-jsmath" version = "1.0.1" description = "A sphinx extension which renders display math in HTML via JavaScript" -category = "dev" +category = "main" optional = false python-versions = ">=3.5" @@ -4036,7 +4101,7 @@ test = ["flake8", "mypy", "pytest"] name = "sphinxcontrib-qthelp" version = "1.0.3" description = "sphinxcontrib-qthelp is a sphinx extension which outputs QtHelp document." -category = "dev" +category = "main" optional = false python-versions = ">=3.5" @@ -4048,7 +4113,7 @@ test = ["pytest"] name = "sphinxcontrib-serializinghtml" version = "1.1.5" description = "sphinxcontrib-serializinghtml is a sphinx extension which outputs \"serialized\" HTML files (json and pickle)." -category = "dev" +category = "main" optional = false python-versions = ">=3.5" @@ -4164,6 +4229,22 @@ python-versions = ">=3.6" [package.extras] doc = ["reno", "sphinx", "tornado (>=4.5)"] +[[package]] +name = "tensorrt" +version = "8.6.0" +description = "A high performance deep learning inference library" +category = "dev" +optional = false +python-versions = "*" + +[package.dependencies] +nvidia-cublas-cu12 = "*" +nvidia-cuda-runtime-cu12 = "*" +nvidia-cudnn-cu12 = "*" + +[package.extras] +numpy = ["numpy"] + [[package]] name = "terminado" version = "0.16.0" @@ -4659,7 +4740,7 @@ testing = ["coverage (>=5.0.3)", "zope.event", "zope.testing"] [metadata] lock-version = "1.1" python-versions = "~3.8" -content-hash = "b7cd75dfa0dcddff224696ccc7f41d87aac64652f744ab386321c1eee920fbe9" +content-hash = "774e90b7d2bef68c6d219c8afc3d5717a104a04b9cd7b1b215655eb48fa62d04" [metadata.files] adal = [ @@ -5579,6 +5660,14 @@ fastcluster = [ {file = "fastcluster-1.2.6-cp310-cp310-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:9020899b67fe492d0ed87a3e993ec9962c5a0b51ea2df71d86b1766f065f1cef"}, {file = "fastcluster-1.2.6-cp310-cp310-win32.whl", hash = "sha256:6cf156d4203708348522393c523c2e61c81f5a6a500e0411dcba2b064551ea2f"}, {file = "fastcluster-1.2.6-cp310-cp310-win_amd64.whl", hash = "sha256:1801c9daa9aa5bbbb0830efe8bd3034b4b7a417e4b8dd353683999be29797df2"}, + {file = "fastcluster-1.2.6-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:ce70c743490f6778b463524d1767a9ecccd31c8bd2dbb5739bb2174168c15d39"}, + {file = "fastcluster-1.2.6-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:ac1b84d4b28456a379a71451d13995eb3242143452ce9c861f8913360de842a3"}, + {file = "fastcluster-1.2.6-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:55b49f6033c45a28f93540847b495ed0f718b5c3f4fef446cf77e3726662e1d5"}, + {file = "fastcluster-1.2.6-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:c1c776a4ec7594f47cd2e1e2da73a30134f1d402d7c93a81e3cb7c3d8e191173"}, + {file = "fastcluster-1.2.6-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:aca61d16435bb7aea3901939d7d7d7e36aff9bb538123e649166a3014b280054"}, + {file = "fastcluster-1.2.6-cp311-cp311-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:04ea4a68e0675072ca761bad33322a0e998cb43693fd41165bc420d7db40429a"}, + {file = "fastcluster-1.2.6-cp311-cp311-win32.whl", hash = "sha256:773043d5db2790e1ff2a4e1eae0b6a60afb2a93ad2c74897a56c80bc800db04f"}, + {file = "fastcluster-1.2.6-cp311-cp311-win_amd64.whl", hash = "sha256:841d128daa6597d13781793eb482b0b566bbd58d2a9d1e2cf1b58838773beb14"}, {file = "fastcluster-1.2.6-cp36-cp36m-macosx_10_9_x86_64.whl", hash = "sha256:cf5acfe1156849279ebd44a8d1fbcbe8b8e21334f7538eda782ae31e7dade9e2"}, {file = "fastcluster-1.2.6-cp36-cp36m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:cb27c13225f5f77f3c5986a27ca27277cce7db12844330cf535019cd38021257"}, {file = "fastcluster-1.2.6-cp36-cp36m-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:5fe543b6d45da27e84e5af6248722475b88943d8ef40d835cbabbb0ba5ee786b"}, @@ -6860,6 +6949,17 @@ numpy = [ {file = "numpy-1.23.4-pp38-pypy38_pp73-win_amd64.whl", hash = "sha256:4d52914c88b4930dafb6c48ba5115a96cbab40f45740239d9f4159c4ba779962"}, {file = "numpy-1.23.4.tar.gz", hash = "sha256:ed2cc92af0efad20198638c69bb0fc2870a58dabfba6eb722c933b48556c686c"}, ] +nvidia-cublas-cu12 = [ + {file = "nvidia_cublas_cu12-12.1.0.26-py3-none-manylinux1_x86_64.whl", hash = "sha256:4fd00bd12d442f53929616f45ba67552a13d8940f6e766d11d83973a21ada910"}, + {file = "nvidia_cublas_cu12-12.1.0.26-py3-none-win_amd64.whl", hash = "sha256:5c668dcb5cbf49e1add058328300aa90fd012eb958a646a8777d55da2eca5eaa"}, +] +nvidia-cuda-runtime-cu12 = [ + {file = "nvidia_cuda_runtime_cu12-12.1.55-py3-none-manylinux1_x86_64.whl", hash = "sha256:a485693383c7a28ba022587c5a640353ef61a21eb2e87382d0a76340bda92e2e"}, + {file = "nvidia_cuda_runtime_cu12-12.1.55-py3-none-win_amd64.whl", hash = "sha256:6939e48161354dbc096dcc6f7910cb2387227f0bac462c2cff51a7d5b50ad200"}, +] +nvidia-cudnn-cu12 = [ + {file = "nvidia_cudnn_cu12-8.9.0.131-py3-none-manylinux1_x86_64.whl", hash = "sha256:2a95c2e0201187509021270f52971435d171e65627a482b9ebdfdde6749ad485"}, +] nvidia-ml-py3 = [ {file = "nvidia-ml-py3-7.352.0.tar.gz", hash = "sha256:390f02919ee9d73fe63a98c73101061a6b37fa694a793abf56673320f1f51277"}, ] @@ -6980,6 +7080,10 @@ pandocfilters = [ {file = "pandocfilters-1.5.0-py2.py3-none-any.whl", hash = "sha256:33aae3f25fd1a026079f5d27bdd52496f0e0803b3469282162bafdcbdf6ef14f"}, {file = "pandocfilters-1.5.0.tar.gz", hash = "sha256:0b679503337d233b4339a817bfc8c50064e2eff681314376a47cb582305a7a38"}, ] +panflute = [ + {file = "panflute-2.3.0-py3-none-any.whl", hash = "sha256:02673bcbdb521a805f08a2ca0ce864de86ad409ad406a01b3700fcf2aca81635"}, + {file = "panflute-2.3.0.tar.gz", hash = "sha256:cefd9dfc48ccd9732a53db57610701d22806da397a8a97e5cc8dc070b55865ca"}, +] parameterized = [ {file = "parameterized-0.8.1-py2.py3-none-any.whl", hash = "sha256:9cbb0b69a03e8695d68b3399a8a5825200976536fe1cb79db60ed6a4c8c9efe9"}, {file = "parameterized-0.8.1.tar.gz", hash = "sha256:41bbff37d6186430f77f900d777e5bb6a24928a1c46fb1de692f8b52b8833b5c"}, @@ -7968,6 +8072,7 @@ scons = [ {file = "SCons-4.4.0-py3-none-any.whl", hash = "sha256:cbbd73b83cf85f1aaaf986370359de1bbfd3af97a765cb3554734f6dcec734e1"}, {file = "SCons-4.4.0.tar.gz", hash = "sha256:7703c4e9d2200b4854a31800c1dbd4587e1fa86e75f58795c740bcfa7eca7eaa"}, ] +sconscontrib = [] secretstorage = [ {file = "SecretStorage-3.3.3-py3-none-any.whl", hash = "sha256:f356e6628222568e3af06f2eba8df495efa13b3b63081dafd4f7d9a7b7bc9f99"}, {file = "SecretStorage-3.3.3.tar.gz", hash = "sha256:2403533ef369eca6d2ba81718576c5e0f564d5cca1b58f73a8b23e7d4eeebd77"}, @@ -8314,6 +8419,13 @@ tenacity = [ {file = "tenacity-8.1.0-py3-none-any.whl", hash = "sha256:35525cd47f82830069f0d6b73f7eb83bc5b73ee2fff0437952cedf98b27653ac"}, {file = "tenacity-8.1.0.tar.gz", hash = "sha256:e48c437fdf9340f5666b92cd7990e96bc5fc955e1298baf4a907e3972067a445"}, ] +tensorrt = [ + {file = "tensorrt-8.6.0-cp310-none-manylinux_2_17_x86_64.whl", hash = "sha256:8850d470a92e17e65686fce2a5105dc51fc89f2b438d60d66027288a165732ba"}, + {file = "tensorrt-8.6.0-cp36-none-manylinux_2_17_x86_64.whl", hash = "sha256:1eb0b9b29f3f6c9a6f737b95d1edfe63353dd6b5427478b1c580c9cb72340749"}, + {file = "tensorrt-8.6.0-cp37-none-manylinux_2_17_x86_64.whl", hash = "sha256:ae2e99fb98952d71d6a7443335f7f8e1a8c471b8136e33bb491f11e410dea3cd"}, + {file = "tensorrt-8.6.0-cp38-none-manylinux_2_17_x86_64.whl", hash = "sha256:ba9eb8d1a7c32c63981b4203b72b90b38402ad000ec554fb8dd85a7401de60dd"}, + {file = "tensorrt-8.6.0-cp39-none-manylinux_2_17_x86_64.whl", hash = "sha256:4dc971cd8def3b41086c34d93ca8bff56f5d7d9a2ab5f8738307d040b0bf751e"}, +] terminado = [ {file = "terminado-0.16.0-py3-none-any.whl", hash = "sha256:3e995072a7178a104c41134548ce9b03e4e7f0a538e9c29df4f1fbc81c7cfc75"}, {file = "terminado-0.16.0.tar.gz", hash = "sha256:fac14374eb5498bdc157ed32e510b1f60d5c3c7981a9f5ba018bb9a64cec0c25"}, diff --git a/pyproject.toml b/pyproject.toml index 47994779b2..25b61eb50b 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -59,6 +59,7 @@ urllib3 = "^1.26.10" utm = "^0.7.0" websocket_client = "^1.3.3" polyline = "^1.4.0" +sconscontrib = {git = "https://github.com/SCons/scons-contrib.git"} [tool.poetry.group.dev.dependencies] @@ -175,6 +176,7 @@ zerorpc = { git = "https://github.com/commaai/zerorpc-python.git", branch = "mas omegaconf = "^2.3.0" osmnx = "==1.2.2" tritonclient = {version = "2.28.0", extras = ["http"]} +tensorrt = "^8.6.0" [build-system] diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index 8f045c2a69..2454ee51d8 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -363,6 +363,8 @@ std::optional send_panda_states(PubMaster *pm, const std::vector } auto ps = pss[i]; + ps.setVoltage(health.voltage_pkt); + ps.setCurrent(health.current_pkt); ps.setUptime(health.uptime_pkt); ps.setSafetyTxBlocked(health.safety_tx_blocked_pkt); ps.setSafetyRxInvalid(health.safety_rx_invalid_pkt); @@ -384,6 +386,7 @@ std::optional send_panda_states(PubMaster *pm, const std::vector ps.setInterruptLoad(health.interrupt_load); ps.setFanPower(health.fan_power); ps.setSafetyRxChecksInvalid((bool)(health.safety_rx_checks_invalid)); + ps.setSpiChecksumErrorCount(health.spi_checksum_error_count); std::array cs = {ps.initCanState0(), ps.initCanState1(), ps.initCanState2()}; @@ -418,7 +421,7 @@ std::optional send_panda_states(PubMaster *pm, const std::vector size_t j = 0; for (size_t f = size_t(cereal::PandaState::FaultType::RELAY_MALFUNCTION); - f <= size_t(cereal::PandaState::FaultType::SIREN_MALFUNCTION); f++) { + f <= size_t(cereal::PandaState::FaultType::HEARTBEAT_LOOP_WATCHDOG); f++) { if (fault_bits.test(f)) { faults.set(j, cereal::PandaState::FaultType(f)); j++; diff --git a/selfdrive/boardd/set_time.py b/selfdrive/boardd/set_time.py index 7d17be4de9..790baa094f 100755 --- a/selfdrive/boardd/set_time.py +++ b/selfdrive/boardd/set_time.py @@ -1,11 +1,9 @@ #!/usr/bin/env python3 -import datetime import os -import struct -import usb1 +import datetime +from panda import Panda -REQUEST_IN = usb1.ENDPOINT_IN | usb1.TYPE_VENDOR | usb1.RECIPIENT_DEVICE -MIN_DATE = datetime.datetime(year=2021, month=4, day=1) +MIN_DATE = datetime.datetime(year=2023, month=4, day=1) def set_time(logger): sys_time = datetime.datetime.today() @@ -14,24 +12,28 @@ def set_time(logger): return try: - ctx = usb1.USBContext() - dev = ctx.openByVendorIDAndProductID(0xbbaa, 0xddcc) - if dev is None: - logger.info("No panda found") + ps = Panda.list() + if len(ps) == 0: + logger.error("Failed to set time, no pandas found") return - # Set system time from panda RTC time - dat = dev.controlRead(REQUEST_IN, 0xa0, 0, 0, 8) - a = struct.unpack("HBBBBBB", dat) - panda_time = datetime.datetime(a[0], a[1], a[2], a[4], a[5], a[6]) - if panda_time > MIN_DATE: - logger.info(f"adjusting time from '{sys_time}' to '{panda_time}'") - os.system(f"TZ=UTC date -s '{panda_time}'") + for s in ps: + with Panda(serial=s) as p: + if not p.is_internal(): + continue + + # Set system time from panda RTC time + panda_time = p.get_datetime() + logger.info(f"adjusting time from '{sys_time}' to '{panda_time}'") + if panda_time > MIN_DATE: + logger.info(f"adjusting time from '{sys_time}' to '{panda_time}'") + os.system(f"TZ=UTC date -s '{panda_time}'") + break except Exception: - logger.warn("Failed to fetch time from panda") + logger.exception("Failed to fetch time from panda") if __name__ == "__main__": import logging - logging.basicConfig(level=logging.INFO) + logging.basicConfig(level=logging.DEBUG) set_time(logging) diff --git a/selfdrive/boardd/spi.cc b/selfdrive/boardd/spi.cc index 9a10e30f95..d418d2bdac 100644 --- a/selfdrive/boardd/spi.cc +++ b/selfdrive/boardd/spi.cc @@ -57,9 +57,12 @@ PandaSpiHandle::PandaSpiHandle(std::string serial) : PandaCommsHandle(serial) { uint8_t uid[uid_len] = {0}; uint32_t spi_mode = SPI_MODE_0; - uint32_t spi_speed = 30000000; uint8_t spi_bits_per_word = 8; + // 50MHz is the max of the 845. note that some older + // revs of the comma three may not support this speed + uint32_t spi_speed = 50000000; + spi_fd = open(SPI_DEVICE.c_str(), O_RDWR); if (spi_fd < 0) { LOGE("failed opening SPI device %d", spi_fd); diff --git a/selfdrive/boardd/tests/test_boardd_loopback.py b/selfdrive/boardd/tests/test_boardd_loopback.py index d614f0b126..6217561bd1 100755 --- a/selfdrive/boardd/tests/test_boardd_loopback.py +++ b/selfdrive/boardd/tests/test_boardd_loopback.py @@ -40,8 +40,9 @@ class TestBoardd(unittest.TestCase): sm.update(1000) num_pandas = len(sm['pandaStates']) - if TICI: - self.assertGreater(num_pandas, 1, "connect another panda for multipanda tests") + expected_pandas = 2 if TICI and "SINGLE_PANDA" not in os.environ else 1 + self.assertEqual(num_pandas, expected_pandas, "connected pandas ({num_pandas}) doesn't match expected panda count ({expected_pandas}). \ + connect another panda for multipanda tests.") # boardd blocks on CarVin and CarParams cp = car.CarParams.new_message() diff --git a/selfdrive/boardd/tests/test_pandad.py b/selfdrive/boardd/tests/test_pandad.py index 3b2369b39b..94da43edf7 100755 --- a/selfdrive/boardd/tests/test_pandad.py +++ b/selfdrive/boardd/tests/test_pandad.py @@ -14,9 +14,9 @@ class TestPandad(unittest.TestCase): def tearDown(self): managed_processes['pandad'].stop() - def _wait_for_boardd(self): + def _wait_for_boardd(self, timeout=30): sm = messaging.SubMaster(['peripheralState']) - for _ in range(30): + for _ in range(timeout): sm.update(1000) if sm.updated['peripheralState']: break @@ -30,7 +30,7 @@ class TestPandad(unittest.TestCase): time.sleep(1) managed_processes['pandad'].start() - self._wait_for_boardd() + self._wait_for_boardd(60) @phone_only def test_in_bootstub(self): diff --git a/selfdrive/car/CARS_template.md b/selfdrive/car/CARS_template.md index 1c80ea3d93..8a879954fa 100644 --- a/selfdrive/car/CARS_template.md +++ b/selfdrive/car/CARS_template.md @@ -6,7 +6,7 @@ # Supported Cars -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. +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. Supported vehicles reference the US market unless otherwise specified. # {{all_car_info | length}} Supported Cars diff --git a/selfdrive/car/docs_definitions.py b/selfdrive/car/docs_definitions.py index c0fb4420df..fa95b03fd8 100644 --- a/selfdrive/car/docs_definitions.py +++ b/selfdrive/car/docs_definitions.py @@ -117,8 +117,20 @@ def split_name(name: str) -> Tuple[str, str, str]: @dataclass class CarInfo: + # make + model + model years name: str + + # Example for Toyota Corolla MY20 + # requirements: Lane Tracing Assist (LTA) and Dynamic Radar Cruise Control (DRCC) + # US Market reference: "All", since all Corolla in the US come standard with LTA and DRCC + + # the simplest description of the requirements for the US market package: str + + # the minimum compatibility requirements for this model, regardless + # of market. can be a package, trim, or list of features + requirements: Optional[str] = None + video_link: Optional[str] = None footnotes: List[Enum] = field(default_factory=list) min_steer_speed: Optional[float] = None diff --git a/selfdrive/car/ford/values.py b/selfdrive/car/ford/values.py index 50c7d93987..110bf59d55 100644 --- a/selfdrive/car/ford/values.py +++ b/selfdrive/car/ford/values.py @@ -84,7 +84,7 @@ CAR_INFO: Dict[str, Union[CarInfo, List[CarInfo]]] = { FordCarInfo("Lincoln Aviator Plug-in Hybrid 2021", "Co-Pilot360 Plus"), ], CAR.FOCUS_MK4: FordCarInfo("Ford Focus EU 2019", "Driver Assistance Pack"), - CAR.MAVERICK_MK1: FordCarInfo("Ford Maverick 2022", "Co-Pilot360 Assist"), + CAR.MAVERICK_MK1: FordCarInfo("Ford Maverick 2022-23", "Co-Pilot360 Assist"), } FW_QUERY_CONFIG = FwQueryConfig( @@ -217,6 +217,7 @@ FW_VERSIONS = { ], (Ecu.abs, 0x760, None): [ b'NZ6C-2D053-AG\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PZ6C-2D053-ED\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x764, None): [ b'NZ6T-14D049-AA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', @@ -228,6 +229,7 @@ FW_VERSIONS = { b'NZ6A-14C204-AAA\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'NZ6A-14C204-PA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'NZ6A-14C204-ZA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PZ6A-14C204-JC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.shiftByWire, 0x732, None): [ b'NZ6P-14G395-AD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py index 6e2797ce24..a5425953d2 100755 --- a/selfdrive/car/gm/interface.py +++ b/selfdrive/car/gm/interface.py @@ -98,7 +98,6 @@ class CarInterface(CarInterfaceBase): # Tuning for experimental long ret.longitudinalTuning.kpV = [2.0, 1.5] ret.longitudinalTuning.kiV = [0.72] - ret.stopAccel = -2.0 ret.stoppingDecelRate = 2.0 # reach brake quickly after enabling ret.vEgoStopping = 0.25 ret.vEgoStarting = 0.25 @@ -235,6 +234,15 @@ class CarInterface(CarInterfaceBase): ret.centerToFront = ret.wheelbase * 0.4 CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) + elif candidate == CAR.TRAILBLAZER: + ret.mass = 1345. + STD_CARGO_KG + ret.wheelbase = 2.64 + ret.steerRatio = 16.8 + ret.centerToFront = ret.wheelbase * 0.4 + tire_stiffness_factor = 1.0 + ret.steerActuatorDelay = 0.2 + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) + # TODO: start from empirically derived lateral slip stiffness for the civic and scale by # mass and CG position, so all cars will have approximately similar dyn behaviors ret.tireStiffnessFront, ret.tireStiffnessRear = scale_tire_stiffness(ret.mass, ret.wheelbase, ret.centerToFront, diff --git a/selfdrive/car/gm/values.py b/selfdrive/car/gm/values.py index 1b814e00b2..bc2858a667 100644 --- a/selfdrive/car/gm/values.py +++ b/selfdrive/car/gm/values.py @@ -73,6 +73,7 @@ class CAR: BOLT_EUV = "CHEVROLET BOLT EUV 2022" SILVERADO = "CHEVROLET SILVERADO 1500 2020" EQUINOX = "CHEVROLET EQUINOX 2019" + TRAILBLAZER = "CHEVROLET TRAILBLAZER 2021" class Footnote(Enum): @@ -105,14 +106,15 @@ CAR_INFO: Dict[str, Union[GMCarInfo, List[GMCarInfo]]] = { CAR.ESCALADE: GMCarInfo("Cadillac Escalade 2017", "Driver Assist Package"), 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", "https://youtu.be/xvwzGMUA210"), + GMCarInfo("Chevrolet Bolt EUV 2022-23", "Premier or Premier Redline Trim without Super Cruise Package", video_link="https://youtu.be/xvwzGMUA210"), GMCarInfo("Chevrolet Bolt EV 2022-23", "2LT Trim with Adaptive Cruise Control Package"), ], CAR.SILVERADO: [ GMCarInfo("Chevrolet Silverado 1500 2020-21", "Safety Package II"), - GMCarInfo("GMC Sierra 1500 2020-21", "Driver Alert Package II", "https://youtu.be/5HbNoBLzRwE"), + GMCarInfo("GMC Sierra 1500 2020-21", "Driver Alert Package II", video_link="https://youtu.be/5HbNoBLzRwE"), ], CAR.EQUINOX: GMCarInfo("Chevrolet Equinox 2019-22"), + CAR.TRAILBLAZER: GMCarInfo("Chevrolet Trailblazer 2021-22"), } @@ -207,6 +209,12 @@ FINGERPRINTS = { { 190: 6, 193: 8, 197: 8, 201: 8, 209: 7, 211: 2, 241: 6, 249: 8, 257: 8, 288: 5, 289: 8, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 8, 384: 4, 386: 8, 388: 8, 413: 8, 451: 8, 452: 8, 453: 6, 455: 7, 463: 3, 479: 3, 481: 7, 485: 8, 489: 8, 497: 8, 500: 6, 501: 8, 510: 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, 753: 5, 761: 7, 789: 5, 800: 6, 810: 8, 840: 5, 842: 5, 844: 8, 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 }], + # Trailblazer also matches as a Silverado, so comment out to avoid conflicts. + # TODO: split with FW versions + CAR.TRAILBLAZER: [ + { + # 190: 6, 193: 8, 197: 8, 201: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 289: 8, 298: 8, 304: 3, 309: 8, 311: 8, 313: 8, 320: 4, 328: 1, 352: 5, 381: 8, 384: 4, 386: 8, 388: 8, 413: 8, 451: 8, 452: 8, 453: 6, 455: 7, 479: 3, 481: 7, 485: 8, 489: 8, 497: 8, 500: 6, 501: 8, 532: 6, 560: 8, 562: 8, 563: 5, 565: 5, 707: 8, 715: 8, 717: 5, 761: 7, 789: 5, 800: 6, 810: 8, 840: 5, 842: 5, 844: 8, 869: 4, 880: 6, 977: 8, 1001: 8, 1011: 6, 1017: 8, 1020: 8, 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, 1609: 8, 1613: 8, 1649: 8, 1792: 8, 1798: 8, 1824: 8, 1825: 8, 1840: 8, 1842: 8, 1858: 8, 1860: 8, 1863: 8, 1872: 8, 1875: 8, 1882: 8, 1888: 8, 1889: 8, 1892: 8, 1930: 7, 1937: 8, 1953: 8, 1968: 8, 2001: 8, 2017: 8, 2018: 8, 2020: 8 + }], } 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')) @@ -214,6 +222,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, CAR.SILVERADO, CAR.EQUINOX} +CAMERA_ACC_CAR = {CAR.BOLT_EUV, CAR.SILVERADO, CAR.EQUINOX, CAR.TRAILBLAZER} STEER_THRESHOLD = 1.0 diff --git a/selfdrive/car/honda/carstate.py b/selfdrive/car/honda/carstate.py index 8189800368..eea78758a8 100644 --- a/selfdrive/car/honda/carstate.py +++ b/selfdrive/car/honda/carstate.py @@ -293,7 +293,7 @@ class CarState(CarStateBase): if self.CP.carFingerprint in HONDA_BOSCH_RADARLESS: self.lkas_hud = cp_cam.vl["LKAS_HUD"] - if self.CP.enableBsm and self.CP.carFingerprint in (CAR.CRV_5G, ): + if self.CP.enableBsm: # BSM messages are on B-CAN, requires a panda forwarding B-CAN messages to CAN 0 # more info here: https://github.com/commaai/openpilot/pull/1867 ret.leftBlindspot = cp_body.vl["BSM_STATUS_LEFT"]["BSM_ALERT"] == 1 @@ -340,7 +340,7 @@ class CarState(CarStateBase): @staticmethod def get_body_can_parser(CP): - if CP.enableBsm and CP.carFingerprint == CAR.CRV_5G: + if CP.enableBsm: signals = [("BSM_ALERT", "BSM_STATUS_RIGHT"), ("BSM_ALERT", "BSM_STATUS_LEFT")] diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py index 009a549afd..f6be1b1e3a 100644 --- a/selfdrive/car/honda/values.py +++ b/selfdrive/car/honda/values.py @@ -116,19 +116,19 @@ class HondaCarInfo(CarInfo): CAR_INFO: Dict[str, Optional[Union[HondaCarInfo, List[HondaCarInfo]]]] = { CAR.ACCORD: [ - HondaCarInfo("Honda Accord 2018-22", "All", "https://www.youtube.com/watch?v=mrUwlj3Mi58", min_steer_speed=3. * CV.MPH_TO_MS), + HondaCarInfo("Honda Accord 2018-22", "All", video_link="https://www.youtube.com/watch?v=mrUwlj3Mi58", min_steer_speed=3. * CV.MPH_TO_MS), HondaCarInfo("Honda Inspire 2018", "All", min_steer_speed=3. * CV.MPH_TO_MS), ], CAR.ACCORDH: HondaCarInfo("Honda Accord Hybrid 2018-22", "All", min_steer_speed=3. * CV.MPH_TO_MS), CAR.CIVIC: HondaCarInfo("Honda Civic 2016-18", min_steer_speed=12. * CV.MPH_TO_MS, video_link="https://youtu.be/-IkImTe1NYE"), CAR.CIVIC_BOSCH: [ - HondaCarInfo("Honda Civic 2019-21", "All", "https://www.youtube.com/watch?v=4Iz1Mz5LGF8", [Footnote.CIVIC_DIESEL], 2. * CV.MPH_TO_MS), + 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), HondaCarInfo("Honda Civic Hatchback 2017-21", min_steer_speed=12. * CV.MPH_TO_MS), ], CAR.CIVIC_BOSCH_DIESEL: None, # same platform CAR.CIVIC_2022: [ - HondaCarInfo("Honda Civic 2022", "All"), - HondaCarInfo("Honda Civic Hatchback 2022", "All"), + HondaCarInfo("Honda Civic 2022", "All", video_link="https://youtu.be/ytiOT5lcp6Q"), + HondaCarInfo("Honda Civic Hatchback 2022", "All", video_link="https://youtu.be/ytiOT5lcp6Q"), ], CAR.ACURA_ILX: HondaCarInfo("Acura ILX 2016-19", "AcuraWatch Plus", min_steer_speed=25. * CV.MPH_TO_MS), CAR.CRV: HondaCarInfo("Honda CR-V 2015-16", "Touring Trim", min_steer_speed=12. * CV.MPH_TO_MS), @@ -1246,6 +1246,7 @@ FW_VERSIONS = { b'37805-5YF-A750\x00\x00', b'37805-5YF-A850\x00\x00', b'37805-5YF-A870\x00\x00', + b'37805-5YF-AD20\x00\x00', b'37805-5YF-C210\x00\x00', b'37805-5YF-C220\x00\x00', b'37805-5YF-C410\000\000', @@ -1254,16 +1255,20 @@ FW_VERSIONS = { (Ecu.vsa, 0x18da28f1, None): [ b'57114-TJB-A030\x00\x00', b'57114-TJB-A040\x00\x00', + b'57114-TJB-A120\x00\x00', ], (Ecu.fwdRadar, 0x18dab0f1, None): [ b'36802-TJB-A040\x00\x00', b'36802-TJB-A050\x00\x00', + b'36802-TJB-A540\x00\x00', ], (Ecu.fwdCamera, 0x18dab5f1, None): [ b'36161-TJB-A040\x00\x00', + b'36161-TJB-A530\x00\x00', ], (Ecu.shiftByWire, 0x18da0bf1, None): [ b'54008-TJB-A520\x00\x00', + b'54008-TJB-A530\x00\x00', ], (Ecu.transmission, 0x18da1ef1, None): [ b'28102-5YK-A610\x00\x00', @@ -1271,6 +1276,7 @@ FW_VERSIONS = { b'28102-5YK-A630\x00\x00', b'28102-5YK-A700\x00\x00', b'28102-5YK-A711\x00\x00', + b'28102-5YK-A800\x00\x00', b'28102-5YL-A620\x00\x00', b'28102-5YL-A700\x00\x00', b'28102-5YL-A711\x00\x00', @@ -1282,6 +1288,7 @@ FW_VERSIONS = { b'78109-TJB-AB10\x00\x00', b'78109-TJB-AD10\x00\x00', b'78109-TJB-AF10\x00\x00', + b'78109-TJB-AQ20\x00\x00', b'78109-TJB-AR10\x00\x00', b'78109-TJB-AS10\000\000', b'78109-TJB-AU10\x00\x00', @@ -1293,22 +1300,26 @@ FW_VERSIONS = { ], (Ecu.srs, 0x18da53f1, None): [ b'77959-TJB-A040\x00\x00', + b'77959-TJB-A120\x00\x00', b'77959-TJB-A210\x00\x00', ], (Ecu.electricBrakeBooster, 0x18da2bf1, None): [ b'46114-TJB-A040\x00\x00', b'46114-TJB-A050\x00\x00', b'46114-TJB-A060\x00\x00', + b'46114-TJB-A120\x00\x00', ], (Ecu.gateway, 0x18daeff1, None): [ b'38897-TJB-A040\x00\x00', b'38897-TJB-A110\x00\x00', b'38897-TJB-A120\x00\x00', + b'38897-TJB-A220\x00\x00', ], (Ecu.eps, 0x18da30f1, None): [ b'39990-TJB-A030\x00\x00', b'39990-TJB-A040\x00\x00', - b'39990-TJB-A130\x00\x00' + b'39990-TJB-A070\x00\x00', + b'39990-TJB-A130\x00\x00', ], }, CAR.RIDGELINE: { diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py index 22934c05b2..427f8cedb1 100644 --- a/selfdrive/car/hyundai/carstate.py +++ b/selfdrive/car/hyundai/carstate.py @@ -7,7 +7,7 @@ from common.conversions import Conversions as CV from opendbc.can.parser import CANParser from opendbc.can.can_define import CANDefine from selfdrive.car.hyundai.hyundaicanfd import get_e_can_bus -from selfdrive.car.hyundai.values import HyundaiFlags, CAR, DBC, FEATURES, CAMERA_SCC_CAR, CANFD_CAR, EV_CAR, HYBRID_CAR, Buttons, CarControllerParams +from selfdrive.car.hyundai.values import HyundaiFlags, CAR, DBC, CAN_GEARS, CAMERA_SCC_CAR, CANFD_CAR, EV_CAR, HYBRID_CAR, Buttons, CarControllerParams from selfdrive.car.interfaces import CarStateBase PREV_BUTTON_SAMPLES = 8 @@ -27,9 +27,9 @@ class CarState(CarStateBase): "GEAR_SHIFTER" if CP.carFingerprint in CANFD_CAR: self.shifter_values = can_define.dv[self.gear_msg_canfd]["GEAR"] - elif self.CP.carFingerprint in FEATURES["use_cluster_gears"]: + elif self.CP.carFingerprint in CAN_GEARS["use_cluster_gears"]: self.shifter_values = can_define.dv["CLU15"]["CF_Clu_Gear"] - elif self.CP.carFingerprint in FEATURES["use_tcu_gears"]: + elif self.CP.carFingerprint in CAN_GEARS["use_tcu_gears"]: self.shifter_values = can_define.dv["TCU12"]["CUR_GR"] else: # preferred and elect gear methods use same definition self.shifter_values = can_define.dv["LVR12"]["CF_Lvr_Gear"] @@ -123,11 +123,11 @@ class CarState(CarStateBase): # Gear Selection via Cluster - For those Kia/Hyundai which are not fully discovered, we can use the Cluster Indicator for Gear Selection, # as this seems to be standard over all cars, but is not the preferred method. - if self.CP.carFingerprint in FEATURES["use_cluster_gears"]: + if self.CP.carFingerprint in CAN_GEARS["use_cluster_gears"]: gear = cp.vl["CLU15"]["CF_Clu_Gear"] - elif self.CP.carFingerprint in FEATURES["use_tcu_gears"]: + elif self.CP.carFingerprint in CAN_GEARS["use_tcu_gears"]: gear = cp.vl["TCU12"]["CUR_GR"] - elif self.CP.carFingerprint in FEATURES["use_elect_gears"]: + elif self.CP.carFingerprint in CAN_GEARS["use_elect_gears"]: gear = cp.vl["ELECT_GEAR"]["Elect_Gear_Shifter"] else: gear = cp.vl["LVR12"]["CF_Lvr_Gear"] @@ -354,12 +354,12 @@ class CarState(CarStateBase): ("EMS16", 100), ] - if CP.carFingerprint in FEATURES["use_cluster_gears"]: + if CP.carFingerprint in CAN_GEARS["use_cluster_gears"]: signals.append(("CF_Clu_Gear", "CLU15")) - elif CP.carFingerprint in FEATURES["use_tcu_gears"]: + elif CP.carFingerprint in CAN_GEARS["use_tcu_gears"]: signals.append(("CUR_GR", "TCU12")) checks.append(("TCU12", 100)) - elif CP.carFingerprint in FEATURES["use_elect_gears"]: + elif CP.carFingerprint in CAN_GEARS["use_elect_gears"]: signals.append(("Elect_Gear_Shifter", "ELECT_GEAR")) checks.append(("ELECT_GEAR", 20)) else: diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 1dd91ac888..bdb75c1fb9 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -136,10 +136,10 @@ class CarInterface(CarInterfaceBase): ret.mass = 1985. + STD_CARGO_KG ret.wheelbase = 2.78 ret.steerRatio = 14.4 * 1.1 # 10% higher at the center seems reasonable - elif candidate in (CAR.KIA_NIRO_EV, CAR.KIA_NIRO_PHEV, CAR.KIA_NIRO_HEV_2021, CAR.KIA_NIRO_HEV_2ND_GEN): - ret.mass = 3452. * CV.LB_TO_KG + STD_CARGO_KG # average of all the cars + elif candidate in (CAR.KIA_NIRO_EV, CAR.KIA_NIRO_EV_2ND_GEN, CAR.KIA_NIRO_PHEV, CAR.KIA_NIRO_HEV_2021, CAR.KIA_NIRO_HEV_2ND_GEN): + ret.mass = 3543. * CV.LB_TO_KG + STD_CARGO_KG # average of all the cars ret.wheelbase = 2.7 - ret.steerRatio = 13.9 if CAR.KIA_NIRO_HEV_2021 else 13.73 # Spec + ret.steerRatio = 13.6 # average of all the cars tire_stiffness_factor = 0.385 if candidate == CAR.KIA_NIRO_PHEV: ret.minSteerSpeed = 32 * CV.MPH_TO_MS diff --git a/selfdrive/car/hyundai/tests/test_hyundai.py b/selfdrive/car/hyundai/tests/test_hyundai.py index 6ecfa03796..fba99ae74d 100755 --- a/selfdrive/car/hyundai/tests/test_hyundai.py +++ b/selfdrive/car/hyundai/tests/test_hyundai.py @@ -2,16 +2,21 @@ import unittest from cereal import car -from selfdrive.car.hyundai.values import CANFD_CAR, FW_QUERY_CONFIG, FW_VERSIONS +from selfdrive.car.hyundai.values import CANFD_CAR, FW_QUERY_CONFIG, FW_VERSIONS, CAN_GEARS, LEGACY_SAFETY_MODE_CAR, CHECKSUM, CAMERA_SCC_CAR Ecu = car.CarParams.Ecu ECU_NAME = {v: k for k, v in Ecu.schema.enumerants.items()} class TestHyundaiFingerprint(unittest.TestCase): + def test_canfd_not_in_can_features(self): + can_specific_feature_list = set.union(*CAN_GEARS.values(), *CHECKSUM.values(), LEGACY_SAFETY_MODE_CAR, CAMERA_SCC_CAR) + for car_model in CANFD_CAR: + self.assertNotIn(car_model, can_specific_feature_list, "CAN FD car unexpectedly found in a CAN feature list") + def test_auxiliary_request_ecu_whitelist(self): # Asserts only auxiliary Ecus can exist in database for CAN-FD cars - whitelisted_ecus = {ecu for r in FW_QUERY_CONFIG.requests for ecu in r.whitelist_ecus if r.bus > 3} + whitelisted_ecus = {ecu for r in FW_QUERY_CONFIG.requests for ecu in r.whitelist_ecus if r.auxiliary} for car_model in CANFD_CAR: ecus = {fw[0] for fw in FW_VERSIONS[car_model].keys()} diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 7fcc5b9140..a793774937 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -100,6 +100,7 @@ class CAR: KIA_K5_2021 = "KIA K5 2021" KIA_K5_HEV_2020 = "KIA K5 HYBRID 2020" KIA_NIRO_EV = "KIA NIRO EV 2020" + KIA_NIRO_EV_2ND_GEN = "KIA NIRO EV 2ND GEN" KIA_NIRO_PHEV = "KIA NIRO HYBRID 2019" KIA_NIRO_HEV_2021 = "KIA NIRO HYBRID 2021" KIA_NIRO_HEV_2ND_GEN = "KIA NIRO HYBRID 2ND GEN" @@ -166,17 +167,17 @@ CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = { CAR.KONA_EV_2022: HyundaiCarInfo("Hyundai Kona Electric 2022", harness=Harness.hyundai_o), CAR.KONA_HEV: HyundaiCarInfo("Hyundai Kona Hybrid 2020", video_link="https://youtu.be/0dwpAHiZgFo", harness=Harness.hyundai_i), # TODO: check packages 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", "https://youtu.be/VnHzSTygTS4", 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-23", "All", "https://www.youtube.com/watch?v=ix63r9kE3Fw", harness=Harness.hyundai_a), + CAR.SONATA: HyundaiCarInfo("Hyundai Sonata 2020-23", "All", video_link="https://www.youtube.com/watch?v=ix63r9kE3Fw", harness=Harness.hyundai_a), CAR.SONATA_LF: HyundaiCarInfo("Hyundai Sonata 2018-19", harness=Harness.hyundai_e), CAR.TUCSON: [ HyundaiCarInfo("Hyundai Tucson 2021", min_enable_speed=19 * CV.MPH_TO_MS, harness=Harness.hyundai_l), HyundaiCarInfo("Hyundai Tucson Diesel 2019", harness=Harness.hyundai_l), ], CAR.PALISADE: [ - HyundaiCarInfo("Hyundai Palisade 2020-22", "All", "https://youtu.be/TAnDqjF4fDY?t=456", harness=Harness.hyundai_h), + HyundaiCarInfo("Hyundai Palisade 2020-22", "All", video_link="https://youtu.be/TAnDqjF4fDY?t=456", harness=Harness.hyundai_h), HyundaiCarInfo("Kia Telluride 2020-22", "All", harness=Harness.hyundai_h), ], CAR.VELOSTER: HyundaiCarInfo("Hyundai Veloster 2019-20", min_enable_speed=5. * CV.MPH_TO_MS, harness=Harness.hyundai_e), @@ -198,11 +199,12 @@ CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = { CAR.KIA_K5_2021: HyundaiCarInfo("Kia K5 2021-22", harness=Harness.hyundai_a), CAR.KIA_K5_HEV_2020: HyundaiCarInfo("Kia K5 Hybrid 2020", harness=Harness.hyundai_a), CAR.KIA_NIRO_EV: [ - HyundaiCarInfo("Kia Niro EV 2019", "All", "https://www.youtube.com/watch?v=lT7zcG6ZpGo", harness=Harness.hyundai_h), - HyundaiCarInfo("Kia Niro EV 2020", "All", "https://www.youtube.com/watch?v=lT7zcG6ZpGo", harness=Harness.hyundai_f), - HyundaiCarInfo("Kia Niro EV 2021", "All", "https://www.youtube.com/watch?v=lT7zcG6ZpGo", harness=Harness.hyundai_c), - HyundaiCarInfo("Kia Niro EV 2022", "All", "https://www.youtube.com/watch?v=lT7zcG6ZpGo", harness=Harness.hyundai_h), + HyundaiCarInfo("Kia Niro EV 2019", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", harness=Harness.hyundai_h), + HyundaiCarInfo("Kia Niro EV 2020", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", harness=Harness.hyundai_f), + HyundaiCarInfo("Kia Niro EV 2021", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", harness=Harness.hyundai_c), + HyundaiCarInfo("Kia Niro EV 2022", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", harness=Harness.hyundai_h), ], + CAR.KIA_NIRO_EV_2ND_GEN: HyundaiCarInfo("Kia Niro EV 2023", "All", harness=Harness.hyundai_a), CAR.KIA_NIRO_PHEV: [ HyundaiCarInfo("Kia Niro Plug-in Hybrid 2018-19", "All", min_enable_speed=10. * CV.MPH_TO_MS, harness=Harness.hyundai_c), HyundaiCarInfo("Kia Niro Plug-in Hybrid 2020", "All", harness=Harness.hyundai_d), @@ -221,7 +223,7 @@ CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = { CAR.KIA_SELTOS: HyundaiCarInfo("Kia Seltos 2021", harness=Harness.hyundai_a), CAR.KIA_SPORTAGE_5TH_GEN: HyundaiCarInfo("Kia Sportage 2023", harness=Harness.hyundai_n), CAR.KIA_SORENTO: [ - HyundaiCarInfo("Kia Sorento 2018", "Advanced Smart Cruise Control", "https://www.youtube.com/watch?v=Fkh3s6WHJz8", harness=Harness.hyundai_c), + HyundaiCarInfo("Kia Sorento 2018", "Advanced Smart Cruise Control", video_link="https://www.youtube.com/watch?v=Fkh3s6WHJz8", harness=Harness.hyundai_c), HyundaiCarInfo("Kia Sorento 2019", video_link="https://www.youtube.com/watch?v=Fkh3s6WHJz8", harness=Harness.hyundai_e), ], CAR.KIA_SORENTO_4TH_GEN: HyundaiCarInfo("Kia Sorento 2021-23", harness=Harness.hyundai_k), @@ -383,14 +385,14 @@ FW_QUERY_CONFIG = FwQueryConfig( Request( [HYUNDAI_VERSION_REQUEST_ALT], [HYUNDAI_VERSION_RESPONSE], - whitelist_ecus=[Ecu.parkingAdas], + whitelist_ecus=[Ecu.parkingAdas, Ecu.hvac], bus=0, auxiliary=True, ), Request( [HYUNDAI_VERSION_REQUEST_ALT], [HYUNDAI_VERSION_RESPONSE], - whitelist_ecus=[Ecu.parkingAdas], + whitelist_ecus=[Ecu.parkingAdas, Ecu.hvac], bus=1, auxiliary=True, obd_multiplexing=False, @@ -540,7 +542,6 @@ FW_VERSIONS = { b'\xf1\x00DN8_ SCC FHCUP 1.00 1.00 99110-L0000 ', b'\xf1\x00DN8_ SCC FHCUP 1.00 1.01 99110-L1000 ', b'\xf1\x00DN89110-L0000 \xaa\xaa\xaa\xaa\xaa\xaa\xaa ', - b'\xf1\x8799110L0000\xf1\x00DN8_ SCC F-CUP 1.00 1.00 99110-L0000 ', ], (Ecu.abs, 0x7d1, None): [ b'\xf1\x00DN ESC \x07 106 \x07\x01 58910-L0100', @@ -549,6 +550,7 @@ FW_VERSIONS = { b'\xf1\x00DN ESC \x06 104\x19\x08\x01 58910-L0100', b'\xf1\x00DN ESC \x07 104\x19\x08\x01 58910-L0100', b'\xf1\x00DN ESC \x08 103\x19\x06\x01 58910-L1300', + b'\xf1\x00DN ESC \x07 107"\x08\x07 58910-L0100', b'\xf1\x8758910-L0100\xf1\x00DN ESC \x07 106 \x07\x01 58910-L0100', b'\xf1\x8758910-L0100\xf1\x00DN ESC \x06 104\x19\x08\x01 58910-L0100', b'\xf1\x8758910-L0100\xf1\x00DN ESC \x06 106 \x07\x01 58910-L0100', @@ -572,6 +574,7 @@ FW_VERSIONS = { b'HM6M2_0a0_BD0', b'\xf1\x8739110-2S278\xf1\x82DNDVD5GMCCXXXL5B', b'\xf1\x8739110-2S041\xf1\x81HM6M1_0a0_M00', + b'\xf1\x8739110-2S042\xf1\x81HM6M1_0a0_M00', b'\xf1\x81HM6M1_0a0_G20', ], (Ecu.eps, 0x7d4, None): [ @@ -591,6 +594,7 @@ FW_VERSIONS = { b'\xf1\x8757700-L0000\xf1\x00DN8 MDPS R 1.00 1.00 57700-L0000 4DNAP100', b'\xf1\x00DN8 MDPS R 1.00 1.00 57700-L0000 4DNAP101', b'\xf1\x00DN8 MDPS C 1.00 1.01 56310-L0210 4DNAC102', + b'\xf1\x00DN8 MDPS C 1.00 1.01 56310L0200\x00 4DNAC102', ], (Ecu.fwdCamera, 0x7c4, None): [ b'\xf1\x00DN8 MFC AT KOR LHD 1.00 1.02 99211-L1000 190422', @@ -911,18 +915,23 @@ FW_VERSIONS = { CAR.KIA_STINGER_2022: { (Ecu.fwdRadar, 0x7d0, None): [ b'\xf1\x00CK__ SCC F-CUP 1.00 1.00 99110-J5500 ', + b'\xf1\x00CK__ SCC FHCUP 1.00 1.00 99110-J5500 ', ], (Ecu.engine, 0x7e0, None): [ b'\xf1\x81640R0051\x00\x00\x00\x00\x00\x00\x00\x00', + b'\xf1\x81HM6M1_0a0_H00', ], (Ecu.eps, 0x7d4, None): [ b'\xf1\x00CK MDPS R 1.00 5.03 57700-J5380 4C2VR503', + b'\xf1\x00CK MDPS R 1.00 5.03 57700-J5300 4C2CL503', ], (Ecu.fwdCamera, 0x7c4, None): [ b'\xf1\x00CK MFC AT AUS RHD 1.00 1.00 99211-J5500 210622', + b'\xf1\x00CK MFC AT KOR LHD 1.00 1.00 99211-J5500 210622', ], (Ecu.transmission, 0x7e1, None): [ b'\xf1\x87VCNLF11383972DK1vffV\x99\x99\x89\x98\x86eUU\x88wg\x89vfff\x97fff\x99\x87o\xff"\xc1\xf1\x81E30\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 E30\x00\x00\x00\x00\x00\x00\x00SCK0T33GH0\xbe`\xfb\xc6', + b'\xf1\x00bcsh8p54 E31\x00\x00\x00\x00\x00\x00\x00SCK0T25KH2B\xfbI\xe2', ], }, CAR.PALISADE: { @@ -1304,6 +1313,14 @@ FW_VERSIONS = { b'\xf1\x00DEE MFC AT KOR LHD 1.00 1.03 95740-Q4000 180821', ], }, + CAR.KIA_NIRO_EV_2ND_GEN: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00SG2_ RDR ----- 1.00 1.01 99110-AT000 ', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00SG2EMFC AT EUR LHD 1.01 1.09 99211-AT000 220801', + ], + }, CAR.KIA_NIRO_PHEV: { (Ecu.engine, 0x7e0, None): [ b'\xf1\x816H6F4051\x00\x00\x00\x00\x00\x00\x00\x00', @@ -1620,6 +1637,7 @@ FW_VERSIONS = { (Ecu.fwdCamera, 0x7c4, None): [ b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-N9210 14G', b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.01 99211-N9240 14T', + b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-CW010 14X', ], (Ecu.fwdRadar, 0x7d0, None): [ b'\xf1\x00NX4__ 1.00 1.00 99110-N9100 ', @@ -1638,6 +1656,7 @@ FW_VERSIONS = { }, CAR.KIA_SPORTAGE_HYBRID_5TH_GEN: { (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00NQ5 FR_CMR AT GEN LHD 1.00 1.00 99211-P1060 665', b'\xf1\x00NQ5 FR_CMR AT USA LHD 1.00 1.00 99211-P1060 665', ], (Ecu.fwdRadar, 0x7d0, None): [ @@ -1710,14 +1729,14 @@ CHECKSUM = { "6B": [CAR.KIA_SORENTO, CAR.HYUNDAI_GENESIS], } -FEATURES = { +CAN_GEARS = { # which message has the gear "use_cluster_gears": {CAR.ELANTRA, CAR.KONA}, "use_tcu_gears": {CAR.KIA_OPTIMA_G4, CAR.KIA_OPTIMA_G4_FL, CAR.SONATA_LF, CAR.VELOSTER, CAR.TUCSON}, "use_elect_gears": {CAR.KIA_NIRO_EV, CAR.KIA_NIRO_PHEV, CAR.KIA_NIRO_HEV_2021, CAR.KIA_OPTIMA_H, CAR.IONIQ_EV_LTD, CAR.KONA_EV, CAR.IONIQ, CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.ELANTRA_HEV_2021, CAR.SONATA_HYBRID, CAR.KONA_HEV, CAR.IONIQ_HEV_2022, CAR.SANTA_FE_HEV_2022, CAR.SANTA_FE_PHEV_2022, CAR.IONIQ_PHEV_2019, CAR.KONA_EV_2022, CAR.KIA_K5_HEV_2020}, } -CANFD_CAR = {CAR.KIA_EV6, CAR.IONIQ_5, CAR.TUCSON_4TH_GEN, CAR.TUCSON_HYBRID_4TH_GEN, CAR.KIA_SPORTAGE_HYBRID_5TH_GEN, CAR.SANTA_CRUZ_1ST_GEN, CAR.KIA_SPORTAGE_5TH_GEN, CAR.GENESIS_GV70_1ST_GEN, CAR.KIA_SORENTO_PHEV_4TH_GEN, CAR.GENESIS_GV60_EV_1ST_GEN, CAR.KIA_SORENTO_4TH_GEN, CAR.KIA_NIRO_HEV_2ND_GEN} +CANFD_CAR = {CAR.KIA_EV6, CAR.IONIQ_5, CAR.TUCSON_4TH_GEN, CAR.TUCSON_HYBRID_4TH_GEN, CAR.KIA_SPORTAGE_HYBRID_5TH_GEN, CAR.SANTA_CRUZ_1ST_GEN, CAR.KIA_SPORTAGE_5TH_GEN, CAR.GENESIS_GV70_1ST_GEN, CAR.KIA_SORENTO_PHEV_4TH_GEN, CAR.GENESIS_GV60_EV_1ST_GEN, CAR.KIA_SORENTO_4TH_GEN, CAR.KIA_NIRO_HEV_2ND_GEN, CAR.KIA_NIRO_EV_2ND_GEN} # The radar does SCC on these cars when HDA I, rather than the camera CANFD_RADAR_SCC_CAR = {CAR.GENESIS_GV70_1ST_GEN, CAR.KIA_SORENTO_PHEV_4TH_GEN, CAR.KIA_SORENTO_4TH_GEN} @@ -1726,7 +1745,7 @@ CANFD_RADAR_SCC_CAR = {CAR.GENESIS_GV70_1ST_GEN, CAR.KIA_SORENTO_PHEV_4TH_GEN, C CAMERA_SCC_CAR = {CAR.KONA_EV_2022, } 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, CAR.TUCSON_HYBRID_4TH_GEN, CAR.KIA_SPORTAGE_HYBRID_5TH_GEN, CAR.KIA_SORENTO_PHEV_4TH_GEN, CAR.KIA_K5_HEV_2020, CAR.KIA_NIRO_HEV_2ND_GEN} # 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, CAR.KIA_EV6, CAR.IONIQ_5, CAR.GENESIS_GV60_EV_1ST_GEN} +EV_CAR = {CAR.IONIQ_EV_2020, CAR.IONIQ_EV_LTD, CAR.KONA_EV, CAR.KIA_NIRO_EV, CAR.KIA_NIRO_EV_2ND_GEN, CAR.KONA_EV_2022, CAR.KIA_EV6, CAR.IONIQ_5, CAR.GENESIS_GV60_EV_1ST_GEN} # these cars require a special panda safety mode due to missing counters and checksums in the messages LEGACY_SAFETY_MODE_CAR = {CAR.HYUNDAI_GENESIS, CAR.IONIQ_EV_2020, CAR.IONIQ_EV_LTD, CAR.IONIQ_PHEV, CAR.IONIQ, CAR.KONA_EV, CAR.KIA_SORENTO, CAR.SONATA_LF, CAR.KIA_OPTIMA_G4, CAR.KIA_OPTIMA_G4_FL, CAR.VELOSTER, @@ -1789,4 +1808,5 @@ DBC = { CAR.GENESIS_GV60_EV_1ST_GEN: dbc_dict('hyundai_canfd', None), CAR.KIA_SORENTO_4TH_GEN: dbc_dict('hyundai_canfd', None), CAR.KIA_NIRO_HEV_2ND_GEN: dbc_dict('hyundai_canfd', None), + CAR.KIA_NIRO_EV_2ND_GEN: dbc_dict('hyundai_canfd', None), } diff --git a/selfdrive/car/interfaces.py b/selfdrive/car/interfaces.py index cf6d7280fa..8b1159f361 100644 --- a/selfdrive/car/interfaces.py +++ b/selfdrive/car/interfaces.py @@ -64,6 +64,7 @@ class CarInterfaceBase(ABC): self.frame = 0 self.steering_unpressed = 0 self.low_speed_alert = False + self.no_steer_warning = False self.silent_steer_warning = True self.v_ego_cluster_seen = False @@ -278,13 +279,19 @@ class CarInterfaceBase(ABC): # Handle permanent and temporary steering faults self.steering_unpressed = 0 if cs_out.steeringPressed else self.steering_unpressed + 1 if cs_out.steerFaultTemporary: - # if the user overrode recently, show a less harsh alert - if self.silent_steer_warning or cs_out.standstill or self.steering_unpressed < int(1.5 / DT_CTRL): - self.silent_steer_warning = True - events.add(EventName.steerTempUnavailableSilent) + if cs_out.steeringPressed and (not self.CS.out.steerFaultTemporary or self.no_steer_warning): + self.no_steer_warning = True else: - events.add(EventName.steerTempUnavailable) + self.no_steer_warning = False + + # if the user overrode recently, show a less harsh alert + if self.silent_steer_warning or cs_out.standstill or self.steering_unpressed < int(1.5 / DT_CTRL): + self.silent_steer_warning = True + events.add(EventName.steerTempUnavailableSilent) + else: + events.add(EventName.steerTempUnavailable) else: + self.no_steer_warning = False self.silent_steer_warning = False if cs_out.steerFaultPermanent: events.add(EventName.steerUnavailable) diff --git a/selfdrive/car/isotp_parallel_query.py b/selfdrive/car/isotp_parallel_query.py index 70f8b5f50d..965d2e1836 100644 --- a/selfdrive/car/isotp_parallel_query.py +++ b/selfdrive/car/isotp_parallel_query.py @@ -100,18 +100,16 @@ class IsoTpParallelQuery: while True: self.rx() - if all(request_done.values()): - break - for tx_addr, msg in msgs.items(): try: - dat, updated = msg.recv() + dat, rx_in_progress = msg.recv() except Exception: cloudlog.exception(f"Error processing UDS response: {tx_addr}") request_done[tx_addr] = True continue - if updated: + # Extend timeout for each consecutive ISO-TP frame to avoid timing out on long responses + if rx_in_progress: response_timeouts[tx_addr] = time.monotonic() + timeout if not dat: @@ -123,6 +121,7 @@ class IsoTpParallelQuery: if response_valid: if counter + 1 < len(self.request): + response_timeouts[tx_addr] = time.monotonic() + timeout msg.send(self.request[counter + 1]) request_counter[tx_addr] += 1 else: @@ -132,18 +131,21 @@ class IsoTpParallelQuery: error_code = dat[2] if len(dat) > 2 else -1 if error_code == 0x78: response_timeouts[tx_addr] = time.monotonic() + self.response_pending_timeout - if self.debug: - cloudlog.warning(f"iso-tp query response pending: {tx_addr}") + cloudlog.error(f"iso-tp query response pending: {tx_addr}") else: - response_timeouts[tx_addr] = 0 request_done[tx_addr] = True cloudlog.error(f"iso-tp query bad response: {tx_addr} - 0x{dat.hex()}") + # Mark request done if address timed out cur_time = time.monotonic() - if cur_time - max(response_timeouts.values()) > 0: - for tx_addr in msgs: + for tx_addr in response_timeouts: + if cur_time - response_timeouts[tx_addr] > 0: if request_counter[tx_addr] > 0 and not request_done[tx_addr]: cloudlog.error(f"iso-tp query timeout after receiving response: {tx_addr}") + request_done[tx_addr] = True + + # Break if all requests are done (finished or timed out) + if all(request_done.values()): break if cur_time - start_time > total_timeout: diff --git a/selfdrive/car/mazda/values.py b/selfdrive/car/mazda/values.py index 598b598a16..4e235fba72 100644 --- a/selfdrive/car/mazda/values.py +++ b/selfdrive/car/mazda/values.py @@ -258,9 +258,11 @@ FW_VERSIONS = { CAR.MAZDA6: { (Ecu.eps, 0x730, None): [ b'GBEF-3210X-B-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GBEF-3210X-C-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'GFBC-3210X-A-00\000\000\000\000\000\000\000\000\000', ], (Ecu.engine, 0x7e0, None): [ + b'PA34-188K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PX4F-188K2-D\000\000\000\000\000\000\000\000\000\000\000\000', b'PYH7-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], @@ -270,13 +272,16 @@ FW_VERSIONS = { ], (Ecu.abs, 0x760, None): [ b'GBVH-437K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GBVH-437K2-C\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', ], (Ecu.fwdCamera, 0x706, None): [ b'B61L-67XK2-S\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'B61L-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'GSH7-67XK2-P\000\000\000\000\000\000\000\000\000\000\000\000', ], (Ecu.transmission, 0x7e1, None): [ + b'PA28-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PYH3-21PS1-D\000\000\000\000\000\000\000\000\000\000\000\000', b'PYH7-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], diff --git a/selfdrive/car/subaru/values.py b/selfdrive/car/subaru/values.py index 9c4447631d..f77de3b34b 100644 --- a/selfdrive/car/subaru/values.py +++ b/selfdrive/car/subaru/values.py @@ -205,6 +205,7 @@ FW_VERSIONS = { b'\xc5!dr\x07', b'\xaa!aw\x07', b'\xaa!av\x07', + b'\xaa\x01bt\x07', ], (Ecu.transmission, 0x7e1, None): [ b'\xe3\xe5\x46\x31\x00', @@ -220,6 +221,7 @@ FW_VERSIONS = { b'\xe4\xf5\002\000\000', b'\xe3\xd0\x081\x00', b'\xe3\xf5\x06\x00\x00', + b'\xe3\xd5\x161\x00', ], }, CAR.IMPREZA_2020: { @@ -274,6 +276,7 @@ FW_VERSIONS = { b'\xa3 \x14\x01', b'\xf1\x00\xbb\r\x05', b'\xa3 \x18&\x00', + b'\xa3 \x19&\x00', ], (Ecu.eps, 0x746, None): [ b'\x8d\xc0\x04\x00', @@ -286,6 +289,8 @@ FW_VERSIONS = { b'\xf1\x00\xac\x02\x00', b'\x00\x00e!\x00\x00\x00\x00', b'\x00\x00e\x97\x00\x00\x00\x00', + b'\x00\x00e^\x1f@ !', + b'\x00\x00e^\x00\x00\x00\x00', ], (Ecu.engine, 0x7e0, None): [ b'\xb6"`A\x07', @@ -303,6 +308,7 @@ FW_VERSIONS = { b'\x1a\xf6B`\x00', b'\x1a\xf6b0\x00', b'\x1a\xe6B1\x00', + b'\x1a\xe6F1\x00', ], }, CAR.FORESTER_PREGLOBAL: { diff --git a/selfdrive/car/tests/routes.py b/selfdrive/car/tests/routes.py index 4dd19d24e3..921bed5406 100644 --- a/selfdrive/car/tests/routes.py +++ b/selfdrive/car/tests/routes.py @@ -59,6 +59,7 @@ routes = [ CarTestRoute("f08912a233c1584f|2022-08-11--18-02-41", GM.BOLT_EUV, segment=1), CarTestRoute("555d4087cf86aa91|2022-12-02--12-15-07", GM.BOLT_EUV, segment=14), # Bolt EV CarTestRoute("38aa7da107d5d252|2022-08-15--16-01-12", GM.SILVERADO), + CarTestRoute("5085c761395d1fe6|2023-04-07--18-20-06", GM.TRAILBLAZER), CarTestRoute("0e7a2ba168465df5|2020-10-18--14-14-22", HONDA.ACURA_RDX_3G), CarTestRoute("a74b011b32b51b56|2020-07-26--17-09-36", HONDA.CIVIC), @@ -129,6 +130,7 @@ routes = [ CarTestRoute("007d5e4ad9f86d13|2021-09-30--15-09-23", HYUNDAI.KIA_K5_2021), CarTestRoute("c58dfc9fc16590e0|2023-01-14--13-51-48", HYUNDAI.KIA_K5_HEV_2020), CarTestRoute("50c6c9b85fd1ff03|2020-10-26--17-56-06", HYUNDAI.KIA_NIRO_EV), + CarTestRoute("b153671049a867b3|2023-04-05--10-00-30", HYUNDAI.KIA_NIRO_EV_2ND_GEN), 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("db04d2c63990e3ba|2023-02-08--16-52-39", HYUNDAI.KIA_NIRO_HEV_2ND_GEN), @@ -185,6 +187,7 @@ routes = [ CarTestRoute("9b36accae406390e|2021-03-30--10-41-38", TOYOTA.MIRAI), CarTestRoute("cd9cff4b0b26c435|2021-05-13--15-12-39", TOYOTA.CHR), CarTestRoute("ea8fbe72b96a185c|2023-02-08--15-11-46", TOYOTA.CHR_TSS2), + CarTestRoute("ea8fbe72b96a185c|2023-02-22--09-20-34", TOYOTA.CHR_TSS2), # openpilot longitudinal, with smartDSU CarTestRoute("57858ede0369a261|2021-05-18--20-34-20", TOYOTA.CHRH), CarTestRoute("6719965b0e1d1737|2023-02-09--22-44-05", TOYOTA.CHRH_TSS2), CarTestRoute("14623aae37e549f3|2021-10-24--01-20-49", TOYOTA.PRIUS_V), diff --git a/selfdrive/car/torque_data/override.yaml b/selfdrive/car/torque_data/override.yaml index 75051316fa..02b586d578 100644 --- a/selfdrive/car/torque_data/override.yaml +++ b/selfdrive/car/torque_data/override.yaml @@ -33,6 +33,7 @@ SUBARU OUTBACK 6TH GEN: [2.3, 2.3, 0.11] CADILLAC ESCALADE 2017: [1.899999976158142, 1.842270016670227, 0.1120000034570694] CHEVROLET BOLT EUV 2022: [2.0, 2.0, 0.05] CHEVROLET SILVERADO 1500 2020: [1.9, 1.9, 0.112] +CHEVROLET TRAILBLAZER 2021: [1.33, 1.9, 0.16] CHEVROLET EQUINOX 2019: [2.0, 2.0, 0.05] VOLKSWAGEN PASSAT NMS: [2.5, 2.5, 0.1] VOLKSWAGEN SHARAN 2ND GEN: [2.5, 2.5, 0.1] @@ -44,6 +45,7 @@ KIA SORENTO PLUG-IN HYBRID 4TH GEN: [2.5, 2.5, 0.1] GENESIS GV60 ELECTRIC 1ST GEN: [2.5, 2.5, 0.1] KIA SORENTO 4TH GEN: [2.5, 2.5, 0.1] KIA NIRO HYBRID 2ND GEN: [2.42, 2.5, 0.12] +KIA NIRO EV 2ND GEN: [2.05, 2.5, 0.14] # Dashcam or fallback configured as ideal car mock: [10.0, 10, 0.0] diff --git a/selfdrive/car/toyota/carstate.py b/selfdrive/car/toyota/carstate.py index 050f8747a2..68adc2ee57 100644 --- a/selfdrive/car/toyota/carstate.py +++ b/selfdrive/car/toyota/carstate.py @@ -115,7 +115,8 @@ class CarState(CarStateBase): 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"] + if not (self.CP.flags & ToyotaFlags.SMART_DSU.value): + 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 @@ -235,12 +236,17 @@ class CarState(CarStateBase): checks.append(("BSM", 1)) if CP.carFingerprint in RADAR_ACC_CAR: + if not CP.flags & ToyotaFlags.SMART_DSU.value: + signals += [ + ("ACC_TYPE", "ACC_CONTROL"), + ] + checks += [ + ("ACC_CONTROL", 33), + ] signals += [ - ("ACC_TYPE", "ACC_CONTROL"), ("FCW", "ACC_HUD"), ] checks += [ - ("ACC_CONTROL", 33), ("ACC_HUD", 1), ] diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py index 33a87451e9..6e8664c340 100644 --- a/selfdrive/car/toyota/interface.py +++ b/selfdrive/car/toyota/interface.py @@ -201,14 +201,18 @@ class CarInterface(CarInterfaceBase): tire_stiffness_factor=tire_stiffness_factor) ret.enableBsm = 0x3F6 in fingerprint[0] and candidate in TSS2_CAR - # Detect smartDSU, which intercepts ACC_CMD from the DSU allowing openpilot to send it - smartDsu = 0x2FF in fingerprint[0] - # In TSS2 cars the camera does long control + + # Detect smartDSU, which intercepts ACC_CMD from the DSU (or radar) allowing openpilot to send it + if 0x2FF in fingerprint[0]: + ret.flags |= ToyotaFlags.SMART_DSU.value + + # In TSS2 cars, the camera does long control found_ecus = [fw.ecu for fw in car_fw] - ret.enableDsu = len(found_ecus) > 0 and Ecu.dsu not in found_ecus and candidate not in (NO_DSU_CAR | UNSUPPORTED_DSU_CAR) and not smartDsu + ret.enableDsu = len(found_ecus) > 0 and Ecu.dsu not in found_ecus and candidate not in (NO_DSU_CAR | UNSUPPORTED_DSU_CAR) and not (ret.flags & ToyotaFlags.SMART_DSU) ret.enableGasInterceptor = 0x201 in fingerprint[0] + # if the smartDSU is detected, openpilot can send ACC_CMD (and the smartDSU will block it from the DSU) or not (the DSU is "connected") - ret.openpilotLongitudinalControl = smartDsu or ret.enableDsu or candidate in (TSS2_CAR - RADAR_ACC_CAR) + ret.openpilotLongitudinalControl = bool(ret.flags & ToyotaFlags.SMART_DSU) or ret.enableDsu or candidate in (TSS2_CAR - RADAR_ACC_CAR) ret.autoResumeSng = ret.openpilotLongitudinalControl and candidate in NO_STOP_TIMER_CAR if not ret.openpilotLongitudinalControl: diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index f0e846cc54..60450b9fe5 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -33,6 +33,7 @@ class CarControllerParams: class ToyotaFlags(IntFlag): HYBRID = 1 + SMART_DSU = 2 class CAR: @@ -140,7 +141,7 @@ CAR_INFO: Dict[str, Union[ToyotaCarInfo, List[ToyotaCarInfo]]] = { CAR.HIGHLANDERH: ToyotaCarInfo("Toyota Highlander Hybrid 2017-19"), CAR.HIGHLANDERH_TSS2: ToyotaCarInfo("Toyota Highlander Hybrid 2020-23"), CAR.PRIUS: [ - ToyotaCarInfo("Toyota Prius 2016", "Toyota Safety Sense P", "https://www.youtube.com/watch?v=8zopPJI8XQ0"), + ToyotaCarInfo("Toyota Prius 2016", "Toyota Safety Sense P", video_link="https://www.youtube.com/watch?v=8zopPJI8XQ0"), ToyotaCarInfo("Toyota Prius 2017-20", video_link="https://www.youtube.com/watch?v=8zopPJI8XQ0"), ToyotaCarInfo("Toyota Prius Prime 2017-20", video_link="https://www.youtube.com/watch?v=8zopPJI8XQ0"), ], @@ -154,7 +155,7 @@ CAR_INFO: Dict[str, Union[ToyotaCarInfo, List[ToyotaCarInfo]]] = { ToyotaCarInfo("Toyota RAV4 2017-18") ], CAR.RAV4H: [ - ToyotaCarInfo("Toyota RAV4 Hybrid 2016", "Toyota Safety Sense P", "https://youtu.be/LhT5VzJVfNI?t=26"), + ToyotaCarInfo("Toyota RAV4 Hybrid 2016", "Toyota Safety Sense P", video_link="https://youtu.be/LhT5VzJVfNI?t=26"), ToyotaCarInfo("Toyota RAV4 Hybrid 2017-18", video_link="https://youtu.be/LhT5VzJVfNI?t=26") ], CAR.RAV4_TSS2: ToyotaCarInfo("Toyota RAV4 2019-21", video_link="https://www.youtube.com/watch?v=wJxjDd42gGA"), @@ -732,12 +733,14 @@ FW_VERSIONS = { (Ecu.eps, 0x7a1, None): [ b'8965B10092\x00\x00\x00\x00\x00\x00', b'8965B10091\x00\x00\x00\x00\x00\x00', + b'8965B10111\x00\x00\x00\x00\x00\x00', ], (Ecu.abs, 0x7b0, None): [ b'F152610041\x00\x00\x00\x00\x00\x00', ], (Ecu.engine, 0x700, None): [ b'\x0189663F438000\x00\x00\x00\x00', + b'\x02896631025000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x0289663F453000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 15): [ @@ -916,6 +919,7 @@ FW_VERSIONS = { b'\x028966312K6000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x028966312L0000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x028966312Q3000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x028966312Q3100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x028966312Q4000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x038966312L7000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF1205001\x00\x00\x00\x00', b'\x038966312N1000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', @@ -926,6 +930,7 @@ FW_VERSIONS = { b'8965B12451\x00\x00\x00\x00\x00\x00', b'8965B16011\x00\x00\x00\x00\x00\x00', b'8965B16101\x00\x00\x00\x00\x00\x00', + b'8965B16170\x00\x00\x00\x00\x00\x00', b'8965B76012\x00\x00\x00\x00\x00\x00', b'8965B76050\x00\x00\x00\x00\x00\x00', b'\x018965B12350\x00\x00\x00\x00\x00\x00', @@ -953,6 +958,7 @@ FW_VERSIONS = { 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'F152616030\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', @@ -1107,6 +1113,7 @@ FW_VERSIONS = { b'\x01F152648J4000\x00\x00\x00\x00', b'\x01F152648J5000\x00\x00\x00\x00', b'\x01F152648J6000\x00\x00\x00\x00', + b'\x01F15264872700\x00\x00\x00\x00', ], (Ecu.engine, 0x700, None): [ b'\x01896630E67000\x00\x00\x00\x00', @@ -1991,6 +1998,7 @@ FW_VERSIONS = { b'\x01896634D12100\x00\x00\x00\x00', b'\x01896634D43000\x00\x00\x00\x00', b'\x01896634D44000\x00\x00\x00\x00', + b'\x018966348X0000\x00\x00\x00\x00', ], (Ecu.abs, 0x7b0, None): [ b'\x01F15260E031\x00\x00\x00\x00\x00\x00', diff --git a/selfdrive/car/volkswagen/mqbcan.py b/selfdrive/car/volkswagen/mqbcan.py index 30a51f6fe6..89de933ae8 100644 --- a/selfdrive/car/volkswagen/mqbcan.py +++ b/selfdrive/car/volkswagen/mqbcan.py @@ -56,18 +56,18 @@ def acc_hud_status_value(main_switch_on, acc_faulted, long_active): return acc_control_value(main_switch_on, acc_faulted, long_active) -def create_acc_accel_control(packer, bus, acc_type, enabled, accel, acc_control, stopping, starting, esp_hold): +def create_acc_accel_control(packer, bus, acc_type, acc_enabled, accel, acc_control, stopping, starting, esp_hold): commands = [] acc_06_values = { "ACC_Typ": acc_type, "ACC_Status_ACC": acc_control, - "ACC_StartStopp_Info": enabled, - "ACC_Sollbeschleunigung_02": accel if enabled else 3.01, + "ACC_StartStopp_Info": acc_enabled, + "ACC_Sollbeschleunigung_02": accel if acc_enabled else 3.01, "ACC_zul_Regelabw_unten": 0.2, # TODO: dynamic adjustment of comfort-band "ACC_zul_Regelabw_oben": 0.2, # TODO: dynamic adjustment of comfort-band - "ACC_neg_Sollbeschl_Grad_02": 4.0 if enabled else 0, # TODO: dynamic adjustment of jerk limits - "ACC_pos_Sollbeschl_Grad_02": 4.0 if enabled else 0, # TODO: dynamic adjustment of jerk limits + "ACC_neg_Sollbeschl_Grad_02": 4.0 if acc_enabled else 0, # TODO: dynamic adjustment of jerk limits + "ACC_pos_Sollbeschl_Grad_02": 4.0 if acc_enabled else 0, # TODO: dynamic adjustment of jerk limits "ACC_Anfahren": starting, "ACC_Anhalten": stopping, } @@ -84,9 +84,9 @@ def create_acc_accel_control(packer, bus, acc_type, enabled, accel, acc_control, acc_07_values = { "ACC_Anhalteweg": 0.75 if stopping else 20.46, # Distance to stop (stopping coordinator handles terminal roll-out) - "ACC_Freilauf_Info": 2 if enabled else 0, + "ACC_Freilauf_Info": 2 if acc_enabled else 0, "ACC_Folgebeschl": 3.02, # Not using secondary controller accel unless and until we understand its impact - "ACC_Sollbeschleunigung_02": accel if enabled else 3.01, + "ACC_Sollbeschleunigung_02": accel if acc_enabled else 3.01, "ACC_Anforderung_HMS": acc_hold_type, "ACC_Anfahren": starting, "ACC_Anhalten": stopping, diff --git a/selfdrive/car/volkswagen/pqcan.py b/selfdrive/car/volkswagen/pqcan.py index 84200c2921..bac3ca121d 100644 --- a/selfdrive/car/volkswagen/pqcan.py +++ b/selfdrive/car/volkswagen/pqcan.py @@ -59,17 +59,18 @@ def acc_hud_status_value(main_switch_on, acc_faulted, long_active): return hud_status -def create_acc_accel_control(packer, bus, acc_type, enabled, accel, acc_control, stopping, starting, esp_hold): +def create_acc_accel_control(packer, bus, acc_type, acc_enabled, accel, acc_control, stopping, starting, esp_hold): commands = [] values = { "ACS_Sta_ADR": acc_control, - "ACS_StSt_Info": acc_control != 1, + "ACS_StSt_Info": acc_enabled, "ACS_Typ_ACC": acc_type, "ACS_Anhaltewunsch": acc_type == 1 and stopping, - "ACS_Sollbeschl": accel if acc_control == 1 else 3.01, - "ACS_zul_Regelabw": 0.2 if acc_control == 1 else 1.27, - "ACS_max_AendGrad": 3.0 if acc_control == 1 else 5.08, + "ACS_FreigSollB": acc_enabled, + "ACS_Sollbeschl": accel if acc_enabled else 3.01, + "ACS_zul_Regelabw": 0.2 if acc_enabled else 1.27, + "ACS_max_AendGrad": 3.0 if acc_enabled else 5.08, } commands.append(packer.make_can_msg("ACC_System", bus, values)) @@ -83,9 +84,9 @@ def create_acc_hud_control(packer, bus, acc_hud_status, set_speed, lead_distance "ACA_Zeitluecke": 2, "ACA_V_Wunsch": set_speed, "ACA_gemZeitl": lead_distance, - # TODO: ACA_ID_StaACC, ACA_AnzDisplay, ACA_kmh_mph, ACA_PrioDisp, ACA_Aend_Zeitluecke - # display/display-prio handling probably needed to stop confusing the instrument cluster - # kmh_mph handling probably needed to resolve rounding errors in displayed setpoint + "ACA_PrioDisp": 3, + # TODO: restore dynamic pop-to-foreground/highlight behavior with ACA_PrioDisp and ACA_AnzDisplay + # TODO: ACA_kmh_mph handling probably needed to resolve rounding errors in displayed setpoint } return packer.make_can_msg("ACC_GRA_Anzeige", bus, values) diff --git a/selfdrive/car/volkswagen/values.py b/selfdrive/car/volkswagen/values.py index 9873b628cd..4d8ca5afb7 100755 --- a/selfdrive/car/volkswagen/values.py +++ b/selfdrive/car/volkswagen/values.py @@ -214,8 +214,8 @@ CAR_INFO: Dict[str, Union[VWCarInfo, List[VWCarInfo]]] = { ], CAR.PASSAT_NMS: VWCarInfo("Volkswagen Passat NMS 2017-22"), CAR.POLO_MK6: [ - VWCarInfo("Volkswagen Polo 2020-22", footnotes=[Footnote.VW_MQB_A0]), - VWCarInfo("Volkswagen Polo GTI 2020-22", footnotes=[Footnote.VW_MQB_A0]), + VWCarInfo("Volkswagen Polo 2018-23", footnotes=[Footnote.VW_MQB_A0]), + VWCarInfo("Volkswagen Polo GTI 2018-23", footnotes=[Footnote.VW_MQB_A0]), ], CAR.SHARAN_MK2: [ VWCarInfo("Volkswagen Sharan 2018-22"), @@ -672,9 +672,11 @@ FW_VERSIONS = { b'\xf1\x8704C906025H \xf1\x895177', ], (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870CW300042D \xf1\x891612', b'\xf1\x870CW300050D \xf1\x891908', ], (Ecu.srs, 0x715, None): [ + b'\xf1\x872Q0959655AG\xf1\x890248\xf1\x82\x1218130411110411--04040404231811152H14', b'\xf1\x872Q0959655AJ\xf1\x890250\xf1\x82\x1248130411110416--04040404784811152H14', ], (Ecu.eps, 0x712, None): [ @@ -814,6 +816,7 @@ FW_VERSIONS = { }, CAR.TRANSPORTER_T61: { (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704L906056AL\xf1\x899970', b'\xf1\x8704L906057AP\xf1\x891186', b'\xf1\x8704L906057N \xf1\x890413', ], @@ -822,10 +825,11 @@ FW_VERSIONS = { b'\xf1\x870BT300012E \xf1\x893105', ], (Ecu.srs, 0x715, None): [ - b'\xf1\x872Q0959655AE\xf1\x890506\xf1\x82\02316170411110411--04041704161611152S1411', + b'\xf1\x872Q0959655AE\xf1\x890506\xf1\x82\x1316170411110411--04041704161611152S1411', b'\xf1\x872Q0959655AF\xf1\x890506\xf1\x82\x1316171111110411--04041711121211152S1413', ], (Ecu.eps, 0x712, None): [ + b'\xf1\x877LA909144G \xf1\x897160\xf1\x82\x05333A5519A2', b'\xf1\x877LA909144F \xf1\x897150\xf1\x82\005323A5519A2', ], (Ecu.fwdRadar, 0x757, None): [ @@ -837,9 +841,11 @@ FW_VERSIONS = { b'\xf1\x8705E906018AT\xf1\x899640', ], (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870CW300050J \xf1\x891911', b'\xf1\x870CW300051M \xf1\x891925', ], (Ecu.srs, 0x715, None): [ + b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x1311110012333300314240681152119333463100', b'\xf1\x875Q0959655CG\xf1\x890421\xf1\x82\x13111100123333003142404M1152119333613100', ], (Ecu.eps, 0x712, None): [ @@ -947,14 +953,17 @@ FW_VERSIONS = { b'\xf1\x8705L906022M \xf1\x890901', b'\xf1\x8783A906259 \xf1\x890001', b'\xf1\x8783A906259 \xf1\x890005', + b'\xf1\x8783A906259F \xf1\x890001', ], (Ecu.transmission, 0x7e1, None): [ b'\xf1\x8709G927158CN\xf1\x893608', + b'\xf1\x8709G927158GP\xf1\x893937', b'\xf1\x870GC300045D \xf1\x892802', b'\xf1\x870GC300046F \xf1\x892701', ], (Ecu.srs, 0x715, None): [ b'\xf1\x875Q0959655BF\xf1\x890403\xf1\x82\x1321211111211200311121232152219321422111', + b'\xf1\x875Q0959655BQ\xf1\x890421\xf1\x82\x132121111121120031112124218C219321532111', b'\xf1\x875Q0959655CC\xf1\x890421\xf1\x82\x131111111111120031111224118A119321532111', b'\xf1\x875Q0959655CC\xf1\x890421\xf1\x82\x131111111111120031111237116A119321532111', ], @@ -962,8 +971,10 @@ FW_VERSIONS = { b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567G6000300', b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567G6000800', b'\xf1\x875QF909144B \xf1\x895582\xf1\x82\x0571G60533A1', + b'\xf1\x875TA907145D \xf1\x891051\xf1\x82\x001PG60A1P7N', ], (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', b'\xf1\x872Q0907572R \xf1\x890372', b'\xf1\x872Q0907572T \xf1\x890383', ], diff --git a/selfdrive/debug/profiling/watch-irqs.sh b/selfdrive/debug/profiling/watch-irqs.sh new file mode 100755 index 0000000000..34cc4596f4 --- /dev/null +++ b/selfdrive/debug/profiling/watch-irqs.sh @@ -0,0 +1,4 @@ +#!/usr/bin/bash +set -e + +RUBYOPT="-W0" irqtop -d1 -R diff --git a/selfdrive/debug/test_car_model.py b/selfdrive/debug/test_car_model.py index 4de5b26762..c2f51c9355 100755 --- a/selfdrive/debug/test_car_model.py +++ b/selfdrive/debug/test_car_model.py @@ -6,6 +6,7 @@ import unittest from selfdrive.car.tests.routes import CarTestRoute from selfdrive.car.tests.test_models import TestCarModel +from tools.lib.route import SegmentName def create_test_models_suite(routes: List[Tuple[str, CarTestRoute]], ci=False) -> unittest.TestSuite: @@ -21,16 +22,17 @@ def create_test_models_suite(routes: List[Tuple[str, CarTestRoute]], ci=False) - if __name__ == "__main__": parser = argparse.ArgumentParser(description="Test any route against common issues with a new car port. " + "Uses selfdrive/car/tests/test_models.py") - parser.add_argument("route", help="Specify route to run tests on") + parser.add_argument("route_or_segment_name", help="Specify route to run tests on") parser.add_argument("--car", help="Specify car model for test route") - parser.add_argument("--segment", type=int, nargs="?", help="Specify segment of route to test") parser.add_argument("--ci", action="store_true", help="Attempt to get logs using openpilotci, need to specify car") args = parser.parse_args() if len(sys.argv) == 1: parser.print_help() sys.exit() - test_route = CarTestRoute(args.route, args.car, segment=args.segment) + route_or_segment_name = SegmentName(args.route_or_segment_name.strip(), allow_route_name=True) + segment_num = route_or_segment_name.segment_num if route_or_segment_name.segment_num != -1 else None + test_route = CarTestRoute(route_or_segment_name.route_name.canonical_name, args.car, segment=segment_num) test_suite = create_test_models_suite([(args.car, test_route)], ci=args.ci) unittest.TextTestRunner().run(test_suite) diff --git a/selfdrive/locationd/locationd.cc b/selfdrive/locationd/locationd.cc index 87c5f644c5..de2373c1da 100755 --- a/selfdrive/locationd/locationd.cc +++ b/selfdrive/locationd/locationd.cc @@ -303,13 +303,7 @@ void Localizer::handle_gps(double current_time, const cereal::GpsLocationData::R bool gps_lat_lng_alt_insane = ((std::abs(log.getLatitude()) > 90) || (std::abs(log.getLongitude()) > 180) || (std::abs(log.getAltitude()) > ALTITUDE_SANITY_CHECK)); bool gps_vel_insane = (floatlist2vector(log.getVNED()).norm() > TRANS_SANITY_CHECK); - // quectel gps verticalAccuracy is clipped to 500 - bool gps_accuracy_insane_quectel = false; - if (!ublox_available) { - gps_accuracy_insane_quectel = log.getVerticalAccuracy() == 500; - } - - if (gps_invalid_flag || gps_unreasonable || gps_accuracy_insane || gps_lat_lng_alt_insane || gps_vel_insane || gps_accuracy_insane_quectel) { + if (gps_invalid_flag || gps_unreasonable || gps_accuracy_insane || gps_lat_lng_alt_insane || gps_vel_insane) { //this->gps_valid = false; this->determine_gps_mode(current_time); return; diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py index 07a3c61bc5..81d68aa877 100755 --- a/selfdrive/test/test_onroad.py +++ b/selfdrive/test/test_onroad.py @@ -25,7 +25,7 @@ PROCS = { "./loggerd": 10.0, "./encoderd": 17.0, "./camerad": 14.5, - "./locationd": 9.1, + "./locationd": 11.0, "selfdrive.controls.plannerd": 16.5, "./_ui": 19.2, "selfdrive.locationd.paramsd": 9.0, diff --git a/system/camerad/cameras/camera_qcom2.cc b/system/camerad/cameras/camera_qcom2.cc index 94116b11cd..e8b8bdc77a 100644 --- a/system/camerad/cameras/camera_qcom2.cc +++ b/system/camerad/cameras/camera_qcom2.cc @@ -71,7 +71,7 @@ const int DC_GAIN_MIN_WEIGHT_OX03C10 = 1; // always on is fine const int DC_GAIN_MAX_WEIGHT_OX03C10 = 1; const float TARGET_GREY_FACTOR_AR0231 = 1.0; -const float TARGET_GREY_FACTOR_OX03C10 = 0.02; +const float TARGET_GREY_FACTOR_OX03C10 = 0.01; const float sensor_analog_gains_AR0231[] = { 1.0/8.0, 2.0/8.0, 2.0/7.0, 3.0/7.0, // 0, 1, 2, 3 @@ -101,7 +101,7 @@ const float ANALOG_GAIN_COST_LOW_AR0231 = 0.1; const float ANALOG_GAIN_COST_HIGH_AR0231 = 5.0; const int ANALOG_GAIN_MIN_IDX_OX03C10 = 0x0; -const int ANALOG_GAIN_REC_IDX_OX03C10 = 0x11; // 2.5x +const int ANALOG_GAIN_REC_IDX_OX03C10 = 0x0; // 1x const int ANALOG_GAIN_MAX_IDX_OX03C10 = 0x36; const int ANALOG_GAIN_COST_DELTA_OX03C10 = -1; const float ANALOG_GAIN_COST_LOW_OX03C10 = 0.4; diff --git a/system/camerad/cameras/real_debayer.cl b/system/camerad/cameras/real_debayer.cl index cff5ae455b..e15a873d6d 100644 --- a/system/camerad/cameras/real_debayer.cl +++ b/system/camerad/cameras/real_debayer.cl @@ -18,6 +18,9 @@ float3 color_correct(float3 rgb) { x += rgb.z * (float3)(-0.25277411, -0.05627105, 1.45875782); #endif + #if IS_OX + return -0.507089*exp(-12.54124638*x)+0.9655*powr(x,0.5)-0.472597*x+0.507089; + #else // tone mapping params const float gamma_k = 0.75; const float gamma_b = 0.125; @@ -28,6 +31,7 @@ float3 color_correct(float3 rgb) { return (x > mp) ? ((rk * (x-mp) * (1-(gamma_k*mp+gamma_b)) * (1+1/(rk*(1-mp))) / (1+rk*(x-mp))) + gamma_k*mp + gamma_b) : ((rk * (x-mp) * (gamma_k*mp+gamma_b) * (1+1/(rk*mp)) / (1-rk*(x-mp))) + gamma_k*mp + gamma_b); + #endif } float get_vignetting_s(float r) { diff --git a/system/hardware/tici/amplifier.py b/system/hardware/tici/amplifier.py index 9725cd689c..979bc757f6 100755 --- a/system/hardware/tici/amplifier.py +++ b/system/hardware/tici/amplifier.py @@ -1,5 +1,7 @@ +import time from smbus2 import SMBus from collections import namedtuple +from typing import List # https://datasheets.maximintegrated.com/en/ds/MAX98089.pdf @@ -104,31 +106,44 @@ class Amplifier: def __init__(self, debug=False): self.debug = debug - def set_config(self, config): - with SMBus(self.AMP_I2C_BUS) as bus: - if self.debug: - print(f"Setting \"{config.name}\" to {config.value}:") - - old_value = bus.read_byte_data(self.AMP_ADDRESS, config.register, force=True) - new_value = (old_value & (~config.mask)) | ((config.value << config.offset) & config.mask) - bus.write_byte_data(self.AMP_ADDRESS, config.register, new_value, force=True) - - if self.debug: - print(f" Changed {hex(config.register)}: {hex(old_value)} -> {hex(new_value)}") - - def set_global_shutdown(self, amp_disabled): - self.set_config(AmpConfig("Global shutdown", 0b0 if amp_disabled else 0b1, 0x51, 7, 0b10000000)) + def _get_shutdown_config(self, amp_disabled: bool) -> AmpConfig: + return AmpConfig("Global shutdown", 0b0 if amp_disabled else 0b1, 0x51, 7, 0b10000000) - def initialize_configuration(self, model): - self.set_global_shutdown(amp_disabled=True) - - for config in BASE_CONFIG: - self.set_config(config) - - for config in CONFIGS[model]: - self.set_config(config) - - self.set_global_shutdown(amp_disabled=False) + def _set_configs(self, configs: List[AmpConfig]) -> None: + with SMBus(self.AMP_I2C_BUS) as bus: + for config in configs: + if self.debug: + print(f"Setting \"{config.name}\" to {config.value}:") + + old_value = bus.read_byte_data(self.AMP_ADDRESS, config.register, force=True) + new_value = (old_value & (~config.mask)) | ((config.value << config.offset) & config.mask) + bus.write_byte_data(self.AMP_ADDRESS, config.register, new_value, force=True) + + if self.debug: + print(f" Changed {hex(config.register)}: {hex(old_value)} -> {hex(new_value)}") + + def set_configs(self, configs: List[AmpConfig]) -> bool: + # retry in case panda is using the amp + for _ in range(10): + try: + self._set_configs(configs) + return True + except OSError: + print("Failed to set amp config, retrying...") + time.sleep(0.02) + return False + + def set_global_shutdown(self, amp_disabled: bool) -> bool: + return self.set_configs([self._get_shutdown_config(amp_disabled), ]) + + def initialize_configuration(self, model: str) -> bool: + cfgs = [ + self._get_shutdown_config(True), + *BASE_CONFIG, + *CONFIGS[model], + self._get_shutdown_config(False), + ] + return self.set_configs(cfgs) if __name__ == "__main__": diff --git a/system/hardware/tici/hardware.py b/system/hardware/tici/hardware.py index 46db097da1..fdddf4d063 100644 --- a/system/hardware/tici/hardware.py +++ b/system/hardware/tici/hardware.py @@ -8,7 +8,7 @@ from functools import cached_property from pathlib import Path from cereal import log -from common.gpio import gpio_set, gpio_init +from common.gpio import gpio_set, gpio_init, get_irq_for_action from system.hardware.base import HardwareBase, ThermalConfig from system.hardware.tici import iwlist from system.hardware.tici.pins import GPIO @@ -63,8 +63,14 @@ MM_MODEM_ACCESS_TECHNOLOGY_LTE = 1 << 14 def sudo_write(val, path): os.system(f"sudo su -c 'echo {val} > {path}'") -def affine_irq(val, irq): - sudo_write(str(val), f"/proc/irq/{irq}/smp_affinity_list") + +def affine_irq(val, action): + irq = get_irq_for_action(action) + if len(irq) == 0: + print(f"No IRQs found for '{action}'") + return + for i in irq: + sudo_write(str(val), f"/proc/irq/{i}/smp_affinity_list") class Tici(HardwareBase): @@ -432,12 +438,20 @@ class Tici(HardwareBase): sudo_write(gov, f'/sys/devices/system/cpu/cpufreq/policy{n}/scaling_governor') # *** IRQ config *** - affine_irq(5, 565) # kgsl-3d0 - affine_irq(4, 126) # SPI goes on boardd core - affine_irq(4, 740) # xhci-hcd:usb1 goes on the boardd core - affine_irq(4, 1069) # xhci-hcd:usb3 goes on the boardd core - for irq in range(237, 246): - affine_irq(5, irq) # camerad + + # GPU + affine_irq(5, "kgsl-3d0") + + # boardd core + affine_irq(4, "spi_geni") # SPI + affine_irq(4, "xhci-hcd:usb3") # aux panda USB (or potentially anything else on USB) + if "tici" in self.model: + affine_irq(4, "xhci-hcd:usb1") # internal panda USB + + # camerad core + camera_irqs = ("cci", "cpas_camnoc", "cpas-cdm", "csid", "ife", "csid", "csid-lite", "ife-lite") + for n in camera_irqs: + affine_irq(5, n) def get_gpu_usage_percent(self): try: @@ -461,9 +475,11 @@ class Tici(HardwareBase): # *** IRQ config *** # move these off the default core - affine_irq(1, 7) # msm_drm - affine_irq(1, 250) # msm_vidc - affine_irq(1, 8) # i2c_geni (sensord) + affine_irq(1, "msm_drm") + affine_irq(1, "msm_vidc") + affine_irq(1, "i2c_geni") + + # mask off big cluster from default affinity sudo_write("f", "/proc/irq/default_smp_affinity") # *** GPU config *** diff --git a/system/hardware/tici/test_agnos_updater.py b/system/hardware/tici/tests/test_agnos_updater.py similarity index 80% rename from system/hardware/tici/test_agnos_updater.py rename to system/hardware/tici/tests/test_agnos_updater.py index e0d6ed8814..86bc78881e 100755 --- a/system/hardware/tici/test_agnos_updater.py +++ b/system/hardware/tici/tests/test_agnos_updater.py @@ -4,8 +4,8 @@ import os import unittest import requests -AGNOS_DIR = os.path.join(os.path.dirname(os.path.abspath(__file__))) -MANIFEST = os.path.join(AGNOS_DIR, "agnos.json") +TEST_DIR = os.path.join(os.path.dirname(os.path.abspath(__file__))) +MANIFEST = os.path.join(TEST_DIR, "../agnos.json") class TestAgnosUpdater(unittest.TestCase): diff --git a/system/hardware/tici/tests/test_amplifier.py b/system/hardware/tici/tests/test_amplifier.py new file mode 100755 index 0000000000..1cad6cfd6b --- /dev/null +++ b/system/hardware/tici/tests/test_amplifier.py @@ -0,0 +1,70 @@ +#!/usr/bin/env python3 +import time +import random +import unittest +import subprocess + +from panda import Panda +from system.hardware import TICI +from system.hardware.tici.hardware import Tici +from system.hardware.tici.amplifier import Amplifier + + +class TestAmplifier(unittest.TestCase): + + @classmethod + def setUpClass(cls): + if not TICI: + raise unittest.SkipTest + + def setUp(self): + # clear dmesg + subprocess.check_call("sudo dmesg -C", shell=True) + + self.panda = Panda() + self.panda.reset() + + def tearDown(self): + self.panda.reset(reconnect=False) + + def _check_for_i2c_errors(self, expected): + dmesg = subprocess.check_output("dmesg", shell=True, encoding='utf8') + i2c_lines = [l for l in dmesg.strip().splitlines() if 'i2c_geni a88000.i2c' in l] + i2c_str = '\n'.join(i2c_lines) + if not expected: + assert len(i2c_lines) == 0 + else: + assert "i2c error :-107" in i2c_str or "Bus arbitration lost" in i2c_str + + def test_init(self): + amp = Amplifier(debug=True) + r = amp.initialize_configuration(Tici().model) + assert r + self._check_for_i2c_errors(False) + + def test_shutdown(self): + amp = Amplifier(debug=True) + for _ in range(10): + r = amp.set_global_shutdown(True) + r = amp.set_global_shutdown(False) + assert r + self._check_for_i2c_errors(False) + + def test_init_while_siren_play(self): + for _ in range(5): + self.panda.set_siren(False) + time.sleep(0.1) + + self.panda.set_siren(True) + time.sleep(random.randint(0, 5)) + + amp = Amplifier(debug=True) + r = amp.initialize_configuration(Tici().model) + assert r + + # make sure we're a good test + self._check_for_i2c_errors(True) + + +if __name__ == "__main__": + unittest.main() diff --git a/system/hardware/tici/test_power_draw.py b/system/hardware/tici/tests/test_power_draw.py similarity index 100% rename from system/hardware/tici/test_power_draw.py rename to system/hardware/tici/tests/test_power_draw.py diff --git a/system/sensord/rawgps/rawgpsd.py b/system/sensord/rawgps/rawgpsd.py index f75ceee7ed..8f243af9a5 100755 --- a/system/sensord/rawgps/rawgpsd.py +++ b/system/sensord/rawgps/rawgpsd.py @@ -270,7 +270,6 @@ def main() -> NoReturn: msg = messaging.new_message('gpsLocation') gps = msg.gpsLocation - gps.flags = 1 gps.latitude = report["t_DblFinalPosLatLon[0]"] * 180/math.pi gps.longitude = report["t_DblFinalPosLatLon[1]"] * 180/math.pi gps.altitude = report["q_FltFinalPosAlt"] @@ -283,6 +282,8 @@ def main() -> NoReturn: gps.verticalAccuracy = report["q_FltVdop"] gps.bearingAccuracyDeg = report["q_FltHeadingUncRad"] * 180/math.pi gps.speedAccuracy = math.sqrt(sum([x**2 for x in vNEDsigma])) + # quectel gps verticalAccuracy is clipped to 500, set invalid if so + gps.flags = 1 if gps.verticalAccuracy != 500 else 0 pm.send('gpsLocation', msg) diff --git a/system/sensord/tests/test_sensord.py b/system/sensord/tests/test_sensord.py index 21b67271d6..6e8dda79bb 100755 --- a/system/sensord/tests/test_sensord.py +++ b/system/sensord/tests/test_sensord.py @@ -1,6 +1,5 @@ #!/usr/bin/env python3 import os -import glob import time import unittest import numpy as np @@ -8,6 +7,7 @@ from collections import namedtuple, defaultdict import cereal.messaging as messaging from cereal import log +from common.gpio import get_irq_for_action from system.hardware import TICI from selfdrive.manager.process_config import managed_processes @@ -113,13 +113,7 @@ class TestSensord(unittest.TestCase): cls.events = read_sensor_events(cls.sample_secs) # determine sensord's irq - cls.sensord_irq = None - for fn in glob.glob('/sys/kernel/irq/*/actions'): - with open(fn) as f: - if "sensord" in f.read(): - cls.sensord_irq = int(fn.split('/')[-2]) - break - assert cls.sensord_irq is not None + cls.sensord_irq = get_irq_for_action("sensord")[0] finally: # teardown won't run if this doesn't succeed managed_processes["sensord"].stop() diff --git a/tools/cabana/.gitignore b/tools/cabana/.gitignore index c74ab7483c..c3f5ef2b69 100644 --- a/tools/cabana/.gitignore +++ b/tools/cabana/.gitignore @@ -1,7 +1,7 @@ moc_* *.moc -_cabana +cabana settings dbc/car_fingerprint_to_dbc.json -tests/_test_cabana +tests/test_cabana diff --git a/tools/cabana/README.md b/tools/cabana/README.md index db247c39c5..4faa7c61d0 100644 --- a/tools/cabana/README.md +++ b/tools/cabana/README.md @@ -8,7 +8,7 @@ Cabana is a tool developed to view raw CAN data. One use for this is creating an ```bash $ ./cabana -h -Usage: ./_cabana [options] route +Usage: ./cabana [options] route Options: -h, --help Displays this help. diff --git a/tools/cabana/SConscript b/tools/cabana/SConscript index 7d5129fc16..77738afae3 100644 --- a/tools/cabana/SConscript +++ b/tools/cabana/SConscript @@ -1,6 +1,6 @@ import os Import('env', 'qt_env', 'arch', 'common', 'messaging', 'visionipc', 'replay_lib', - 'cereal', 'transformations', 'widgets', 'opendbc') + 'cereal', 'transformations', 'widgets') base_frameworks = qt_env['FRAMEWORKS'] base_libs = [common, messaging, cereal, visionipc, transformations, 'zmq', @@ -15,8 +15,9 @@ else: qt_libs = ['qt_util'] + base_libs -cabana_libs = [widgets, cereal, messaging, visionipc, replay_lib, opendbc,'avutil', 'avcodec', 'avformat', 'bz2', 'curl', 'yuv'] + qt_libs cabana_env = qt_env.Clone() +cabana_env["LIBPATH"] += ['../../opendbc/can'] +cabana_libs = [widgets, cereal, messaging, visionipc, replay_lib, 'libdbc_static', 'avutil', 'avcodec', 'avformat', 'bz2', 'curl', 'yuv'] + qt_libs opendbc_path = '-DOPENDBC_FILE_PATH=\'"%s"\'' % (cabana_env.Dir("../../opendbc").abspath) cabana_env['CXXFLAGS'] += [opendbc_path] @@ -28,16 +29,14 @@ cabana_env.Depends(assets, Glob('/assets/*', exclude=[assets, assets_src, "asset prev_moc_path = cabana_env['QT_MOCHPREFIX'] cabana_env['QT_MOCHPREFIX'] = os.path.dirname(prev_moc_path) + '/cabana/moc_' -cabana_lib = cabana_env.Library("cabana_lib", ['mainwin.cc', 'streams/livestream.cc', 'streams/abstractstream.cc', 'streams/replaystream.cc', 'binaryview.cc', 'chartswidget.cc', 'historylog.cc', 'videowidget.cc', 'signalview.cc', +cabana_lib = cabana_env.Library("cabana_lib", ['mainwin.cc', 'streams/livestream.cc', 'streams/abstractstream.cc', 'streams/replaystream.cc', 'binaryview.cc', 'historylog.cc', 'videowidget.cc', 'signalview.cc', 'dbc/dbc.cc', 'dbc/dbcfile.cc', 'dbc/dbcmanager.cc', + 'chart/chartswidget.cc', 'chart/chart.cc', 'chart/signalselector.cc', 'chart/tiplabel.cc', 'commands.cc', 'messageswidget.cc', 'route.cc', 'settings.cc', 'util.cc', 'detailwidget.cc', 'tools/findsimilarbits.cc'], LIBS=cabana_libs, FRAMEWORKS=base_frameworks) -cabana_env.Program('_cabana', ['cabana.cc', cabana_lib, assets], LIBS=cabana_libs, FRAMEWORKS=base_frameworks) - -if arch == "Darwin": - cabana_env.Execute('install_name_tool -change opendbc/can/libdbc.dylib @loader_path/../../opendbc/can/libdbc.dylib ./_cabana') +cabana_env.Program('cabana', ['cabana.cc', cabana_lib, assets], LIBS=cabana_libs, FRAMEWORKS=base_frameworks) if GetOption('test'): - cabana_env.Program('tests/_test_cabana', ['tests/test_runner.cc', 'tests/test_cabana.cc', cabana_lib], LIBS=[cabana_libs]) + cabana_env.Program('tests/test_cabana', ['tests/test_runner.cc', 'tests/test_cabana.cc', cabana_lib], LIBS=[cabana_libs]) def generate_dbc_json(target, source, env): env.Execute('tools/cabana/dbc/generate_dbc_json.py --out tools/cabana/dbc/car_fingerprint_to_dbc.json') diff --git a/tools/cabana/cabana b/tools/cabana/cabana deleted file mode 100755 index 14647b6a10..0000000000 --- a/tools/cabana/cabana +++ /dev/null @@ -1,4 +0,0 @@ -#!/bin/sh -cd "$(dirname "$0")" -export LD_LIBRARY_PATH="../../opendbc/can:$LD_LIBRARY_PATH" -exec ./_cabana "$@" diff --git a/tools/cabana/cabana.cc b/tools/cabana/cabana.cc index 5c182f435f..329b6070ae 100644 --- a/tools/cabana/cabana.cc +++ b/tools/cabana/cabana.cc @@ -15,6 +15,7 @@ int main(int argc, char *argv[]) { QApplication app(argc, argv); app.setApplicationDisplayName("Cabana"); app.setWindowIcon(QIcon(":cabana-icon.png")); + utils::setTheme(settings.theme); QCommandLineParser cmd_parser; cmd_parser.addHelpOption(); diff --git a/tools/cabana/chart/chart.cc b/tools/cabana/chart/chart.cc new file mode 100644 index 0000000000..ee1cdab6d2 --- /dev/null +++ b/tools/cabana/chart/chart.cc @@ -0,0 +1,751 @@ +#include "tools/cabana/chart/chart.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "tools/cabana/chart/chartswidget.h" + +static inline bool xLessThan(const QPointF &p, float x) { return p.x() < x; } + +ChartView::ChartView(const std::pair &x_range, ChartsWidget *parent) : charts_widget(parent), tip_label(this), QChartView(nullptr, parent) { + series_type = (SeriesType)settings.chart_series_type; + QChart *chart = new QChart(); + chart->setBackgroundVisible(false); + axis_x = new QValueAxis(this); + axis_y = new QValueAxis(this); + chart->addAxis(axis_x, Qt::AlignBottom); + chart->addAxis(axis_y, Qt::AlignLeft); + chart->legend()->layout()->setContentsMargins(0, 0, 0, 0); + chart->legend()->setShowToolTips(true); + chart->setMargins({0, 0, 0, 0}); + + axis_x->setRange(x_range.first, x_range.second); + setChart(chart); + + createToolButtons(); + // TODO: enable zoomIn/seekTo in live streaming mode. + setRubberBand(can->liveStreaming() ? QChartView::NoRubberBand : QChartView::HorizontalRubberBand); + setMouseTracking(true); + setTheme(settings.theme == DARK_THEME ? QChart::QChart::ChartThemeDark : QChart::ChartThemeLight); + + QObject::connect(axis_y, &QValueAxis::rangeChanged, [this]() { resetChartCache(); }); + QObject::connect(axis_y, &QAbstractAxis::titleTextChanged, [this]() { resetChartCache(); }); + + QObject::connect(dbc(), &DBCManager::signalRemoved, this, &ChartView::signalRemoved); + QObject::connect(dbc(), &DBCManager::signalUpdated, this, &ChartView::signalUpdated); + QObject::connect(dbc(), &DBCManager::msgRemoved, this, &ChartView::msgRemoved); + QObject::connect(dbc(), &DBCManager::msgUpdated, this, &ChartView::msgUpdated); +} + +void ChartView::createToolButtons() { + move_icon = new QGraphicsPixmapItem(utils::icon("grip-horizontal"), chart()); + move_icon->setToolTip(tr("Drag and drop to move chart")); + + QToolButton *remove_btn = new ToolButton("x", tr("Remove Chart")); + close_btn_proxy = new QGraphicsProxyWidget(chart()); + close_btn_proxy->setWidget(remove_btn); + close_btn_proxy->setZValue(chart()->zValue() + 11); + + // series types + QMenu *menu = new QMenu(this); + auto change_series_group = new QActionGroup(menu); + change_series_group->setExclusive(true); + QStringList types{tr("Line"), tr("Step Line"), tr("Scatter")}; + for (int i = 0; i < types.size(); ++i) { + QAction *act = new QAction(types[i], change_series_group); + act->setData(i); + act->setCheckable(true); + act->setChecked(i == (int)series_type); + menu->addAction(act); + } + menu->addSeparator(); + menu->addAction(tr("Manage Signals"), this, &ChartView::manageSignals); + split_chart_act = menu->addAction(tr("Split Chart"), [this]() { charts_widget->splitChart(this); }); + + QToolButton *manage_btn = new ToolButton("list", ""); + manage_btn->setMenu(menu); + manage_btn->setPopupMode(QToolButton::InstantPopup); + manage_btn->setStyleSheet("QToolButton::menu-indicator { image: none; }"); + manage_btn_proxy = new QGraphicsProxyWidget(chart()); + manage_btn_proxy->setWidget(manage_btn); + manage_btn_proxy->setZValue(chart()->zValue() + 11); + + QObject::connect(remove_btn, &QToolButton::clicked, [this]() { charts_widget->removeChart(this); }); + QObject::connect(change_series_group, &QActionGroup::triggered, [this](QAction *action) { + setSeriesType((SeriesType)action->data().toInt()); + }); +} + +QSize ChartView::sizeHint() const { + return {CHART_MIN_WIDTH, settings.chart_height}; +} + +void ChartView::setTheme(QChart::ChartTheme theme) { + chart()->setTheme(theme); + if (theme == QChart::ChartThemeDark) { + axis_x->setTitleBrush(palette().text()); + axis_x->setLabelsBrush(palette().text()); + axis_y->setTitleBrush(palette().text()); + axis_y->setLabelsBrush(palette().text()); + chart()->legend()->setLabelColor(palette().color(QPalette::Text)); + } + for (auto &s : sigs) { + s.series->setColor(getColor(s.sig)); + } +} + +void ChartView::addSignal(const MessageId &msg_id, const cabana::Signal *sig) { + if (hasSignal(msg_id, sig)) return; + + QXYSeries *series = createSeries(series_type, getColor(sig)); + sigs.push_back({.msg_id = msg_id, .sig = sig, .series = series}); + updateSeries(sig); + updateSeriesPoints(); + updateTitle(); + emit charts_widget->seriesChanged(); +} + +bool ChartView::hasSignal(const MessageId &msg_id, const cabana::Signal *sig) const { + return std::any_of(sigs.begin(), sigs.end(), [&](auto &s) { return s.msg_id == msg_id && s.sig == sig; }); +} + +void ChartView::removeIf(std::function predicate) { + int prev_size = sigs.size(); + for (auto it = sigs.begin(); it != sigs.end(); /**/) { + if (predicate(*it)) { + chart()->removeSeries(it->series); + it->series->deleteLater(); + it = sigs.erase(it); + } else { + ++it; + } + } + if (sigs.empty()) { + charts_widget->removeChart(this); + } else if (sigs.size() != prev_size) { + emit charts_widget->seriesChanged(); + updateAxisY(); + resetChartCache(); + } +} + +void ChartView::signalUpdated(const cabana::Signal *sig) { + if (std::any_of(sigs.begin(), sigs.end(), [=](auto &s) { return s.sig == sig; })) { + updateTitle(); + updateSeries(sig); + } +} + +void ChartView::msgUpdated(MessageId id) { + if (std::any_of(sigs.begin(), sigs.end(), [=](auto &s) { return s.msg_id == id; })) + updateTitle(); +} + +void ChartView::manageSignals() { + SignalSelector dlg(tr("Mange Chart"), this); + for (auto &s : sigs) { + dlg.addSelected(s.msg_id, s.sig); + } + if (dlg.exec() == QDialog::Accepted) { + auto items = dlg.seletedItems(); + for (auto s : items) { + addSignal(s->msg_id, s->sig); + } + removeIf([&](auto &s) { + return std::none_of(items.cbegin(), items.cend(), [&](auto &it) { return s.msg_id == it->msg_id && s.sig == it->sig; }); + }); + } +} + +void ChartView::resizeEvent(QResizeEvent *event) { + qreal left, top, right, bottom; + chart()->layout()->getContentsMargins(&left, &top, &right, &bottom); + move_icon->setPos(left, top); + close_btn_proxy->setPos(rect().right() - right - close_btn_proxy->size().width(), top); + int x = close_btn_proxy->pos().x() - manage_btn_proxy->size().width() - style()->pixelMetric(QStyle::PM_LayoutHorizontalSpacing); + manage_btn_proxy->setPos(x, top); + if (align_to > 0) { + updatePlotArea(align_to, true); + } + QChartView::resizeEvent(event); +} + +void ChartView::updatePlotArea(int left_pos, bool force) { + if (align_to != left_pos || force) { + align_to = left_pos; + + qreal left, top, right, bottom; + chart()->layout()->getContentsMargins(&left, &top, &right, &bottom); + chart()->legend()->setGeometry({move_icon->sceneBoundingRect().topRight(), manage_btn_proxy->sceneBoundingRect().bottomLeft()}); + QSizeF x_label_size = QFontMetrics(axis_x->labelsFont()).size(Qt::TextSingleLine, QString::number(axis_x->max(), 'f', 2)); + x_label_size += QSizeF{5, 5}; + int adjust_top = chart()->legend()->geometry().height() + style()->pixelMetric(QStyle::PM_LayoutTopMargin); + chart()->setPlotArea(rect().adjusted(align_to + left, adjust_top + top, -x_label_size.width() / 2 - right, -x_label_size.height() - bottom)); + chart()->layout()->invalidate(); + resetChartCache(); + } +} + +void ChartView::updateTitle() { + for (QLegendMarker *marker : chart()->legend()->markers()) { + QObject::connect(marker, &QLegendMarker::clicked, this, &ChartView::handleMarkerClicked, Qt::UniqueConnection); + } + for (auto &s : sigs) { + auto decoration = s.series->isVisible() ? "none" : "line-through"; + s.series->setName(QString("%2 %3 %4").arg(decoration, s.sig->name, msgName(s.msg_id), s.msg_id.toString())); + } + split_chart_act->setEnabled(sigs.size() > 1); + resetChartCache(); +} + +void ChartView::updatePlot(double cur, double min, double max) { + cur_sec = cur; + if (min != axis_x->min() || max != axis_x->max()) { + axis_x->setRange(min, max); + updateAxisY(); + updateSeriesPoints(); + // update tooltip + if (tooltip_x >= 0) { + showTip(chart()->mapToValue({tooltip_x, 0}).x()); + } + resetChartCache(); + } + viewport()->update(); +} + +void ChartView::updateSeriesPoints() { + // Show points when zoomed in enough + for (auto &s : sigs) { + auto begin = std::lower_bound(s.vals.begin(), s.vals.end(), axis_x->min(), xLessThan); + auto end = std::lower_bound(begin, s.vals.end(), axis_x->max(), xLessThan); + if (begin != end) { + int num_points = std::max((end - begin), 1); + QPointF right_pt = end == s.vals.end() ? s.vals.back() : *end; + double pixels_per_point = (chart()->mapToPosition(right_pt).x() - chart()->mapToPosition(*begin).x()) / num_points; + + if (series_type == SeriesType::Scatter) { + qreal size = std::clamp(pixels_per_point / 2.0, 2.0, 8.0); + if (s.series->useOpenGL()) { + size *= devicePixelRatioF(); + } + ((QScatterSeries *)s.series)->setMarkerSize(size); + } else { + s.series->setPointsVisible(pixels_per_point > 20); + } + } + } +} + +void ChartView::updateSeries(const cabana::Signal *sig) { + for (auto &s : sigs) { + if (!sig || s.sig == sig) { + if (!can->liveStreaming()) { + s.vals.clear(); + s.step_vals.clear(); + s.last_value_mono_time = 0; + } + s.series->setColor(getColor(s.sig)); + + const auto &msgs = can->events().at(s.msg_id); + auto first = std::upper_bound(msgs.cbegin(), msgs.cend(), CanEvent{.mono_time = s.last_value_mono_time}); + int new_size = std::max(s.vals.size() + std::distance(first, msgs.cend()), settings.max_cached_minutes * 60 * 100); + if (s.vals.capacity() <= new_size) { + s.vals.reserve(new_size * 2); + s.step_vals.reserve(new_size * 4); + } + + const double route_start_time = can->routeStartTime(); + for (auto end = msgs.cend(); first != end; ++first) { + double value = get_raw_value(first->dat, first->size, *s.sig); + double ts = first->mono_time / 1e9 - route_start_time; // seconds + s.vals.append({ts, value}); + if (!s.step_vals.empty()) { + s.step_vals.append({ts, s.step_vals.back().y()}); + } + s.step_vals.append({ts, value}); + s.last_value_mono_time = first->mono_time; + } + if (!can->liveStreaming()) { + s.segment_tree.build(s.vals); + } + s.series->replace(series_type == SeriesType::StepLine ? s.step_vals : s.vals); + } + } + updateAxisY(); + // invoke resetChartCache in ui thread + QMetaObject::invokeMethod(this, &ChartView::resetChartCache, Qt::QueuedConnection); +} + +// auto zoom on yaxis +void ChartView::updateAxisY() { + if (sigs.isEmpty()) return; + + double min = std::numeric_limits::max(); + double max = std::numeric_limits::lowest(); + QString unit = sigs[0].sig->unit; + + for (auto &s : sigs) { + if (!s.series->isVisible()) continue; + + // Only show unit when all signals have the same unit + if (unit != s.sig->unit) { + unit.clear(); + } + + auto first = std::lower_bound(s.vals.begin(), s.vals.end(), axis_x->min(), xLessThan); + auto last = std::lower_bound(first, s.vals.end(), axis_x->max(), xLessThan); + s.min = std::numeric_limits::max(); + s.max = std::numeric_limits::lowest(); + if (can->liveStreaming()) { + for (auto it = first; it != last; ++it) { + if (it->y() < s.min) s.min = it->y(); + if (it->y() > s.max) s.max = it->y(); + } + } else { + auto [min_y, max_y] = s.segment_tree.minmax(std::distance(s.vals.begin(), first), std::distance(s.vals.begin(), last)); + s.min = min_y; + s.max = max_y; + } + min = std::min(min, s.min); + max = std::max(max, s.max); + } + if (min == std::numeric_limits::max()) min = 0; + if (max == std::numeric_limits::lowest()) max = 0; + + if (axis_y->titleText() != unit) { + axis_y->setTitleText(unit); + y_label_width = 0; // recalc width + } + + double delta = std::abs(max - min) < 1e-3 ? 1 : (max - min) * 0.05; + auto [min_y, max_y, tick_count] = getNiceAxisNumbers(min - delta, max + delta, axis_y->tickCount()); + if (min_y != axis_y->min() || max_y != axis_y->max() || y_label_width == 0) { + axis_y->setRange(min_y, max_y); + axis_y->setTickCount(tick_count); + + int n = qMax(int(-qFloor(std::log10((max_y - min_y) / (tick_count - 1)))), 0) + 1; + int max_label_width = 0; + QFontMetrics fm(axis_y->labelsFont()); + for (int i = 0; i < tick_count; i++) { + qreal value = min_y + (i * (max_y - min_y) / (tick_count - 1)); + max_label_width = std::max(max_label_width, fm.width(QString::number(value, 'f', n))); + } + + int title_spacing = unit.isEmpty() ? 0 : QFontMetrics(axis_y->titleFont()).size(Qt::TextSingleLine, unit).height(); + y_label_width = title_spacing + max_label_width + 15; + axis_y->setLabelFormat(QString("%.%1f").arg(n)); + emit axisYLabelWidthChanged(y_label_width); + } +} + +std::tuple ChartView::getNiceAxisNumbers(qreal min, qreal max, int tick_count) { + qreal range = niceNumber((max - min), true); // range with ceiling + qreal step = niceNumber(range / (tick_count - 1), false); + min = qFloor(min / step); + max = qCeil(max / step); + tick_count = int(max - min) + 1; + return {min * step, max * step, tick_count}; +} + +// nice numbers can be expressed as form of 1*10^n, 2* 10^n or 5*10^n +qreal ChartView::niceNumber(qreal x, bool ceiling) { + qreal z = qPow(10, qFloor(std::log10(x))); //find corresponding number of the form of 10^n than is smaller than x + qreal q = x / z; //q<10 && q>=1; + if (ceiling) { + if (q <= 1.0) q = 1; + else if (q <= 2.0) q = 2; + else if (q <= 5.0) q = 5; + else q = 10; + } else { + if (q < 1.5) q = 1; + else if (q < 3.0) q = 2; + else if (q < 7.0) q = 5; + else q = 10; + } + return q * z; +} + +void ChartView::leaveEvent(QEvent *event) { + if (tip_label.isVisible()) { + charts_widget->showValueTip(-1); + } + QChartView::leaveEvent(event); +} + +QPixmap getBlankShadowPixmap(const QSize &size, int extent) { + QGraphicsDropShadowEffect *e = new QGraphicsDropShadowEffect; + e->setColor(QColor(40, 40, 40, 245)); + e->setOffset(0, 2); + e->setBlurRadius(10); + + QGraphicsScene scene; + QGraphicsPixmapItem item; + QPixmap src(size); + src.fill(Qt::white); + item.setPixmap(src); + item.setGraphicsEffect(e); + scene.addItem(&item); + QImage target(src.size() + QSize(extent * 2, extent * 2), QImage::Format_ARGB32); + target.fill(Qt::transparent); + QPainter p(&target); + scene.render(&p, QRectF(), QRectF(-extent, -extent, src.width() + extent * 2, src.height() + extent * 2)); + return QPixmap::fromImage(target); +} + +static QPixmap getDropPixmap(const QPixmap &src) { + static QPixmap shadow_px; + const int extent = 10; + if (shadow_px.size() != src.size() + QSize(extent * 2, extent * 2)) { + shadow_px = getBlankShadowPixmap(src.size(), extent); + } + QPixmap px = shadow_px; + QPainter p(&px); + int delta_w = px.width() - src.width(); + int delta_h = px.height() - src.height(); + p.drawPixmap(QPoint(delta_w / 2, delta_h / 2), src); + p.setCompositionMode(QPainter::CompositionMode_DestinationIn); + p.fillRect(delta_w / 2, delta_h / 2, src.width(), src.height(), QColor(0, 0, 0, 200)); + return px; +} + +void ChartView::mousePressEvent(QMouseEvent *event) { + if (event->button() == Qt::LeftButton && move_icon->sceneBoundingRect().contains(event->pos())) { + QMimeData *mimeData = new QMimeData; + mimeData->setData(CHART_MIME_TYPE, QByteArray::number((qulonglong)this)); + QPixmap px = grab().scaledToWidth(CHART_MIN_WIDTH, Qt::SmoothTransformation); + QDrag *drag = new QDrag(this); + drag->setMimeData(mimeData); + drag->setPixmap(getDropPixmap(px)); + drag->setHotSpot(-QPoint(5, 5)); + drag->exec(Qt::CopyAction | Qt::MoveAction, Qt::MoveAction); + charts_widget->stopAutoScroll(); + } else if (event->button() == Qt::LeftButton && QApplication::keyboardModifiers().testFlag(Qt::ShiftModifier)) { + if (!can->liveStreaming()) { + // Save current playback state when scrubbing + resume_after_scrub = !can->isPaused(); + if (resume_after_scrub) { + can->pause(true); + } + is_scrubbing = true; + } + } else { + QChartView::mousePressEvent(event); + } +} + +void ChartView::mouseReleaseEvent(QMouseEvent *event) { + auto rubber = findChild(); + if (event->button() == Qt::LeftButton && rubber && rubber->isVisible()) { + rubber->hide(); + QRectF rect = rubber->geometry().normalized(); + double min = chart()->mapToValue(rect.topLeft()).x(); + double max = chart()->mapToValue(rect.bottomRight()).x(); + + // Prevent zooming/seeking past the end of the route + min = std::clamp(min, 0., can->totalSeconds()); + max = std::clamp(max, 0., can->totalSeconds()); + + if (rubber->width() <= 0) { + // no rubber dragged, seek to mouse position + can->seekTo(min); + } else if (rubber->width() > 10) { + charts_widget->zoom_undo_stack->push(new ZoomCommand(charts_widget, {min, max})); + } else { + viewport()->update(); + } + event->accept(); + } else if (!can->liveStreaming() && event->button() == Qt::RightButton) { + charts_widget->zoom_undo_stack->undo(); + event->accept(); + } else { + QGraphicsView::mouseReleaseEvent(event); + } + + // Resume playback if we were scrubbing + is_scrubbing = false; + if (resume_after_scrub) { + can->pause(false); + resume_after_scrub = false; + } +} + +void ChartView::mouseMoveEvent(QMouseEvent *ev) { + const auto plot_area = chart()->plotArea(); + // Scrubbing + if (is_scrubbing && QApplication::keyboardModifiers().testFlag(Qt::ShiftModifier)) { + if (plot_area.contains(ev->pos())) { + can->seekTo(std::clamp(chart()->mapToValue(ev->pos()).x(), 0., can->totalSeconds())); + } + } + + auto rubber = findChild(); + bool is_zooming = rubber && rubber->isVisible(); + clearTrackPoints(); + + if (!is_zooming && plot_area.contains(ev->pos())) { + const double sec = chart()->mapToValue(ev->pos()).x(); + charts_widget->showValueTip(sec); + } else if (tip_label.isVisible()) { + charts_widget->showValueTip(-1); + } + + QChartView::mouseMoveEvent(ev); + if (is_zooming) { + QRect rubber_rect = rubber->geometry(); + rubber_rect.setLeft(std::max(rubber_rect.left(), (int)plot_area.left())); + rubber_rect.setRight(std::min(rubber_rect.right(), (int)plot_area.right())); + if (rubber_rect != rubber->geometry()) { + rubber->setGeometry(rubber_rect); + } + viewport()->update(); + } +} + +void ChartView::showTip(double sec) { + tooltip_x = chart()->mapToPosition({sec, 0}).x(); + qreal x = tooltip_x; + QStringList text_list(QString::number(chart()->mapToValue({x, 0}).x(), 'f', 3)); + for (auto &s : sigs) { + if (s.series->isVisible()) { + QString value = "--"; + // use reverse iterator to find last item <= sec. + auto it = std::lower_bound(s.vals.rbegin(), s.vals.rend(), sec, [](auto &p, double x) { return p.x() > x; }); + if (it != s.vals.rend() && it->x() >= axis_x->min()) { + value = QString::number(it->y()); + s.track_pt = *it; + x = std::max(x, chart()->mapToPosition(*it).x()); + } + QString name = sigs.size() > 1 ? s.sig->name + ": " : ""; + QString min = s.min == std::numeric_limits::max() ? "--" : QString::number(s.min); + QString max = s.max == std::numeric_limits::lowest() ? "--" : QString::number(s.max); + text_list << QString("%2%3 (%4, %5)") + .arg(s.series->color().name(), name, value, min, max); + } + } + QPointF tooltip_pt(x, chart()->plotArea().top()); + int plot_right = mapToGlobal(chart()->plotArea().topRight().toPoint()).x(); + tip_label.showText(mapToGlobal(tooltip_pt.toPoint()), "

" + text_list.join("
") + "

", plot_right); + viewport()->update(); +} + +void ChartView::hideTip() { + clearTrackPoints(); + tooltip_x = -1; + tip_label.hide(); + viewport()->update(); +} + +void ChartView::dragEnterEvent(QDragEnterEvent *event) { + if (event->mimeData()->hasFormat(CHART_MIME_TYPE)) { + drawDropIndicator(event->source() != this); + event->acceptProposedAction(); + } +} + +void ChartView::dragMoveEvent(QDragMoveEvent *event) { + if (event->mimeData()->hasFormat(CHART_MIME_TYPE)) { + event->setDropAction(event->source() == this ? Qt::MoveAction : Qt::CopyAction); + event->accept(); + } + charts_widget->startAutoScroll(); +} + +void ChartView::dropEvent(QDropEvent *event) { + if (event->mimeData()->hasFormat(CHART_MIME_TYPE)) { + if (event->source() != this) { + ChartView *source_chart = (ChartView *)event->source(); + for (auto &s : source_chart->sigs) { + source_chart->chart()->removeSeries(s.series); + addSeries(s.series); + } + sigs.append(source_chart->sigs); + updateAxisY(); + updateTitle(); + startAnimation(); + + source_chart->sigs.clear(); + charts_widget->removeChart(source_chart); + event->acceptProposedAction(); + } + can_drop = false; + } +} + +void ChartView::resetChartCache() { + chart_pixmap = QPixmap(); + viewport()->update(); +} + +void ChartView::startAnimation() { + QGraphicsOpacityEffect *eff = new QGraphicsOpacityEffect(this); + viewport()->setGraphicsEffect(eff); + QPropertyAnimation *a = new QPropertyAnimation(eff, "opacity"); + a->setDuration(250); + a->setStartValue(0.3); + a->setEndValue(1); + a->setEasingCurve(QEasingCurve::InBack); + a->start(QPropertyAnimation::DeleteWhenStopped); +} + +void ChartView::paintEvent(QPaintEvent *event) { + if (!can->liveStreaming()) { + if (chart_pixmap.isNull()) { + const qreal dpr = viewport()->devicePixelRatioF(); + chart_pixmap = QPixmap(viewport()->size() * dpr); + chart_pixmap.setDevicePixelRatio(dpr); + QPainter p(&chart_pixmap); + p.setRenderHints(QPainter::Antialiasing); + drawBackground(&p, viewport()->rect()); + scene()->setSceneRect(viewport()->rect()); + scene()->render(&p); + } + + QPainter painter(viewport()); + painter.setRenderHints(QPainter::Antialiasing); + painter.drawPixmap(QPoint(), chart_pixmap); + if (can_drop) { + painter.setPen(QPen(palette().color(QPalette::Highlight), 4)); + painter.drawRect(viewport()->rect()); + } + QRectF exposed_rect = mapToScene(event->region().boundingRect()).boundingRect(); + drawForeground(&painter, exposed_rect); + } else { + QChartView::paintEvent(event); + } +} + +void ChartView::drawBackground(QPainter *painter, const QRectF &rect) { + painter->fillRect(rect, palette().color(QPalette::Base)); +} + +void ChartView::drawForeground(QPainter *painter, const QRectF &rect) { + // draw time line + qreal x = chart()->mapToPosition(QPointF{cur_sec, 0}).x(); + x = std::clamp(x, chart()->plotArea().left(), chart()->plotArea().right()); + qreal y1 = chart()->plotArea().top() - 2; + qreal y2 = chart()->plotArea().bottom() + 2; + painter->setPen(QPen(chart()->titleBrush().color(), 2)); + painter->drawLine(QPointF{x, y1}, QPointF{x, y2}); + + // draw track points + painter->setPen(Qt::NoPen); + qreal track_line_x = -1; + for (auto &s : sigs) { + if (!s.track_pt.isNull() && s.series->isVisible()) { + painter->setBrush(s.series->color().darker(125)); + QPointF pos = chart()->mapToPosition(s.track_pt); + painter->drawEllipse(pos, 5.5, 5.5); + track_line_x = std::max(track_line_x, pos.x()); + } + } + if (track_line_x > 0) { + painter->setPen(QPen(Qt::darkGray, 1, Qt::DashLine)); + painter->drawLine(QPointF{track_line_x, y1}, QPointF{track_line_x, y2}); + } + + // paint points. OpenGL mode lacks certain features (such as showing points) + painter->setPen(Qt::NoPen); + for (auto &s : sigs) { + if (s.series->useOpenGL() && s.series->isVisible() && s.series->pointsVisible()) { + auto first = std::lower_bound(s.vals.begin(), s.vals.end(), axis_x->min(), xLessThan); + auto last = std::lower_bound(first, s.vals.end(), axis_x->max(), xLessThan); + painter->setBrush(s.series->color()); + for (auto it = first; it != last; ++it) { + painter->drawEllipse(chart()->mapToPosition(*it), 4, 4); + } + } + } + + // paint zoom range + auto rubber = findChild(); + if (rubber && rubber->isVisible() && rubber->width() > 1) { + painter->setPen(Qt::white); + auto rubber_rect = rubber->geometry().normalized(); + for (const auto &pt : {rubber_rect.bottomLeft(), rubber_rect.bottomRight()}) { + QString sec = QString::number(chart()->mapToValue(pt).x(), 'f', 1); + // ChartAxisElement's padding is 4 (https://codebrowser.dev/qt5/qtcharts/src/charts/axis/chartaxiselement_p.h.html) + auto r = painter->fontMetrics().boundingRect(sec).adjusted(-6, -4, 6, 4); + pt == rubber_rect.bottomLeft() ? r.moveTopRight(pt + QPoint{0, 2}) : r.moveTopLeft(pt + QPoint{0, 2}); + painter->fillRect(r, Qt::gray); + painter->drawText(r, Qt::AlignCenter, sec); + } + } +} + +QXYSeries *ChartView::createSeries(SeriesType type, QColor color) { + QXYSeries *series = nullptr; + if (type == SeriesType::Line) { + series = new QLineSeries(this); + chart()->legend()->setMarkerShape(QLegend::MarkerShapeRectangle); + } else if (type == SeriesType::StepLine) { + series = new QLineSeries(this); + chart()->legend()->setMarkerShape(QLegend::MarkerShapeFromSeries); + } else { + series = new QScatterSeries(this); + chart()->legend()->setMarkerShape(QLegend::MarkerShapeCircle); + } + series->setColor(color); + // TODO: Due to a bug in CameraWidget the camera frames + // are drawn instead of the graphs on MacOS. Re-enable OpenGL when fixed +#ifndef __APPLE__ + series->setUseOpenGL(true); + // Qt doesn't properly apply device pixel ratio in OpenGL mode + QPen pen = series->pen(); + pen.setWidthF(2.0 * devicePixelRatioF()); + series->setPen(pen); +#endif + addSeries(series); + return series; +} + +void ChartView::addSeries(QXYSeries *series) { + chart()->addSeries(series); + series->attachAxis(axis_x); + series->attachAxis(axis_y); + + // disables the delivery of mouse events to the opengl widget. + // this enables the user to select the zoom area when the mouse press on the data point. + auto glwidget = findChild(); + if (glwidget && !glwidget->testAttribute(Qt::WA_TransparentForMouseEvents)) { + glwidget->setAttribute(Qt::WA_TransparentForMouseEvents); + } +} + +void ChartView::setSeriesType(SeriesType type) { + if (type != series_type) { + series_type = type; + for (auto &s : sigs) { + chart()->removeSeries(s.series); + s.series->deleteLater(); + } + for (auto &s : sigs) { + auto series = createSeries(series_type, getColor(s.sig)); + series->replace(series_type == SeriesType::StepLine ? s.step_vals : s.vals); + s.series = series; + } + updateSeriesPoints(); + updateTitle(); + } +} + +void ChartView::handleMarkerClicked() { + auto marker = qobject_cast(sender()); + Q_ASSERT(marker); + if (sigs.size() > 1) { + auto series = marker->series(); + series->setVisible(!series->isVisible()); + marker->setVisible(true); + updateAxisY(); + updateTitle(); + } +} diff --git a/tools/cabana/chart/chart.h b/tools/cabana/chart/chart.h new file mode 100644 index 0000000000..fda9271560 --- /dev/null +++ b/tools/cabana/chart/chart.h @@ -0,0 +1,109 @@ +#pragma once + +#include +#include +#include +#include +#include +#include +#include +using namespace QtCharts; + +#include "tools/cabana/chart/tiplabel.h" +#include "tools/cabana/dbc/dbcmanager.h" +#include "tools/cabana/streams/abstractstream.h" + +enum class SeriesType { + Line = 0, + StepLine, + Scatter +}; + +class ChartsWidget; +class ChartView : public QChartView { + Q_OBJECT + +public: + ChartView(const std::pair &x_range, ChartsWidget *parent = nullptr); + void addSignal(const MessageId &msg_id, const cabana::Signal *sig); + bool hasSignal(const MessageId &msg_id, const cabana::Signal *sig) const; + void updateSeries(const cabana::Signal *sig = nullptr); + void updatePlot(double cur, double min, double max); + void setSeriesType(SeriesType type); + void updatePlotArea(int left, bool force = false); + void showTip(double sec); + void hideTip(); + void startAnimation(); + + struct SigItem { + MessageId msg_id; + const cabana::Signal *sig = nullptr; + QXYSeries *series = nullptr; + QVector vals; + QVector step_vals; + uint64_t last_value_mono_time = 0; + QPointF track_pt{}; + SegmentTree segment_tree; + double min = 0; + double max = 0; + }; + +signals: + void axisYLabelWidthChanged(int w); + +private slots: + void signalUpdated(const cabana::Signal *sig); + void manageSignals(); + void handleMarkerClicked(); + void msgUpdated(MessageId id); + void msgRemoved(MessageId id) { removeIf([=](auto &s) { return s.msg_id == id; }); } + void signalRemoved(const cabana::Signal *sig) { removeIf([=](auto &s) { return s.sig == sig; }); } + +private: + void createToolButtons(); + void addSeries(QXYSeries *series); + void mousePressEvent(QMouseEvent *event) override; + void mouseReleaseEvent(QMouseEvent *event) override; + void mouseMoveEvent(QMouseEvent *ev) override; + void dragEnterEvent(QDragEnterEvent *event) override; + void dragLeaveEvent(QDragLeaveEvent *event) override { drawDropIndicator(false); } + void dragMoveEvent(QDragMoveEvent *event) override; + void dropEvent(QDropEvent *event) override; + void leaveEvent(QEvent *event) override; + void resizeEvent(QResizeEvent *event) override; + QSize sizeHint() const override; + void updateAxisY(); + void updateTitle(); + void resetChartCache(); + void setTheme(QChart::ChartTheme theme); + void paintEvent(QPaintEvent *event) override; + void drawForeground(QPainter *painter, const QRectF &rect) override; + void drawBackground(QPainter *painter, const QRectF &rect) override; + void drawDropIndicator(bool draw) { if (std::exchange(can_drop, draw) != can_drop) viewport()->update(); } + std::tuple getNiceAxisNumbers(qreal min, qreal max, int tick_count); + qreal niceNumber(qreal x, bool ceiling); + QXYSeries *createSeries(SeriesType type, QColor color); + void updateSeriesPoints(); + void removeIf(std::function predicate); + inline void clearTrackPoints() { for (auto &s : sigs) s.track_pt = {}; } + + int y_label_width = 0; + int align_to = 0; + QValueAxis *axis_x; + QValueAxis *axis_y; + QAction *split_chart_act; + QGraphicsPixmapItem *move_icon; + QGraphicsProxyWidget *close_btn_proxy; + QGraphicsProxyWidget *manage_btn_proxy; + TipLabel tip_label; + QList sigs; + double cur_sec = 0; + SeriesType series_type = SeriesType::Line; + bool is_scrubbing = false; + bool resume_after_scrub = false; + QPixmap chart_pixmap; + bool can_drop = false; + double tooltip_x = -1; + ChartsWidget *charts_widget; + friend class ChartsWidget; +}; diff --git a/tools/cabana/chart/chartswidget.cc b/tools/cabana/chart/chartswidget.cc new file mode 100644 index 0000000000..2700f6519e --- /dev/null +++ b/tools/cabana/chart/chartswidget.cc @@ -0,0 +1,514 @@ +#include "tools/cabana/chart/chartswidget.h" + +#include +#include +#include +#include +#include +#include + +#include "tools/cabana/chart/chart.h" + +const int MAX_COLUMN_COUNT = 4; +const int CHART_SPACING = 10; + +ChartsWidget::ChartsWidget(QWidget *parent) : align_timer(this), auto_scroll_timer(this), QFrame(parent) { + setFrameStyle(QFrame::StyledPanel | QFrame::Plain); + QVBoxLayout *main_layout = new QVBoxLayout(this); + main_layout->setContentsMargins(0, 0, 0, 0); + main_layout->setSpacing(0); + + // toolbar + QToolBar *toolbar = new QToolBar(tr("Charts"), this); + int icon_size = style()->pixelMetric(QStyle::PM_SmallIconSize); + toolbar->setIconSize({icon_size, icon_size}); + + auto new_plot_btn = new ToolButton("file-plus", tr("New Chart")); + auto new_tab_btn = new ToolButton("window-stack", tr("New Tab")); + toolbar->addWidget(new_plot_btn); + toolbar->addWidget(new_tab_btn); + toolbar->addWidget(title_label = new QLabel()); + title_label->setContentsMargins(0, 0, style()->pixelMetric(QStyle::PM_LayoutHorizontalSpacing), 0); + + QMenu *menu = new QMenu(this); + for (int i = 0; i < MAX_COLUMN_COUNT; ++i) { + menu->addAction(tr("%1").arg(i + 1), [=]() { setColumnCount(i + 1); }); + } + columns_action = toolbar->addAction(""); + columns_action->setMenu(menu); + qobject_cast(toolbar->widgetForAction(columns_action))->setPopupMode(QToolButton::InstantPopup); + + QLabel *stretch_label = new QLabel(this); + stretch_label->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Preferred); + toolbar->addWidget(stretch_label); + + range_lb_action = toolbar->addWidget(range_lb = new QLabel(this)); + range_slider = new LogSlider(1000, Qt::Horizontal, this); + range_slider->setMaximumWidth(200); + range_slider->setToolTip(tr("Set the chart range")); + range_slider->setRange(1, settings.max_cached_minutes * 60); + range_slider->setSingleStep(1); + range_slider->setPageStep(60); // 1 min + range_slider_action = toolbar->addWidget(range_slider); + + // zoom controls + zoom_undo_stack = new QUndoStack(this); + toolbar->addAction(undo_zoom_action = zoom_undo_stack->createUndoAction(this)); + undo_zoom_action->setIcon(utils::icon("arrow-counterclockwise")); + toolbar->addAction(redo_zoom_action = zoom_undo_stack->createRedoAction(this)); + redo_zoom_action->setIcon(utils::icon("arrow-clockwise")); + reset_zoom_action = toolbar->addWidget(reset_zoom_btn = new ToolButton("zoom-out", tr("Reset Zoom"))); + reset_zoom_btn->setToolButtonStyle(Qt::ToolButtonTextBesideIcon); + + toolbar->addWidget(remove_all_btn = new ToolButton("x", tr("Remove all charts"))); + toolbar->addWidget(dock_btn = new ToolButton("")); + main_layout->addWidget(toolbar); + + // tabbar + tabbar = new QTabBar(this); + tabbar->setAutoHide(true); + tabbar->setExpanding(false); + tabbar->setDrawBase(true); + tabbar->setAcceptDrops(true); + tabbar->setChangeCurrentOnDrag(true); + tabbar->setTabsClosable(true); + tabbar->setUsesScrollButtons(true); + main_layout->addWidget(tabbar); + + // charts + charts_container = new ChartsContainer(this); + + charts_scroll = new QScrollArea(this); + charts_scroll->setFrameStyle(QFrame::NoFrame); + charts_scroll->setWidgetResizable(true); + charts_scroll->setWidget(charts_container); + charts_scroll->setHorizontalScrollBarPolicy(Qt::ScrollBarAlwaysOff); + main_layout->addWidget(charts_scroll); + + // init settings + current_theme = settings.theme; + column_count = std::clamp(settings.chart_column_count, 1, MAX_COLUMN_COUNT); + max_chart_range = std::clamp(settings.chart_range, 1, settings.max_cached_minutes * 60); + display_range = {0, max_chart_range}; + range_slider->setValue(max_chart_range); + updateToolBar(); + + align_timer.setSingleShot(true); + QObject::connect(&align_timer, &QTimer::timeout, this, &ChartsWidget::alignCharts); + QObject::connect(&auto_scroll_timer, &QTimer::timeout, this, &ChartsWidget::doAutoScroll); + QObject::connect(dbc(), &DBCManager::DBCFileChanged, this, &ChartsWidget::removeAll); + QObject::connect(can, &AbstractStream::eventsMerged, this, &ChartsWidget::eventsMerged); + QObject::connect(can, &AbstractStream::updated, this, &ChartsWidget::updateState); + QObject::connect(range_slider, &QSlider::valueChanged, this, &ChartsWidget::setMaxChartRange); + QObject::connect(new_plot_btn, &QToolButton::clicked, this, &ChartsWidget::newChart); + QObject::connect(remove_all_btn, &QToolButton::clicked, this, &ChartsWidget::removeAll); + QObject::connect(reset_zoom_btn, &QToolButton::clicked, this, &ChartsWidget::zoomReset); + QObject::connect(&settings, &Settings::changed, this, &ChartsWidget::settingChanged); + QObject::connect(new_tab_btn, &QToolButton::clicked, this, &ChartsWidget::newTab); + QObject::connect(tabbar, &QTabBar::tabCloseRequested, this, &ChartsWidget::removeTab); + QObject::connect(tabbar, &QTabBar::currentChanged, [this](int index) { + if (index != -1) updateLayout(true); + }); + QObject::connect(dock_btn, &QToolButton::clicked, [this]() { + emit dock(!docking); + docking = !docking; + updateToolBar(); + }); + + newTab(); + setWhatsThis(tr(R"( + Chart view
+ + )")); +} + +void ChartsWidget::newTab() { + static int tab_unique_id = 0; + int idx = tabbar->addTab(""); + tabbar->setTabData(idx, tab_unique_id++); + for (int i = 0; i < tabbar->count(); ++i) { + tabbar->setTabText(i, QString("Tab %1").arg(i + 1)); + } + tabbar->setCurrentIndex(idx); +} + +void ChartsWidget::removeTab(int index) { + int id = tabbar->tabData(index).toInt(); + for (auto &c : tab_charts[id]) { + removeChart(c); + } + tab_charts.erase(id); + tabbar->removeTab(index); +} + +void ChartsWidget::eventsMerged() { + QFutureSynchronizer future_synchronizer; + for (auto c : charts) { + future_synchronizer.addFuture(QtConcurrent::run(c, &ChartView::updateSeries, nullptr)); + } +} + +void ChartsWidget::setZoom(double min, double max) { + zoomed_range = {min, max}; + is_zoomed = zoomed_range != display_range; + updateToolBar(); + updateState(); + emit rangeChanged(min, max, is_zoomed); +} + +void ChartsWidget::zoomReset() { + setZoom(display_range.first, display_range.second); + zoom_undo_stack->clear(); +} + +void ChartsWidget::showValueTip(double sec) { + const QRect visible_rect(-charts_container->pos(), charts_scroll->viewport()->size()); + for (auto c : currentCharts()) { + if (sec >= 0 && visible_rect.contains(QRect(c->mapTo(charts_container, QPoint(0, 0)), c->size()))) { + c->showTip(sec); + } else { + c->hideTip(); + } + } +} + +void ChartsWidget::updateState() { + if (charts.isEmpty()) return; + + const double cur_sec = can->currentSec(); + if (!is_zoomed) { + double pos = (cur_sec - display_range.first) / std::max(1.0, max_chart_range); + if (pos < 0 || pos > 0.8) { + display_range.first = std::max(0.0, cur_sec - max_chart_range * 0.1); + } + double max_sec = std::min(std::floor(display_range.first + max_chart_range), can->lastEventSecond()); + display_range.first = std::max(0.0, max_sec - max_chart_range); + display_range.second = display_range.first + max_chart_range; + } else if (cur_sec < zoomed_range.first || cur_sec >= zoomed_range.second) { + // loop in zoomed range + can->seekTo(zoomed_range.first); + } + + const auto &range = is_zoomed ? zoomed_range : display_range; + for (auto c : charts) { + c->updatePlot(cur_sec, range.first, range.second); + } +} + +void ChartsWidget::setMaxChartRange(int value) { + max_chart_range = settings.chart_range = range_slider->value(); + updateToolBar(); + updateState(); +} + +void ChartsWidget::updateToolBar() { + title_label->setText(tr("Charts: %1").arg(charts.size())); + columns_action->setText(tr("Column: %1").arg(column_count)); + range_lb->setText(utils::formatSeconds(max_chart_range)); + range_lb_action->setVisible(!is_zoomed); + range_slider_action->setVisible(!is_zoomed); + undo_zoom_action->setVisible(is_zoomed); + redo_zoom_action->setVisible(is_zoomed); + reset_zoom_action->setVisible(is_zoomed); + reset_zoom_btn->setText(is_zoomed ? tr("%1-%2").arg(zoomed_range.first, 0, 'f', 1).arg(zoomed_range.second, 0, 'f', 1) : ""); + remove_all_btn->setEnabled(!charts.isEmpty()); + dock_btn->setIcon(docking ? "arrow-up-right-square" : "arrow-down-left-square"); + dock_btn->setToolTip(docking ? tr("Undock charts") : tr("Dock charts")); +} + +void ChartsWidget::settingChanged() { + if (std::exchange(current_theme, settings.theme) != current_theme) { + undo_zoom_action->setIcon(utils::icon("arrow-counterclockwise")); + redo_zoom_action->setIcon(utils::icon("arrow-clockwise")); + auto theme = settings.theme == DARK_THEME ? QChart::QChart::ChartThemeDark : QChart::ChartThemeLight; + for (auto c : charts) { + c->setTheme(theme); + } + } + range_slider->setRange(1, settings.max_cached_minutes * 60); + for (auto c : charts) { + c->setFixedHeight(settings.chart_height); + c->setSeriesType((SeriesType)settings.chart_series_type); + c->resetChartCache(); + } +} + +ChartView *ChartsWidget::findChart(const MessageId &id, const cabana::Signal *sig) { + for (auto c : charts) + if (c->hasSignal(id, sig)) return c; + return nullptr; +} + +ChartView *ChartsWidget::createChart() { + auto chart = new ChartView(is_zoomed ? zoomed_range : display_range, this); + chart->setFixedHeight(settings.chart_height); + chart->setMinimumWidth(CHART_MIN_WIDTH); + chart->setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::Fixed); + QObject::connect(chart, &ChartView::axisYLabelWidthChanged, &align_timer, qOverload<>(&QTimer::start)); + charts.push_front(chart); + currentCharts().push_front(chart); + updateLayout(true); + updateToolBar(); + return chart; +} + +void ChartsWidget::showChart(const MessageId &id, const cabana::Signal *sig, bool show, bool merge) { + ChartView *chart = findChart(id, sig); + if (show && !chart) { + chart = merge && currentCharts().size() > 0 ? currentCharts().front() : createChart(); + chart->addSignal(id, sig); + } else if (!show && chart) { + chart->removeIf([&](auto &s) { return s.msg_id == id && s.sig == sig; }); + } +} + +void ChartsWidget::splitChart(ChartView *src_chart) { + if (src_chart->sigs.size() > 1) { + for (auto it = src_chart->sigs.begin() + 1; it != src_chart->sigs.end(); /**/) { + auto c = createChart(); + src_chart->chart()->removeSeries(it->series); + c->addSeries(it->series); + c->sigs.push_back(*it); + c->updateAxisY(); + c->updateTitle(); + it = src_chart->sigs.erase(it); + } + src_chart->updateAxisY(); + src_chart->updateTitle(); + } +} + +void ChartsWidget::setColumnCount(int n) { + n = std::clamp(n, 1, MAX_COLUMN_COUNT); + if (column_count != n) { + column_count = settings.chart_column_count = n; + updateToolBar(); + updateLayout(); + } +} + +void ChartsWidget::updateLayout(bool force) { + auto charts_layout = charts_container->charts_layout; + int n = MAX_COLUMN_COUNT; + for (; n > 1; --n) { + if ((n * CHART_MIN_WIDTH + (n - 1) * charts_layout->spacing()) < charts_layout->geometry().width()) break; + } + + bool show_column_cb = n > 1; + columns_action->setVisible(show_column_cb); + + n = std::min(column_count, n); + auto ¤t_charts = currentCharts(); + if ((current_charts.size() != charts_layout->count() || n != current_column_count) || force) { + current_column_count = n; + charts_container->setUpdatesEnabled(false); + for (auto c : charts) { + c->setVisible(false); + } + for (int i = 0; i < current_charts.size(); ++i) { + charts_layout->addWidget(current_charts[i], i / n, i % n); + current_charts[i]->setVisible(true); + } + charts_container->setUpdatesEnabled(true); + } +} + +void ChartsWidget::startAutoScroll() { + auto_scroll_timer.start(50); +} + +void ChartsWidget::stopAutoScroll() { + auto_scroll_timer.stop(); + auto_scroll_count = 0; +} + +void ChartsWidget::doAutoScroll() { + QScrollBar *scroll = charts_scroll->verticalScrollBar(); + if (auto_scroll_count < scroll->pageStep()) { + ++auto_scroll_count; + } + + int value = scroll->value(); + QPoint pos = charts_scroll->viewport()->mapFromGlobal(QCursor::pos()); + QRect area = charts_scroll->viewport()->rect(); + + if (pos.y() - area.top() < settings.chart_height / 2) { + scroll->setValue(value - auto_scroll_count); + } else if (area.bottom() - pos.y() < settings.chart_height / 2) { + scroll->setValue(value + auto_scroll_count); + } + bool vertical_unchanged = value == scroll->value(); + if (vertical_unchanged) { + stopAutoScroll(); + } else { + // mouseMoveEvent to updates the drag-selection rectangle + const QPoint globalPos = charts_scroll->viewport()->mapToGlobal(pos); + const QPoint windowPos = charts_scroll->window()->mapFromGlobal(globalPos); + QMouseEvent mm(QEvent::MouseMove, pos, windowPos, globalPos, + Qt::NoButton, Qt::LeftButton, Qt::NoModifier, Qt::MouseEventSynthesizedByQt); + QApplication::sendEvent(charts_scroll->viewport(), &mm); + } +} + +void ChartsWidget::resizeEvent(QResizeEvent *event) { + QWidget::resizeEvent(event); + updateLayout(); +} + +void ChartsWidget::newChart() { + SignalSelector dlg(tr("New Chart"), this); + if (dlg.exec() == QDialog::Accepted) { + auto items = dlg.seletedItems(); + if (!items.isEmpty()) { + auto c = createChart(); + for (auto it : items) { + c->addSignal(it->msg_id, it->sig); + } + } + } +} + +void ChartsWidget::removeChart(ChartView *chart) { + charts.removeOne(chart); + chart->deleteLater(); + for (auto &[_, list] : tab_charts) { + list.removeOne(chart); + } + updateToolBar(); + updateLayout(true); + alignCharts(); + emit seriesChanged(); +} + +void ChartsWidget::removeAll() { + if (!charts.isEmpty()) { + for (auto c : charts) { + c->deleteLater(); + } + charts.clear(); + tab_charts.clear(); + updateToolBar(); + emit seriesChanged(); + } + while (tabbar->count() > 1) { + tabbar->removeTab(1); + } +} + +void ChartsWidget::alignCharts() { + int plot_left = 0; + for (auto c : charts) { + plot_left = std::max(plot_left, c->y_label_width); + } + plot_left = std::max((plot_left / 10) * 10 + 10, 50); + for (auto c : charts) { + c->updatePlotArea(plot_left); + } +} + +bool ChartsWidget::eventFilter(QObject *obj, QEvent *event) { + if (obj != this && event->type() == QEvent::Close) { + emit dock_btn->clicked(); + return true; + } + return false; +} + +bool ChartsWidget::event(QEvent *event) { + bool back_button = false; + switch (event->type()) { + case QEvent::MouseButtonPress: { + QMouseEvent *ev = static_cast(event); + back_button = ev->button() == Qt::BackButton; + break; + } + case QEvent::NativeGesture: { + QNativeGestureEvent *ev = static_cast(event); + back_button = (ev->value() == 180); + break; + } + case QEvent::WindowActivate: + case QEvent::WindowDeactivate: + case QEvent::FocusIn: + case QEvent::FocusOut: + case QEvent::Leave: + showValueTip(-1); + break; + default: + break; + } + + if (back_button) { + zoom_undo_stack->undo(); + return true; + } + return QFrame::event(event); +} + +// ChartsContainer + +ChartsContainer::ChartsContainer(ChartsWidget *parent) : charts_widget(parent), QWidget(parent) { + setAcceptDrops(true); + QVBoxLayout *charts_main_layout = new QVBoxLayout(this); + charts_main_layout->setContentsMargins(0, 10, 0, 0); + charts_layout = new QGridLayout(); + charts_layout->setSpacing(CHART_SPACING); + charts_main_layout->addLayout(charts_layout); + charts_main_layout->addStretch(0); +} + +void ChartsContainer::dragEnterEvent(QDragEnterEvent *event) { + if (event->mimeData()->hasFormat(CHART_MIME_TYPE)) { + event->acceptProposedAction(); + drawDropIndicator(event->pos()); + } +} + +void ChartsContainer::dropEvent(QDropEvent *event) { + if (event->mimeData()->hasFormat(CHART_MIME_TYPE)) { + auto w = getDropAfter(event->pos()); + auto chart = qobject_cast(event->source()); + if (w != chart) { + for (auto &[_, list] : charts_widget->tab_charts) { + list.removeOne(chart); + } + int to = w ? charts_widget->currentCharts().indexOf(w) + 1 : 0; + charts_widget->currentCharts().insert(to, chart); + charts_widget->updateLayout(true); + event->acceptProposedAction(); + chart->startAnimation(); + } + drawDropIndicator({}); + } +} + +void ChartsContainer::paintEvent(QPaintEvent *ev) { + if (!drop_indictor_pos.isNull() && !childAt(drop_indictor_pos)) { + QRect r; + if (auto insert_after = getDropAfter(drop_indictor_pos)) { + QRect area = insert_after->geometry(); + r = QRect(area.left(), area.bottom() + 1, area.width(), CHART_SPACING); + } else { + r = geometry(); + r.setHeight(CHART_SPACING); + } + + const int margin = (CHART_SPACING - 2) / 2; + QPainterPath path; + path.addPolygon(QPolygonF({r.topLeft(), QPointF(r.left() + CHART_SPACING, r.top() + r.height() / 2), r.bottomLeft()})); + path.addPolygon(QPolygonF({r.topRight(), QPointF(r.right() - CHART_SPACING, r.top() + r.height() / 2), r.bottomRight()})); + + QPainter p(this); + p.setRenderHint(QPainter::Antialiasing); + p.fillPath(path, palette().highlight()); + p.fillRect(r.adjusted(2, margin, -2, -margin), palette().highlight()); + } +} + +ChartView *ChartsContainer::getDropAfter(const QPoint &pos) const { + auto it = std::find_if(charts_widget->currentCharts().crbegin(), charts_widget->currentCharts().crend(), [&pos](auto c) { + auto area = c->geometry(); + return pos.x() >= area.left() && pos.x() <= area.right() && pos.y() >= area.bottom(); + }); + return it == charts_widget->currentCharts().crend() ? nullptr : *it; +} diff --git a/tools/cabana/chart/chartswidget.h b/tools/cabana/chart/chartswidget.h new file mode 100644 index 0000000000..5fe227b156 --- /dev/null +++ b/tools/cabana/chart/chartswidget.h @@ -0,0 +1,126 @@ +#pragma once + +#include +#include +#include +#include +#include +#include +#include + +#include "tools/cabana/chart/signalselector.h" +#include "tools/cabana/dbc/dbcmanager.h" +#include "tools/cabana/streams/abstractstream.h" + +const int CHART_MIN_WIDTH = 300; +const QString CHART_MIME_TYPE = "application/x-cabanachartview"; + +class ChartView; +class ChartsWidget; + +class ChartsContainer : public QWidget { +public: + ChartsContainer(ChartsWidget *parent); + void dragEnterEvent(QDragEnterEvent *event) override; + void dropEvent(QDropEvent *event) override; + void dragLeaveEvent(QDragLeaveEvent *event) override { drawDropIndicator({}); } + void drawDropIndicator(const QPoint &pt) { drop_indictor_pos = pt; update(); } + void paintEvent(QPaintEvent *ev) override; + ChartView *getDropAfter(const QPoint &pos) const; + + QGridLayout *charts_layout; + ChartsWidget *charts_widget; + QPoint drop_indictor_pos; +}; + +class ChartsWidget : public QFrame { + Q_OBJECT + +public: + ChartsWidget(QWidget *parent = nullptr); + void showChart(const MessageId &id, const cabana::Signal *sig, bool show, bool merge); + inline bool hasSignal(const MessageId &id, const cabana::Signal *sig) { return findChart(id, sig) != nullptr; } + +public slots: + void setColumnCount(int n); + void removeAll(); + void setZoom(double min, double max); + +signals: + void dock(bool floating); + void rangeChanged(double min, double max, bool is_zommed); + void seriesChanged(); + +private: + void resizeEvent(QResizeEvent *event) override; + bool event(QEvent *event) override; + void alignCharts(); + void newChart(); + ChartView *createChart(); + void removeChart(ChartView *chart); + void splitChart(ChartView *chart); + void eventsMerged(); + void updateState(); + void zoomReset(); + void startAutoScroll(); + void stopAutoScroll(); + void doAutoScroll(); + void updateToolBar(); + void setMaxChartRange(int value); + void updateLayout(bool force = false); + void settingChanged(); + void showValueTip(double sec); + bool eventFilter(QObject *obj, QEvent *event) override; + void newTab(); + void removeTab(int index); + inline QList ¤tCharts() { return tab_charts[tabbar->tabData(tabbar->currentIndex()).toInt()]; } + ChartView *findChart(const MessageId &id, const cabana::Signal *sig); + + QLabel *title_label; + QLabel *range_lb; + LogSlider *range_slider; + QAction *range_lb_action; + QAction *range_slider_action; + bool docking = true; + ToolButton *dock_btn; + + QAction *undo_zoom_action; + QAction *redo_zoom_action; + QAction *reset_zoom_action; + ToolButton *reset_zoom_btn; + QUndoStack *zoom_undo_stack; + + ToolButton *remove_all_btn; + QList charts; + std::unordered_map> tab_charts; + QTabBar *tabbar; + ChartsContainer *charts_container; + QScrollArea *charts_scroll; + uint32_t max_chart_range = 0; + bool is_zoomed = false; + std::pair display_range; + std::pair zoomed_range; + QAction *columns_action; + int column_count = 1; + int current_column_count = 0; + int auto_scroll_count = 0; + QTimer auto_scroll_timer; + QTimer align_timer; + int current_theme = 0; + friend class ZoomCommand; + friend class ChartView; + friend class ChartsContainer; +}; + +class ZoomCommand : public QUndoCommand { +public: + ZoomCommand(ChartsWidget *charts, std::pair range) : charts(charts), range(range), QUndoCommand() { + prev_range = charts->is_zoomed ? charts->zoomed_range : charts->display_range; + setText(QObject::tr("Zoom to %1-%2").arg(range.first, 0, 'f', 1).arg(range.second, 0, 'f', 1)); + } + void undo() override { charts->setZoom(prev_range.first, prev_range.second); } + void redo() override { charts->setZoom(range.first, range.second); } + ChartsWidget *charts; + std::pair prev_range, range; +}; + diff --git a/tools/cabana/chart/signalselector.cc b/tools/cabana/chart/signalselector.cc new file mode 100644 index 0000000000..1aa8fc5016 --- /dev/null +++ b/tools/cabana/chart/signalselector.cc @@ -0,0 +1,108 @@ +#include "tools/cabana/chart/signalselector.h" + +#include +#include +#include +#include +#include +#include +#include + +#include "tools/cabana/streams/abstractstream.h" + +SignalSelector::SignalSelector(QString title, QWidget *parent) : QDialog(parent) { + setWindowTitle(title); + QGridLayout *main_layout = new QGridLayout(this); + + // left column + main_layout->addWidget(new QLabel(tr("Available Signals")), 0, 0); + main_layout->addWidget(msgs_combo = new QComboBox(this), 1, 0); + msgs_combo->setEditable(true); + msgs_combo->lineEdit()->setPlaceholderText(tr("Select a msg...")); + msgs_combo->setInsertPolicy(QComboBox::NoInsert); + msgs_combo->completer()->setCompletionMode(QCompleter::PopupCompletion); + msgs_combo->completer()->setFilterMode(Qt::MatchContains); + + main_layout->addWidget(available_list = new QListWidget(this), 2, 0); + + // buttons + QVBoxLayout *btn_layout = new QVBoxLayout(); + QPushButton *add_btn = new QPushButton(utils::icon("chevron-right"), "", this); + add_btn->setEnabled(false); + QPushButton *remove_btn = new QPushButton(utils::icon("chevron-left"), "", this); + remove_btn->setEnabled(false); + btn_layout->addStretch(0); + btn_layout->addWidget(add_btn); + btn_layout->addWidget(remove_btn); + btn_layout->addStretch(0); + main_layout->addLayout(btn_layout, 0, 1, 3, 1); + + // right column + main_layout->addWidget(new QLabel(tr("Selected Signals")), 0, 2); + main_layout->addWidget(selected_list = new QListWidget(this), 1, 2, 2, 1); + + auto buttonBox = new QDialogButtonBox(QDialogButtonBox::Ok | QDialogButtonBox::Cancel); + main_layout->addWidget(buttonBox, 3, 2); + + for (auto it = can->last_msgs.cbegin(); it != can->last_msgs.cend(); ++it) { + if (auto m = dbc()->msg(it.key())) { + msgs_combo->addItem(QString("%1 (%2)").arg(m->name).arg(it.key().toString()), QVariant::fromValue(it.key())); + } + } + msgs_combo->model()->sort(0); + msgs_combo->setCurrentIndex(-1); + + QObject::connect(msgs_combo, qOverload(&QComboBox::currentIndexChanged), this, &SignalSelector::updateAvailableList); + QObject::connect(available_list, &QListWidget::currentRowChanged, [=](int row) { add_btn->setEnabled(row != -1); }); + QObject::connect(selected_list, &QListWidget::currentRowChanged, [=](int row) { remove_btn->setEnabled(row != -1); }); + QObject::connect(available_list, &QListWidget::itemDoubleClicked, this, &SignalSelector::add); + QObject::connect(selected_list, &QListWidget::itemDoubleClicked, this, &SignalSelector::remove); + QObject::connect(add_btn, &QPushButton::clicked, [this]() { if (auto item = available_list->currentItem()) add(item); }); + QObject::connect(remove_btn, &QPushButton::clicked, [this]() { if (auto item = selected_list->currentItem()) remove(item); }); + QObject::connect(buttonBox, &QDialogButtonBox::accepted, this, &QDialog::accept); + QObject::connect(buttonBox, &QDialogButtonBox::rejected, this, &QDialog::reject); +} + +void SignalSelector::add(QListWidgetItem *item) { + auto it = (ListItem *)item; + addItemToList(selected_list, it->msg_id, it->sig, true); + delete item; +} + +void SignalSelector::remove(QListWidgetItem *item) { + auto it = (ListItem *)item; + if (it->msg_id == msgs_combo->currentData().value()) { + addItemToList(available_list, it->msg_id, it->sig); + } + delete item; +} + +void SignalSelector::updateAvailableList(int index) { + if (index == -1) return; + available_list->clear(); + MessageId msg_id = msgs_combo->itemData(index).value(); + auto selected_items = seletedItems(); + for (auto s : dbc()->msg(msg_id)->getSignals()) { + bool is_selected = std::any_of(selected_items.begin(), selected_items.end(), [=, sig = s](auto it) { return it->msg_id == msg_id && it->sig == sig; }); + if (!is_selected) { + addItemToList(available_list, msg_id, s); + } + } +} + +void SignalSelector::addItemToList(QListWidget *parent, const MessageId id, const cabana::Signal *sig, bool show_msg_name) { + QString text = QString(" %1").arg(getColor(sig).name(), sig->name); + if (show_msg_name) text += QString(" %0 %1").arg(msgName(id), id.toString()); + + QLabel *label = new QLabel(text); + label->setContentsMargins(5, 0, 5, 0); + auto new_item = new ListItem(id, sig, parent); + new_item->setSizeHint(label->sizeHint()); + parent->setItemWidget(new_item, label); +} + +QList SignalSelector::seletedItems() { + QList ret; + for (int i = 0; i < selected_list->count(); ++i) ret.push_back((ListItem *)selected_list->item(i)); + return ret; +} diff --git a/tools/cabana/chart/signalselector.h b/tools/cabana/chart/signalselector.h new file mode 100644 index 0000000000..f46779f044 --- /dev/null +++ b/tools/cabana/chart/signalselector.h @@ -0,0 +1,30 @@ +#pragma once + +#include +#include +#include + +#include "tools/cabana/dbc/dbcmanager.h" + +class SignalSelector : public QDialog { +public: + struct ListItem : public QListWidgetItem { + ListItem(const MessageId &msg_id, const cabana::Signal *sig, QListWidget *parent) : msg_id(msg_id), sig(sig), QListWidgetItem(parent) {} + MessageId msg_id; + const cabana::Signal *sig; + }; + + SignalSelector(QString title, QWidget *parent); + QList seletedItems(); + inline void addSelected(const MessageId &id, const cabana::Signal *sig) { addItemToList(selected_list, id, sig, true); } + +private: + void updateAvailableList(int index); + void addItemToList(QListWidget *parent, const MessageId id, const cabana::Signal *sig, bool show_msg_name = false); + void add(QListWidgetItem *item); + void remove(QListWidgetItem *item); + + QComboBox *msgs_combo; + QListWidget *available_list; + QListWidget *selected_list; +}; diff --git a/tools/cabana/chart/tiplabel.cc b/tools/cabana/chart/tiplabel.cc new file mode 100644 index 0000000000..db686e44fa --- /dev/null +++ b/tools/cabana/chart/tiplabel.cc @@ -0,0 +1,46 @@ +#include "tools/cabana/chart/tiplabel.h" + +#include +#include +#include + +#include "tools/cabana/settings.h" + +TipLabel::TipLabel(QWidget *parent) : QLabel(parent, Qt::ToolTip | Qt::FramelessWindowHint) { + setForegroundRole(QPalette::ToolTipText); + setBackgroundRole(QPalette::ToolTipBase); + auto palette = QToolTip::palette(); + if (settings.theme != DARK_THEME) { + palette.setColor(QPalette::ToolTipBase, QApplication::palette().color(QPalette::Base)); + palette.setColor(QPalette::ToolTipText, QRgb(0x404044)); // same color as chart label brush + } + setPalette(palette); + ensurePolished(); + setMargin(1 + style()->pixelMetric(QStyle::PM_ToolTipLabelFrameWidth, nullptr, this)); + setAttribute(Qt::WA_ShowWithoutActivating); + setTextFormat(Qt::RichText); + setVisible(false); +} + +void TipLabel::showText(const QPoint &pt, const QString &text, int right_edge) { + setText(text); + if (!text.isEmpty()) { + QSize extra(1, 1); + resize(sizeHint() + extra); + QPoint tip_pos(pt.x() + 12, pt.y()); + if (tip_pos.x() + size().width() >= right_edge) { + tip_pos.rx() = pt.x() - size().width() - 12; + } + move(tip_pos); + } + setVisible(!text.isEmpty()); +} + +void TipLabel::paintEvent(QPaintEvent *ev) { + QStylePainter p(this); + QStyleOptionFrame opt; + opt.init(this); + p.drawPrimitive(QStyle::PE_PanelTipLabel, opt); + p.end(); + QLabel::paintEvent(ev); +} diff --git a/tools/cabana/chart/tiplabel.h b/tools/cabana/chart/tiplabel.h new file mode 100644 index 0000000000..568aa3d726 --- /dev/null +++ b/tools/cabana/chart/tiplabel.h @@ -0,0 +1,10 @@ +#pragma once + +#include + +class TipLabel : public QLabel { +public: + TipLabel(QWidget *parent = nullptr); + void showText(const QPoint &pt, const QString &sec, int right_edge); + void paintEvent(QPaintEvent *ev) override; +}; diff --git a/tools/cabana/chartswidget.cc b/tools/cabana/chartswidget.cc deleted file mode 100644 index 2c9a01b752..0000000000 --- a/tools/cabana/chartswidget.cc +++ /dev/null @@ -1,1041 +0,0 @@ -#include "tools/cabana/chartswidget.h" - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -const int MAX_COLUMN_COUNT = 4; -static inline bool xLessThan(const QPointF &p, float x) { return p.x() < x; } - -// ChartsWidget - -ChartsWidget::ChartsWidget(QWidget *parent) : align_timer(this), QFrame(parent) { - setFrameStyle(QFrame::StyledPanel | QFrame::Plain); - QVBoxLayout *main_layout = new QVBoxLayout(this); - main_layout->setContentsMargins(0, 0, 0, 0); - - // toolbar - QToolBar *toolbar = new QToolBar(tr("Charts"), this); - int icon_size = style()->pixelMetric(QStyle::PM_SmallIconSize); - toolbar->setIconSize({icon_size, icon_size}); - - QAction *new_plot_btn = toolbar->addAction(utils::icon("file-plus"), tr("New Plot")); - toolbar->addWidget(title_label = new QLabel()); - title_label->setContentsMargins(0, 0, style()->pixelMetric(QStyle::PM_LayoutHorizontalSpacing), 0); - - QMenu *menu = new QMenu(this); - for (int i = 0; i < MAX_COLUMN_COUNT; ++i) { - menu->addAction(tr("%1").arg(i + 1), [=]() { setColumnCount(i + 1); }); - } - columns_action = toolbar->addAction(""); - columns_action->setMenu(menu); - qobject_cast(toolbar->widgetForAction(columns_action))->setPopupMode(QToolButton::InstantPopup); - - QLabel *stretch_label = new QLabel(this); - stretch_label->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Preferred); - toolbar->addWidget(stretch_label); - - range_lb_action = toolbar->addWidget(range_lb = new QLabel(this)); - range_slider = new LogSlider(1000, Qt::Horizontal, this); - range_slider->setMaximumWidth(200); - range_slider->setToolTip(tr("Set the chart range")); - range_slider->setRange(1, settings.max_cached_minutes * 60); - range_slider->setSingleStep(1); - range_slider->setPageStep(60); // 1 min - range_slider_action = toolbar->addWidget(range_slider); - - undo_zoom_action = toolbar->addAction(utils::icon("arrow-counterclockwise"), tr("Previous zoom")); - qobject_cast(toolbar->widgetForAction(undo_zoom_action))->setToolButtonStyle(Qt::ToolButtonTextBesideIcon); - - reset_zoom_action = toolbar->addAction(utils::icon("zoom-out"), tr("Reset Zoom")); - qobject_cast(toolbar->widgetForAction(reset_zoom_action))->setToolButtonStyle(Qt::ToolButtonTextBesideIcon); - - remove_all_btn = toolbar->addAction(utils::icon("x"), tr("Remove all charts")); - dock_btn = toolbar->addAction(""); - main_layout->addWidget(toolbar); - - // charts - charts_layout = new QGridLayout(); - charts_layout->setSpacing(10); - - QWidget *charts_container = new QWidget(this); - QVBoxLayout *charts_main_layout = new QVBoxLayout(charts_container); - charts_main_layout->setContentsMargins(0, 0, 0, 0); - charts_main_layout->addLayout(charts_layout); - charts_main_layout->addStretch(0); - - QScrollArea *charts_scroll = new QScrollArea(this); - charts_scroll->setFrameStyle(QFrame::NoFrame); - charts_scroll->setWidgetResizable(true); - charts_scroll->setWidget(charts_container); - charts_scroll->setHorizontalScrollBarPolicy(Qt::ScrollBarAlwaysOff); - main_layout->addWidget(charts_scroll); - - // init settings - use_dark_theme = QApplication::palette().color(QPalette::WindowText).value() > - QApplication::palette().color(QPalette::Background).value(); - column_count = std::clamp(settings.chart_column_count, 1, MAX_COLUMN_COUNT); - max_chart_range = std::clamp(settings.chart_range, 1, settings.max_cached_minutes * 60); - display_range = {0, max_chart_range}; - range_slider->setValue(max_chart_range); - updateToolBar(); - - align_timer.setSingleShot(true); - QObject::connect(&align_timer, &QTimer::timeout, this, &ChartsWidget::alignCharts); - QObject::connect(dbc(), &DBCManager::DBCFileChanged, this, &ChartsWidget::removeAll); - QObject::connect(can, &AbstractStream::eventsMerged, this, &ChartsWidget::eventsMerged); - QObject::connect(can, &AbstractStream::updated, this, &ChartsWidget::updateState); - QObject::connect(range_slider, &QSlider::valueChanged, this, &ChartsWidget::setMaxChartRange); - QObject::connect(new_plot_btn, &QAction::triggered, this, &ChartsWidget::newChart); - QObject::connect(remove_all_btn, &QAction::triggered, this, &ChartsWidget::removeAll); - QObject::connect(undo_zoom_action, &QAction::triggered, this, &ChartsWidget::zoomUndo); - QObject::connect(reset_zoom_action, &QAction::triggered, this, &ChartsWidget::zoomReset); - QObject::connect(&settings, &Settings::changed, this, &ChartsWidget::settingChanged); - QObject::connect(dock_btn, &QAction::triggered, [this]() { - emit dock(!docking); - docking = !docking; - updateToolBar(); - }); - - setWhatsThis(tr(R"( - Chart view
- - )")); -} - -void ChartsWidget::eventsMerged() { - { - QFutureSynchronizer future_synchronizer; - for (auto c : charts) { - future_synchronizer.addFuture(QtConcurrent::run(c, &ChartView::updateSeries, nullptr)); - } - } - if (can->isPaused()) { - updateState(); - } -} - -void ChartsWidget::setZoom(double min, double max) { - zoomed_range = {min, max}; - is_zoomed = zoomed_range != display_range; - updateToolBar(); - updateState(); - emit rangeChanged(min, max, is_zoomed); -} - -void ChartsWidget::zoomIn(double min, double max) { - // Save previous zoom on undo stack - if (is_zoomed) { - zoom_stack.push({zoomed_range.first, zoomed_range.second}); - } - setZoom(min, max); -} - -void ChartsWidget::zoomReset() { - setZoom(display_range.first, display_range.second); - zoom_stack.clear(); -} - -void ChartsWidget::zoomUndo() { - if (!zoom_stack.isEmpty()) { - auto r = zoom_stack.pop(); - setZoom(r.first, r.second); - } else { - zoomReset(); - } -} - -void ChartsWidget::updateState() { - if (charts.isEmpty()) return; - - const double cur_sec = can->currentSec(); - if (!is_zoomed) { - double pos = (cur_sec - display_range.first) / std::max(1.0, max_chart_range); - if (pos < 0 || pos > 0.8) { - display_range.first = std::max(0.0, cur_sec - max_chart_range * 0.1); - } - double max_sec = std::min(std::floor(display_range.first + max_chart_range), can->lastEventSecond()); - display_range.first = std::max(0.0, max_sec - max_chart_range); - display_range.second = display_range.first + max_chart_range; - } else if (cur_sec < zoomed_range.first || cur_sec >= zoomed_range.second) { - // loop in zoomed range - can->seekTo(zoomed_range.first); - } - - const auto &range = is_zoomed ? zoomed_range : display_range; - for (auto c : charts) { - c->updatePlot(cur_sec, range.first, range.second); - } -} - -void ChartsWidget::setMaxChartRange(int value) { - max_chart_range = settings.chart_range = range_slider->value(); - updateToolBar(); - updateState(); -} - -void ChartsWidget::updateToolBar() { - title_label->setText(tr("Charts: %1").arg(charts.size())); - columns_action->setText(tr("Column: %1").arg(column_count)); - range_lb->setText(QString("Range: %1 ").arg(utils::formatSeconds(max_chart_range))); - range_lb_action->setVisible(!is_zoomed); - range_slider_action->setVisible(!is_zoomed); - undo_zoom_action->setVisible(is_zoomed); - reset_zoom_action->setVisible(is_zoomed); - reset_zoom_action->setText(is_zoomed ? tr("Zoomin: %1-%2").arg(zoomed_range.first, 0, 'f', 1).arg(zoomed_range.second, 0, 'f', 1) : ""); - remove_all_btn->setEnabled(!charts.isEmpty()); - dock_btn->setIcon(utils::icon(docking ? "arrow-up-right-square" : "arrow-down-left-square")); - dock_btn->setToolTip(docking ? tr("Undock charts") : tr("Dock charts")); -} - -void ChartsWidget::settingChanged() { - range_slider->setRange(1, settings.max_cached_minutes * 60); - for (auto c : charts) { - c->setFixedHeight(settings.chart_height); - c->setSeriesType((SeriesType)settings.chart_series_type); - } -} - -ChartView *ChartsWidget::findChart(const MessageId &id, const cabana::Signal *sig) { - for (auto c : charts) - if (c->hasSeries(id, sig)) return c; - return nullptr; -} - -ChartView *ChartsWidget::createChart() { - auto chart = new ChartView(this); - chart->setFixedHeight(settings.chart_height); - chart->setMinimumWidth(CHART_MIN_WIDTH); - chart->setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::Fixed); - chart->chart()->setTheme(use_dark_theme ? QChart::QChart::ChartThemeDark : QChart::ChartThemeLight); - QObject::connect(chart, &ChartView::remove, [=]() { removeChart(chart); }); - QObject::connect(chart, &ChartView::zoomIn, this, &ChartsWidget::zoomIn); - QObject::connect(chart, &ChartView::zoomUndo, this, &ChartsWidget::zoomUndo); - QObject::connect(chart, &ChartView::seriesRemoved, this, &ChartsWidget::seriesChanged); - QObject::connect(chart, &ChartView::seriesAdded, this, &ChartsWidget::seriesChanged); - QObject::connect(chart, &ChartView::axisYLabelWidthChanged, &align_timer, qOverload<>(&QTimer::start)); - charts.push_back(chart); - updateLayout(); - return chart; -} - -void ChartsWidget::showChart(const MessageId &id, const cabana::Signal *sig, bool show, bool merge) { - ChartView *chart = findChart(id, sig); - if (show && !chart) { - chart = merge && charts.size() > 0 ? charts.back() : createChart(); - chart->addSeries(id, sig); - updateState(); - } else if (!show && chart) { - chart->removeIf([&](auto &s) { return s.msg_id == id && s.sig == sig; }); - } - updateToolBar(); -} - -void ChartsWidget::setColumnCount(int n) { - n = std::clamp(n, 1, MAX_COLUMN_COUNT); - if (column_count != n) { - column_count = settings.chart_column_count = n; - updateToolBar(); - updateLayout(); - } -} - -void ChartsWidget::updateLayout() { - int n = MAX_COLUMN_COUNT; - for (; n > 1; --n) { - if ((n * CHART_MIN_WIDTH + (n - 1) * charts_layout->spacing()) < charts_layout->geometry().width()) break; - } - - bool show_column_cb = n > 1; - columns_action->setVisible(show_column_cb); - - n = std::min(column_count, n); - if (charts.size() != charts_layout->count() || n != current_column_count) { - current_column_count = n; - charts_layout->parentWidget()->setUpdatesEnabled(false); - for (int i = 0; i < charts.size(); ++i) { - charts_layout->addWidget(charts[charts.size() - i - 1], i / n, i % n); - } - QTimer::singleShot(0, [this]() { charts_layout->parentWidget()->setUpdatesEnabled(true); }); - } -} - -void ChartsWidget::resizeEvent(QResizeEvent *event) { - QWidget::resizeEvent(event); - updateLayout(); -} - -void ChartsWidget::newChart() { - SeriesSelector dlg(tr("New Chart"), this); - if (dlg.exec() == QDialog::Accepted) { - auto items = dlg.seletedItems(); - if (!items.isEmpty()) { - auto c = createChart(); - for (auto it : items) { - c->addSeries(it->msg_id, it->sig); - } - } - } -} - -void ChartsWidget::removeChart(ChartView *chart) { - charts.removeOne(chart); - chart->deleteLater(); - updateToolBar(); - alignCharts(); - updateLayout(); - emit seriesChanged(); -} - -void ChartsWidget::removeAll() { - for (auto c : charts) { - c->deleteLater(); - } - charts.clear(); - updateToolBar(); - emit seriesChanged(); -} - -void ChartsWidget::alignCharts() { - int plot_left = 0; - for (auto c : charts) { - plot_left = std::max(plot_left, c->y_label_width); - } - plot_left = std::max((plot_left / 10) * 10 + 10, 50); - for (auto c : charts) { - c->updatePlotArea(plot_left); - } -} - -bool ChartsWidget::eventFilter(QObject *obj, QEvent *event) { - if (obj != this && event->type() == QEvent::Close) { - emit dock_btn->triggered(); - return true; - } - return false; -} - -bool ChartsWidget::event(QEvent *event) { - bool back_button = false; - if (event->type() == QEvent::MouseButtonPress) { - QMouseEvent *ev = static_cast(event); - back_button = ev->button() == Qt::BackButton; - } else if (event->type() == QEvent::NativeGesture) { // MacOS emulates a back swipe on pressing the mouse back button - QNativeGestureEvent *ev = static_cast(event); - back_button = (ev->value() == 180); - } - - if (back_button) { - zoomUndo(); - return true; - } - return QFrame::event(event); -} - -// ChartView - -ChartView::ChartView(QWidget *parent) : QChartView(nullptr, parent) { - series_type = (SeriesType)settings.chart_series_type; - QChart *chart = new QChart(); - chart->setBackgroundVisible(false); - axis_x = new QValueAxis(this); - axis_y = new QValueAxis(this); - chart->addAxis(axis_x, Qt::AlignBottom); - chart->addAxis(axis_y, Qt::AlignLeft); - chart->legend()->layout()->setContentsMargins(0, 0, 0, 0); - chart->legend()->setShowToolTips(true); - chart->setMargins({0, 0, 0, 0}); - - background = new QGraphicsRectItem(chart); - background->setBrush(QApplication::palette().color(QPalette::Base)); - background->setPen(Qt::NoPen); - background->setZValue(chart->zValue() - 1); - - setChart(chart); - - createToolButtons(); - setRenderHint(QPainter::Antialiasing); - // TODO: enable zoomIn/seekTo in live streaming mode. - setRubberBand(can->liveStreaming() ? QChartView::NoRubberBand : QChartView::HorizontalRubberBand); - setMouseTracking(true); - - QObject::connect(dbc(), &DBCManager::signalRemoved, this, &ChartView::signalRemoved); - QObject::connect(dbc(), &DBCManager::signalUpdated, this, &ChartView::signalUpdated); - QObject::connect(dbc(), &DBCManager::msgRemoved, this, &ChartView::msgRemoved); - QObject::connect(dbc(), &DBCManager::msgUpdated, this, &ChartView::msgUpdated); -} - -void ChartView::createToolButtons() { - move_icon = new QGraphicsPixmapItem(utils::icon("grip-horizontal"), chart()); - move_icon->setToolTip(tr("Drag and drop to combine charts")); - - QToolButton *remove_btn = toolButton("x", tr("Remove Chart")); - close_btn_proxy = new QGraphicsProxyWidget(chart()); - close_btn_proxy->setWidget(remove_btn); - close_btn_proxy->setZValue(chart()->zValue() + 11); - - // series types - QMenu *menu = new QMenu(this); - auto change_series_group = new QActionGroup(menu); - change_series_group->setExclusive(true); - QStringList types{tr("line"), tr("Step Line"), tr("Scatter")}; - for (int i = 0; i < types.size(); ++i) { - QAction *act = new QAction(types[i], change_series_group); - act->setData(i); - act->setCheckable(true); - act->setChecked(i == (int)series_type); - menu->addAction(act); - } - menu->addSeparator(); - menu->addAction(tr("Manage series"), this, &ChartView::manageSeries); - - QToolButton *manage_btn = toolButton("list", ""); - manage_btn->setMenu(menu); - manage_btn->setPopupMode(QToolButton::InstantPopup); - manage_btn_proxy = new QGraphicsProxyWidget(chart()); - manage_btn_proxy->setWidget(manage_btn); - manage_btn_proxy->setZValue(chart()->zValue() + 11); - - QObject::connect(remove_btn, &QToolButton::clicked, this, &ChartView::remove); - QObject::connect(change_series_group, &QActionGroup::triggered, [this](QAction *action) { - setSeriesType((SeriesType)action->data().toInt()); - }); -} - -void ChartView::addSeries(const MessageId &msg_id, const cabana::Signal *sig) { - if (hasSeries(msg_id, sig)) return; - - QXYSeries *series = createSeries(series_type, getColor(sig)); - sigs.push_back({.msg_id = msg_id, .sig = sig, .series = series}); - updateTitle(); - updateSeries(sig); - updateSeriesPoints(); - emit seriesAdded(msg_id, sig); -} - -bool ChartView::hasSeries(const MessageId &msg_id, const cabana::Signal *sig) const { - return std::any_of(sigs.begin(), sigs.end(), [&](auto &s) { return s.msg_id == msg_id && s.sig == sig; }); -} - -void ChartView::removeIf(std::function predicate) { - int prev_size = sigs.size(); - for (auto it = sigs.begin(); it != sigs.end(); /**/) { - if (predicate(*it)) { - chart()->removeSeries(it->series); - it->series->deleteLater(); - auto msg_id = it->msg_id; - auto sig = it->sig; - it = sigs.erase(it); - emit seriesRemoved(msg_id, sig); - } else { - ++it; - } - } - if (sigs.empty()) { - emit remove(); - } else if (sigs.size() != prev_size) { - updateAxisY(); - } -} - -void ChartView::signalUpdated(const cabana::Signal *sig) { - if (std::any_of(sigs.begin(), sigs.end(), [=](auto &s) { return s.sig == sig; })) { - updateTitle(); - // TODO: don't update series if only name changed. - updateSeries(sig); - } -} - -void ChartView::msgUpdated(MessageId id) { - if (std::any_of(sigs.begin(), sigs.end(), [=](auto &s) { return s.msg_id == id; })) - updateTitle(); -} - -void ChartView::manageSeries() { - SeriesSelector dlg(tr("Mange Chart"), this); - for (auto &s : sigs) { - dlg.addSelected(s.msg_id, s.sig); - } - if (dlg.exec() == QDialog::Accepted) { - auto items = dlg.seletedItems(); - for (auto s : items) { - addSeries(s->msg_id, s->sig); - } - removeIf([&](auto &s) { - return std::none_of(items.cbegin(), items.cend(), [&](auto &it) { return s.msg_id == it->msg_id && s.sig == it->sig; }); - }); - } -} - -void ChartView::resizeEvent(QResizeEvent *event) { - qreal left, top, right, bottom; - chart()->layout()->getContentsMargins(&left, &top, &right, &bottom); - move_icon->setPos(left, top); - close_btn_proxy->setPos(rect().right() - right - close_btn_proxy->size().width(), top); - int x = close_btn_proxy->pos().x() - manage_btn_proxy->size().width() - style()->pixelMetric(QStyle::PM_LayoutHorizontalSpacing); - manage_btn_proxy->setPos(x, top); - chart()->legend()->setGeometry({move_icon->sceneBoundingRect().topRight(), manage_btn_proxy->sceneBoundingRect().bottomLeft()}); - if (align_to > 0) { - updatePlotArea(align_to); - } - QChartView::resizeEvent(event); -} - -void ChartView::updatePlotArea(int left_pos) { - if (align_to != left_pos || rect() != background->rect()) { - align_to = left_pos; - background->setRect(rect()); - - qreal left, top, right, bottom; - chart()->layout()->getContentsMargins(&left, &top, &right, &bottom); - QSizeF x_label_size = QFontMetrics(axis_x->labelsFont()).size(Qt::TextSingleLine, QString::number(axis_x->max(), 'f', 2)); - x_label_size += QSizeF{5 * devicePixelRatioF(), 5 * devicePixelRatioF()}; - int adjust_top = chart()->legend()->geometry().height() + style()->pixelMetric(QStyle::PM_LayoutTopMargin); - chart()->setPlotArea(rect().adjusted(align_to + left, adjust_top + top, -x_label_size.width() / 2 - right, -x_label_size.height() - bottom)); - chart()->layout()->invalidate(); - if (can->isPaused()) { - update(); - } - } -} - -void ChartView::updateTitle() { - for (QLegendMarker *marker : chart()->legend()->markers()) { - QObject::connect(marker, &QLegendMarker::clicked, this, &ChartView::handleMarkerClicked, Qt::UniqueConnection); - } - for (auto &s : sigs) { - auto decoration = s.series->isVisible() ? "none" : "line-through"; - s.series->setName(QString("%2 %3 %4").arg(decoration, s.sig->name, msgName(s.msg_id), s.msg_id.toString())); - } -} - -void ChartView::updatePlot(double cur, double min, double max) { - cur_sec = cur; - if (min != axis_x->min() || max != axis_x->max()) { - axis_x->setRange(min, max); - updateAxisY(); - updateSeriesPoints(); - } - scene()->invalidate({}, QGraphicsScene::ForegroundLayer); -} - -void ChartView::updateSeriesPoints() { - // Show points when zoomed in enough - for (auto &s : sigs) { - auto begin = std::lower_bound(s.vals.begin(), s.vals.end(), axis_x->min(), xLessThan); - auto end = std::lower_bound(begin, s.vals.end(), axis_x->max(), xLessThan); - if (begin != end) { - int num_points = std::max((end - begin), 1); - QPointF right_pt = end == s.vals.end() ? s.vals.back() : *end; - double pixels_per_point = (chart()->mapToPosition(right_pt).x() - chart()->mapToPosition(*begin).x()) / num_points; - - if (series_type == SeriesType::Scatter) { - ((QScatterSeries *)s.series)->setMarkerSize(std::clamp(pixels_per_point / 2.0, 2.0, 8.0) * devicePixelRatioF()); - } else { - s.series->setPointsVisible(pixels_per_point > 20); - } - } - } -} - -void ChartView::updateSeries(const cabana::Signal *sig) { - for (auto &s : sigs) { - if (!sig || s.sig == sig) { - if (!can->liveStreaming()) { - s.vals.clear(); - s.step_vals.clear(); - s.last_value_mono_time = 0; - } - s.series->setColor(getColor(s.sig)); - - const auto &msgs = can->events().at(s.msg_id); - auto first = std::upper_bound(msgs.cbegin(), msgs.cend(), CanEvent{.mono_time = s.last_value_mono_time}); - int new_size = std::max(s.vals.size() + std::distance(first, msgs.cend()), settings.max_cached_minutes * 60 * 100); - if (s.vals.capacity() <= new_size) { - s.vals.reserve(new_size * 2); - s.step_vals.reserve(new_size * 4); - } - - const double route_start_time = can->routeStartTime(); - for (auto end = msgs.cend(); first != end; ++first) { - double value = get_raw_value(first->dat, first->size, *s.sig); - double ts = first->mono_time / 1e9 - route_start_time; // seconds - s.vals.append({ts, value}); - if (!s.step_vals.empty()) { - s.step_vals.append({ts, s.step_vals.back().y()}); - } - s.step_vals.append({ts, value}); - s.last_value_mono_time = first->mono_time; - } - if (!can->liveStreaming()) { - s.segment_tree.build(s.vals); - } - s.series->replace(series_type == SeriesType::StepLine ? s.step_vals : s.vals); - } - } - updateAxisY(); -} - -// auto zoom on yaxis -void ChartView::updateAxisY() { - if (sigs.isEmpty()) return; - - double min = std::numeric_limits::max(); - double max = std::numeric_limits::lowest(); - QString unit = sigs[0].sig->unit; - - for (auto &s : sigs) { - if (!s.series->isVisible()) continue; - - // Only show unit when all signals have the same unit - if (unit != s.sig->unit) { - unit.clear(); - } - - auto first = std::lower_bound(s.vals.begin(), s.vals.end(), axis_x->min(), xLessThan); - auto last = std::lower_bound(first, s.vals.end(), axis_x->max(), xLessThan); - s.min = std::numeric_limits::max(); - s.max = std::numeric_limits::lowest(); - if (can->liveStreaming()) { - for (auto it = first; it != last; ++it) { - if (it->y() < s.min) s.min = it->y(); - if (it->y() > s.max) s.max = it->y(); - } - } else { - auto [min_y, max_y] = s.segment_tree.minmax(std::distance(s.vals.begin(), first), std::distance(s.vals.begin(), last)); - s.min = min_y; - s.max = max_y; - } - min = std::min(min, s.min); - max = std::max(max, s.max); - } - if (min == std::numeric_limits::max()) min = 0; - if (max == std::numeric_limits::lowest()) max = 0; - - if (axis_y->titleText() != unit) { - axis_y->setTitleText(unit); - y_label_width = 0; // recalc width - } - - double delta = std::abs(max - min) < 1e-3 ? 1 : (max - min) * 0.05; - auto [min_y, max_y, tick_count] = getNiceAxisNumbers(min - delta, max + delta, axis_y->tickCount()); - if (min_y != axis_y->min() || max_y != axis_y->max() || y_label_width == 0) { - axis_y->setRange(min_y, max_y); - axis_y->setTickCount(tick_count); - - int title_spacing = unit.isEmpty() ? 0 : QFontMetrics(axis_y->titleFont()).size(Qt::TextSingleLine, unit).height(); - QFontMetrics fm(axis_y->labelsFont()); - int n = qMax(int(-qFloor(std::log10((max_y - min_y) / (tick_count - 1)))), 0) + 1; - y_label_width = title_spacing + qMax(fm.width(QString::number(min_y, 'f', n)), fm.width(QString::number(max_y, 'f', n))) + 15; - axis_y->setLabelFormat(QString("%.%1f").arg(n)); - emit axisYLabelWidthChanged(y_label_width); - } -} - -std::tuple ChartView::getNiceAxisNumbers(qreal min, qreal max, int tick_count) { - qreal range = niceNumber((max - min), true); // range with ceiling - qreal step = niceNumber(range / (tick_count - 1), false); - min = qFloor(min / step); - max = qCeil(max / step); - tick_count = int(max - min) + 1; - return {min * step, max * step, tick_count}; -} - -// nice numbers can be expressed as form of 1*10^n, 2* 10^n or 5*10^n -qreal ChartView::niceNumber(qreal x, bool ceiling) { - qreal z = qPow(10, qFloor(std::log10(x))); //find corresponding number of the form of 10^n than is smaller than x - qreal q = x / z; //q<10 && q>=1; - if (ceiling) { - if (q <= 1.0) q = 1; - else if (q <= 2.0) q = 2; - else if (q <= 5.0) q = 5; - else q = 10; - } else { - if (q < 1.5) q = 1; - else if (q < 3.0) q = 2; - else if (q < 7.0) q = 5; - else q = 10; - } - return q * z; -} - -void ChartView::leaveEvent(QEvent *event) { - clearTrackPoints(); - scene()->update(); - QChartView::leaveEvent(event); -} - -void ChartView::mousePressEvent(QMouseEvent *event) { - if (event->button() == Qt::LeftButton && move_icon->sceneBoundingRect().contains(event->pos())) { - QMimeData *mimeData = new QMimeData; - mimeData->setData(mime_type, QByteArray::number((qulonglong)this)); - QDrag *drag = new QDrag(this); - drag->setMimeData(mimeData); - drag->setPixmap(grab()); - drag->setHotSpot(event->pos()); - drag->exec(Qt::CopyAction | Qt::MoveAction, Qt::MoveAction); - } else if (event->button() == Qt::LeftButton && QApplication::keyboardModifiers().testFlag(Qt::ShiftModifier)) { - if (!can->liveStreaming()) { - // Save current playback state when scrubbing - resume_after_scrub = !can->isPaused(); - if (resume_after_scrub) { - can->pause(true); - } - is_scrubbing = true; - } - } else { - QChartView::mousePressEvent(event); - } -} - -void ChartView::mouseReleaseEvent(QMouseEvent *event) { - auto rubber = findChild(); - if (event->button() == Qt::LeftButton && rubber && rubber->isVisible()) { - rubber->hide(); - QRectF rect = rubber->geometry().normalized(); - double min = chart()->mapToValue(rect.topLeft()).x(); - double max = chart()->mapToValue(rect.bottomRight()).x(); - - // Prevent zooming/seeking past the end of the route - min = std::clamp(min, 0., can->totalSeconds()); - max = std::clamp(max, 0., can->totalSeconds()); - - double min_rounded = std::floor(min * 10.0) / 10.0; - double max_rounded = std::floor(max * 10.0) / 10.0; - if (rubber->width() <= 0) { - // no rubber dragged, seek to mouse position - can->seekTo(min); - } else if (rubber->width() > 10) { - emit zoomIn(min_rounded, max_rounded); - } else { - scene()->invalidate({}, QGraphicsScene::ForegroundLayer); - } - event->accept(); - } else if (!can->liveStreaming() && event->button() == Qt::RightButton) { - emit zoomUndo(); - event->accept(); - } else { - QGraphicsView::mouseReleaseEvent(event); - } - - // Resume playback if we were scrubbing - is_scrubbing = false; - if (resume_after_scrub) { - can->pause(false); - resume_after_scrub = false; - } -} - -void ChartView::mouseMoveEvent(QMouseEvent *ev) { - const auto plot_area = chart()->plotArea(); - // Scrubbing - if (is_scrubbing && QApplication::keyboardModifiers().testFlag(Qt::ShiftModifier)) { - if (plot_area.contains(ev->pos())) { - can->seekTo(std::clamp(chart()->mapToValue(ev->pos()).x(), 0., can->totalSeconds())); - } - return; - } - - auto rubber = findChild(); - bool is_zooming = rubber && rubber->isVisible(); - is_scrubbing = false; - clearTrackPoints(); - - if (!is_zooming && plot_area.contains(ev->pos())) { - QStringList text_list; - const double sec = chart()->mapToValue(ev->pos()).x(); - qreal x = -1; - for (auto &s : sigs) { - if (!s.series->isVisible()) continue; - - // use reverse iterator to find last item <= sec. - double value = 0; - auto it = std::lower_bound(s.vals.rbegin(), s.vals.rend(), sec, [](auto &p, double x) { return p.x() > x; }); - if (it != s.vals.rend() && it->x() >= axis_x->min()) { - value = it->y(); - s.track_pt = chart()->mapToPosition(*it); - x = std::max(x, s.track_pt.x()); - } - text_list.push_back(QString("%2: %3 (%4 - %5)") - .arg(s.series->color().name(), s.sig->name, - s.track_pt.isNull() ? "--" : QString::number(value), - QString::number(s.min), QString::number(s.max))); - - } - if (x < 0) { - x = ev->pos().x(); - } - text_list.push_front(QString::number(chart()->mapToValue({x, 0}).x(), 'f', 3)); - QPointF tooltip_pt(x + 12, plot_area.top() - 20); - QToolTip::showText(mapToGlobal(tooltip_pt.toPoint()), "

" + text_list.join("
"), this, plot_area.toRect()); - scene()->invalidate({}, QGraphicsScene::ForegroundLayer); - } else { - QToolTip::hideText(); - } - - QChartView::mouseMoveEvent(ev); - if (is_zooming) { - QRect rubber_rect = rubber->geometry(); - rubber_rect.setLeft(std::max(rubber_rect.left(), (int)plot_area.left())); - rubber_rect.setRight(std::min(rubber_rect.right(), (int)plot_area.right())); - if (rubber_rect != rubber->geometry()) { - rubber->setGeometry(rubber_rect); - } - scene()->invalidate({}, QGraphicsScene::ForegroundLayer); - } -} - -void ChartView::dragMoveEvent(QDragMoveEvent *event) { - if (event->mimeData()->hasFormat(mime_type)) { - event->setDropAction(event->source() == this ? Qt::MoveAction : Qt::CopyAction); - event->accept(); - } else { - event->ignore(); - } -} - -void ChartView::dropEvent(QDropEvent *event) { - if (event->mimeData()->hasFormat(mime_type)) { - if (event->source() == this) { - event->setDropAction(Qt::MoveAction); - event->accept(); - } else { - ChartView *source_chart = (ChartView *)event->source(); - for (auto &s : source_chart->sigs) { - addSeries(s.msg_id, s.sig); - } - emit source_chart->remove(); - event->acceptProposedAction(); - } - } else { - event->ignore(); - } -} - -void ChartView::drawForeground(QPainter *painter, const QRectF &rect) { - // draw time line - qreal x = chart()->mapToPosition(QPointF{cur_sec, 0}).x(); - x = std::clamp(x, chart()->plotArea().left(), chart()->plotArea().right()); - qreal y1 = chart()->plotArea().top() - 2; - qreal y2 = chart()->plotArea().bottom() + 2; - painter->setPen(QPen(chart()->titleBrush().color(), 2)); - painter->drawLine(QPointF{x, y1}, QPointF{x, y2}); - - // draw track points - painter->setPen(Qt::NoPen); - qreal track_line_x = -1; - for (auto &s : sigs) { - if (!s.track_pt.isNull() && s.series->isVisible()) { - painter->setBrush(s.series->color().darker(125)); - painter->drawEllipse(s.track_pt, 5.5, 5.5); - track_line_x = std::max(track_line_x, s.track_pt.x()); - } - } - if (track_line_x > 0) { - painter->setPen(QPen(Qt::darkGray, 1, Qt::DashLine)); - painter->drawLine(QPointF{track_line_x, y1}, QPointF{track_line_x, y2}); - } - - // paint points. OpenGL mode lacks certain features (such as showing points) - painter->setPen(Qt::NoPen); - for (auto &s : sigs) { - if (s.series->useOpenGL() && s.series->isVisible() && s.series->pointsVisible()) { - auto first = std::lower_bound(s.vals.begin(), s.vals.end(), axis_x->min(), xLessThan); - auto last = std::lower_bound(first, s.vals.end(), axis_x->max(), xLessThan); - painter->setBrush(s.series->color()); - for (auto it = first; it != last; ++it) { - painter->drawEllipse(chart()->mapToPosition(*it), 4, 4); - } - } - } - - // paint zoom range - auto rubber = findChild(); - if (rubber && rubber->isVisible() && rubber->width() > 1) { - painter->setPen(Qt::white); - auto rubber_rect = rubber->geometry().normalized(); - for (const auto &pt : {rubber_rect.bottomLeft(), rubber_rect.bottomRight()}) { - QString sec = QString::number(chart()->mapToValue(pt).x(), 'f', 1); - // ChartAxisElement's padding is 4 (https://codebrowser.dev/qt5/qtcharts/src/charts/axis/chartaxiselement_p.h.html) - auto r = painter->fontMetrics().boundingRect(sec).adjusted(-6, -4, 6, 4); - pt == rubber_rect.bottomLeft() ? r.moveTopRight(pt + QPoint{0, 2}) : r.moveTopLeft(pt + QPoint{0, 2}); - painter->fillRect(r, Qt::gray); - painter->drawText(r, Qt::AlignCenter, sec); - } - } -} - -QXYSeries *ChartView::createSeries(SeriesType type, QColor color) { - QXYSeries *series = nullptr; - if (type == SeriesType::Line) { - series = new QLineSeries(this); - chart()->legend()->setMarkerShape(QLegend::MarkerShapeRectangle); - } else if (type == SeriesType::StepLine) { - series = new QLineSeries(this); - chart()->legend()->setMarkerShape(QLegend::MarkerShapeFromSeries); - } else { - series = new QScatterSeries(this); - chart()->legend()->setMarkerShape(QLegend::MarkerShapeCircle); - } - series->setColor(color); - // TODO: Due to a bug in CameraWidget the camera frames - // are drawn instead of the graphs on MacOS. Re-enable OpenGL when fixed -#ifndef __APPLE__ - series->setUseOpenGL(true); - // Qt doesn't properly apply device pixel ratio in OpenGL mode - QPen pen = series->pen(); - pen.setWidthF(2.0 * devicePixelRatioF()); - series->setPen(pen); -#endif - chart()->addSeries(series); - series->attachAxis(axis_x); - series->attachAxis(axis_y); - - // disables the delivery of mouse events to the opengl widget. - // this enables the user to select the zoom area when the mouse press on the data point. - auto glwidget = findChild(); - if (glwidget && !glwidget->testAttribute(Qt::WA_TransparentForMouseEvents)) { - glwidget->setAttribute(Qt::WA_TransparentForMouseEvents); - } - return series; -} - -void ChartView::setSeriesType(SeriesType type) { - if (type != series_type) { - series_type = type; - for (auto &s : sigs) { - chart()->removeSeries(s.series); - s.series->deleteLater(); - } - for (auto &s : sigs) { - auto series = createSeries(series_type, getColor(s.sig)); - series->replace(series_type == SeriesType::StepLine ? s.step_vals : s.vals); - s.series = series; - } - updateSeriesPoints(); - updateTitle(); - } -} - -void ChartView::handleMarkerClicked() { - auto marker = qobject_cast(sender()); - Q_ASSERT(marker); - if (sigs.size() > 1) { - auto series = marker->series(); - series->setVisible(!series->isVisible()); - marker->setVisible(true); - updateAxisY(); - updateTitle(); - } -} - -// SeriesSelector - -SeriesSelector::SeriesSelector(QString title, QWidget *parent) : QDialog(parent) { - setWindowTitle(title); - QGridLayout *main_layout = new QGridLayout(this); - - // left column - main_layout->addWidget(new QLabel(tr("Available Signals")), 0, 0); - main_layout->addWidget(msgs_combo = new QComboBox(this), 1, 0); - msgs_combo->setEditable(true); - msgs_combo->lineEdit()->setPlaceholderText(tr("Select a msg...")); - msgs_combo->setInsertPolicy(QComboBox::NoInsert); - msgs_combo->completer()->setCompletionMode(QCompleter::PopupCompletion); - msgs_combo->completer()->setFilterMode(Qt::MatchContains); - - main_layout->addWidget(available_list = new QListWidget(this), 2, 0); - - // buttons - QVBoxLayout *btn_layout = new QVBoxLayout(); - QPushButton *add_btn = new QPushButton(utils::icon("chevron-right"), "", this); - add_btn->setEnabled(false); - QPushButton *remove_btn = new QPushButton(utils::icon("chevron-left"), "", this); - remove_btn->setEnabled(false); - btn_layout->addStretch(0); - btn_layout->addWidget(add_btn); - btn_layout->addWidget(remove_btn); - btn_layout->addStretch(0); - main_layout->addLayout(btn_layout, 0, 1, 3, 1); - - // right column - main_layout->addWidget(new QLabel(tr("Selected Signals")), 0, 2); - main_layout->addWidget(selected_list = new QListWidget(this), 1, 2, 2, 1); - - auto buttonBox = new QDialogButtonBox(QDialogButtonBox::Ok | QDialogButtonBox::Cancel); - main_layout->addWidget(buttonBox, 3, 2); - - for (auto it = can->last_msgs.cbegin(); it != can->last_msgs.cend(); ++it) { - if (auto m = dbc()->msg(it.key())) { - msgs_combo->addItem(QString("%1 (%2)").arg(m->name).arg(it.key().toString()), QVariant::fromValue(it.key())); - } - } - msgs_combo->model()->sort(0); - msgs_combo->setCurrentIndex(-1); - - QObject::connect(msgs_combo, qOverload(&QComboBox::currentIndexChanged), this, &SeriesSelector::updateAvailableList); - QObject::connect(available_list, &QListWidget::currentRowChanged, [=](int row) { add_btn->setEnabled(row != -1); }); - QObject::connect(selected_list, &QListWidget::currentRowChanged, [=](int row) { remove_btn->setEnabled(row != -1); }); - QObject::connect(available_list, &QListWidget::itemDoubleClicked, this, &SeriesSelector::add); - QObject::connect(selected_list, &QListWidget::itemDoubleClicked, this, &SeriesSelector::remove); - QObject::connect(add_btn, &QPushButton::clicked, [this]() { if (auto item = available_list->currentItem()) add(item); }); - QObject::connect(remove_btn, &QPushButton::clicked, [this]() { if (auto item = selected_list->currentItem()) remove(item); }); - QObject::connect(buttonBox, &QDialogButtonBox::accepted, this, &QDialog::accept); - QObject::connect(buttonBox, &QDialogButtonBox::rejected, this, &QDialog::reject); -} - -void SeriesSelector::add(QListWidgetItem *item) { - auto it = (ListItem *)item; - addItemToList(selected_list, it->msg_id, it->sig, true); - delete item; -} - -void SeriesSelector::remove(QListWidgetItem *item) { - auto it = (ListItem *)item; - if (it->msg_id == msgs_combo->currentData().value()) { - addItemToList(available_list, it->msg_id, it->sig); - } - delete item; -} - -void SeriesSelector::updateAvailableList(int index) { - if (index == -1) return; - available_list->clear(); - MessageId msg_id = msgs_combo->itemData(index).value(); - auto selected_items = seletedItems(); - for (auto s : dbc()->msg(msg_id)->getSignals()) { - bool is_selected = std::any_of(selected_items.begin(), selected_items.end(), [=, sig=s](auto it) { return it->msg_id == msg_id && it->sig == sig; }); - if (!is_selected) { - addItemToList(available_list, msg_id, s); - } - } -} - -void SeriesSelector::addItemToList(QListWidget *parent, const MessageId id, const cabana::Signal *sig, bool show_msg_name) { - QString text = QString(" %1").arg(getColor(sig).name(), sig->name); - if (show_msg_name) text += QString(" %0 %1").arg(msgName(id), id.toString()); - - QLabel *label = new QLabel(text); - label->setContentsMargins(5, 0, 5, 0); - auto new_item = new ListItem(id, sig, parent); - new_item->setSizeHint(label->sizeHint()); - parent->setItemWidget(new_item, label); -} - -QList SeriesSelector::seletedItems() { - QList ret; - for (int i = 0; i < selected_list->count(); ++i) ret.push_back((ListItem *)selected_list->item(i)); - return ret; -} diff --git a/tools/cabana/chartswidget.h b/tools/cabana/chartswidget.h deleted file mode 100644 index 592e063163..0000000000 --- a/tools/cabana/chartswidget.h +++ /dev/null @@ -1,188 +0,0 @@ -#pragma once - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include "tools/cabana/dbc/dbcmanager.h" -#include "tools/cabana/streams/abstractstream.h" -using namespace QtCharts; - -const int CHART_MIN_WIDTH = 300; - -enum class SeriesType { - Line = 0, - StepLine, - Scatter -}; - -class ChartView : public QChartView { - Q_OBJECT - -public: - ChartView(QWidget *parent = nullptr); - void addSeries(const MessageId &msg_id, const cabana::Signal *sig); - bool hasSeries(const MessageId &msg_id, const cabana::Signal *sig) const; - void updateSeries(const cabana::Signal *sig = nullptr); - void updatePlot(double cur, double min, double max); - void setSeriesType(SeriesType type); - void updatePlotArea(int left); - - struct SigItem { - MessageId msg_id; - const cabana::Signal *sig = nullptr; - QXYSeries *series = nullptr; - QVector vals; - QVector step_vals; - uint64_t last_value_mono_time = 0; - QPointF track_pt{}; - SegmentTree segment_tree; - double min = 0; - double max = 0; - }; - -signals: - void seriesRemoved(const MessageId &id, const cabana::Signal *sig); - void seriesAdded(const MessageId &id, const cabana::Signal *sig); - void zoomIn(double min, double max); - void zoomUndo(); - void remove(); - void axisYLabelWidthChanged(int w); - -private slots: - void signalUpdated(const cabana::Signal *sig); - void manageSeries(); - void handleMarkerClicked(); - void msgUpdated(MessageId id); - void msgRemoved(MessageId id) { removeIf([=](auto &s) { return s.msg_id == id; }); } - void signalRemoved(const cabana::Signal *sig) { removeIf([=](auto &s) { return s.sig == sig; }); } - -private: - void createToolButtons(); - void mousePressEvent(QMouseEvent *event) override; - void mouseReleaseEvent(QMouseEvent *event) override; - void mouseMoveEvent(QMouseEvent *ev) override; - void dragMoveEvent(QDragMoveEvent *event) override; - void dropEvent(QDropEvent *event) override; - void leaveEvent(QEvent *event) override; - void resizeEvent(QResizeEvent *event) override; - QSize sizeHint() const override { return {CHART_MIN_WIDTH, settings.chart_height}; } - void updateAxisY(); - void updateTitle(); - void drawForeground(QPainter *painter, const QRectF &rect) override; - std::tuple getNiceAxisNumbers(qreal min, qreal max, int tick_count); - qreal niceNumber(qreal x, bool ceiling); - QXYSeries *createSeries(SeriesType type, QColor color); - void updateSeriesPoints(); - void removeIf(std::function predicate); - inline void clearTrackPoints() { for (auto &s : sigs) s.track_pt = {}; } - - int y_label_width = 0; - int align_to = 0; - QValueAxis *axis_x; - QValueAxis *axis_y; - QGraphicsPixmapItem *move_icon; - QGraphicsProxyWidget *close_btn_proxy; - QGraphicsProxyWidget *manage_btn_proxy; - QGraphicsRectItem *background; - QList sigs; - double cur_sec = 0; - const QString mime_type = "application/x-cabanachartview"; - SeriesType series_type = SeriesType::Line; - bool is_scrubbing = false; - bool resume_after_scrub = false; - friend class ChartsWidget; - }; - -class ChartsWidget : public QFrame { - Q_OBJECT - -public: - ChartsWidget(QWidget *parent = nullptr); - void showChart(const MessageId &id, const cabana::Signal *sig, bool show, bool merge); - inline bool hasSignal(const MessageId &id, const cabana::Signal *sig) { return findChart(id, sig) != nullptr; } - -public slots: - void setColumnCount(int n); - void removeAll(); - -signals: - void dock(bool floating); - void rangeChanged(double min, double max, bool is_zommed); - void seriesChanged(); - -private: - void resizeEvent(QResizeEvent *event) override; - bool event(QEvent *event) override; - void alignCharts(); - void newChart(); - ChartView *createChart(); - void removeChart(ChartView *chart); - void eventsMerged(); - void updateState(); - void zoomIn(double min, double max); - void zoomReset(); - void zoomUndo(); - void setZoom(double min, double max); - void updateToolBar(); - void setMaxChartRange(int value); - void updateLayout(); - void settingChanged(); - bool eventFilter(QObject *obj, QEvent *event) override; - ChartView *findChart(const MessageId &id, const cabana::Signal *sig); - - QLabel *title_label; - QLabel *range_lb; - LogSlider *range_slider; - QAction *range_lb_action; - QAction *range_slider_action; - bool docking = true; - QAction *dock_btn; - QAction *undo_zoom_action; - QAction *reset_zoom_action; - QAction *remove_all_btn; - QGridLayout *charts_layout; - QList charts; - uint32_t max_chart_range = 0; - bool is_zoomed = false; - std::pair display_range; - std::pair zoomed_range; - QStack> zoom_stack; - bool use_dark_theme = false; - QAction *columns_action; - int column_count = 1; - int current_column_count = 0; - QTimer align_timer; -}; - -class SeriesSelector : public QDialog { -public: - struct ListItem : public QListWidgetItem { - ListItem(const MessageId &msg_id, const cabana::Signal *sig, QListWidget *parent) : msg_id(msg_id), sig(sig), QListWidgetItem(parent) {} - MessageId msg_id; - const cabana::Signal *sig; - }; - - SeriesSelector(QString title, QWidget *parent); - QList seletedItems(); - inline void addSelected(const MessageId &id, const cabana::Signal *sig) { addItemToList(selected_list, id, sig, true); } - -private: - void updateAvailableList(int index); - void addItemToList(QListWidget *parent, const MessageId id, const cabana::Signal *sig, bool show_msg_name = false); - void add(QListWidgetItem *item); - void remove(QListWidgetItem *item); - - QComboBox *msgs_combo; - QListWidget *available_list; - QListWidget *selected_list; -}; diff --git a/tools/cabana/dbc/dbc.h b/tools/cabana/dbc/dbc.h index 701908112f..8b1e5a16e9 100644 --- a/tools/cabana/dbc/dbc.h +++ b/tools/cabana/dbc/dbc.h @@ -11,8 +11,8 @@ const QString UNTITLED = "untitled"; struct MessageId { - uint8_t source; - uint32_t address; + uint8_t source = 0; + uint32_t address = 0; QString toString() const { return QString("%1:%2").arg(source).arg(address, 1, 16); diff --git a/tools/cabana/dbc/dbcmanager.cc b/tools/cabana/dbc/dbcmanager.cc index 49527765a8..24803a303f 100644 --- a/tools/cabana/dbc/dbcmanager.cc +++ b/tools/cabana/dbc/dbcmanager.cc @@ -59,6 +59,8 @@ bool DBCManager::open(SourceSet s, const QString &name, const QString &content, } void DBCManager::closeAll() { + if (dbc_files.isEmpty()) return; + while (dbc_files.size()) { DBCFile *dbc_file = dbc_files.back().second; dbc_files.pop_back(); diff --git a/tools/cabana/detailwidget.cc b/tools/cabana/detailwidget.cc index 543946b19a..dd12d4c8a3 100644 --- a/tools/cabana/detailwidget.cc +++ b/tools/cabana/detailwidget.cc @@ -22,7 +22,7 @@ DetailWidget::DetailWidget(ChartsWidget *charts, QWidget *parent) : charts(chart // message title QHBoxLayout *title_layout = new QHBoxLayout(); - title_layout->setContentsMargins(0, 6, 0, 0); + title_layout->setContentsMargins(3, 6, 3, 0); time_label = new QLabel(this); time_label->setToolTip(tr("Current time")); time_label->setStyleSheet("QLabel{font-weight:bold;}"); @@ -32,9 +32,9 @@ DetailWidget::DetailWidget(ChartsWidget *charts, QWidget *parent) : charts(chart name_label->setAlignment(Qt::AlignCenter); name_label->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Preferred); title_layout->addWidget(name_label); - auto edit_btn = toolButton("pencil", tr("Edit Message")); + auto edit_btn = new ToolButton("pencil", tr("Edit Message")); title_layout->addWidget(edit_btn); - remove_btn = toolButton("x-lg", tr("Remove Message")); + remove_btn = new ToolButton("x-lg", tr("Remove Message")); title_layout->addWidget(remove_btn); main_layout->addLayout(title_layout); diff --git a/tools/cabana/detailwidget.h b/tools/cabana/detailwidget.h index b7cfed376c..074ce3b4d3 100644 --- a/tools/cabana/detailwidget.h +++ b/tools/cabana/detailwidget.h @@ -6,7 +6,7 @@ #include "selfdrive/ui/qt/widgets/controls.h" #include "tools/cabana/binaryview.h" -#include "tools/cabana/chartswidget.h" +#include "tools/cabana/chart/chartswidget.h" #include "tools/cabana/historylog.h" #include "tools/cabana/signalview.h" diff --git a/tools/cabana/historylog.cc b/tools/cabana/historylog.cc index 4ebe8e0473..5d09d8a90b 100644 --- a/tools/cabana/historylog.cc +++ b/tools/cabana/historylog.cc @@ -39,7 +39,7 @@ void HistoryLogModel::refresh(bool fetch_message) { last_fetch_time = 0; has_more_data = true; messages.clear(); - hex_colors.clear(); + hex_colors = {}; if (fetch_message) { updateState(); } @@ -146,7 +146,7 @@ std::deque HistoryLogModel::fetchData(uint64_t from_ti auto msgs = fetchData(first, events.rend(), min_time); if (update_colors && (min_time > 0 || messages.empty())) { for (auto it = msgs.rbegin(); it != msgs.rend(); ++it) { - hex_colors.compute(it->data, it->mono_time / (double)1e9, freq); + hex_colors.compute(it->data.data(), it->data.size(), it->mono_time / (double)1e9, freq); it->colors = hex_colors.colors; } } @@ -157,7 +157,7 @@ std::deque HistoryLogModel::fetchData(uint64_t from_ti auto msgs = fetchData(first, events.end(), 0); if (update_colors) { for (auto it = msgs.begin(); it != msgs.end(); ++it) { - hex_colors.compute(it->data, it->mono_time / (double)1e9, freq); + hex_colors.compute(it->data.data(), it->data.size(), it->mono_time / (double)1e9, freq); it->colors = hex_colors.colors; } } @@ -186,6 +186,7 @@ void HeaderView::paintSection(QPainter *painter, const QRect &rect, int logicalI painter->fillRect(rect, bg_role.value()); } QString text = model()->headerData(logicalIndex, Qt::Horizontal, Qt::DisplayRole).toString(); + painter->setPen(palette().color(settings.theme == DARK_THEME ? QPalette::BrightText : QPalette::Text)); painter->drawText(rect.adjusted(5, 3, -5, -3), defaultAlignment(), text.replace(QChar('_'), ' ')); } diff --git a/tools/cabana/historylog.h b/tools/cabana/historylog.h index 8b8d1b06d2..1f8c157f21 100644 --- a/tools/cabana/historylog.h +++ b/tools/cabana/historylog.h @@ -54,7 +54,7 @@ public: std::deque fetchData(uint64_t from_time, uint64_t min_time = 0); MessageId msg_id; - ChangeTracker hex_colors; + CanData hex_colors; bool has_more_data = true; const int batch_size = 50; int filter_sig_idx = -1; diff --git a/tools/cabana/mainwin.h b/tools/cabana/mainwin.h index 991a34931d..3445642d4d 100644 --- a/tools/cabana/mainwin.h +++ b/tools/cabana/mainwin.h @@ -7,7 +7,7 @@ #include #include -#include "tools/cabana/chartswidget.h" +#include "tools/cabana/chart/chartswidget.h" #include "tools/cabana/dbc/dbcmanager.h" #include "tools/cabana/detailwidget.h" #include "tools/cabana/messageswidget.h" diff --git a/tools/cabana/settings.cc b/tools/cabana/settings.cc index 9e829708b1..3a1fc14751 100644 --- a/tools/cabana/settings.cc +++ b/tools/cabana/settings.cc @@ -1,11 +1,13 @@ #include "tools/cabana/settings.h" +#include #include #include #include #include -// Settings +#include "tools/cabana/util.h" + Settings settings; Settings::Settings() { @@ -27,6 +29,7 @@ void Settings::save() { s.setValue("recent_files", recent_files); s.setValue("message_header_state", message_header_state); s.setValue("chart_series_type", chart_series_type); + s.setValue("theme", theme); s.setValue("sparkline_range", sparkline_range); } @@ -45,6 +48,7 @@ void Settings::load() { recent_files = s.value("recent_files").toStringList(); message_header_state = s.value("message_header_state").toByteArray(); chart_series_type = s.value("chart_series_type", 0).toInt(); + theme = s.value("theme", 0).toInt(); sparkline_range = s.value("sparkline_range", 15).toInt(); } @@ -54,6 +58,12 @@ SettingsDlg::SettingsDlg(QWidget *parent) : QDialog(parent) { setWindowTitle(tr("Settings")); QFormLayout *form_layout = new QFormLayout(this); + theme = new QComboBox(this); + theme->setToolTip(tr("You may need to restart cabana after changes theme")); + theme->addItems({tr("Automatic"), tr("Light"), tr("Dark")}); + theme->setCurrentIndex(settings.theme); + form_layout->addRow(tr("Color Theme"), theme); + fps = new QSpinBox(this); fps->setRange(10, 100); fps->setSingleStep(10); @@ -77,20 +87,32 @@ SettingsDlg::SettingsDlg(QWidget *parent) : QDialog(parent) { chart_height->setValue(settings.chart_height); form_layout->addRow(tr("Chart Height"), chart_height); - auto buttonBox = new QDialogButtonBox(QDialogButtonBox::Ok | QDialogButtonBox::Cancel); + auto buttonBox = new QDialogButtonBox(QDialogButtonBox::Ok | QDialogButtonBox::Cancel | QDialogButtonBox::Apply); form_layout->addRow(buttonBox); setFixedWidth(360); - connect(buttonBox, &QDialogButtonBox::accepted, this, &SettingsDlg::save); - connect(buttonBox, &QDialogButtonBox::rejected, this, &QDialog::reject); + connect(buttonBox, &QDialogButtonBox::clicked, [=](QAbstractButton *button) { + auto role = buttonBox->buttonRole(button); + if (role == QDialogButtonBox::AcceptRole) { + save(); + accept(); + } else if (role == QDialogButtonBox::ApplyRole) { + save(); + } else if (role == QDialogButtonBox::RejectRole) { + reject(); + } + }); } void SettingsDlg::save() { settings.fps = fps->value(); + if (std::exchange(settings.theme, theme->currentIndex()) != settings.theme) { + // set theme before emit changed + utils::setTheme(settings.theme); + } settings.max_cached_minutes = cached_minutes->value(); settings.chart_series_type = chart_series_type->currentIndex(); settings.chart_height = chart_height->value(); settings.save(); - accept(); emit settings.changed(); } diff --git a/tools/cabana/settings.h b/tools/cabana/settings.h index a8b6d189a5..dd01b602e7 100644 --- a/tools/cabana/settings.h +++ b/tools/cabana/settings.h @@ -5,6 +5,9 @@ #include #include +#define LIGHT_THEME 1 +#define DARK_THEME 2 + class Settings : public QObject { Q_OBJECT @@ -19,6 +22,7 @@ public: int chart_column_count = 1; int chart_range = 3 * 60; // 3 minutes int chart_series_type = 0; + int theme = 0; int sparkline_range = 15; // 15 seconds QString last_dir; QString last_route_dir; @@ -42,6 +46,7 @@ public: QSpinBox *cached_minutes; QSpinBox *chart_height; QComboBox *chart_series_type; + QComboBox *theme; }; extern Settings settings; diff --git a/tools/cabana/signalview.cc b/tools/cabana/signalview.cc index 4eb1456b1e..f404dd3346 100644 --- a/tools/cabana/signalview.cc +++ b/tools/cabana/signalview.cc @@ -6,6 +6,7 @@ #include #include #include +#include #include #include @@ -35,6 +36,7 @@ void SignalModel::insertItem(SignalModel::Item *parent_item, int pos, const caba void SignalModel::setMessage(const MessageId &id) { msg_id = id; filter_str = ""; + value_width = 0; refresh(); updateState(nullptr); } @@ -60,7 +62,6 @@ void SignalModel::refresh() { void SignalModel::updateState(const QHash *msgs) { if (!msgs || msgs->contains(msg_id)) { auto &dat = can->lastMessage(msg_id).dat; - int row = 0; for (auto item : root->children) { double value = get_raw_value((uint8_t *)dat.constData(), dat.size(), *item->sig); item->sig_val = QString::number(value, 'f', item->sig->precision); @@ -76,9 +77,11 @@ void SignalModel::updateState(const QHash *msgs) { item->sig_val = desc; } } + value_width = std::max(value_width, QFontMetrics(QFont()).width(item->sig_val)); + } - emit dataChanged(index(row, 1), index(row, 1), {Qt::DisplayRole}); - ++row; + for (int i = 0; i < root->children.size(); ++i) { + emit dataChanged(index(i, 1), index(i, 1), {Qt::DisplayRole}); } } } @@ -313,7 +316,8 @@ SignalItemDelegate::SignalItemDelegate(QObject *parent) : QStyledItemDelegate(pa name_validator = new NameValidator(this); double_validator = new QDoubleValidator(this); double_validator->setLocale(QLocale::C); // Match locale of QString::toDouble() instead of system - small_font.setPointSize(8); + label_font.setPointSize(8); + minmax_font.setPixelSize(10); } QSize SignalItemDelegate::sizeHint(const QStyleOptionViewItem &option, const QModelIndex &index) const { @@ -344,6 +348,17 @@ bool SignalItemDelegate::helpEvent(QHelpEvent *event, QAbstractItemView *view, c return QStyledItemDelegate::helpEvent(event, view, option, index); } +void SignalItemDelegate::updateEditorGeometry(QWidget *editor, const QStyleOptionViewItem &option, const QModelIndex &index) const { + auto item = (SignalModel::Item *)index.internalPointer(); + if (editor && item->type == SignalModel::Item::Sig && index.column() == 1) { + QRect geom = option.widget->style()->subElementRect(QStyle::SE_ItemViewItemText, &option); + geom.setLeft(geom.right() - editor->sizeHint().width()); + editor->setGeometry(geom); + return; + } + QStyledItemDelegate::updateEditorGeometry(editor, option, index); +} + void SignalItemDelegate::paint(QPainter *painter, const QStyleOptionViewItem &option, const QModelIndex &index) const { int h_margin = option.widget->style()->pixelMetric(QStyle::PM_FocusFrameHMargin) + 1; int v_margin = option.widget->style()->pixelMetric(QStyle::PM_FocusFrameVMargin); @@ -362,7 +377,7 @@ void SignalItemDelegate::paint(QPainter *painter, const QStyleOptionViewItem &op painter->setBrush(item->highlight ? bg_color.darker(125) : bg_color); painter->drawRoundedRect(rc.adjusted(0, v_margin, 0, -v_margin), 3, 3); painter->setPen(item->highlight ? Qt::white : Qt::black); - painter->setFont(small_font); + painter->setFont(label_font); painter->drawText(rc, Qt::AlignCenter, QString::number(item->row() + 1)); // signal name @@ -375,26 +390,28 @@ void SignalItemDelegate::paint(QPainter *painter, const QStyleOptionViewItem &op painter->drawText(text_rect, option.displayAlignment, text); painter->restore(); } else if (index.column() == 1 && item && item->type == SignalModel::Item::Sig) { + painter->save(); if (option.state & QStyle::State_Selected) { painter->fillRect(option.rect, option.palette.highlight()); } + SignalModel *model = (SignalModel*)index.model(); int adjust_right = ((SignalView *)parent())->tree->indexWidget(index)->sizeHint().width() + 2 * h_margin; QRect r = option.rect.adjusted(h_margin, v_margin, -adjust_right, -v_margin); - // draw signal value - QRect value_rect = r.adjusted(r.width() * 0.6 + h_margin, 0, 0, 0); + + int value_width = std::min(model->value_width, r.width() * 0.4); + QRect value_rect = r.adjusted(r.width() - value_width - h_margin, 0, 0, 0); auto text = painter->fontMetrics().elidedText(index.data(Qt::DisplayRole).toString(), Qt::ElideRight, value_rect.width()); painter->setPen(option.palette.color(option.state & QStyle::State_Selected ? QPalette::HighlightedText : QPalette::Text)); painter->drawText(value_rect, Qt::AlignRight | Qt::AlignVCenter, text); - - QRect sparkline_rect = r.adjusted(0, 0, -r.width() * 0.4 - h_margin, 0); - drawSparkline(painter, sparkline_rect, index); + drawSparkline(painter, r.adjusted(0, 0, -value_width, 0), option, index); + painter->restore(); } else { QStyledItemDelegate::paint(painter, option, index); } } -void SignalItemDelegate::drawSparkline(QPainter *painter, const QRect &rect, const QModelIndex &index) const { +void SignalItemDelegate::drawSparkline(QPainter *painter, const QRect &rect, const QStyleOptionViewItem &option, const QModelIndex &index) const { static std::vector points; const auto &msg_id = ((SignalView *)parent())->msg_id; const auto &msgs = can->events().at(msg_id); @@ -406,7 +423,8 @@ void SignalItemDelegate::drawSparkline(QPainter *painter, const QRect &rect, con if (first != last) { double min = std::numeric_limits::max(); double max = std::numeric_limits::lowest(); - const auto sig = ((SignalModel::Item *)index.internalPointer())->sig; + const auto item = (const SignalModel::Item *)index.internalPointer(); + const auto sig = item->sig; points.clear(); for (auto it = first; it != last; ++it) { double value = get_raw_value(it->dat, it->size, *sig); @@ -419,22 +437,34 @@ void SignalItemDelegate::drawSparkline(QPainter *painter, const QRect &rect, con max += 1; } - const double xscale = rect.width() / (double)settings.sparkline_range; - const double yscale = rect.height() / (max - min); + const double min_max_width = std::min(rect.width() - 10, QFontMetrics(minmax_font).width("000.00") + 5); + const QRect r = rect.adjusted(0, 0, -min_max_width, 0); + const double xscale = r.width() / (double)settings.sparkline_range; + const double yscale = r.height() / (max - min); for (auto &pt : points) { - pt.rx() = rect.left() + pt.x() * xscale; - pt.ry() = rect.top() + std::abs(pt.y() - max) * yscale; + pt.rx() = r.left() + pt.x() * xscale; + pt.ry() = r.top() + std::abs(pt.y() - max) * yscale; } - painter->setPen(getColor(sig)); + auto color = item->highlight ? getColor(sig).darker(125) : getColor(sig); + painter->setPen(color); painter->drawPolyline(points.data(), points.size()); if ((points.back().x() - points.front().x()) / points.size() > 10) { painter->setPen(Qt::NoPen); - painter->setBrush(getColor(sig)); + painter->setBrush(color); for (const auto &pt : points) { painter->drawEllipse(pt, 2, 2); } } + + if (item->highlight || option.state & QStyle::State_Selected) { + painter->setFont(minmax_font); + painter->setPen(option.state & QStyle::State_Selected ? option.palette.color(QPalette::HighlightedText) : Qt::darkGray); + painter->drawLine(r.topRight(), r.bottomRight()); + QRect minmax_rect{r.right() + 5, r.top(), 1000, r.height()}; + painter->drawText(minmax_rect, Qt::AlignLeft | Qt::AlignTop, QString::number(max)); + painter->drawText(minmax_rect, Qt::AlignLeft | Qt::AlignBottom, QString::number(min)); + } } } @@ -496,7 +526,7 @@ SignalView::SignalView(ChartsWidget *charts, QWidget *parent) : charts(charts), sparkline_range_slider->setValue(settings.sparkline_range); sparkline_range_slider->setToolTip(tr("Sparkline time range")); - auto collapse_btn = toolButton("dash-square", tr("Collapse All")); + auto collapse_btn = new ToolButton("dash-square", tr("Collapse All")); collapse_btn->setIconSize({12, 12}); hl->addWidget(collapse_btn); @@ -552,10 +582,9 @@ void SignalView::rowsChanged() { int h_margin = style()->pixelMetric(QStyle::PM_FocusFrameHMargin); h->setContentsMargins(0, v_margin, -h_margin, v_margin); h->setSpacing(style()->pixelMetric(QStyle::PM_ToolBarItemSpacing)); - h->addStretch(0); - auto remove_btn = toolButton("x", tr("Remove signal")); - auto plot_btn = toolButton("graph-up", ""); + auto remove_btn = new ToolButton("x", tr("Remove signal")); + auto plot_btn = new ToolButton("graph-up", ""); plot_btn->setCheckable(true); h->addWidget(plot_btn); h->addWidget(remove_btn); @@ -612,13 +641,14 @@ void SignalView::signalHovered(const cabana::Signal *sig) { bool highlight = children[i]->sig == sig; if (std::exchange(children[i]->highlight, highlight) != highlight) { emit model->dataChanged(model->index(i, 0), model->index(i, 0), {Qt::DecorationRole}); + emit model->dataChanged(model->index(i, 1), model->index(i, 1), {Qt::DisplayRole}); } } } void SignalView::updateToolBar() { signal_count_lb->setText(tr("Signals: %1").arg(model->rowCount())); - sparkline_label->setText(QString("Range: %1 ").arg(utils::formatSeconds(settings.sparkline_range))); + sparkline_label->setText(utils::formatSeconds(settings.sparkline_range)); } void SignalView::setSparklineRange(int value) { diff --git a/tools/cabana/signalview.h b/tools/cabana/signalview.h index 8bc9477888..a2102ff9a7 100644 --- a/tools/cabana/signalview.h +++ b/tools/cabana/signalview.h @@ -8,7 +8,7 @@ #include #include -#include "tools/cabana/chartswidget.h" +#include "tools/cabana/chart/chartswidget.h" class SignalModel : public QAbstractItemModel { Q_OBJECT @@ -59,7 +59,9 @@ private: MessageId msg_id; QString filter_str; std::unique_ptr root; + int value_width = 0; friend class SignalView; + friend class SignalItemDelegate; }; class ValueDescriptionDlg : public QDialog { @@ -84,9 +86,10 @@ public: QSize sizeHint(const QStyleOptionViewItem &option, const QModelIndex &index) const; QWidget *createEditor(QWidget *parent, const QStyleOptionViewItem &option, const QModelIndex &index) const override; bool helpEvent(QHelpEvent *event, QAbstractItemView *view, const QStyleOptionViewItem &option, const QModelIndex &index) override; - void drawSparkline(QPainter *painter, const QRect &rect, const QModelIndex &index) const; + void drawSparkline(QPainter *painter, const QRect &rect, const QStyleOptionViewItem &option, const QModelIndex &index) const; + void updateEditorGeometry(QWidget *editor, const QStyleOptionViewItem &option, const QModelIndex &index) const override; QValidator *name_validator, *double_validator; - QFont small_font; + QFont label_font, minmax_font; const int color_label_width = 18; mutable QHash width_cache; }; diff --git a/tools/cabana/streams/abstractstream.cc b/tools/cabana/streams/abstractstream.cc index d60beed0c8..bab8777580 100644 --- a/tools/cabana/streams/abstractstream.cc +++ b/tools/cabana/streams/abstractstream.cc @@ -11,8 +11,14 @@ AbstractStream::AbstractStream(QObject *parent, bool is_live_streaming) : is_liv } void AbstractStream::process(QHash *messages) { + auto prev_src_size = sources.size(); for (auto it = messages->begin(); it != messages->end(); ++it) { - last_msgs[it.key()] = it.value(); + const auto &id = it.key(); + last_msgs[id] = it.value(); + sources.insert(id.source); + } + if (sources.size() != prev_src_size) { + emit sourcesUpdated(sources); } emit updated(); emit msgsReceived(messages); @@ -22,34 +28,24 @@ void AbstractStream::process(QHash *messages) { bool AbstractStream::updateEvent(const Event *event) { static double prev_update_ts = 0; - if (event->which == cereal::Event::Which::CAN) { double current_sec = event->mono_time / 1e9 - routeStartTime(); for (const auto &c : event->event.getCan()) { MessageId id = {.source = c.getSrc(), .address = c.getAddress()}; - CanData &data = (*new_msgs)[id]; - data.ts = current_sec; - data.dat = QByteArray((char *)c.getDat().begin(), c.getDat().size()); - data.count = ++counters[id]; - data.freq = data.count / std::max(1.0, current_sec); - - auto &tracker = change_trackers[id]; - tracker.compute(data.dat, data.ts, data.freq); - data.colors = tracker.colors; - data.last_change_t = tracker.last_change_t; - data.bit_change_counts = tracker.bit_change_counts; - - if (!sources.contains(id.source)) { - sources.insert(id.source); - emit sourcesUpdated(sources); + const auto dat = c.getDat(); + all_msgs[id].compute((const char *)dat.begin(), dat.size(), current_sec); + if (!new_msgs->contains(id)) { + new_msgs->insert(id, {}); } } - double ts = millis_since_boot(); + // delay posting CAN message if UI thread is busy if ((ts - prev_update_ts) > (1000.0 / settings.fps) && !processing && !new_msgs->isEmpty()) { - // delay posting CAN message if UI thread is busy processing = true; prev_update_ts = ts; + for (auto it = new_msgs->begin(); it != new_msgs->end(); ++it) { + it.value() = all_msgs[it.key()]; + } // use pointer to avoid data copy in queued connection. emit received(new_msgs.release()); new_msgs.reset(new QHash); @@ -69,25 +65,22 @@ const CanData &AbstractStream::lastMessage(const MessageId &id) { // updateEvent will not be called before replayStream::seekedTo return. void AbstractStream::updateLastMsgsTo(double sec) { new_msgs->clear(); - change_trackers.clear(); + all_msgs.clear(); last_msgs.clear(); - counters.clear(); CanEvent last_event = {.mono_time = uint64_t((sec + routeStartTime()) * 1e9)}; for (auto &[id, e] : events_) { auto it = std::lower_bound(e.crbegin(), e.crend(), last_event, std::greater()); if (it != e.crend()) { - auto &m = last_msgs[id]; - m.dat = QByteArray((const char *)it->dat, it->size); - m.ts = it->mono_time / 1e9 - routeStartTime(); + double ts = it->mono_time / 1e9 - routeStartTime(); + auto &m = all_msgs[id]; + m.compute((const char *)it->dat, it->size, ts); m.count = std::distance(it, e.crend()); - m.freq = m.count / std::max(1.0, m.ts); - m.last_change_t = QVector(m.dat.size(), m.ts); - m.colors = QVector(m.dat.size(), QColor(0, 0, 0, 0)); - m.bit_change_counts = QVector>(m.dat.size()); - counters[id] = m.count; + m.freq = m.count / std::max(1.0, ts); } } + last_msgs = all_msgs; + // use a timer to prevent recursive calls QTimer::singleShot(0, [this]() { emit updated(); emit msgsReceived(&last_msgs); @@ -96,18 +89,20 @@ void AbstractStream::updateLastMsgsTo(double sec) { void AbstractStream::parseEvents(std::unordered_map> &msgs, std::vector::const_iterator first, std::vector::const_iterator last) { + uint64_t ts = 0; for (; first != last; ++first) { if ((*first)->which == cereal::Event::Which::CAN) { + ts = (*first)->mono_time; for (const auto &c : (*first)->event.getCan()) { auto dat = c.getDat(); auto &m = msgs[{.source = c.getSrc(), .address = c.getAddress()}].emplace_back(); m.size = std::min(dat.size(), std::size(m.dat)); memcpy(m.dat, (uint8_t *)dat.begin(), m.size); - m.mono_time = (*first)->mono_time; + m.mono_time = ts; } - last_event_ts = std::max(last_event_ts, (*first)->mono_time); } } + last_event_ts = std::max(last_event_ts, ts); } void AbstractStream::mergeEvents(std::vector::const_iterator first, std::vector::const_iterator last, bool append) { @@ -126,3 +121,67 @@ void AbstractStream::mergeEvents(std::vector::const_iterator first, std } emit eventsMerged(); } + +// CanData + +constexpr int periodic_threshold = 10; +constexpr int start_alpha = 128; +constexpr float fade_time = 2.0; +const QColor CYAN = QColor(0, 187, 255, start_alpha); +const QColor RED = QColor(255, 0, 0, start_alpha); +const QColor GREYISH_BLUE = QColor(102, 86, 169, start_alpha / 2); +const QColor CYAN_LIGHTER = QColor(0, 187, 255, start_alpha).lighter(135); +const QColor RED_LIGHTER = QColor(255, 0, 0, start_alpha).lighter(135); +const QColor GREYISH_BLUE_LIGHTER = QColor(102, 86, 169, start_alpha / 2).lighter(135); + +static inline QColor blend(const QColor &a, const QColor &b) { + return QColor((a.red() + b.red()) / 2, (a.green() + b.green()) / 2, (a.blue() + b.blue()) / 2, (a.alpha() + b.alpha()) / 2); +} + +void CanData::compute(const char *can_data, const int size, double current_sec, uint32_t in_freq) { + ts = current_sec; + ++count; + freq = in_freq == 0 ? count / std::max(1.0, current_sec) : in_freq; + if (dat.size() != size) { + dat.resize(size); + bit_change_counts.resize(size); + colors = QVector(size, QColor(0, 0, 0, 0)); + last_change_t = QVector(size, ts); + } else { + bool lighter = settings.theme == DARK_THEME; + const QColor &cyan = !lighter ? CYAN : CYAN_LIGHTER; + const QColor &red = !lighter ? RED : RED_LIGHTER; + const QColor &greyish_blue = !lighter ? GREYISH_BLUE : GREYISH_BLUE_LIGHTER; + + for (int i = 0; i < size; ++i) { + const uint8_t last = dat[i]; + const uint8_t cur = can_data[i]; + + if (last != cur) { + double delta_t = ts - last_change_t[i]; + if (delta_t * freq > periodic_threshold) { + // Last change was while ago, choose color based on delta up or down + colors[i] = (cur > last) ? cyan : red; + } else { + // Periodic changes + colors[i] = blend(colors[i], greyish_blue); + } + + // Track bit level changes + const uint8_t tmp = (cur ^ last); + for (int bit = 0; bit < 8; bit++) { + if (tmp & (1 << bit)) { + bit_change_counts[i][bit] += 1; + } + } + + last_change_t[i] = ts; + } else { + // Fade out + float alpha_delta = 1.0 / (freq + 1) / fade_time; + colors[i].setAlphaF(std::max(0.0, colors[i].alphaF() - alpha_delta)); + } + } + } + memcpy(dat.data(), can_data, size); +} diff --git a/tools/cabana/streams/abstractstream.h b/tools/cabana/streams/abstractstream.h index 0515f7c7e8..caa17ab177 100644 --- a/tools/cabana/streams/abstractstream.h +++ b/tools/cabana/streams/abstractstream.h @@ -1,5 +1,6 @@ #pragma once +#include #include #include #include @@ -12,6 +13,8 @@ #include "tools/replay/replay.h" struct CanData { + void compute(const char *dat, const int size, double current_sec, uint32_t in_freq = 0); + double ts = 0.; uint32_t count = 0; uint32_t freq = 0; @@ -22,9 +25,9 @@ struct CanData { }; struct CanEvent { - uint64_t mono_time; - uint8_t size; - uint8_t dat[64]; + uint64_t mono_time = 0; + uint8_t size = 0; + uint8_t dat[64] = {}; inline bool operator<(const CanEvent &r) const { return mono_time < r.mono_time; } inline bool operator>(const CanEvent &r) const { return mono_time > r.mono_time; } }; @@ -78,9 +81,8 @@ protected: bool is_live_streaming = false; std::atomic processing = false; - QHash counters; std::unique_ptr> new_msgs; - QHash change_trackers; + QHash all_msgs; std::unordered_map> events_; uint64_t last_event_ts = 0; }; diff --git a/tools/cabana/tests/test_cabana b/tools/cabana/tests/test_cabana deleted file mode 100755 index bac242fbdd..0000000000 --- a/tools/cabana/tests/test_cabana +++ /dev/null @@ -1,4 +0,0 @@ -#!/bin/sh -cd "$(dirname "$0")" -export LD_LIBRARY_PATH="../../../opendbc/can:$LD_LIBRARY_PATH" -exec ./_test_cabana "$1" diff --git a/tools/cabana/util.cc b/tools/cabana/util.cc index e5a9749103..58c1deb349 100644 --- a/tools/cabana/util.cc +++ b/tools/cabana/util.cc @@ -1,70 +1,11 @@ #include "tools/cabana/util.h" -#include #include #include #include -#include -#include #include "selfdrive/ui/qt/util.h" -static QColor blend(QColor a, QColor b) { - return QColor((a.red() + b.red()) / 2, (a.green() + b.green()) / 2, (a.blue() + b.blue()) / 2, (a.alpha() + b.alpha()) / 2); -} - -void ChangeTracker::compute(const QByteArray &dat, double ts, uint32_t freq) { - if (prev_dat.size() != dat.size()) { - colors.resize(dat.size()); - last_change_t.resize(dat.size()); - bit_change_counts.resize(dat.size()); - std::fill(colors.begin(), colors.end(), QColor(0, 0, 0, 0)); - std::fill(last_change_t.begin(), last_change_t.end(), ts); - } else { - for (int i = 0; i < dat.size(); ++i) { - const uint8_t last = prev_dat[i]; - const uint8_t cur = dat[i]; - - if (last != cur) { - double delta_t = ts - last_change_t[i]; - if (delta_t * freq > periodic_threshold) { - // Last change was while ago, choose color based on delta up or down - if (cur > last) { - colors[i] = QColor(0, 187, 255, start_alpha); // Cyan - } else { - colors[i] = QColor(255, 0, 0, start_alpha); // Red - } - } else { - // Periodic changes - colors[i] = blend(colors[i], QColor(102, 86, 169, start_alpha / 2)); // Greyish/Blue - } - - // Track bit level changes - for (int bit = 0; bit < 8; bit++) { - if ((cur ^ last) & (1 << bit)) { - bit_change_counts[i][bit] += 1; - } - } - - last_change_t[i] = ts; - } else { - // Fade out - float alpha_delta = 1.0 / (freq + 1) / fade_time; - colors[i].setAlphaF(std::max(0.0, colors[i].alphaF() - alpha_delta)); - } - } - } - - prev_dat = dat; -} - -void ChangeTracker::clear() { - prev_dat.clear(); - last_change_t.clear(); - bit_change_counts.clear(); - colors.clear(); -} - // SegmentTree void SegmentTree::build(const QVector &arr) { @@ -145,8 +86,7 @@ QValidator::State NameValidator::validate(QString &input, int &pos) const { namespace utils { QPixmap icon(const QString &id) { - static bool dark_theme = QApplication::palette().color(QPalette::WindowText).value() > - QApplication::palette().color(QPalette::Background).value(); + bool dark_theme = settings.theme == DARK_THEME; QPixmap pm; QString key = "bootstrap_" % id % (dark_theme ? "1" : "0"); if (!QPixmapCache::find(key, &pm)) { @@ -154,23 +94,52 @@ QPixmap icon(const QString &id) { if (dark_theme) { QPainter p(&pm); p.setCompositionMode(QPainter::CompositionMode_SourceIn); - p.fillRect(pm.rect(), Qt::lightGray); + p.fillRect(pm.rect(), QColor("#bbbbbb")); } QPixmapCache::insert(key, pm); } return pm; } -} // namespace utils -QToolButton *toolButton(const QString &icon, const QString &tooltip) { - auto btn = new QToolButton(); - btn->setIcon(utils::icon(icon)); - btn->setToolTip(tooltip); - btn->setAutoRaise(true); - const int metric = qApp->style()->pixelMetric(QStyle::PM_SmallIconSize); - btn->setIconSize({metric, metric}); - return btn; -}; +void setTheme(int theme) { + auto style = QApplication::style(); + if (!style) return; + + static int prev_theme = 0; + if (theme != prev_theme) { + prev_theme = theme; + QPalette new_palette; + if (theme == DARK_THEME) { + // "Darcula" like dark theme + new_palette.setColor(QPalette::Window, QColor("#353535")); + new_palette.setColor(QPalette::WindowText, QColor("#bbbbbb")); + new_palette.setColor(QPalette::Base, QColor("#3c3f41")); + new_palette.setColor(QPalette::AlternateBase, QColor("#3c3f41")); + new_palette.setColor(QPalette::ToolTipBase, QColor("#3c3f41")); + new_palette.setColor(QPalette::ToolTipText, QColor("#bbb")); + new_palette.setColor(QPalette::Text, QColor("#bbbbbb")); + new_palette.setColor(QPalette::Button, QColor("#3c3f41")); + new_palette.setColor(QPalette::ButtonText, QColor("#bbbbbb")); + new_palette.setColor(QPalette::Highlight, QColor("#2f65ca")); + new_palette.setColor(QPalette::HighlightedText, QColor("#bbbbbb")); + new_palette.setColor(QPalette::BrightText, QColor("#f0f0f0")); + new_palette.setColor(QPalette::Disabled, QPalette::ButtonText, QColor("#777777")); + new_palette.setColor(QPalette::Disabled, QPalette::WindowText, QColor("#777777")); + new_palette.setColor(QPalette::Disabled, QPalette::Text, QColor("#777777"));; + new_palette.setColor(QPalette::Light, QColor("#3c3f41")); + new_palette.setColor(QPalette::Dark, QColor("#353535")); + } else { + new_palette = style->standardPalette(); + } + qApp->setPalette(new_palette); + style->polish(qApp); + for (auto w : QApplication::allWidgets()) { + w->setPalette(new_palette); + } + } +} + +} // namespace utils QString toHex(uint8_t byte) { static std::array hex = []() { diff --git a/tools/cabana/util.h b/tools/cabana/util.h index e90a838af8..3b3a10ea17 100644 --- a/tools/cabana/util.h +++ b/tools/cabana/util.h @@ -1,8 +1,8 @@ #pragma once -#include #include +#include #include #include #include @@ -14,22 +14,7 @@ #include #include "tools/cabana/dbc/dbc.h" - -class ChangeTracker { -public: - void compute(const QByteArray &dat, double ts, uint32_t freq); - void clear(); - - QVector last_change_t; - QVector colors; - QVector> bit_change_counts; - -private: - const int periodic_threshold = 10; - const int start_alpha = 128; - const float fade_time = 2.0; - QByteArray prev_dat; -}; +#include "tools/cabana/settings.h" class LogSlider : public QSlider { Q_OBJECT @@ -98,10 +83,33 @@ public: namespace utils { QPixmap icon(const QString &id); +void setTheme(int theme); inline QString formatSeconds(int seconds) { return QDateTime::fromTime_t(seconds).toString(seconds > 60 * 60 ? "hh:mm:ss" : "mm:ss"); } } -QToolButton *toolButton(const QString &icon, const QString &tooltip); +class ToolButton : public QToolButton { + Q_OBJECT +public: + ToolButton(const QString &icon, const QString &tooltip = {}, QWidget *parent = nullptr) : QToolButton(parent) { + setIcon(icon); + setToolTip(tooltip); + setAutoRaise(true); + const int metric = QApplication::style()->pixelMetric(QStyle::PM_SmallIconSize); + setIconSize({metric, metric}); + theme = settings.theme; + connect(&settings, &Settings::changed, this, &ToolButton::updateIcon); + } + void setIcon(const QString &icon) { + icon_str = icon; + QToolButton::setIcon(utils::icon(icon_str)); + } + +private: + void updateIcon() { if (std::exchange(theme, settings.theme) != theme) setIcon(icon_str); } + QString icon_str; + int theme; +}; + int num_decimals(double num); diff --git a/tools/cabana/videowidget.cc b/tools/cabana/videowidget.cc index fe9e00bc45..99992907c5 100644 --- a/tools/cabana/videowidget.cc +++ b/tools/cabana/videowidget.cc @@ -3,6 +3,7 @@ #include #include #include +#include #include #include #include @@ -19,6 +20,18 @@ static const QColor timeline_colors[] = { [(int)TimelineType::AlertCritical] = QColor(199, 0, 57), }; +bool sortTimelineBasedOnEventPriority(const std::tuple &left, const std::tuple &right){ + const static std::map timelinePriority = { + { TimelineType::None, 0 }, + { TimelineType::Engaged, 10 }, + { TimelineType::AlertInfo, 20 }, + { TimelineType::AlertWarning, 30 }, + { TimelineType::AlertCritical, 40 }, + { TimelineType::UserFlag, 35 } + }; + return timelinePriority.at(std::get<2>(left)) < timelinePriority.at(std::get<2>(right)); +} + VideoWidget::VideoWidget(QWidget *parent) : QFrame(parent) { setFrameStyle(QFrame::StyledPanel | QFrame::Plain); auto main_layout = new QVBoxLayout(this); @@ -50,6 +63,7 @@ VideoWidget::VideoWidget(QWidget *parent) : QFrame(parent) { QObject::connect(play_btn, &QPushButton::clicked, []() { can->pause(!can->isPaused()); }); QObject::connect(can, &AbstractStream::paused, this, &VideoWidget::updatePlayBtnState); QObject::connect(can, &AbstractStream::resume, this, &VideoWidget::updatePlayBtnState); + QObject::connect(&settings, &Settings::changed, this, &VideoWidget::updatePlayBtnState); updatePlayBtnState(); setWhatsThis(tr(R"( @@ -78,10 +92,14 @@ QWidget *VideoWidget::createCameraWidget() { QWidget *w = new QWidget(this); QVBoxLayout *l = new QVBoxLayout(w); l->setContentsMargins(0, 0, 0, 0); - cam_widget = new CameraWidget("camerad", can->visionStreamType(), false); + + QStackedLayout *stacked = new QStackedLayout(); + stacked->setStackingMode(QStackedLayout::StackAll); + stacked->addWidget(cam_widget = new CameraWidget("camerad", can->visionStreamType(), false)); cam_widget->setMinimumHeight(MIN_VIDEO_HEIGHT); cam_widget->setSizePolicy(QSizePolicy::Preferred, QSizePolicy::MinimumExpanding); - l->addWidget(cam_widget); + stacked->addWidget(alert_label = new InfoLabel(this)); + l->addLayout(stacked); // slider controls slider_layout = new QHBoxLayout(); @@ -116,8 +134,17 @@ void VideoWidget::rangeChanged(double min, double max, bool is_zoomed) { } void VideoWidget::updateState() { - if (!slider->isSliderDown()) + if (!slider->isSliderDown()) { slider->setValue(can->currentSec() * 1000); + } + std::lock_guard lk(slider->thumbnail_lock); + uint64_t mono_time = (can->currentSec() + can->routeStartTime()) * 1e9; + auto it = slider->alerts.lower_bound(mono_time); + if (it != slider->alerts.end() && (it->first - mono_time) < 1e9) { + alert_label->showAlert(it->second); + } else { + alert_label->showAlert({}); + } } void VideoWidget::updatePlayBtnState() { @@ -126,9 +153,10 @@ void VideoWidget::updatePlayBtnState() { } // Slider -Slider::Slider(QWidget *parent) : timer(this), thumbnail_label(this), QSlider(Qt::Horizontal, parent) { +Slider::Slider(QWidget *parent) : timer(this), thumbnail_label(parent), QSlider(Qt::Horizontal, parent) { timer.callOnTimeout([this]() { timeline = can->getTimeline(); + std::sort(timeline.begin(), timeline.end(), sortTimelineBasedOnEventPriority); update(); }); setMouseTracking(true); @@ -153,11 +181,11 @@ void Slider::streamStarted() { void Slider::loadThumbnails() { const auto &segments = can->route()->segments(); for (auto it = segments.rbegin(); it != segments.rend() && !abort_load_thumbnail; ++it) { + LogReader log; std::string qlog = it->second.qlog.toStdString(); - if (!qlog.empty()) { - LogReader log; - if (log.load(qlog, &abort_load_thumbnail, {cereal::Event::Which::THUMBNAIL}, true, 0, 3)) { - for (auto ev = log.events.cbegin(); ev != log.events.cend() && !abort_load_thumbnail; ++ev) { + if (!qlog.empty() && log.load(qlog, &abort_load_thumbnail, {cereal::Event::Which::THUMBNAIL, cereal::Event::Which::CONTROLS_STATE}, true, 0, 3)) { + for (auto ev = log.events.cbegin(); ev != log.events.cend() && !abort_load_thumbnail; ++ev) { + if ((*ev)->which == cereal::Event::Which::THUMBNAIL) { auto thumb = (*ev)->event.getThumbnail(); auto data = thumb.getThumbnail(); if (QPixmap pm; pm.loadFromData(data.begin(), data.size(), "jpeg")) { @@ -165,6 +193,12 @@ void Slider::loadThumbnails() { std::lock_guard lk(thumbnail_lock); thumbnails[thumb.getTimestampEof()] = pm; } + } else if ((*ev)->which == cereal::Event::Which::CONTROLS_STATE) { + auto cs = (*ev)->event.getControlsState(); + if (cs.getAlertType().size() > 0 && cs.getAlertText1().size() > 0) { + std::lock_guard lk(thumbnail_lock); + alerts.emplace((*ev)->mono_time, AlertInfo{cs.getAlertStatus(), cs.getAlertText1().cStr(), cs.getAlertText2().cStr()}); + } } } } @@ -189,6 +223,7 @@ void Slider::paintEvent(QPaintEvent *ev) { p.fillRect(r, timeline_colors[(int)TimelineType::None]); double min = minimum() / 1000.0; double max = maximum() / 1000.0; + for (auto [begin, end, type] : timeline) { if (begin > max || end < min) continue; @@ -217,44 +252,96 @@ void Slider::mousePressEvent(QMouseEvent *e) { void Slider::mouseMoveEvent(QMouseEvent *e) { QPixmap thumb; + AlertInfo alert; double seconds = (minimum() + e->pos().x() * ((maximum() - minimum()) / (double)width())) / 1000.0; { std::lock_guard lk(thumbnail_lock); - auto it = thumbnails.lowerBound((seconds + can->routeStartTime()) * 1e9); + uint64_t mono_time = (seconds + can->routeStartTime()) * 1e9; + auto it = thumbnails.lowerBound(mono_time); if (it != thumbnails.end()) thumb = it.value(); + auto alert_it = alerts.lower_bound(mono_time); + if (alert_it != alerts.end() && (alert_it->first - mono_time) < 1e9) { + alert = alert_it->second; + } } int x = std::clamp(e->pos().x() - thumb.width() / 2, THUMBNAIL_MARGIN, rect().right() - thumb.width() - THUMBNAIL_MARGIN); - int y = -thumb.height() - THUMBNAIL_MARGIN - style()->pixelMetric(QStyle::PM_LayoutVerticalSpacing); - thumbnail_label.showPixmap(mapToGlobal({x, y}), utils::formatSeconds(seconds), thumb); + int y = -thumb.height(); + thumbnail_label.showPixmap(mapToParent({x, y}), utils::formatSeconds(seconds), thumb, alert); QSlider::mouseMoveEvent(e); } -void Slider::leaveEvent(QEvent *event) { - thumbnail_label.hide(); - QSlider::leaveEvent(event); +bool Slider::event(QEvent *event) { + switch (event->type()) { + case QEvent::WindowActivate: + case QEvent::WindowDeactivate: + case QEvent::FocusIn: + case QEvent::FocusOut: + case QEvent::Leave: + thumbnail_label.hide(); + break; + default: + break; + } + return QSlider::event(event); } -// ThumbnailLabel +// InfoLabel -ThumbnailLabel::ThumbnailLabel(QWidget *parent) : QWidget(parent, Qt::Tool | Qt::FramelessWindowHint) { +InfoLabel::InfoLabel(QWidget *parent) : QWidget(parent, Qt::WindowStaysOnTopHint) { setAttribute(Qt::WA_ShowWithoutActivating); setVisible(false); } -void ThumbnailLabel::showPixmap(const QPoint &pt, const QString &sec, const QPixmap &pm) { +void InfoLabel::showPixmap(const QPoint &pt, const QString &sec, const QPixmap &pm, const AlertInfo &alert) { pixmap = pm; second = sec; + alert_info = alert; setVisible(!pm.isNull()); if (isVisible()) { - setGeometry({pt, pm.size()}); + resize(pm.size()); + move(pt); update(); } } -void ThumbnailLabel::paintEvent(QPaintEvent *event) { +void InfoLabel::showAlert(const AlertInfo &alert) { + alert_info = alert; + pixmap = {}; + setVisible(!alert_info.text1.isEmpty()); + if (isVisible()) { + update(); + } +} + +void InfoLabel::paintEvent(QPaintEvent *event) { QPainter p(this); - p.drawPixmap(0, 0, pixmap); - p.setPen(QPen(Qt::white, 2)); - p.drawRect(rect()); - p.drawText(rect().adjusted(0, 0, 0, -THUMBNAIL_MARGIN), second, Qt::AlignHCenter | Qt::AlignBottom); + p.setPen(QPen(palette().color(QPalette::BrightText), 2)); + if (!pixmap.isNull()) { + p.drawPixmap(0, 0, pixmap); + p.drawRect(rect()); + p.drawText(rect().adjusted(0, 0, 0, -THUMBNAIL_MARGIN), second, Qt::AlignHCenter | Qt::AlignBottom); + } + if (alert_info.text1.size() > 0) { + QColor color = timeline_colors[(int)TimelineType::AlertInfo]; + if (alert_info.status == cereal::ControlsState::AlertStatus::USER_PROMPT) { + color = timeline_colors[(int)TimelineType::AlertWarning]; + } else if (alert_info.status == cereal::ControlsState::AlertStatus::CRITICAL) { + color = timeline_colors[(int)TimelineType::AlertCritical]; + } + color.setAlphaF(0.5); + QString text = alert_info.text1; + if (!alert_info.text2.isEmpty()) { + text += "\n" + alert_info.text2; + } + + if (!pixmap.isNull()) { + QFont font; + font.setPixelSize(11); + p.setFont(font); + } + QRect text_rect = rect().adjusted(2, 2, -2, -2); + QRect r = p.fontMetrics().boundingRect(text_rect, Qt::AlignTop | Qt::AlignHCenter | Qt::TextWordWrap, text); + p.fillRect(text_rect.left(), r.top(), text_rect.width(), r.height(), color); + p.drawText(text_rect, Qt::AlignTop | Qt::AlignHCenter | Qt::TextWordWrap, text); + } } diff --git a/tools/cabana/videowidget.h b/tools/cabana/videowidget.h index 00b059428d..960053f9a3 100644 --- a/tools/cabana/videowidget.h +++ b/tools/cabana/videowidget.h @@ -13,13 +13,21 @@ #include "selfdrive/ui/qt/widgets/cameraview.h" #include "tools/cabana/streams/abstractstream.h" -class ThumbnailLabel : public QWidget { +struct AlertInfo { + cereal::ControlsState::AlertStatus status; + QString text1; + QString text2; +}; + +class InfoLabel : public QWidget { public: - ThumbnailLabel(QWidget *parent); - void showPixmap(const QPoint &pt, const QString &sec, const QPixmap &pm); + InfoLabel(QWidget *parent); + void showPixmap(const QPoint &pt, const QString &sec, const QPixmap &pm, const AlertInfo &alert); + void showAlert(const AlertInfo &alert); void paintEvent(QPaintEvent *event) override; QPixmap pixmap; QString second; + AlertInfo alert_info; }; class Slider : public QSlider { @@ -32,7 +40,7 @@ public: private: void mousePressEvent(QMouseEvent *e) override; void mouseMoveEvent(QMouseEvent *e) override; - void leaveEvent(QEvent *event) override; + bool event(QEvent *event) override; void sliderChange(QAbstractSlider::SliderChange change) override; void paintEvent(QPaintEvent *ev) override; void streamStarted(); @@ -43,9 +51,11 @@ private: std::mutex thumbnail_lock; std::atomic abort_load_thumbnail = false; QMap thumbnails; + std::map alerts; QFuture thumnail_future; - ThumbnailLabel thumbnail_label; + InfoLabel thumbnail_label; QTimer timer; + friend class VideoWidget; }; class VideoWidget : public QFrame { @@ -65,5 +75,6 @@ protected: QLabel *time_label; QHBoxLayout *slider_layout; QPushButton *play_btn; + InfoLabel *alert_label; Slider *slider; }; diff --git a/tools/plotjuggler/layouts/camera-timings.xml b/tools/plotjuggler/layouts/camera-timings.xml new file mode 100644 index 0000000000..bef2adb00b --- /dev/null +++ b/tools/plotjuggler/layouts/camera-timings.xml @@ -0,0 +1,100 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/tools/plotjuggler/layouts/ublox-debug.xml b/tools/plotjuggler/layouts/ublox-debug.xml new file mode 100644 index 0000000000..d595a9ecc7 --- /dev/null +++ b/tools/plotjuggler/layouts/ublox-debug.xml @@ -0,0 +1,44 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +