diff --git a/RELEASES.md b/RELEASES.md index 989df5c7bf..ed42b577fe 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -3,7 +3,7 @@ Version 0.9.2 (2023-03-XX) * Draw MPC path instead of model predicted path, this is a more accurate representation of what the car will do. * Honda HR-V 2023 support thanks to Takeda! -Version 0.9.1 (2023-02-23) +Version 0.9.1 (2023-02-28) ======================== * New driving model * 30% improved height estimation resulting in better driving performance for tall cars diff --git a/cereal b/cereal index b88523f05a..42f84fd85d 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit b88523f05ac958f87a8f6d57c3f4bb20da55f216 +Subproject commit 42f84fd85d06c0fc85371daa2b4820fca49d763e diff --git a/common/params.cc b/common/params.cc index 2ba4f7e8ab..e74c63bf6a 100644 --- a/common/params.cc +++ b/common/params.cc @@ -99,7 +99,6 @@ std::unordered_map keys = { {"CompletedTrainingVersion", PERSISTENT}, {"ControlsReady", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_ON}, {"CurrentRoute", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_ON}, - {"DashcamOverride", PERSISTENT}, {"DisableLogging", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_ON}, {"DisablePowerDown", PERSISTENT}, {"ExperimentalMode", PERSISTENT}, diff --git a/docs/CARS.md b/docs/CARS.md index 65728eaf5a..7bc29cbc66 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -182,7 +182,7 @@ A supported vehicle is one that just works when you install a comma three. All s |Toyota|C-HR Hybrid 2017-20|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Toyota|| |Toyota|C-HR Hybrid 2021-22|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Toyota|| |Toyota|Camry 2018-20|All|Stock|0 mph[6](#footnotes)|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Toyota|| -|Toyota|Camry 2021-22|All|openpilot|0 mph[6](#footnotes)|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Toyota|| +|Toyota|Camry 2021-23|All|openpilot|0 mph[6](#footnotes)|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Toyota|| |Toyota|Camry Hybrid 2018-20|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Toyota|| |Toyota|Camry Hybrid 2021-23|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Toyota|| |Toyota|Corolla 2017-19|All|openpilot available[2](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Toyota|| diff --git a/laika_repo b/laika_repo index 278b44ba8c..b740b71c82 160000 --- a/laika_repo +++ b/laika_repo @@ -1 +1 @@ -Subproject commit 278b44ba8c2dec28adc5b30cce13dabc195f15fc +Subproject commit b740b71c82a748e3520b1599487d9a7aaf728670 diff --git a/panda b/panda index 9fe24bd368..e0e754de2c 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 9fe24bd3683377146b04c68ab94d0935f0bd9d78 +Subproject commit e0e754de2c7fdbf943dd02db203b7bb40bf3e9b5 diff --git a/poetry.lock b/poetry.lock index 91e1b5c826..ec4022c81f 100644 --- a/poetry.lock +++ b/poetry.lock @@ -4355,6 +4355,14 @@ python-versions = "*" [package.dependencies] types-urllib3 = "<1.27" +[[package]] +name = "types-tabulate" +version = "0.9.0.1" +description = "Typing stubs for tabulate" +category = "main" +optional = false +python-versions = "*" + [[package]] name = "types-urllib3" version = "1.26.25.1" @@ -4567,7 +4575,7 @@ testing = ["coverage (>=5.0.3)", "zope.event", "zope.testing"] [metadata] lock-version = "1.1" python-versions = "~3.8" -content-hash = "9e9495c896e6fd0855803aeaf46513c6c22424b86be820759a8baf27d44e73ee" +content-hash = "669485055bf8d77336509cb7a3878e06aa32431c520825948914d76b57347fde" [metadata.files] adal = [ @@ -6616,7 +6624,6 @@ onnx = [ ] onnx2torch = [ {file = "onnx2torch-1.5.4-py3-none-any.whl", hash = "sha256:fd1a0fe05072bfb9f3d86d9330299b130b41f11bd4ae634db17078974e711725"}, - {file = "onnx2torch-1.5.4.tar.gz", hash = "sha256:df837b557a63540223d85fde4a1d679fde0ca8d8bb89d5379c030b01eddc9c24"}, ] onnxoptimizer = [ {file = "onnxoptimizer-0.3.1-cp37-cp37m-macosx_10_15_x86_64.whl", hash = "sha256:e73a5e2e3ca4db9bff54f7131768749c861677b97ee811a136fcf1a52783cf6e"}, @@ -7002,7 +7009,6 @@ pycryptodome = [ {file = "pycryptodome-3.15.0-cp27-cp27m-manylinux2010_i686.whl", hash = "sha256:7c9ed8aa31c146bef65d89a1b655f5f4eab5e1120f55fc297713c89c9e56ff0b"}, {file = "pycryptodome-3.15.0-cp27-cp27m-manylinux2010_x86_64.whl", hash = "sha256:5099c9ca345b2f252f0c28e96904643153bae9258647585e5e6f649bb7a1844a"}, {file = "pycryptodome-3.15.0-cp27-cp27m-manylinux2014_aarch64.whl", hash = "sha256:2ec709b0a58b539a4f9d33fb8508264c3678d7edb33a68b8906ba914f71e8c13"}, - {file = "pycryptodome-3.15.0-cp27-cp27m-musllinux_1_1_aarch64.whl", hash = "sha256:2ae53125de5b0d2c95194d957db9bb2681da8c24d0fb0fe3b056de2bcaf5d837"}, {file = "pycryptodome-3.15.0-cp27-cp27m-win32.whl", hash = "sha256:fd2184aae6ee2a944aaa49113e6f5787cdc5e4db1eb8edb1aea914bd75f33a0c"}, {file = "pycryptodome-3.15.0-cp27-cp27m-win_amd64.whl", hash = "sha256:7e3a8f6ee405b3bd1c4da371b93c31f7027944b2bcce0697022801db93120d83"}, {file = "pycryptodome-3.15.0-cp27-cp27mu-manylinux1_i686.whl", hash = "sha256:b9c5b1a1977491533dfd31e01550ee36ae0249d78aae7f632590db833a5012b8"}, @@ -7010,14 +7016,12 @@ pycryptodome = [ {file = "pycryptodome-3.15.0-cp27-cp27mu-manylinux2010_i686.whl", hash = "sha256:2aa55aae81f935a08d5a3c2042eb81741a43e044bd8a81ea7239448ad751f763"}, {file = "pycryptodome-3.15.0-cp27-cp27mu-manylinux2010_x86_64.whl", hash = "sha256:c3640deff4197fa064295aaac10ab49a0d55ef3d6a54ae1499c40d646655c89f"}, {file = "pycryptodome-3.15.0-cp27-cp27mu-manylinux2014_aarch64.whl", hash = "sha256:045d75527241d17e6ef13636d845a12e54660aa82e823b3b3341bcf5af03fa79"}, - {file = "pycryptodome-3.15.0-cp27-cp27mu-musllinux_1_1_aarch64.whl", hash = "sha256:eb6fce570869e70cc8ebe68eaa1c26bed56d40ad0f93431ee61d400525433c54"}, {file = "pycryptodome-3.15.0-cp35-abi3-macosx_10_9_x86_64.whl", hash = "sha256:9ee40e2168f1348ae476676a2e938ca80a2f57b14a249d8fe0d3cdf803e5a676"}, {file = "pycryptodome-3.15.0-cp35-abi3-manylinux1_i686.whl", hash = "sha256:4c3ccad74eeb7b001f3538643c4225eac398c77d617ebb3e57571a897943c667"}, {file = "pycryptodome-3.15.0-cp35-abi3-manylinux1_x86_64.whl", hash = "sha256:1b22bcd9ec55e9c74927f6b1f69843cb256fb5a465088ce62837f793d9ffea88"}, {file = "pycryptodome-3.15.0-cp35-abi3-manylinux2010_i686.whl", hash = "sha256:57f565acd2f0cf6fb3e1ba553d0cb1f33405ec1f9c5ded9b9a0a5320f2c0bd3d"}, {file = "pycryptodome-3.15.0-cp35-abi3-manylinux2010_x86_64.whl", hash = "sha256:4b52cb18b0ad46087caeb37a15e08040f3b4c2d444d58371b6f5d786d95534c2"}, {file = "pycryptodome-3.15.0-cp35-abi3-manylinux2014_aarch64.whl", hash = "sha256:092a26e78b73f2530b8bd6b3898e7453ab2f36e42fd85097d705d6aba2ec3e5e"}, - {file = "pycryptodome-3.15.0-cp35-abi3-musllinux_1_1_aarch64.whl", hash = "sha256:50ca7e587b8e541eb6c192acf92449d95377d1f88908c0a32ac5ac2703ebe28b"}, {file = "pycryptodome-3.15.0-cp35-abi3-win32.whl", hash = "sha256:e244ab85c422260de91cda6379e8e986405b4f13dc97d2876497178707f87fc1"}, {file = "pycryptodome-3.15.0-cp35-abi3-win_amd64.whl", hash = "sha256:c77126899c4b9c9827ddf50565e93955cb3996813c18900c16b2ea0474e130e9"}, {file = "pycryptodome-3.15.0-pp27-pypy_73-macosx_10_9_x86_64.whl", hash = "sha256:9eaadc058106344a566dc51d3d3a758ab07f8edde013712bc8d22032a86b264f"}, @@ -7659,18 +7663,6 @@ setproctitle = [ {file = "setproctitle-1.3.2-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:7f2719a398e1a2c01c2a63bf30377a34d0b6ef61946ab9cf4d550733af8f1ef1"}, {file = "setproctitle-1.3.2-cp310-cp310-win32.whl", hash = "sha256:e425be62524dc0c593985da794ee73eb8a17abb10fe692ee43bb39e201d7a099"}, {file = "setproctitle-1.3.2-cp310-cp310-win_amd64.whl", hash = "sha256:e85e50b9c67854f89635a86247412f3ad66b132a4d8534ac017547197c88f27d"}, - {file = "setproctitle-1.3.2-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:2a97d51c17d438cf5be284775a322d57b7ca9505bb7e118c28b1824ecaf8aeaa"}, - {file = "setproctitle-1.3.2-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:587c7d6780109fbd8a627758063d08ab0421377c0853780e5c356873cdf0f077"}, - {file = "setproctitle-1.3.2-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d7d17c8bd073cbf8d141993db45145a70b307385b69171d6b54bcf23e5d644de"}, - {file = "setproctitle-1.3.2-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:e932089c35a396dc31a5a1fc49889dd559548d14cb2237adae260382a090382e"}, - {file = "setproctitle-1.3.2-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:8e4f8f12258a8739c565292a551c3db62cca4ed4f6b6126664e2381acb4931bf"}, - {file = "setproctitle-1.3.2-cp311-cp311-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:570d255fd99c7f14d8f91363c3ea96bd54f8742275796bca67e1414aeca7d8c3"}, - {file = "setproctitle-1.3.2-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:a8e0881568c5e6beff91ef73c0ec8ac2a9d3ecc9edd6bd83c31ca34f770910c4"}, - {file = "setproctitle-1.3.2-cp311-cp311-musllinux_1_1_i686.whl", hash = "sha256:4bba3be4c1fabf170595b71f3af46c6d482fbe7d9e0563999b49999a31876f77"}, - {file = "setproctitle-1.3.2-cp311-cp311-musllinux_1_1_ppc64le.whl", hash = "sha256:37ece938110cab2bb3957e3910af8152ca15f2b6efdf4f2612e3f6b7e5459b80"}, - {file = "setproctitle-1.3.2-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:db684d6bbb735a80bcbc3737856385b55d53f8a44ce9b46e9a5682c5133a9bf7"}, - {file = "setproctitle-1.3.2-cp311-cp311-win32.whl", hash = "sha256:ca58cd260ea02759238d994cfae844fc8b1e206c684beb8f38877dcab8451dfc"}, - {file = "setproctitle-1.3.2-cp311-cp311-win_amd64.whl", hash = "sha256:88486e6cce2a18a033013d17b30a594f1c5cb42520c49c19e6ade40b864bb7ff"}, {file = "setproctitle-1.3.2-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:92c626edc66169a1b09e9541b9c0c9f10488447d8a2b1d87c8f0672e771bc927"}, {file = "setproctitle-1.3.2-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:710e16fa3bade3b026907e4a5e841124983620046166f355bbb84be364bf2a02"}, {file = "setproctitle-1.3.2-cp37-cp37m-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:1f29b75e86260b0ab59adb12661ef9f113d2f93a59951373eb6d68a852b13e83"}, @@ -8066,6 +8058,10 @@ types-requests = [ {file = "types-requests-2.28.11.2.tar.gz", hash = "sha256:fdcd7bd148139fb8eef72cf4a41ac7273872cad9e6ada14b11ff5dfdeee60ed3"}, {file = "types_requests-2.28.11.2-py3-none-any.whl", hash = "sha256:14941f8023a80b16441b3b46caffcbfce5265fd14555844d6029697824b5a2ef"}, ] +types-tabulate = [ + {file = "types-tabulate-0.9.0.1.tar.gz", hash = "sha256:e486292c279f19247865bdabe802419740a0e74b53444e7f7a8009e08129da5d"}, + {file = "types_tabulate-0.9.0.1-py3-none-any.whl", hash = "sha256:be2ea0de05f615ccfcbadf6206aa720e265955eb1de23e343aec9d8bf3fa9aaa"}, +] types-urllib3 = [ {file = "types-urllib3-1.26.25.1.tar.gz", hash = "sha256:a948584944b2412c9a74b9cf64f6c48caf8652cb88b38361316f6d15d8a184cd"}, {file = "types_urllib3-1.26.25.1-py3-none-any.whl", hash = "sha256:f6422596cc9ee5fdf68f9d547f541096a20c2dcfd587e37c804c9ea720bf5cb2"}, diff --git a/pyproject.toml b/pyproject.toml index 6b4b0bb5fa..b1ad273cd7 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" +types-tabulate = "^0.9.0.1" [tool.poetry.group.dev.dependencies] diff --git a/release/check-submodules.sh b/release/check-submodules.sh index 2585db6bd7..5f4e307e49 100755 --- a/release/check-submodules.sh +++ b/release/check-submodules.sh @@ -1,7 +1,7 @@ #!/bin/bash while read hash submodule ref; do - git -C $submodule fetch --depth 300 origin master + git -C $submodule fetch --depth 1000 origin master git -C $submodule branch -r --contains $hash | grep "origin/master" if [ "$?" -eq 0 ]; then echo "$submodule ok" diff --git a/release/files_common b/release/files_common index 5b310d5c80..e0f989e9be 100644 --- a/release/files_common +++ b/release/files_common @@ -577,13 +577,14 @@ opendbc/tesla_can.dbc opendbc/tesla_radar.dbc opendbc/tesla_powertrain.dbc -tinygrad_repo/accel/opencl/* -tinygrad_repo/tinygrad/llops/ops_opencl.py tinygrad_repo/openpilot/compile.py tinygrad_repo/extra/onnx.py +tinygrad_repo/extra/onnx_ops.py tinygrad_repo/extra/thneed.py tinygrad_repo/extra/utils.py -tinygrad_repo/tinygrad/llops/ops_gpu.py -tinygrad_repo/tinygrad/shape/* +tinygrad_repo/tinygrad/codegen/ast.py +tinygrad_repo/tinygrad/codegen/gpu.py tinygrad_repo/tinygrad/nn/* +tinygrad_repo/tinygrad/runtime/ops_gpu.py +tinygrad_repo/tinygrad/shape/* tinygrad_repo/tinygrad/*.py diff --git a/selfdrive/assets/img_driver_face.png b/selfdrive/assets/img_driver_face.png index 03765a0376..e2d943e537 100644 Binary files a/selfdrive/assets/img_driver_face.png and b/selfdrive/assets/img_driver_face.png differ diff --git a/selfdrive/assets/img_driver_face_static.png b/selfdrive/assets/img_driver_face_static.png new file mode 100644 index 0000000000..d8bc5f1371 Binary files /dev/null and b/selfdrive/assets/img_driver_face_static.png differ diff --git a/selfdrive/car/__init__.py b/selfdrive/car/__init__.py index c056f7ca3d..58cde85817 100644 --- a/selfdrive/car/__init__.py +++ b/selfdrive/car/__init__.py @@ -73,7 +73,7 @@ def dbc_dict(pt_dbc, radar_dbc, chassis_dbc=None, body_dbc=None) -> Dict[str, st return {'pt': pt_dbc, 'radar': radar_dbc, 'chassis': chassis_dbc, 'body': body_dbc} -def apply_std_steer_torque_limits(apply_torque, apply_torque_last, driver_torque, LIMITS): +def apply_driver_steer_torque_limits(apply_torque, apply_torque_last, driver_torque, LIMITS): # limits due to driver torque driver_max_torque = LIMITS.STEER_MAX + (LIMITS.STEER_DRIVER_ALLOWANCE + driver_torque * LIMITS.STEER_DRIVER_FACTOR) * LIMITS.STEER_DRIVER_MULTIPLIER @@ -93,29 +93,37 @@ def apply_std_steer_torque_limits(apply_torque, apply_torque_last, driver_torque return int(round(float(apply_torque))) -def apply_toyota_steer_torque_limits(apply_torque, apply_torque_last, motor_torque, LIMITS): - # limits due to comparison of commanded torque VS motor reported torque - max_lim = min(max(motor_torque + LIMITS.STEER_ERROR_MAX, LIMITS.STEER_ERROR_MAX), LIMITS.STEER_MAX) - min_lim = max(min(motor_torque - LIMITS.STEER_ERROR_MAX, -LIMITS.STEER_ERROR_MAX), -LIMITS.STEER_MAX) +def apply_dist_to_meas_limits(val, val_last, val_meas, + STEER_DELTA_UP, STEER_DELTA_DOWN, + STEER_ERROR_MAX, STEER_MAX): + # limits due to comparison of commanded val VS measured val (torque/angle/curvature) + max_lim = min(max(val_meas + STEER_ERROR_MAX, STEER_ERROR_MAX), STEER_MAX) + min_lim = max(min(val_meas - STEER_ERROR_MAX, -STEER_ERROR_MAX), -STEER_MAX) - apply_torque = clip(apply_torque, min_lim, max_lim) + val = clip(val, min_lim, max_lim) - # slow rate if steer torque increases in magnitude - if apply_torque_last > 0: - apply_torque = clip(apply_torque, - max(apply_torque_last - LIMITS.STEER_DELTA_DOWN, -LIMITS.STEER_DELTA_UP), - apply_torque_last + LIMITS.STEER_DELTA_UP) + # slow rate if val increases in magnitude + if val_last > 0: + val = clip(val, + max(val_last - STEER_DELTA_DOWN, -STEER_DELTA_UP), + val_last + STEER_DELTA_UP) else: - apply_torque = clip(apply_torque, - apply_torque_last - LIMITS.STEER_DELTA_UP, - min(apply_torque_last + LIMITS.STEER_DELTA_DOWN, LIMITS.STEER_DELTA_UP)) + val = clip(val, + val_last - STEER_DELTA_UP, + min(val_last + STEER_DELTA_DOWN, STEER_DELTA_UP)) - return int(round(float(apply_torque))) + return float(val) + + +def apply_meas_steer_torque_limits(apply_torque, apply_torque_last, motor_torque, LIMITS): + return int(round(apply_dist_to_meas_limits(apply_torque, apply_torque_last, motor_torque, + LIMITS.STEER_DELTA_UP, LIMITS.STEER_DELTA_DOWN, + LIMITS.STEER_ERROR_MAX, LIMITS.STEER_MAX))) def apply_std_steer_angle_limits(apply_angle, apply_angle_last, v_ego, LIMITS): # pick angle rate limits based on wind up/down - steer_up = apply_angle_last * apply_angle > 0. and abs(apply_angle) > abs(apply_angle_last) + steer_up = apply_angle_last * apply_angle >= 0. and abs(apply_angle) > abs(apply_angle_last) rate_limits = LIMITS.ANGLE_RATE_LIMIT_UP if steer_up else LIMITS.ANGLE_RATE_LIMIT_DOWN angle_rate_lim = interp(v_ego, rate_limits.speed_bp, rate_limits.angle_v) diff --git a/selfdrive/car/chrysler/carcontroller.py b/selfdrive/car/chrysler/carcontroller.py index 20a44bce21..b418179e0e 100644 --- a/selfdrive/car/chrysler/carcontroller.py +++ b/selfdrive/car/chrysler/carcontroller.py @@ -1,6 +1,6 @@ from opendbc.can.packer import CANPacker from common.realtime import DT_CTRL -from selfdrive.car import apply_toyota_steer_torque_limits +from selfdrive.car import apply_meas_steer_torque_limits from selfdrive.car.chrysler.chryslercan import create_lkas_hud, create_lkas_command, create_cruise_buttons from selfdrive.car.chrysler.values import RAM_CARS, CarControllerParams, ChryslerFlags @@ -67,7 +67,7 @@ class CarController: # steer torque new_steer = int(round(CC.actuators.steer * self.params.STEER_MAX)) - apply_steer = apply_toyota_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorqueEps, self.params) + apply_steer = apply_meas_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorqueEps, self.params) if not lkas_active or not lkas_control_bit: apply_steer = 0 self.apply_steer_last = apply_steer diff --git a/selfdrive/car/chrysler/values.py b/selfdrive/car/chrysler/values.py index 2a5daf440c..2af5246b88 100644 --- a/selfdrive/car/chrysler/values.py +++ b/selfdrive/car/chrysler/values.py @@ -135,7 +135,7 @@ FINGERPRINTS = { }], CAR.JEEP_CHEROKEE_2019: [{ # Jeep Grand Cherokee 2019, including most 2020 models - 55: 8, 168: 8, 179: 8, 181: 8, 256: 4, 257: 5, 258: 8, 264: 8, 268: 8, 272: 6, 273: 6, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 341: 8, 344: 8, 352: 8, 362: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 530: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 8, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 618: 8, 624: 8, 625: 8, 632: 8, 639: 8, 640: 1, 656: 4, 658: 6, 660: 8, 671: 8, 672: 8, 676: 8, 678: 8, 680: 8, 683: 8, 684: 8, 703: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 738: 8, 746: 5, 752: 2, 754: 8, 760: 8, 761: 8, 764: 8, 766: 8, 773: 8, 776: 8, 779: 8, 782: 8, 783: 8, 784: 8, 785: 8, 792: 8, 799: 8, 800: 8, 804: 8, 806: 2, 808: 8, 810: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 831: 6, 832: 8, 838: 2, 840: 8, 844: 5, 847: 1, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 874: 2, 882: 8, 897: 8, 906: 8, 924: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 960: 4, 968: 8, 969: 4, 970: 8, 973: 8, 974: 5, 976: 8, 977: 4, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1062: 8, 1098: 8, 1100: 8, 1216: 8, 1218: 8, 1220: 8, 1223: 8, 1225: 8, 1227: 8, 1235: 8, 1242: 8, 1250: 8, 1251: 8, 1252: 8, 1254: 8, 1264: 8, 1284: 8, 1536: 8, 1537: 8, 1543: 8, 1545: 8, 1562: 8, 1568: 8, 1570: 8, 1572: 8, 1593: 8, 1856: 8, 1858: 8, 1860: 8, 1863: 8, 1865: 8, 1867: 8, 1875: 8, 1882: 8, 1890: 8, 1891: 8, 1892: 8, 1894: 8, 1896: 8, 1904: 8, 2015: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8 + 55: 8, 168: 8, 179: 8, 181: 8, 256: 4, 257: 5, 258: 8, 264: 8, 268: 8, 272: 6, 273: 6, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 341: 8, 344: 8, 352: 8, 362: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 530: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 8, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 618: 8, 624: 8, 625: 8, 632: 8, 639: 8, 640: 1, 656: 4, 658: 6, 660: 8, 671: 8, 672: 8, 676: 8, 678: 8, 680: 8, 683: 8, 684: 8, 703: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 738: 8, 746: 5, 752: 2, 754: 8, 760: 8, 761: 8, 764: 8, 766: 8, 773: 8, 776: 8, 779: 8, 782: 8, 783: 8, 784: 8, 785: 8, 792: 8, 799: 8, 800: 8, 804: 8, 806: 2, 808: 8, 810: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 831: 6, 832: 8, 838: 2, 840: 8, 844: 5, 847: 1, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 874: 2, 882: 8, 897: 8, 906: 8, 924: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 960: 4, 968: 8, 969: 4, 970: 8, 973: 8, 974: 5, 976: 8, 977: 4, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1062: 8, 1098: 8, 1100: 8, 1216: 8, 1218: 8, 1220: 8, 1223: 8, 1225: 8, 1227: 8, 1235: 8, 1242: 8, 1250: 8, 1251: 8, 1252: 8, 1254: 8, 1264: 8, 1284: 8, 1536: 8, 1537: 8, 1538: 8, 1543: 8, 1545: 8, 1562: 8, 1568: 8, 1570: 8, 1572: 8, 1593: 8, 1856: 8, 1858: 8, 1860: 8, 1863: 8, 1865: 8, 1867: 8, 1875: 8, 1882: 8, 1890: 8, 1891: 8, 1892: 8, 1894: 8, 1896: 8, 1904: 8, 2015: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8 }], } diff --git a/selfdrive/car/ford/values.py b/selfdrive/car/ford/values.py index 1c8917446a..50c7d93987 100644 --- a/selfdrive/car/ford/values.py +++ b/selfdrive/car/ford/values.py @@ -28,8 +28,8 @@ class CarControllerParams: # Curvature rate limits # TODO: unify field names used by curvature and angle control cars - # ~2 m/s^3 up, -3 m/s^3 down - ANGLE_RATE_LIMIT_UP = AngleRateLimit(speed_bp=[5, 15, 25], angle_v=[0.004, 0.00044, 0.0002]) + # ~2 m/s^3 up, ~-3 m/s^3 down + ANGLE_RATE_LIMIT_UP = AngleRateLimit(speed_bp=[5, 15, 25], angle_v=[0.004, 0.00044, 0.00016]) ANGLE_RATE_LIMIT_DOWN = AngleRateLimit(speed_bp=[5, 15, 25], angle_v=[0.006, 0.00066, 0.00024]) ACCEL_MAX = 2.0 # m/s^s max acceleration @@ -165,6 +165,7 @@ FW_VERSIONS = { b'M1MC-14D003-AB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.abs, 0x760, None): [ + b'L1MC-2D053-BA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'L1MC-2D053-BB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'L1MC-2D053-BF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'L1MC-2D053-KB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', @@ -178,6 +179,7 @@ FW_VERSIONS = { b'LC5T-14F397-AH\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.engine, 0x7E0, None): [ + b'LB5A-14C204-BUJ\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'LB5A-14C204-EAC\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'MB5A-14C204-MD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'MB5A-14C204-RC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', diff --git a/selfdrive/car/gm/carcontroller.py b/selfdrive/car/gm/carcontroller.py index 42eaf7e88a..2a996c0ff6 100644 --- a/selfdrive/car/gm/carcontroller.py +++ b/selfdrive/car/gm/carcontroller.py @@ -3,7 +3,7 @@ from common.conversions import Conversions as CV from common.numpy_fast import interp from common.realtime import DT_CTRL from opendbc.can.packer import CANPacker -from selfdrive.car import apply_std_steer_torque_limits +from selfdrive.car import apply_driver_steer_torque_limits from selfdrive.car.gm import gmcan from selfdrive.car.gm.values import DBC, CanBus, CarControllerParams, CruiseButtons @@ -73,7 +73,7 @@ class CarController: if CC.latActive: new_steer = int(round(actuators.steer * self.params.STEER_MAX)) - apply_steer = apply_std_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.params) + apply_steer = apply_driver_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.params) else: apply_steer = 0 diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py index 7bf8c89fbd..0e48670cca 100644 --- a/selfdrive/car/honda/values.py +++ b/selfdrive/car/honda/values.py @@ -370,10 +370,12 @@ FW_VERSIONS = { b'57114-TWA-A050\x00\x00', b'57114-TWA-A530\x00\x00', b'57114-TWA-B520\x00\x00', + b'57114-TWB-H030\x00\x00', ], (Ecu.srs, 0x18da53f1, None): [ b'77959-TWA-A440\x00\x00', b'77959-TWA-L420\x00\x00', + b'77959-TWB-H220\x00\x00', ], (Ecu.combinationMeter, 0x18da60f1, None): [ b'78109-TWA-A010\x00\x00', @@ -387,6 +389,7 @@ FW_VERSIONS = { b'78109-TWA-A230\x00\x00', b'78109-TWA-L010\x00\x00', b'78109-TWA-L210\x00\x00', + b'78109-TWA-H210\x00\x00', ], (Ecu.shiftByWire, 0x18da0bf1, None): [ b'54008-TWA-A910\x00\x00', @@ -398,16 +401,19 @@ FW_VERSIONS = { (Ecu.fwdCamera, 0x18dab5f1, None): [ b'36161-TWA-A070\x00\x00', b'36161-TWA-A330\x00\x00', + b'36161-TWB-H040\x00\x00', ], (Ecu.fwdRadar, 0x18dab0f1, None): [ b'36802-TWA-A070\x00\x00', b'36802-TWA-A080\x00\x00', b'36802-TWA-A330\x00\x00', + b'36802-TWB-H060\x00\x00', ], (Ecu.eps, 0x18da30f1, None): [ b'39990-TVA-A160\x00\x00', b'39990-TVA-A150\x00\x00', b'39990-TVA-A340\x00\x00', + b'39990-TWB-H120\x00\x00', ], }, CAR.CIVIC: { diff --git a/selfdrive/car/hyundai/carcontroller.py b/selfdrive/car/hyundai/carcontroller.py index 1e6f78af20..2572038492 100644 --- a/selfdrive/car/hyundai/carcontroller.py +++ b/selfdrive/car/hyundai/carcontroller.py @@ -3,7 +3,7 @@ from common.conversions import Conversions as CV from common.numpy_fast import clip from common.realtime import DT_CTRL from opendbc.can.packer import CANPacker -from selfdrive.car import apply_std_steer_torque_limits +from selfdrive.car import apply_driver_steer_torque_limits from selfdrive.car.hyundai import hyundaicanfd, hyundaican from selfdrive.car.hyundai.values import HyundaiFlags, Buttons, CarControllerParams, CANFD_CAR, CAR @@ -60,7 +60,7 @@ class CarController: # steering torque new_steer = int(round(actuators.steer * self.params.STEER_MAX)) - apply_steer = apply_std_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.params) + apply_steer = apply_driver_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.params) if not CC.latActive: apply_steer = 0 diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 4b7a295246..cf0143543a 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -512,7 +512,6 @@ FW_VERSIONS = { 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 ', - b'\xf1\x8799110L0000\xf1\x00DN8_ SCC FHCUP 1.00 1.00 99110-L0000 ', ], (Ecu.abs, 0x7d1, None): [ b'\xf1\x00DN ESC \x07 106 \x07\x01 58910-L0100', @@ -525,7 +524,6 @@ FW_VERSIONS = { 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', b'\xf1\x8758910-L0100\xf1\x00DN ESC \x07 104\x19\x08\x01 58910-L0100', - b'\xf1\x8758910-L0300\xf1\x00DN ESC \x03 100 \x08\x01 58910-L0300', b'\xf1\x00DN ESC \x06 106 \x07\x01 58910-L0100', ], (Ecu.engine, 0x7e0, None): [ @@ -587,6 +585,7 @@ FW_VERSIONS = { b'\xf1\x00HT6WA280BLHT6WAD10A1SDN8G25NB4\x00\x00\x00\x00\x00\x00g!l[', b'\xf1\x00T02601BL T02730A1 VDN8T25XXX730NS5\xf7_\x92\xf5', b'\xf1\x00T02601BL T02832A1 VDN8T25XXX832NS8G\x0e\xfeE', + b'\xf1\x00T02601BL T02900A1 VDN8T25XXX900NSCF\xe4!Y', b'\xf1\x87954A02N060\x00\x00\x00\x00\x00\xf1\x81T02730A1 \xf1\x00T02601BL T02730A1 VDN8T25XXX730NS5\xf7_\x92\xf5', b'\xf1\x87SAKFBA2926554GJ2VefVww\x87xwwwww\x88\x87xww\x87wTo\xfb\xffvUo\xff\x8d\x16\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v', b'\xf1\x87SAKFBA3030524GJ2UVugww\x97yx\x88\x87\x88vw\x87gww\x87wto\xf9\xfffUo\xff\xa2\x0c\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v', @@ -1566,6 +1565,7 @@ FW_VERSIONS = { b'\xf1\x00NE1 MFC AT EUR RHD 1.00 1.01 99211-GI010 211007', b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.01 99211-GI010 211007', b'\xf1\x00NE1 MFC AT EUR RHD 1.00 1.02 99211-GI010 211206', + b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.03 99211-GI010 220401', ], }, CAR.TUCSON_4TH_GEN: { diff --git a/selfdrive/car/mazda/carcontroller.py b/selfdrive/car/mazda/carcontroller.py index 524a02a370..cb401a8abd 100644 --- a/selfdrive/car/mazda/carcontroller.py +++ b/selfdrive/car/mazda/carcontroller.py @@ -1,6 +1,6 @@ from cereal import car from opendbc.can.packer import CANPacker -from selfdrive.car import apply_std_steer_torque_limits +from selfdrive.car import apply_driver_steer_torque_limits from selfdrive.car.mazda import mazdacan from selfdrive.car.mazda.values import CarControllerParams, Buttons @@ -23,8 +23,8 @@ class CarController: if CC.latActive: # calculate steer and also set limits due to driver torque new_steer = int(round(CC.actuators.steer * CarControllerParams.STEER_MAX)) - apply_steer = apply_std_steer_torque_limits(new_steer, self.apply_steer_last, - CS.out.steeringTorque, CarControllerParams) + apply_steer = apply_driver_steer_torque_limits(new_steer, self.apply_steer_last, + CS.out.steeringTorque, CarControllerParams) if CC.cruiseControl.cancel: # If brake is pressed, let us wait >70ms before trying to disable crz to avoid diff --git a/selfdrive/car/subaru/carcontroller.py b/selfdrive/car/subaru/carcontroller.py index 24d85877d7..a6dbf4a39e 100644 --- a/selfdrive/car/subaru/carcontroller.py +++ b/selfdrive/car/subaru/carcontroller.py @@ -1,5 +1,5 @@ from opendbc.can.packer import CANPacker -from selfdrive.car import apply_std_steer_torque_limits +from selfdrive.car import apply_driver_steer_torque_limits from selfdrive.car.subaru import subarucan from selfdrive.car.subaru.values import DBC, GLOBAL_GEN2, PREGLOBAL_CARS, CarControllerParams @@ -34,7 +34,7 @@ class CarController: # limits due to driver torque new_steer = int(round(apply_steer)) - apply_steer = apply_std_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.p) + apply_steer = apply_driver_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.p) if not CC.latActive: apply_steer = 0 diff --git a/selfdrive/car/toyota/carcontroller.py b/selfdrive/car/toyota/carcontroller.py index 2e0d7009c8..8004ea9dca 100644 --- a/selfdrive/car/toyota/carcontroller.py +++ b/selfdrive/car/toyota/carcontroller.py @@ -1,6 +1,6 @@ from cereal import car from common.numpy_fast import clip, interp -from selfdrive.car import apply_toyota_steer_torque_limits, create_gas_interceptor_command, make_can_msg +from selfdrive.car import apply_meas_steer_torque_limits, create_gas_interceptor_command, make_can_msg from selfdrive.car.toyota.toyotacan import create_steer_command, create_ui_command, \ create_accel_command, create_acc_cancel_command, \ create_fcw_command, create_lta_steer_command @@ -60,7 +60,7 @@ class CarController: # steer torque new_steer = int(round(actuators.steer * CarControllerParams.STEER_MAX)) - apply_steer = apply_toyota_steer_torque_limits(new_steer, self.last_steer, CS.out.steeringTorqueEps, self.torque_rate_limits) + apply_steer = apply_meas_steer_torque_limits(new_steer, self.last_steer, CS.out.steeringTorqueEps, self.torque_rate_limits) # Count up to MAX_STEER_RATE_FRAMES, at which point we need to cut torque to avoid a steering fault if lat_active and abs(CS.out.steeringRateDeg) >= MAX_STEER_RATE: diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 0639d46ec0..35e2db8b1e 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -115,7 +115,7 @@ CAR_INFO: Dict[str, Union[ToyotaCarInfo, List[ToyotaCarInfo]]] = { CAR.AVALONH_TSS2: ToyotaCarInfo("Toyota Avalon Hybrid 2022"), CAR.CAMRY: ToyotaCarInfo("Toyota Camry 2018-20", video_link="https://www.youtube.com/watch?v=fkcjviZY9CM", footnotes=[Footnote.CAMRY]), CAR.CAMRYH: ToyotaCarInfo("Toyota Camry Hybrid 2018-20", video_link="https://www.youtube.com/watch?v=Q2DYY0AWKgk"), - CAR.CAMRY_TSS2: ToyotaCarInfo("Toyota Camry 2021-22", footnotes=[Footnote.CAMRY]), + CAR.CAMRY_TSS2: ToyotaCarInfo("Toyota Camry 2021-23", footnotes=[Footnote.CAMRY]), CAR.CAMRYH_TSS2: ToyotaCarInfo("Toyota Camry Hybrid 2021-23"), CAR.CHR: ToyotaCarInfo("Toyota C-HR 2017-20"), CAR.CHR_TSS2: ToyotaCarInfo("Toyota C-HR 2021"), diff --git a/selfdrive/car/volkswagen/carcontroller.py b/selfdrive/car/volkswagen/carcontroller.py index 5d00b5a52f..c17b632450 100644 --- a/selfdrive/car/volkswagen/carcontroller.py +++ b/selfdrive/car/volkswagen/carcontroller.py @@ -3,7 +3,7 @@ from opendbc.can.packer import CANPacker from common.numpy_fast import clip from common.conversions import Conversions as CV from common.realtime import DT_CTRL -from selfdrive.car import apply_std_steer_torque_limits +from selfdrive.car import apply_driver_steer_torque_limits from selfdrive.car.volkswagen import mqbcan, pqcan from selfdrive.car.volkswagen.values import CANBUS, PQ_CARS, CarControllerParams @@ -44,7 +44,7 @@ class CarController: if CC.latActive: new_steer = int(round(actuators.steer * self.CCP.STEER_MAX)) - apply_steer = apply_std_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.CCP) + apply_steer = apply_driver_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.CCP) if apply_steer == 0: hcaEnabled = False self.hcaEnabledFrameCount = 0 diff --git a/selfdrive/car/volkswagen/values.py b/selfdrive/car/volkswagen/values.py index 158a178b03..4eef1307be 100755 --- a/selfdrive/car/volkswagen/values.py +++ b/selfdrive/car/volkswagen/values.py @@ -739,12 +739,14 @@ FW_VERSIONS = { b'\xf1\x8783A907115B \xf1\x890005', b'\xf1\x8783A907115F \xf1\x890002', b'\xf1\x8783A907115G \xf1\x890001', + b'\xf1\x8783A907115K \xf1\x890001', ], (Ecu.transmission, 0x7e1, None): [ b'\xf1\x8709G927158DT\xf1\x893698', b'\xf1\x8709G927158FM\xf1\x893757', b'\xf1\x8709G927158GC\xf1\x893821', b'\xf1\x8709G927158GD\xf1\x893820', + b'\xf1\x8709G927158GM\xf1\x893936', b'\xf1\x870D9300043 \xf1\x895202', b'\xf1\x870DL300011N \xf1\x892001', b'\xf1\x870DL300011N \xf1\x892012', @@ -775,6 +777,7 @@ FW_VERSIONS = { b'\xf1\x875QM909144B \xf1\x891081\xf1\x82\x0521A60604A1', b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\x0521A60604A1', b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\00521A60804A1', + b'\xf1\x875QM907144D \xf1\x891063\xf1\x82\x002SA6092SOM', ], (Ecu.fwdRadar, 0x757, None): [ b'\xf1\x872Q0907572AA\xf1\x890396', @@ -1049,6 +1052,7 @@ FW_VERSIONS = { (Ecu.engine, 0x7e0, None): [ b'\xf1\x8704E906027DD\xf1\x893123', b'\xf1\x8704L906026DE\xf1\x895418', + b'\xf1\x8704L906026HT\xf1\x893617', b'\xf1\x875NA907115E \xf1\x890003', b'\xf1\x875NA907115E \xf1\x890005', ], @@ -1060,17 +1064,20 @@ FW_VERSIONS = { ], (Ecu.srs, 0x715, None): [ b'\xf1\x873Q0959655BJ\xf1\x890703\xf1\x82\x0e1213001211001205212111052100', + b'\xf1\x873Q0959655BK\xf1\x890703\xf1\x82\x0e1213001211001244212111442100', b'\xf1\x873Q0959655CN\xf1\x890720\xf1\x82\x0e1213001211001205212112052100', b'\xf1\x873Q0959655CQ\xf1\x890720\xf1\x82\x0e1213111211001205212112052111', ], (Ecu.eps, 0x712, None): [ b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820527T6050405', b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820527T6060405', + b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820527T6070405', b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567T600G600', ], (Ecu.fwdRadar, 0x757, None): [ b'\xf1\x872Q0907572Q \xf1\x890342', b'\xf1\x872Q0907572R \xf1\x890372', + b'\xf1\x872Q0907572AA\xf1\x890396', ], }, CAR.SKODA_OCTAVIA_MK3: { @@ -1140,6 +1147,7 @@ FW_VERSIONS = { b'\xf1\x8704L906026FP\xf1\x891196', b'\xf1\x8704L906026KB\xf1\x894071', b'\xf1\x8704L906026KD\xf1\x894798', + b'\xf1\x873G0906259 \xf1\x890004', b'\xf1\x873G0906259B \xf1\x890002', b'\xf1\x873G0906264A \xf1\x890002', ], @@ -1149,12 +1157,14 @@ FW_VERSIONS = { b'\xf1\x870D9300012 \xf1\x894940', b'\xf1\x870D9300041H \xf1\x894905', b'\xf1\x870GC300043 \xf1\x892301', + b'\xf1\x870D9300043F \xf1\x895202', ], (Ecu.srs, 0x715, None): [ b'\xf1\x875Q0959655AE\xf1\x890130\xf1\x82\x12111200111121001121110012211292221111', b'\xf1\x875Q0959655AE\xf1\x890130\xf1\x82\022111200111121001121118112231292221111', b'\xf1\x875Q0959655AK\xf1\x890130\xf1\x82\022111200111121001121110012211292221111', b'\xf1\x875Q0959655BH\xf1\x890336\xf1\x82\02331310031313100313131013141319331413100', + b'\xf1\x875Q0959655CA\xf1\x890403\xf1\x82\x1331310031313100313151013141319331423100', ], (Ecu.eps, 0x712, None): [ b'\xf1\x875Q0909143K \xf1\x892033\xf1\x820514UZ070203', diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index f49b58212a..1391d6570c 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -112,9 +112,6 @@ class Controls: if not self.disengage_on_accelerator: self.CP.alternativeExperience |= ALTERNATIVE_EXPERIENCE.DISABLE_DISENGAGE_ON_GAS - if self.CP.dashcamOnly and self.params.get_bool("DashcamOverride"): - self.CP.dashcamOnly = False - # read params self.is_metric = self.params.get_bool("IsMetric") self.is_ldw_enabled = self.params.get_bool("IsLdwEnabled") diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index 4e664d8cf0..e4ddfb5326 100644 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -317,9 +317,9 @@ def modeld_lagging_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubM def wrong_car_mode_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int) -> Alert: - text = "Cruise Mode Disabled" + text = "Enable Adaptive Cruise to Engage" if CP.carName == "honda": - text = "Main Switch Off" + text = "Enable Main Switch to Engage" return NoEntryAlert(text) diff --git a/selfdrive/controls/lib/longitudinal_planner.py b/selfdrive/controls/lib/longitudinal_planner.py index 2ef9051122..e959b14ee3 100755 --- a/selfdrive/controls/lib/longitudinal_planner.py +++ b/selfdrive/controls/lib/longitudinal_planner.py @@ -122,8 +122,9 @@ class LongitudinalPlanner: self.mpc.update(sm['radarState'], v_cruise, x, v, a, j) self.v_desired_trajectory_full = np.interp(T_IDXS, T_IDXS_MPC, self.mpc.v_solution) + self.a_desired_trajectory_full = np.interp(T_IDXS, T_IDXS_MPC, self.mpc.a_solution) self.v_desired_trajectory = self.v_desired_trajectory_full[:CONTROL_N] - self.a_desired_trajectory = np.interp(T_IDXS[:CONTROL_N], T_IDXS_MPC, self.mpc.a_solution) + self.a_desired_trajectory = self.a_desired_trajectory_full[:CONTROL_N] self.j_desired_trajectory = np.interp(T_IDXS[:CONTROL_N], T_IDXS_MPC[:-1], self.mpc.j_solution) # TODO counter is only needed because radar is glitchy, remove once radar is gone diff --git a/selfdrive/controls/plannerd.py b/selfdrive/controls/plannerd.py index 543274d841..d8cf9386d1 100755 --- a/selfdrive/controls/plannerd.py +++ b/selfdrive/controls/plannerd.py @@ -22,6 +22,7 @@ def publish_ui_plan(sm, pm, lateral_planner, longitudinal_planner): uiPlan.position.x = np.interp(plan_odo, model_odo, lateral_planner.lat_mpc.x_sol[:,0]).tolist() uiPlan.position.y = np.interp(plan_odo, model_odo, lateral_planner.lat_mpc.x_sol[:,1]).tolist() uiPlan.position.z = np.interp(plan_odo, model_odo, lateral_planner.path_xyz[:,2]).tolist() + uiPlan.accel = longitudinal_planner.a_desired_trajectory_full.tolist() pm.send('uiPlan', ui_send) def plannerd_thread(sm=None, pm=None): diff --git a/selfdrive/debug/test_fw_query_on_routes.py b/selfdrive/debug/test_fw_query_on_routes.py index ba7d96dba0..dc6688324f 100755 --- a/selfdrive/debug/test_fw_query_on_routes.py +++ b/selfdrive/debug/test_fw_query_on_routes.py @@ -74,7 +74,7 @@ if __name__ == "__main__": elif msg.which() == "carParams": CP = msg.carParams - car_fw = CP.carFw + car_fw = [fw for fw in CP.carFw if not fw.logging] if len(car_fw) == 0: print("no fw") break diff --git a/selfdrive/locationd/laikad.py b/selfdrive/locationd/laikad.py index 2eb1e94526..2b18dcf152 100755 --- a/selfdrive/locationd/laikad.py +++ b/selfdrive/locationd/laikad.py @@ -97,19 +97,25 @@ class Laikad: def get_lsq_fix(self, t, measurements): if self.last_fix_t is None or abs(self.last_fix_t - t) > 0: - min_measurements = 7 if any(p.constellation_id == ConstellationId.GLONASS for p in measurements) else 6 - position_solution, pr_residuals = calc_pos_fix(measurements, self.posfix_functions, min_measurements=min_measurements) + min_measurements = 5 if any(p.constellation_id == ConstellationId.GLONASS for p in measurements) else 4 + position_solution, pr_residuals, pos_std = calc_pos_fix(measurements, self.posfix_functions, min_measurements=min_measurements) if len(position_solution) < 3: return None position_estimate = position_solution[:3] - #TODO median abs residual is decent estimate of std, can be improved with measurements stds and/or DOP - position_std = np.median(np.abs(pr_residuals)) * np.ones(3) - velocity_solution, prr_residuals = calc_vel_fix(measurements, position_estimate, self.velfix_function, min_measurements=min_measurements) + + position_std_residual = np.median(np.abs(pr_residuals)) + position_std = np.median(np.abs(pos_std))/10 + position_std = max(position_std_residual, position_std) * np.ones(3) + + velocity_solution, prr_residuals, vel_std = calc_vel_fix(measurements, position_estimate, self.velfix_function, min_measurements=min_measurements) if len(velocity_solution) < 3: return None - velocity_estimate = velocity_solution[:3] - velocity_std = np.median(np.abs(prr_residuals)) * np.ones(3) + + velocity_std_residual = np.median(np.abs(prr_residuals)) + velocity_std = np.median(np.abs(vel_std))/10 + velocity_std = max(velocity_std, velocity_std_residual) * np.ones(3) + return position_estimate, position_std, velocity_estimate, velocity_std def is_good_report(self, gnss_msg): @@ -187,10 +193,10 @@ class Laikad: elif self.is_good_report(gnss_msg): week, tow, new_meas = self.read_report(gnss_msg) + self.gps_week = week if len(new_meas) == 0: return None - self.gps_week = week t = gnss_mono_time * 1e-9 if week > 0: self.got_first_gnss_msg = True diff --git a/selfdrive/locationd/test/test_laikad.py b/selfdrive/locationd/test/test_laikad.py index d89f521228..10ac7790b6 100755 --- a/selfdrive/locationd/test/test_laikad.py +++ b/selfdrive/locationd/test/test_laikad.py @@ -160,7 +160,7 @@ class TestLaikad(unittest.TestCase): laikad = Laikad(auto_update=True, valid_ephem_types=EphemerisType.ULTRA_RAPID_ORBIT) correct_msgs = verify_messages(self.logs, laikad) - correct_msgs_expected = 554 + correct_msgs_expected = 559 self.assertEqual(correct_msgs_expected, len(correct_msgs)) self.assertEqual(correct_msgs_expected, len([m for m in correct_msgs if m.gnssMeasurements.positionECEF.valid])) @@ -180,7 +180,7 @@ class TestLaikad(unittest.TestCase): laikad = Laikad(auto_update=True, valid_ephem_types=EphemerisType.NAV) # Disable fetch_orbits to test NAV only correct_msgs = verify_messages(self.logs, laikad) - correct_msgs_expected = 554 + correct_msgs_expected = 559 self.assertEqual(correct_msgs_expected, len(correct_msgs)) self.assertEqual(correct_msgs_expected, len([m for m in correct_msgs if m.gnssMeasurements.positionECEF.valid])) @@ -195,8 +195,8 @@ class TestLaikad(unittest.TestCase): downloader_mock.side_effect = DownloadFailed laikad = Laikad(auto_update=False) correct_msgs = verify_messages(self.logs, laikad) - self.assertEqual(0, len(correct_msgs)) - self.assertEqual(0, len([m for m in correct_msgs if m.gnssMeasurements.positionECEF.valid])) + self.assertEqual(255, len(correct_msgs)) + self.assertEqual(255, len([m for m in correct_msgs if m.gnssMeasurements.positionECEF.valid])) def test_laika_get_orbits(self): laikad = Laikad(auto_update=False) @@ -282,7 +282,7 @@ class TestLaikad(unittest.TestCase): gm = msg.gnssMeasurements if len(gm.correctedMeasurements) != 0 and gm.positionECEF.valid: cnt += 1 - self.assertEqual(cnt, 554) + self.assertEqual(cnt, 559) def dict_has_values(self, dct): self.assertGreater(len(dct), 0) diff --git a/selfdrive/manager/manager.py b/selfdrive/manager/manager.py index 865966d6c5..963d94066b 100755 --- a/selfdrive/manager/manager.py +++ b/selfdrive/manager/manager.py @@ -36,7 +36,7 @@ def manager_init() -> None: default_params: List[Tuple[str, Union[str, bytes]]] = [ ("CompletedTrainingVersion", "0"), - ("DisengageOnAccelerator", "1"), + ("DisengageOnAccelerator", "0"), ("GsmMetered", "1"), ("HasAcceptedTerms", "0"), ("LanguageSetting", "main_en"), diff --git a/selfdrive/modeld/SConscript b/selfdrive/modeld/SConscript index 7bbc1b3477..c7e0dc5d86 100644 --- a/selfdrive/modeld/SConscript +++ b/selfdrive/modeld/SConscript @@ -70,7 +70,7 @@ lenv.Program('_dmonitoringmodeld', [ if use_thneed and arch == "larch64" or GetOption('pc_thneed'): fn = File("models/supercombo").abspath - tinygrad_opts = ["NATIVE_EXPLOG=1", "VALIDHACKS=1", "OPTWG=1", "IMAGE=2", "GPU=1", "CLCACHE=0"] + tinygrad_opts = ["NATIVE_EXPLOG=1", "VALIDHACKS=1", "OPTLOCAL=1", "IMAGE=2", "GPU=1", "ENABLE_METHOD_CACHE=1"] if not GetOption('pc_thneed'): # use FLOAT16 on device for speed + don't cache the CL kernels for space tinygrad_opts += ["FLOAT16=1", "PYOPENCL_NO_CACHE=1"] diff --git a/selfdrive/test/process_replay/model_replay_ref_commit b/selfdrive/test/process_replay/model_replay_ref_commit index c64f522352..ad09668a46 100644 --- a/selfdrive/test/process_replay/model_replay_ref_commit +++ b/selfdrive/test/process_replay/model_replay_ref_commit @@ -1 +1 @@ -ba947edbb131a2a36ced7c490dfcf3280ad5b167 +ab64afd1abd1059c14f50c67b51e5ef89029f216 diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index 7dc0b139a3..971ddb3fe2 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -449,9 +449,6 @@ def setup_env(simulation=False, CP=None, cfg=None, controlsState=None): if CP.openpilotLongitudinalControl: params.put_bool("ExperimentalLongitudinalEnabled", True) - # controlsd process configuration assume all routes are out of dashcam - params.put_bool("DashcamOverride", True) - def python_replay_process(cfg, lr, fingerprint=None): sub_sockets = [s for _, sub in cfg.pub_sub.items() for s in sub] diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 1d807d75cd..79769e14b6 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -5f45771d28c8e7112d474edcdd991689c6440acf +f9c7e05b836c4bff364978752e82d64b90f9d6e6 diff --git a/selfdrive/test/process_replay/test_processes.py b/selfdrive/test/process_replay/test_processes.py index 569090f606..07117c2e7f 100755 --- a/selfdrive/test/process_replay/test_processes.py +++ b/selfdrive/test/process_replay/test_processes.py @@ -29,12 +29,12 @@ source_segments = [ ("SUBARU", "341dccd5359e3c97|2022-09-12--10-35-33--3"), # SUBARU.OUTBACK ("GM", "0c58b6a25109da2b|2021-02-23--16-35-50--11"), # GM.VOLT ("GM2", "376bf99325883932|2022-10-27--13-41-22--1"), # GM.BOLT_EUV - ("FORD", "54827bf84c38b14f|2023-01-26--21-59-07--4"), # FORD.BRONCO_SPORT_MK1 ("NISSAN", "35336926920f3571|2021-02-12--18-38-48--46"), # NISSAN.XTRAIL ("VOLKSWAGEN", "de9592456ad7d144|2021-06-29--11-00-15--6"), # VOLKSWAGEN.GOLF ("MAZDA", "bd6a637565e91581|2021-10-30--15-14-53--4"), # MAZDA.CX9_2021 # Enable when port is tested and dashcamOnly is no longer set + #("FORD", "54827bf84c38b14f|2023-01-26--21-59-07--4"), # FORD.BRONCO_SPORT_MK1 #("TESLA", "bb50caf5f0945ab1|2021-06-19--17-20-18--3"), # TESLA.AP2_MODELS #("VOLKSWAGEN2", "3cfdec54aa035f3f|2022-07-19--23-45-10--2"), # VOLKSWAGEN.PASSAT_NMS ] @@ -53,7 +53,6 @@ segments = [ ("SUBARU", "regen1E72BBDCED5|2022-09-27--15-55-31--0"), ("GM", "regen45B05A80EF6|2022-09-27--15-57-22--0"), ("GM2", "376bf99325883932|2022-10-27--13-41-22--1"), - ("FORD", "54827bf84c38b14f|2023-01-26--21-59-07--4"), ("NISSAN", "regenC19D899B46D|2022-09-27--15-59-13--0"), ("VOLKSWAGEN", "regenD8F7AC4BD0D|2022-09-27--16-41-45--0"), ("MAZDA", "regenFC3F9ECBB64|2022-09-27--16-03-09--0"), diff --git a/selfdrive/ui/qt/offroad/driverview.cc b/selfdrive/ui/qt/offroad/driverview.cc index 2f366a9b38..327c7537a2 100644 --- a/selfdrive/ui/qt/offroad/driverview.cc +++ b/selfdrive/ui/qt/offroad/driverview.cc @@ -27,7 +27,7 @@ void DriverViewWindow::mouseReleaseEvent(QMouseEvent* e) { } DriverViewScene::DriverViewScene(QWidget* parent) : sm({"driverStateV2"}), QWidget(parent) { - face_img = loadPixmap("../assets/img_driver_face.png", {FACE_IMG_SIZE, FACE_IMG_SIZE}); + face_img = loadPixmap("../assets/img_driver_face_static.png", {FACE_IMG_SIZE, FACE_IMG_SIZE}); } void DriverViewScene::showEvent(QShowEvent* event) { diff --git a/selfdrive/ui/qt/onroad.cc b/selfdrive/ui/qt/onroad.cc index 98c636b0a4..dc2f1368ac 100644 --- a/selfdrive/ui/qt/onroad.cc +++ b/selfdrive/ui/qt/onroad.cc @@ -573,7 +573,10 @@ void AnnotatedCameraWidget::drawDriverState(QPainter &painter, const UIState *s) const int arc_l = 133; const float arc_t_default = 6.7; const float arc_t_extend = 12.0; - QColor arc_color = QColor::fromRgbF(0.09, 0.945, 0.26, 0.4*(1.0-dm_fade_state)*(s->engaged())); + QColor arc_color = QColor::fromRgbF(0.545 - 0.445 * s->engaged(), + 0.545 + 0.4 * s->engaged(), + 0.545 - 0.285 * s->engaged(), + 0.4 * (1.0 - dm_fade_state)); float delta_x = -scene.driver_pose_sins[1] * arc_l / 2; float delta_y = -scene.driver_pose_sins[0] * arc_l / 2; painter.setPen(QPen(arc_color, arc_t_default+arc_t_extend*fmin(1.0, scene.driver_pose_diff[1] * 5.0), Qt::SolidLine, Qt::RoundCap)); diff --git a/selfdrive/ui/qt/setup/setup.cc b/selfdrive/ui/qt/setup/setup.cc index 392be68a12..de5021c8bc 100644 --- a/selfdrive/ui/qt/setup/setup.cc +++ b/selfdrive/ui/qt/setup/setup.cc @@ -34,7 +34,7 @@ bool is_elf(char *fname) { void Setup::download(QString url) { CURL *curl = curl_easy_init(); if (!curl) { - emit finished(false); + emit finished(url, tr("Something went wrong. Reboot the device.")); return; } @@ -53,15 +53,24 @@ void Setup::download(QString url) { curl_easy_setopt(curl, CURLOPT_FOLLOWLOCATION, 1L); curl_easy_setopt(curl, CURLOPT_USERAGENT, (USER_AGENT + version).c_str()); curl_easy_setopt(curl, CURLOPT_HTTPHEADER, list); + curl_easy_setopt(curl, CURLOPT_TIMEOUT, 30L); int ret = curl_easy_perform(curl); long res_status = 0; curl_easy_getinfo(curl, CURLINFO_RESPONSE_CODE, &res_status); - if (ret == CURLE_OK && res_status == 200 && is_elf(tmpfile)) { - rename(tmpfile, "/tmp/installer"); - emit finished(true); + + if (ret != CURLE_OK || res_status != 200) { + emit finished(url, tr("Ensure the entered URL is valid, and the device’s internet connection is good.")); + } else if (!is_elf(tmpfile)) { + emit finished(url, tr("No custom software found at this URL.")); } else { - emit finished(false); + rename(tmpfile, "/tmp/installer"); + + FILE *fp_url = fopen("/tmp/installer_url", "w"); + fprintf(fp_url, "%s", url.toStdString().c_str()); + fclose(fp_url); + + emit finished(url); } curl_slist_free_all(list); @@ -234,10 +243,10 @@ QWidget * Setup::downloading() { return widget; } -QWidget * Setup::download_failed() { +QWidget * Setup::download_failed(QLabel *url, QLabel *body) { QWidget *widget = new QWidget(); QVBoxLayout *main_layout = new QVBoxLayout(widget); - main_layout->setContentsMargins(55, 225, 55, 55); + main_layout->setContentsMargins(55, 185, 55, 55); main_layout->setSpacing(0); QLabel *title = new QLabel(tr("Download Failed")); @@ -246,7 +255,13 @@ QWidget * Setup::download_failed() { main_layout->addSpacing(67); - QLabel *body = new QLabel(tr("Ensure the entered URL is valid, and the device’s internet connection is good.")); + url->setWordWrap(true); + url->setAlignment(Qt::AlignTop | Qt::AlignLeft); + url->setStyleSheet("font-family: \"JetBrains Mono\"; font-size: 64px; font-weight: 400; margin-right: 100px;"); + main_layout->addWidget(url); + + main_layout->addSpacing(48); + body->setWordWrap(true); body->setAlignment(Qt::AlignTop | Qt::AlignLeft); body->setStyleSheet("font-size: 80px; font-weight: 300; margin-right: 100px;"); @@ -271,7 +286,7 @@ QWidget * Setup::download_failed() { restart->setProperty("primary", true); blayout->addWidget(restart); QObject::connect(restart, &QPushButton::clicked, this, [=]() { - setCurrentIndex(2); + setCurrentIndex(1); }); widget->setStyleSheet(R"( @@ -304,15 +319,19 @@ Setup::Setup(QWidget *parent) : QStackedWidget(parent) { downloading_widget = downloading(); addWidget(downloading_widget); - failed_widget = download_failed(); + QLabel *url_label = new QLabel(); + QLabel *body_label = new QLabel(); + failed_widget = download_failed(url_label, body_label); addWidget(failed_widget); - QObject::connect(this, &Setup::finished, [=](bool success) { - // hide setup on success - qDebug() << "finished" << success; - if (success) { + QObject::connect(this, &Setup::finished, [=](const QString &url, const QString &error) { + qDebug() << "finished" << url << error; + if (error.isEmpty()) { + // hide setup on success QTimer::singleShot(3000, this, &QWidget::hide); } else { + url_label->setText(url); + body_label->setText(error); setCurrentWidget(failed_widget); } }); diff --git a/selfdrive/ui/qt/setup/setup.h b/selfdrive/ui/qt/setup/setup.h index f990b5a6cb..bf5d97070d 100644 --- a/selfdrive/ui/qt/setup/setup.h +++ b/selfdrive/ui/qt/setup/setup.h @@ -1,5 +1,6 @@ #pragma once +#include #include #include #include @@ -15,13 +16,13 @@ private: QWidget *getting_started(); QWidget *network_setup(); QWidget *downloading(); - QWidget *download_failed(); + QWidget *download_failed(QLabel *url, QLabel *body); QWidget *failed_widget; QWidget *downloading_widget; signals: - void finished(bool success); + void finished(const QString &url, const QString &error = ""); public slots: void nextPage(); diff --git a/selfdrive/ui/translations/main_de.ts b/selfdrive/ui/translations/main_de.ts index 77670ede3b..5f3511d3cc 100644 --- a/selfdrive/ui/translations/main_de.ts +++ b/selfdrive/ui/translations/main_de.ts @@ -703,6 +703,14 @@ This may take up to a minute. Start over Von neuem beginnen + + No custom software found at this URL. + + + + Something went wrong. Reboot the device. + + SetupWidget diff --git a/selfdrive/ui/translations/main_ja.ts b/selfdrive/ui/translations/main_ja.ts index 856beee7bc..1e0223606b 100644 --- a/selfdrive/ui/translations/main_ja.ts +++ b/selfdrive/ui/translations/main_ja.ts @@ -701,6 +701,14 @@ This may take up to a minute. Start over 最初からやり直す + + No custom software found at this URL. + + + + Something went wrong. Reboot the device. + + SetupWidget diff --git a/selfdrive/ui/translations/main_ko.ts b/selfdrive/ui/translations/main_ko.ts index ee5bb4fd36..be11f2efde 100644 --- a/selfdrive/ui/translations/main_ko.ts +++ b/selfdrive/ui/translations/main_ko.ts @@ -403,7 +403,7 @@ location set Waiting for GPS - GPS를 기다리는 중 + GPS 수신중 입니다 @@ -592,16 +592,17 @@ location set Unable to mount data partition. Partition may be corrupted. Press confirm to erase and reset your device. - + 데이터 파티션을 마운트할 수 없습니다. 파티션이 손상되었을 수 있습니다. 장치를 초기화하려면 확인을 누르세요. Press confirm to erase all content and settings. Press cancel to resume boot. - + 모든 콘텐츠와 설정을 지우려면 확인을 누르세요. 부팅을 재개하려면 취소를 누르세요. Resetting device... This may take up to a minute. - + 장치 초기화 중... +최대 1분이 소요될 수 있습니다. @@ -701,6 +702,14 @@ This may take up to a minute. Start over 다시 시작 + + Something went wrong. Reboot the device. + 문제가 발생했습니다. 장치를 재부팅하세요. + + + No custom software found at this URL. + 이 URL에서 커스텀 소프트웨어를 찾을 수 없습니다. + SetupWidget diff --git a/selfdrive/ui/translations/main_pt-BR.ts b/selfdrive/ui/translations/main_pt-BR.ts index 156b6f16c1..5c4eab3327 100644 --- a/selfdrive/ui/translations/main_pt-BR.ts +++ b/selfdrive/ui/translations/main_pt-BR.ts @@ -705,6 +705,14 @@ This may take up to a minute. Start over Inicializar + + No custom software found at this URL. + + + + Something went wrong. Reboot the device. + + SetupWidget diff --git a/selfdrive/ui/translations/main_th.ts b/selfdrive/ui/translations/main_th.ts index ce394ecb97..45f91f1cdb 100644 --- a/selfdrive/ui/translations/main_th.ts +++ b/selfdrive/ui/translations/main_th.ts @@ -311,18 +311,6 @@ Installing... กำลังติดตั้ง... - - Receiving objects: - กำลังรับข้อมูล: - - - Resolving deltas: - การแก้ไขเดลต้า: - - - Updating files: - กำลังอัปเดตไฟล์: - MapETA @@ -586,18 +574,10 @@ location set Are you sure you want to reset your device? คุณแน่ใจหรือไม่ว่าต้องการรีเซ็ตอุปกรณ์? - - Resetting device... - กำลังรีเซ็ตอุปกรณ์... - System Reset รีเซ็ตระบบ - - System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot. - มีการสั่งรีเซ็ตระบบ กดยืนยันเพื่อลบข้อมูลและการตั้งค่าทั้งหมด กดยกเลิกเพื่อบูตเข้าระบบตามปกติ - Cancel ยกเลิก @@ -611,8 +591,18 @@ location set ยืนยัน - Unable to mount data partition. Press confirm to reset your device. - ไม่สามารถเมานต์พาร์ติชั่นข้อมูล กดยืนยันเพื่อรีเซ็ตอุปกรณ์ของคุณ + Resetting device... +This may take up to a minute. + กำลังรีเซ็ตอุปกรณ์... +อาจใช้เวลาถึงหนึ่งนาที + + + Press confirm to erase all content and settings. Press cancel to resume boot. + กดยืนยันเพื่อลบข้อมูลและการตั้งค่าทั้งหมด กดยกเลิกเพื่อบูตต่อ + + + Unable to mount data partition. Partition may be corrupted. Press confirm to erase and reset your device. + ไม่สามารถเมานต์พาร์ติชั่นข้อมูลได้ พาร์ติชั่นอาจเสียหาย กดยืนยันเพื่อลบและรีเซ็ตอุปกรณ์ของคุณ @@ -684,18 +674,6 @@ location set Waiting for internet กำลังรอสัญญาณอินเตอร์เน็ต - - Choose Software to Install - เลือกซอฟต์แวร์ที่จะติดตั้ง - - - Dashcam - กล้องติดรถยนต์ - - - Custom Software - ซอฟต์แวร์ที่กำหนดเอง - Enter URL ป้อน URL @@ -724,6 +702,14 @@ location set Start over เริ่มต้นใหม่ + + Something went wrong. Reboot the device. + มีบางอย่างผิดพลาด รีบูตอุปกรณ์ + + + No custom software found at this URL. + ไม่พบซอฟต์แวร์ที่กำหนดเองที่ URL นี้ + SetupWidget diff --git a/selfdrive/ui/translations/main_zh-CHS.ts b/selfdrive/ui/translations/main_zh-CHS.ts index f295a72938..cfc055ac98 100644 --- a/selfdrive/ui/translations/main_zh-CHS.ts +++ b/selfdrive/ui/translations/main_zh-CHS.ts @@ -699,6 +699,14 @@ This may take up to a minute. Start over 重来 + + No custom software found at this URL. + + + + Something went wrong. Reboot the device. + + SetupWidget diff --git a/selfdrive/ui/translations/main_zh-CHT.ts b/selfdrive/ui/translations/main_zh-CHT.ts index b7636c18c5..e4058ee0db 100644 --- a/selfdrive/ui/translations/main_zh-CHT.ts +++ b/selfdrive/ui/translations/main_zh-CHT.ts @@ -701,6 +701,14 @@ This may take up to a minute. Start over 重新開始 + + No custom software found at this URL. + + + + Something went wrong. Reboot the device. + + SetupWidget diff --git a/system/hardware/tici/test_power_draw.py b/system/hardware/tici/test_power_draw.py index 2460152998..f563933285 100755 --- a/system/hardware/tici/test_power_draw.py +++ b/system/hardware/tici/test_power_draw.py @@ -3,6 +3,7 @@ import unittest import time import math from dataclasses import dataclass +from tabulate import tabulate from system.hardware import HARDWARE, TICI from system.hardware.tici.power_monitor import get_power @@ -20,7 +21,7 @@ class Proc: PROCS = [ Proc('camerad', 2.15), - Proc('modeld', 1.15, atol=0.2), + Proc('modeld', 0.93, atol=0.2), Proc('dmonitoringmodeld', 0.4), Proc('encoderd', 0.23), ] @@ -58,15 +59,16 @@ class TestPowerDraw(unittest.TestCase): manager_cleanup() - print("-"*35) - print(f"Baseline {baseline:.2f}W\n") + tab = [] + tab.append(['process', 'expected (W)', 'current (W)']) for proc in PROCS: cur = used[proc.name] expected = proc.power - print(f"{proc.name.ljust(20)} {expected:.2f}W {cur:.2f}W") + tab.append([proc.name, round(expected, 2), round(cur, 2)]) with self.subTest(proc=proc.name): self.assertTrue(math.isclose(cur, expected, rel_tol=proc.rtol, abs_tol=proc.atol)) - print("-"*35) + print(tabulate(tab)) + print(f"Baseline {baseline:.2f}W\n") if __name__ == "__main__": diff --git a/tinygrad_repo b/tinygrad_repo index 2e1d47b166..d8dda2af3a 160000 --- a/tinygrad_repo +++ b/tinygrad_repo @@ -1 +1 @@ -Subproject commit 2e1d47b16625ff343516287cdd9e4bcb26f5c4ef +Subproject commit d8dda2af3afcef0bb772fff580cfa8b3eabf7f69 diff --git a/tools/cabana/binaryview.cc b/tools/cabana/binaryview.cc index d9b00f6882..120a85a330 100644 --- a/tools/cabana/binaryview.cc +++ b/tools/cabana/binaryview.cc @@ -293,7 +293,6 @@ void BinaryViewModel::updateState() { double max_f = 255.0; double factor = 0.25; double scaler = max_f / log2(1.0 + factor); - char hex[3] = {'\0'}; for (int i = 0; i < binary.size(); ++i) { for (int j = 0; j < 8; ++j) { auto &item = items[i * column_count + j]; @@ -305,9 +304,7 @@ void BinaryViewModel::updateState() { double alpha = std::clamp(offset + log2(1.0 + factor * (double)n / (double)last_msg.count) * scaler, min_f, max_f); item.bg_color.setAlpha(alpha); } - hex[0] = toHex(binary[i] >> 4); - hex[1] = toHex(binary[i] & 0xf); - items[i * column_count + 8].val = hex; + items[i * column_count + 8].val = toHex(binary[i]); items[i * column_count + 8].bg_color = last_msg.colors[i]; } for (int i = binary.size() * column_count; i < items.size(); ++i) { @@ -375,7 +372,7 @@ void BinaryItemDelegate::paint(QPainter *painter, const QStyleOptionViewItem &op bg.setAlpha(std::max(50, bg.alpha())); } painter->fillRect(option.rect, bg); - painter->setPen(Qt::black); + painter->setPen(option.palette.color(QPalette::Text)); } } diff --git a/tools/cabana/chartswidget.cc b/tools/cabana/chartswidget.cc index 8a3a59d989..54966be578 100644 --- a/tools/cabana/chartswidget.cc +++ b/tools/cabana/chartswidget.cc @@ -1,5 +1,6 @@ #include "tools/cabana/chartswidget.h" +#include #include #include #include @@ -24,11 +25,12 @@ ChartsWidget::ChartsWidget(QWidget *parent) : QFrame(parent) { // toolbar QToolBar *toolbar = new QToolBar(tr("Charts"), this); - toolbar->setIconSize({16, 16}); + 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, 12, 0); + 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) { @@ -76,8 +78,8 @@ ChartsWidget::ChartsWidget(QWidget *parent) : QFrame(parent) { main_layout->addWidget(charts_scroll); // init settings - use_dark_theme = QApplication::style()->standardPalette().color(QPalette::WindowText).value() > - QApplication::style()->standardPalette().color(QPalette::Background).value(); + 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}; @@ -183,7 +185,7 @@ void ChartsWidget::settingChanged() { range_slider->setRange(1, settings.max_cached_minutes * 60); for (auto c : charts) { c->setFixedHeight(settings.chart_height); - c->setSeriesType(settings.chart_series_type == 0 ? QAbstractSeries::SeriesTypeLine : QAbstractSeries::SeriesTypeScatter); + c->setSeriesType((SeriesType)settings.chart_series_type); } } @@ -309,7 +311,7 @@ bool ChartsWidget::eventFilter(QObject *obj, QEvent *event) { // ChartView ChartView::ChartView(QWidget *parent) : QChartView(nullptr, parent) { - series_type = settings.chart_series_type == 0 ? QAbstractSeries::SeriesTypeLine : QAbstractSeries::SeriesTypeScatter; + series_type = (SeriesType)settings.chart_series_type; QChart *chart = new QChart(); chart->setBackgroundVisible(false); axis_x = new QValueAxis(this); @@ -321,44 +323,58 @@ ChartView::ChartView(QWidget *parent) : QChartView(nullptr, parent) { chart->setMargins({0, 0, 0, 0}); background = new QGraphicsRectItem(chart); - background->setBrush(Qt::white); + background->setBrush(QApplication::palette().color(QPalette::Base)); background->setPen(Qt::NoPen); background->setZValue(chart->zValue() - 1); - move_icon = new QGraphicsPixmapItem(utils::icon("grip-horizontal"), chart); + setChart(chart); + + createToolButtons(); + setRenderHint(QPainter::Antialiasing); + // TODO: enable zoomIn/seekTo in live streaming mode. + setRubberBand(can->liveStreaming() ? QChartView::NoRubberBand : QChartView::HorizontalRubberBand); + + 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 = new QGraphicsProxyWidget(chart()); close_btn_proxy->setWidget(remove_btn); - close_btn_proxy->setZValue(chart->zValue() + 11); + close_btn_proxy->setZValue(chart()->zValue() + 11); - QToolButton *manage_btn = toolButton("list", ""); + // series types QMenu *menu = new QMenu(this); - line_series_action = menu->addAction(tr("Line"), [this]() { setSeriesType(QAbstractSeries::SeriesTypeLine); }); - line_series_action->setCheckable(true); - line_series_action->setChecked(series_type == QAbstractSeries::SeriesTypeLine); - scatter_series_action = menu->addAction(tr("Scatter"), [this]() { setSeriesType(QAbstractSeries::SeriesTypeScatter); }); - scatter_series_action->setCheckable(true); - scatter_series_action->setChecked(series_type == QAbstractSeries::SeriesTypeScatter); + 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 = new QGraphicsProxyWidget(chart()); manage_btn_proxy->setWidget(manage_btn); - manage_btn_proxy->setZValue(chart->zValue() + 11); - - setChart(chart); - setRenderHint(QPainter::Antialiasing); - // TODO: enable zoomIn/seekTo in live streaming mode. - setRubberBand(can->liveStreaming() ? QChartView::NoRubberBand : QChartView::HorizontalRubberBand); + manage_btn_proxy->setZValue(chart()->zValue() + 11); - 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); 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 Signal *sig) { @@ -428,10 +444,12 @@ void ChartView::manageSeries() { void ChartView::resizeEvent(QResizeEvent *event) { updatePlotArea(align_to); - int x = event->size().width() - close_btn_proxy->size().width() - 11; - close_btn_proxy->setPos(x, 8); - manage_btn_proxy->setPos(x - manage_btn_proxy->size().width() - 5, 8); - move_icon->setPos(11, 8); + int top_margin = style()->pixelMetric(QStyle::PM_LayoutTopMargin); + int spacing = style()->pixelMetric(QStyle::PM_LayoutHorizontalSpacing); + int x = event->size().width() - close_btn_proxy->size().width() - style()->pixelMetric(QStyle::PM_LayoutRightMargin); + close_btn_proxy->setPos(x, top_margin); + manage_btn_proxy->setPos(x - manage_btn_proxy->size().width() - spacing, top_margin); + move_icon->setPos(style()->pixelMetric(QStyle::PM_LayoutLeftMargin), top_margin); QChartView::resizeEvent(event); } @@ -476,7 +494,7 @@ void ChartView::updateSeriesPoints() { int num_points = std::max(end - begin, 1); int pixels_per_point = width() / num_points; - if (series_type == QAbstractSeries::SeriesTypeScatter) { + if (series_type == SeriesType::Scatter) { ((QScatterSeries *)s.series)->setMarkerSize(std::clamp(pixels_per_point / 3, 2, 8)); } else { s.series->setPointsVisible(pixels_per_point > 20); @@ -490,7 +508,9 @@ void ChartView::updateSeries(const Signal *sig, const std::vector *even if (!sig || s.sig == sig) { if (clear) { s.vals.clear(); + s.step_vals.clear(); s.vals.reserve(settings.max_cached_minutes * 60 * 100); // [n]seconds * 100hz + s.step_vals.reserve(settings.max_cached_minutes * 60 * 100 * 2); s.last_value_mono_time = 0; } s.series->setColor(getColor(s.sig)); @@ -498,6 +518,7 @@ void ChartView::updateSeries(const Signal *sig, const std::vector *even struct Chunk { std::vector::const_iterator first, second; QVector vals; + QVector step_vals; }; // split into one minitue chunks QVector chunks; @@ -510,6 +531,7 @@ void ChartView::updateSeries(const Signal *sig, const std::vector *even QtConcurrent::blockingMap(chunks, [&](Chunk &chunk) { chunk.vals.reserve(60 * 100); // 100 hz + chunk.step_vals.reserve(60 * 100 * 2); // 100 hz double route_start_time = can->routeStartTime(); for (auto it = chunk.first; it != chunk.second; ++it) { if ((*it)->which == cereal::Event::Which::CAN) { @@ -519,6 +541,10 @@ void ChartView::updateSeries(const Signal *sig, const std::vector *even double value = get_raw_value((uint8_t *)dat.begin(), dat.size(), *s.sig); double ts = ((*it)->mono_time / (double)1e9) - route_start_time; // seconds chunk.vals.push_back({ts, value}); + if (!chunk.step_vals.empty()) { + chunk.step_vals.push_back({ts, chunk.step_vals.back().y()}); + } + chunk.step_vals.push_back({ts,value}); } } } @@ -526,11 +552,20 @@ void ChartView::updateSeries(const Signal *sig, const std::vector *even }); for (auto &c : chunks) { s.vals.append(c.vals); + if (!c.step_vals.empty()) { + if (!s.step_vals.empty()) { + s.step_vals.append({c.step_vals.first().x(), s.step_vals.back().y()}); + } + s.step_vals.append(c.step_vals); + } } if (events->size()) { s.last_value_mono_time = events->back()->mono_time; } - s.series->replace(s.vals); + if (!can->liveStreaming()) { + s.segment_tree.build(s.vals); + } + s.series->replace(series_type == SeriesType::StepLine ? s.step_vals : s.vals); } } updateAxisY(); @@ -542,19 +577,37 @@ void ChartView::updateAxisY() { 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(), [](auto &p, double x) { return p.x() < x; }); auto last = std::lower_bound(first, s.vals.end(), axis_x->max(), [](auto &p, double x) { return p.x() < x; }); - for (auto it = first; it != last; ++it) { - if (it->y() < min) min = it->y(); - if (it->y() > max) max = it->y(); + if (can->liveStreaming()) { + for (auto it = first; it != last; ++it) { + if (it->y() < min) min = it->y(); + if (it->y() > max) 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)); + min = std::min(min, min_y); + max = std::max(max, max_y); } } 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) { @@ -563,7 +616,8 @@ void ChartView::updateAxisY() { QFontMetrics fm(axis_y->labelsFont()); int n = qMax(int(-qFloor(std::log10((max_y - min_y) / (tick_count - 1)))), 0) + 1; - y_label_width = qMax(fm.width(QString::number(min_y, 'f', n)), fm.width(QString::number(max_y, 'f', n))) + 15; // left margin 15 + int title_spacing = axis_y->titleText().isEmpty() ? 0 : 20; + y_label_width = title_spacing + qMax(fm.width(QString::number(min_y, 'f', n)), fm.width(QString::number(max_y, 'f', n))) + 15; // left margin 15 axis_y->setLabelFormat(QString("%.%1f").arg(n)); emit axisYLabelWidthChanged(y_label_width); } @@ -597,7 +651,7 @@ qreal ChartView::niceNumber(qreal x, bool ceiling) { } void ChartView::leaveEvent(QEvent *event) { - track_pts.clear(); + clearTrackPoints(); scene()->update(); QChartView::leaveEvent(event); } @@ -653,26 +707,33 @@ void ChartView::mouseMoveEvent(QMouseEvent *ev) { auto rubber = findChild(); bool is_zooming = rubber && rubber->isVisible(); const auto plot_area = chart()->plotArea(); - track_pts.clear(); + clearTrackPoints(); + if (!is_zooming && plot_area.contains(ev->pos())) { - track_pts.resize(sigs.size()); QStringList text_list; const double sec = chart()->mapToValue(ev->pos()).x(); - for (int i = 0; i < sigs.size(); ++i) { - QString value = "--"; + qreal x = -1; + for (auto &s : sigs) { + if (!s.series->isVisible()) continue; + // use reverse iterator to find last item <= sec. - auto it = std::lower_bound(sigs[i].vals.rbegin(), sigs[i].vals.rend(), sec, [](auto &p, double x) { return p.x() > x; }); - if (it != sigs[i].vals.rend() && it->x() >= axis_x->min()) { - value = QString::number(it->y()); - track_pts[i] = chart()->mapToPosition(*it); + 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").arg(sigs[i].series->color().name(), sigs[i].sig->name, value)); + text_list.push_back(QString("%2: %3") + .arg(s.series->color().name(), s.sig->name, + s.track_pt.isNull() ? "--" : QString::number(value))); + } + if (x < 0) { + x = ev->pos().x(); } - auto max = std::max_element(track_pts.begin(), track_pts.end(), [](auto &a, auto &b) { return a.x() < b.x(); }); - auto pt = (max == track_pts.end()) ? ev->pos() : *max; - text_list.push_front(QString::number(chart()->mapToValue(pt).x(), 'f', 3)); - QPointF tooltip_pt(pt.x() + 12, plot_area.top() - 20); - QToolTip::showText(mapToGlobal(tooltip_pt.toPoint()), pt.isNull() ? "" : text_list.join("
"), this, plot_area.toRect()); + 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(); @@ -717,6 +778,7 @@ void ChartView::dropEvent(QDropEvent *event) { } 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; @@ -724,18 +786,20 @@ void ChartView::drawForeground(QPainter *painter, const QRectF &rect) { painter->setPen(QPen(chart()->titleBrush().color(), 2)); painter->drawLine(QPointF{x, y1}, QPointF{x, y2}); - auto max = std::max_element(track_pts.begin(), track_pts.end(), [](auto &a, auto &b) { return a.x() < b.x(); }); - if (max != track_pts.end() && !max->isNull()) { - painter->setPen(QPen(Qt::darkGray, 1, Qt::DashLine)); - painter->drawLine(QPointF{max->x(), y1}, QPointF{max->x(), y2}); - painter->setPen(Qt::NoPen); - for (int i = 0; i < track_pts.size(); ++i) { - if (!track_pts[i].isNull() && i < sigs.size()) { - painter->setBrush(sigs[i].series->color().darker(125)); - painter->drawEllipse(track_pts[i], 5.5, 5.5); - } + // 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); @@ -751,11 +815,14 @@ void ChartView::drawForeground(QPainter *painter, const QRectF &rect) { } } -QXYSeries *ChartView::createSeries(QAbstractSeries::SeriesType type, QColor color) { +QXYSeries *ChartView::createSeries(SeriesType type, QColor color) { QXYSeries *series = nullptr; - if (type == QAbstractSeries::SeriesTypeLine) { + 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); @@ -776,9 +843,7 @@ QXYSeries *ChartView::createSeries(QAbstractSeries::SeriesType type, QColor colo return series; } -void ChartView::setSeriesType(QAbstractSeries::SeriesType type) { - line_series_action->setChecked(type == QAbstractSeries::SeriesTypeLine); - scatter_series_action->setChecked(type == QAbstractSeries::SeriesTypeScatter); +void ChartView::setSeriesType(SeriesType type) { if (type != series_type) { series_type = type; for (auto &s : sigs) { @@ -787,7 +852,7 @@ void ChartView::setSeriesType(QAbstractSeries::SeriesType type) { } for (auto &s : sigs) { auto series = createSeries(series_type, getColor(s.sig)); - series->replace(s.vals); + series->replace(series_type == SeriesType::StepLine ? s.step_vals : s.vals); s.series = series; } updateSeriesPoints(); diff --git a/tools/cabana/chartswidget.h b/tools/cabana/chartswidget.h index a1dcf32513..c86c19a04e 100644 --- a/tools/cabana/chartswidget.h +++ b/tools/cabana/chartswidget.h @@ -20,6 +20,12 @@ using namespace QtCharts; const int CHART_MIN_WIDTH = 300; +enum class SeriesType { + Line = 0, + StepLine, + Scatter +}; + class ChartView : public QChartView { Q_OBJECT @@ -29,7 +35,7 @@ public: bool hasSeries(const MessageId &msg_id, const Signal *sig) const; void updateSeries(const Signal *sig = nullptr, const std::vector *events = nullptr, bool clear = true); void updatePlot(double cur, double min, double max); - void setSeriesType(QAbstractSeries::SeriesType type); + void setSeriesType(SeriesType type); void updatePlotArea(int left); struct SigItem { @@ -37,7 +43,10 @@ public: const Signal *sig = nullptr; QXYSeries *series = nullptr; QVector vals; + QVector step_vals; uint64_t last_value_mono_time = 0; + QPointF track_pt{}; + SegmentTree segment_tree; }; signals: @@ -57,6 +66,7 @@ private slots: void signalRemoved(const 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; @@ -70,15 +80,15 @@ private: 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(QAbstractSeries::SeriesType type, QColor color); + 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; - QVector track_pts; QGraphicsPixmapItem *move_icon; QGraphicsProxyWidget *close_btn_proxy; QGraphicsProxyWidget *manage_btn_proxy; @@ -86,9 +96,7 @@ private: QList sigs; double cur_sec = 0; const QString mime_type = "application/x-cabanachartview"; - QAbstractSeries::SeriesType series_type = QAbstractSeries::SeriesTypeLine; - QAction *line_series_action; - QAction *scatter_series_action; + SeriesType series_type = SeriesType::Line; friend class ChartsWidget; }; diff --git a/tools/cabana/historylog.cc b/tools/cabana/historylog.cc index abf0b53af8..57f65b97d8 100644 --- a/tools/cabana/historylog.cc +++ b/tools/cabana/historylog.cc @@ -15,8 +15,10 @@ QVariant HistoryLogModel::data(const QModelIndex &index, int role) const { return QString::number((m.mono_time / (double)1e9) - can->routeStartTime(), 'f', 2); } return show_signals ? QString::number(m.sig_values[index.column() - 1]) : toHex(m.data); - } else if (role == Qt::UserRole && index.column() == 1 && !show_signals) { + } else if (role == ColorsRole) { return QVariant::fromValue(m.colors); + } else if (role == BytesRole) { + return m.data; } return {}; } @@ -48,7 +50,15 @@ QVariant HistoryLogModel::headerData(int section, Qt::Orientation orientation, i if (section == 0) { return "Time"; } - return show_signals ? sigs[section - 1]->name : "Data"; + if (show_signals) { + QString name = sigs[section - 1]->name; + if (!sigs[section - 1]->unit.isEmpty()) { + name += QString(" (%1)").arg(sigs[section - 1]->unit); + } + return name; + } else { + return "Data"; + } } else if (role == Qt::BackgroundRole && section > 0 && show_signals) { return QBrush(getColor(sigs[section - 1])); } diff --git a/tools/cabana/mainwin.cc b/tools/cabana/mainwin.cc index bc090b2cc0..abcb4948a9 100644 --- a/tools/cabana/mainwin.cc +++ b/tools/cabana/mainwin.cc @@ -58,14 +58,21 @@ MainWindow::MainWindow() : QMainWindow() { fingerprint_to_dbc = QJsonDocument::fromJson(json_file.readAll()); } + setStyleSheet(QString(R"(QMainWindow::separator { + width: %1px; /* when vertical */ + height: %1px; /* when horizontal */ + })").arg(style()->pixelMetric(QStyle::PM_SplitterWidth))); + QObject::connect(this, &MainWindow::showMessage, statusBar(), &QStatusBar::showMessage); QObject::connect(this, &MainWindow::updateProgressBar, this, &MainWindow::updateDownloadProgress); QObject::connect(messages_widget, &MessagesWidget::msgSelectionChanged, center_widget, &CenterWidget::setMessage); QObject::connect(charts_widget, &ChartsWidget::dock, this, &MainWindow::dockCharts); QObject::connect(can, &AbstractStream::streamStarted, this, &MainWindow::loadDBCFromFingerprint); + QObject::connect(can, &AbstractStream::eventsMerged, this, &MainWindow::updateStatus); QObject::connect(dbc(), &DBCManager::DBCFileChanged, this, &MainWindow::DBCFileChanged); QObject::connect(UndoStack::instance(), &QUndoStack::cleanChanged, this, &MainWindow::undoStackCleanChanged); QObject::connect(UndoStack::instance(), &QUndoStack::indexChanged, this, &MainWindow::undoStackIndexChanged); + QObject::connect(&settings, &Settings::changed, this, &MainWindow::updateStatus); } void MainWindow::createActions() { @@ -179,11 +186,16 @@ void MainWindow::createStatusBar() { progress_bar->setVisible(false); statusBar()->addWidget(new QLabel(tr("For Help, Press F1"))); statusBar()->addPermanentWidget(progress_bar); + + statusBar()->addPermanentWidget(status_label = new QLabel(this)); + updateStatus(); } void MainWindow::createShortcuts() { auto shortcut = new QShortcut(QKeySequence(Qt::Key_Space), this, nullptr, nullptr, Qt::ApplicationShortcut); QObject::connect(shortcut, &QShortcut::activated, []() { can->pause(!can->isPaused()); }); + shortcut = new QShortcut(QKeySequence(QKeySequence::FullScreen), this, nullptr, nullptr, Qt::ApplicationShortcut); + QObject::connect(shortcut, &QShortcut::activated, this, &MainWindow::toggleFullScreen); // TODO: add more shortcuts here. } @@ -403,6 +415,18 @@ void MainWindow::updateDownloadProgress(uint64_t cur, uint64_t total, bool succe } } +void MainWindow::updateStatus() { + float cached_minutes = 0; + if (!can->liveStreaming()) { + if (auto events = can->events(); !events->empty()) { + cached_minutes = (events->back()->mono_time - events->front()->mono_time) / (1e9 * 60); + } + } else { + settings.max_cached_minutes = settings.max_cached_minutes; + } + status_label->setText(tr("Cached Minutes:%1 FPS:%2").arg(cached_minutes, 0, 'f', 1).arg(settings.fps)); +} + void MainWindow::dockCharts(bool dock) { if (dock && floating_window) { floating_window->removeEventFilter(charts_widget); @@ -460,6 +484,19 @@ void MainWindow::onlineHelp() { } } +void MainWindow::toggleFullScreen() { + if (isFullScreen()) { + menuBar()->show(); + statusBar()->show(); + showNormal(); + showMaximized(); + } else { + menuBar()->hide(); + statusBar()->hide(); + showFullScreen(); + } +} + // HelpOverlay HelpOverlay::HelpOverlay(MainWindow *parent) : QWidget(parent) { setAttribute(Qt::WA_NoSystemBackground, true); diff --git a/tools/cabana/mainwin.h b/tools/cabana/mainwin.h index dd53b1f213..1c21d69370 100644 --- a/tools/cabana/mainwin.h +++ b/tools/cabana/mainwin.h @@ -56,6 +56,8 @@ protected: void undoStackCleanChanged(bool clean); void undoStackIndexChanged(int index); void onlineHelp(); + void toggleFullScreen(); + void updateStatus(); VideoWidget *video_widget = nullptr; QDockWidget *video_dock; @@ -65,6 +67,7 @@ protected: QWidget *floating_window = nullptr; QVBoxLayout *charts_layout; QProgressBar *progress_bar; + QLabel *status_label; QJsonDocument fingerprint_to_dbc; QSplitter *video_splitter;; QString current_file = ""; diff --git a/tools/cabana/messageswidget.cc b/tools/cabana/messageswidget.cc index c880c61058..b4a7ed7b34 100644 --- a/tools/cabana/messageswidget.cc +++ b/tools/cabana/messageswidget.cc @@ -20,11 +20,15 @@ MessagesWidget::MessagesWidget(QWidget *parent) : QWidget(parent) { table_widget = new QTableView(this); model = new MessageListModel(this); table_widget->setModel(model); - table_widget->setItemDelegateForColumn(4, new MessageBytesDelegate(table_widget)); + table_widget->setItemDelegateForColumn(5, new MessageBytesDelegate(table_widget)); table_widget->setSelectionBehavior(QAbstractItemView::SelectRows); table_widget->setSelectionMode(QAbstractItemView::SingleSelection); table_widget->setSortingEnabled(true); table_widget->sortByColumn(0, Qt::AscendingOrder); + table_widget->setColumnWidth(0, 150); + table_widget->setColumnWidth(1, 50); + table_widget->setColumnWidth(2, 50); + table_widget->setColumnWidth(3, 50); table_widget->horizontalHeader()->setStretchLastSection(true); table_widget->verticalHeader()->hide(); main_layout->addWidget(table_widget); @@ -108,7 +112,7 @@ void MessagesWidget::reset() { QVariant MessageListModel::headerData(int section, Qt::Orientation orientation, int role) const { if (orientation == Qt::Horizontal && role == Qt::DisplayRole) - return (QString[]){"Name", "ID", "Freq", "Count", "Bytes"}[section]; + return (QString[]){"Name", "Bus", "ID", "Freq", "Count", "Bytes"}[section]; return {}; } @@ -119,12 +123,13 @@ QVariant MessageListModel::data(const QModelIndex &index, int role) const { if (role == Qt::DisplayRole) { switch (index.column()) { case 0: return msgName(id); - case 1: return id.toString(); // TODO: put source and address in separate columns - case 2: return can_data.freq; - case 3: return can_data.count; - case 4: return toHex(can_data.dat); + case 1: return id.source; + case 2: return QString::number(id.address, 16);; + case 3: return can_data.freq; + case 4: return can_data.count; + case 5: return toHex(can_data.dat); } - } else if (role == Qt::UserRole && index.column() == 4) { + } else if (role == ColorsRole) { QVector colors = can_data.colors; if (!suppressed_bytes.empty()) { for (int i = 0; i < colors.size(); i++) { @@ -134,6 +139,8 @@ QVariant MessageListModel::data(const QModelIndex &index, int role) const { } } return QVariant::fromValue(colors); + } else if (role == BytesRole) { + return can_data.dat; } return {}; } @@ -171,15 +178,23 @@ void MessageListModel::sortMessages() { }); } else if (sort_column == 1) { std::sort(msgs.begin(), msgs.end(), [this](auto &l, auto &r) { - return sort_order == Qt::AscendingOrder ? l < r : l > r; + auto ll = std::pair{l.source, l}; + auto rr = std::pair{r.source, r}; + return sort_order == Qt::AscendingOrder ? ll < rr : ll > rr; }); } else if (sort_column == 2) { + std::sort(msgs.begin(), msgs.end(), [this](auto &l, auto &r) { + auto ll = std::pair{l.address, l}; + auto rr = std::pair{r.address, r}; + return sort_order == Qt::AscendingOrder ? ll < rr : ll > rr; + }); + } else if (sort_column == 3) { std::sort(msgs.begin(), msgs.end(), [this](auto &l, auto &r) { auto ll = std::pair{can->lastMessage(l).freq, l}; auto rr = std::pair{can->lastMessage(r).freq, r}; return sort_order == Qt::AscendingOrder ? ll < rr : ll > rr; }); - } else if (sort_column == 3) { + } else if (sort_column == 4) { std::sort(msgs.begin(), msgs.end(), [this](auto &l, auto &r) { auto ll = std::pair{can->lastMessage(l).count, l}; auto rr = std::pair{can->lastMessage(r).count, r}; @@ -200,7 +215,7 @@ void MessageListModel::msgsReceived(const QHash *new_msgs) { } for (int i = 0; i < msgs.size(); ++i) { if (new_msgs->contains(msgs[i])) { - for (int col = 2; col < columnCount(); ++col) + for (int col = 3; col < columnCount(); ++col) emit dataChanged(index(i, col), index(i, col), {Qt::DisplayRole}); } } diff --git a/tools/cabana/messageswidget.h b/tools/cabana/messageswidget.h index 926d131c8d..ed9e241b0c 100644 --- a/tools/cabana/messageswidget.h +++ b/tools/cabana/messageswidget.h @@ -16,7 +16,7 @@ Q_OBJECT public: MessageListModel(QObject *parent) : QAbstractTableModel(parent) {} QVariant headerData(int section, Qt::Orientation orientation, int role = Qt::DisplayRole) const override; - int columnCount(const QModelIndex &parent = QModelIndex()) const override { return 5; } + int columnCount(const QModelIndex &parent = QModelIndex()) const override { return 6; } QVariant data(const QModelIndex &index, int role = Qt::DisplayRole) const; int rowCount(const QModelIndex &parent = QModelIndex()) const override { return msgs.size(); } void sort(int column, Qt::SortOrder order = Qt::AscendingOrder) override; diff --git a/tools/cabana/settings.cc b/tools/cabana/settings.cc index 6cbd16cabf..23f001efff 100644 --- a/tools/cabana/settings.cc +++ b/tools/cabana/settings.cc @@ -65,7 +65,7 @@ SettingsDlg::SettingsDlg(QWidget *parent) : QDialog(parent) { form_layout->addRow(tr("Max Cached Minutes"), cached_minutes); chart_series_type = new QComboBox(this); - chart_series_type->addItems({tr("Line"), tr("Scatter")}); + chart_series_type->addItems({tr("Line"), tr("Step Line"), tr("Scatter")}); chart_series_type->setCurrentIndex(settings.chart_series_type); form_layout->addRow(tr("Chart Default Series Type"), chart_series_type); diff --git a/tools/cabana/signaledit.cc b/tools/cabana/signaledit.cc index c614ecb247..e425a13f82 100644 --- a/tools/cabana/signaledit.cc +++ b/tools/cabana/signaledit.cc @@ -62,6 +62,9 @@ void SignalModel::updateState(const QHash *msgs) { int row = 0; for (auto item : root->children) { QString value = QString::number(get_raw_value((uint8_t *)dat.begin(), dat.size(), *item->sig)); + if (!item->sig->unit.isEmpty()){ + value += " " + item->sig->unit; + } if (value != item->sig_val) { item->sig_val = value; emit dataChanged(index(row, 1), index(row, 1), {Qt::DisplayRole}); @@ -319,22 +322,34 @@ void SignalItemDelegate::paint(QPainter *painter, const QStyleOptionViewItem &op // color label auto bg_color = getColor(item->sig); - QRect rc{option.rect.left(), option.rect.top(), color_label_width, option.rect.height()}; + int h_margin = option.widget->style()->pixelMetric(QStyle::PM_FocusFrameHMargin) + 1; + int v_margin = option.widget->style()->pixelMetric(QStyle::PM_FocusFrameVMargin); + QRect rc{option.rect.left() + h_margin, option.rect.top(), color_label_width, option.rect.height()}; painter->setPen(Qt::NoPen); painter->setBrush(item->highlight ? bg_color.darker(125) : bg_color); - painter->drawRoundedRect(rc.adjusted(0, 2, 0, -2), 3, 3); + 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->drawText(rc, Qt::AlignCenter, QString::number(item->row() + 1)); // signal name painter->setFont(option.font); - painter->setPen((option.state & QStyle::State_Selected ? option.palette.highlightedText() : option.palette.text()).color()); + painter->setPen(option.palette.color(option.state & QStyle::State_Selected ? QPalette::HighlightedText : QPalette::Text)); QString text = index.data(Qt::DisplayRole).toString(); - QRect text_rect = option.rect.adjusted(rc.width() + 6, 0, 0, 0); + QRect text_rect = option.rect; + text_rect.setLeft(rc.right() + h_margin * 2); text = painter->fontMetrics().elidedText(text, Qt::ElideRight, text_rect.width()); painter->drawText(text_rect, option.displayAlignment, text); painter->restore(); + } else if (index.column() == 1 && item && item->type == SignalModel::Item::Sig) { + // draw signal value + if (option.state & QStyle::State_Selected) { + painter->fillRect(option.rect, option.palette.highlight()); + } + painter->setPen(option.palette.color(option.state & QStyle::State_Selected ? QPalette::HighlightedText : QPalette::Text)); + QRect rc = option.rect.adjusted(0, 0, -70, 0); + auto text = painter->fontMetrics().elidedText(index.data(Qt::DisplayRole).toString(), Qt::ElideRight, rc.width()); + painter->drawText(rc, Qt::AlignRight | Qt::AlignVCenter, text); } else { QStyledItemDelegate::paint(painter, option, index); } @@ -430,8 +445,11 @@ void SignalView::rowsChanged() { if (!tree->indexWidget(index)) { QWidget *w = new QWidget(this); QHBoxLayout *h = new QHBoxLayout(w); - h->setContentsMargins(0, 2, 0, 2); - h->addStretch(1); + int v_margin = style()->pixelMetric(QStyle::PM_FocusFrameVMargin); + 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", ""); diff --git a/tools/cabana/streams/livestream.cc b/tools/cabana/streams/livestream.cc index b2fc7ea4a6..8f63d3baec 100644 --- a/tools/cabana/streams/livestream.cc +++ b/tools/cabana/streams/livestream.cc @@ -89,10 +89,11 @@ void LiveStream::removeExpiredEvents() { } const std::vector *LiveStream::events() const { - events_vector.clear(); std::lock_guard lk(lock); - events_vector.reserve(can_events.size()); - std::copy(can_events.begin(), can_events.end(), std::back_inserter(events_vector)); + if (events_vector.capacity() <= can_events.size()) { + events_vector.reserve(can_events.size() * 2); + } + events_vector.assign(can_events.begin(), can_events.end()); return &events_vector; } diff --git a/tools/cabana/util.cc b/tools/cabana/util.cc index 4f79f9a3ac..1a0b9d93ef 100644 --- a/tools/cabana/util.cc +++ b/tools/cabana/util.cc @@ -67,30 +67,64 @@ void ChangeTracker::clear() { colors.clear(); } + +// SegmentTree + +void SegmentTree::build(const QVector &arr) { + size = arr.size(); + tree.resize(4 * size); // size of the tree is 4 times the size of the array + if (size > 0) { + build_tree(arr, 1, 0, size - 1); + } +} + +void SegmentTree::build_tree(const QVector &arr, int n, int left, int right) { + if (left == right) { + const double y = arr[left].y(); + tree[n] = {y, y}; + } else { + const int mid = (left + right) >> 1; + build_tree(arr, 2 * n, left, mid); + build_tree(arr, 2 * n + 1, mid + 1, right); + tree[n] = {std::min(tree[2 * n].first, tree[2 * n + 1].first), std::max(tree[2 * n].second, tree[2 * n + 1].second)}; + } +} + +std::pair SegmentTree::get_minmax(int n, int left, int right, int range_left, int range_right) const { + if (range_left > right || range_right < left) + return {std::numeric_limits::max(), std::numeric_limits::lowest()}; + if (range_left <= left && range_right >= right) + return tree[n]; + int mid = (left + right) >> 1; + auto l = get_minmax(2 * n, left, mid, range_left, range_right); + auto r = get_minmax(2 * n + 1, mid + 1, right, range_left, range_right); + return {std::min(l.first, r.first), std::max(l.second, r.second)}; +} + // MessageBytesDelegate MessageBytesDelegate::MessageBytesDelegate(QObject *parent) : QStyledItemDelegate(parent) { fixed_font = QFontDatabase::systemFont(QFontDatabase::FixedFont); + byte_width = QFontMetrics(fixed_font).width("00 "); } void MessageBytesDelegate::paint(QPainter *painter, const QStyleOptionViewItem &option, const QModelIndex &index) const { + auto colors = index.data(ColorsRole).value>(); + auto byte_list = index.data(BytesRole).toByteArray(); + + int v_margin = option.widget->style()->pixelMetric(QStyle::PM_FocusFrameVMargin); + int h_margin = option.widget->style()->pixelMetric(QStyle::PM_FocusFrameHMargin); + QRect rc{option.rect.left() + h_margin, option.rect.top() + v_margin, byte_width, option.rect.height() - 2 * v_margin}; + auto color_role = option.state & QStyle::State_Selected ? QPalette::HighlightedText: QPalette::Text; painter->setPen(option.palette.color(color_role)); painter->setFont(fixed_font); - int space = painter->boundingRect(option.rect, option.displayAlignment, " ").width(); - QRect pos = painter->boundingRect(option.rect, option.displayAlignment, "00").adjusted(0, 0, 2, 0); - pos.moveLeft(pos.x() + space); - int m = space / 2; - const QMargins margins(m, m, m, m); - - auto colors = index.data(Qt::UserRole).value>(); - auto byte_list = index.data(Qt::DisplayRole).toString().split(" "); for (int i = 0; i < byte_list.size(); ++i) { if (i < colors.size() && colors[i].alpha() > 0) { - painter->fillRect(pos.marginsAdded(margins), colors[i]); + painter->fillRect(rc, colors[i]); } - painter->drawText(pos, Qt::AlignCenter, byte_list[i]); - pos.moveLeft(pos.right() + space); + painter->drawText(rc, Qt::AlignCenter, toHex(byte_list[i])); + rc.moveLeft(rc.right() + 1); } } @@ -114,8 +148,8 @@ QValidator::State NameValidator::validate(QString &input, int &pos) const { namespace utils { QPixmap icon(const QString &id) { - static bool dark_theme = QApplication::style()->standardPalette().color(QPalette::WindowText).value() > - QApplication::style()->standardPalette().color(QPalette::Background).value(); + static bool dark_theme = QApplication::palette().color(QPalette::WindowText).value() > + QApplication::palette().color(QPalette::Background).value(); QPixmap pm; QString key = "bootstrap_" % id % (dark_theme ? "1" : "0"); if (!QPixmapCache::find(key, &pm)) { @@ -138,3 +172,13 @@ QToolButton *toolButton(const QString &icon, const QString &tooltip) { btn->setAutoRaise(true); return btn; }; + + +QString toHex(uint8_t byte) { + static std::array hex = []() { + std::array ret; + for (int i = 0; i < 256; ++i) ret[i] = QStringLiteral("%1").arg(i, 2, 16, QLatin1Char('0')).toUpper(); + return ret; + }(); + return hex[byte]; +} diff --git a/tools/cabana/util.h b/tools/cabana/util.h index b72ddfcaa0..cf1b5d4b20 100644 --- a/tools/cabana/util.h +++ b/tools/cabana/util.h @@ -14,7 +14,6 @@ #include "tools/cabana/dbcmanager.h" using namespace dbcmanager; - class ChangeTracker { public: void compute(const QByteArray &dat, double ts, uint32_t freq); @@ -31,16 +30,35 @@ private: QByteArray prev_dat; }; +enum { + ColorsRole = Qt::UserRole + 1, + BytesRole = Qt::UserRole + 2 +}; + +class SegmentTree { +public: + SegmentTree() = default; + void build(const QVector &arr); + inline std::pair minmax(int left, int right) const { return get_minmax(1, 0, size - 1, left, right); } + +private: + std::pair get_minmax(int n, int left, int right, int range_left, int range_right) const; + void build_tree(const QVector &arr, int n, int left, int right); + std::vector> tree; + int size = 0; +}; + class MessageBytesDelegate : public QStyledItemDelegate { Q_OBJECT public: MessageBytesDelegate(QObject *parent); void paint(QPainter *painter, const QStyleOptionViewItem &option, const QModelIndex &index) const override; QFont fixed_font; + int byte_width; }; inline QString toHex(const QByteArray &dat) { return dat.toHex(' ').toUpper(); } -inline char toHex(uint value) { return "0123456789ABCDEF"[value & 0xF]; } +QString toHex(uint8_t byte); QColor getColor(const dbcmanager::Signal *sig); class NameValidator : public QRegExpValidator { diff --git a/tools/replay/consoleui.cc b/tools/replay/consoleui.cc index 5ad702590c..077861ff96 100644 --- a/tools/replay/consoleui.cc +++ b/tools/replay/consoleui.cc @@ -165,7 +165,10 @@ void ConsoleUI::updateStatus() { sm.update(0); if (status != Status::Paused) { - status = (sm.updated("carState") || sm.updated("liveParameters")) ? Status::Playing : Status::Waiting; + auto events = replay->events(); + uint64_t current_mono_time = replay->routeStartTime() + replay->currentSeconds() * 1e9; + bool playing = !events->empty() && events->back()->mono_time > current_mono_time; + status = playing ? Status::Playing : Status::Waiting; } auto [status_str, status_color] = status_text[status]; write_item(0, 0, "STATUS: ", status_str, " ", false, status_color);