Merge remote-tracking branch 'upstream/master' into new-nav-settings-button

pull/29068/head
Shane Smiskol 2 years ago
commit db7fb1f314
  1. 5
      .github/workflows/selfdrive_tests.yaml
  2. 1
      .pre-commit-config.yaml
  3. 33
      Jenkinsfile
  4. 8
      RELEASES.md
  5. 2
      body
  6. 22
      common/gpio.py
  7. 1
      common/params.cc
  8. 2
      docs/CARS.md
  9. 24
      poetry.lock
  10. 3
      pyproject.toml
  11. 27
      selfdrive/athena/athenad.py
  12. 18
      selfdrive/athena/tests/test_athenad_ping.py
  13. 8
      selfdrive/car/disable_ecu.py
  14. 7
      selfdrive/car/toyota/values.py
  15. 7
      selfdrive/controls/lib/lateral_mpc_lib/SConscript
  16. 7
      selfdrive/controls/lib/longitudinal_mpc_lib/SConscript
  17. 3
      selfdrive/modeld/dmonitoringmodeld.cc
  18. 8
      selfdrive/modeld/navmodeld.cc
  19. 2
      selfdrive/test/process_replay/model_replay.py
  20. 12
      selfdrive/thermald/thermald.py
  21. 2
      selfdrive/ui/qt/maps/map.h
  22. 1
      selfdrive/ui/qt/maps/map_settings.cc
  23. 1
      selfdrive/ui/qt/maps/map_settings.h
  24. 8
      selfdrive/ui/qt/offroad/settings.cc
  25. 42
      system/hardware/tici/hardware.py
  26. 31
      system/hardware/tici/tests/test_hardware.py
  27. 36
      system/loggerd/loggerd.cc
  28. 51
      system/sensord/rawgps/rawgpsd.py
  29. 53
      system/sensord/rawgps/test_rawgps.py
  30. 4
      system/sensord/tests/test_sensord.py
  31. 9
      tools/cabana/SConscript

@ -136,6 +136,11 @@ jobs:
run: |
source tools/openpilot_env.sh
poetry run scons -j$(nproc)
- name: Run tests
run: |
source tools/openpilot_env.sh
export PYTHONPATH=$PWD
poetry run tools/plotjuggler/test_plotjuggler.py
- name: Pre Cache - Cleanup scons cache
if: github.ref == 'refs/heads/master'
run: |

@ -32,6 +32,7 @@ repos:
entry: mypy
language: system
types: [python]
args: ['--explicit-package-bases']
exclude: '^(third_party/)|(cereal/)|(opendbc/)|(panda/)|(laika/)|(laika_repo/)|(rednose/)|(rednose_repo/)|(tinygrad/)|(tinygrad_repo/)|(xx/)'
- repo: https://github.com/PyCQA/flake8
rev: 6.0.0

33
Jenkinsfile vendored

@ -18,6 +18,12 @@ export GIT_SSH_COMMAND="ssh -i /data/gitkey"
source ~/.bash_profile
if [ -f /TICI ]; then
source /etc/profile
if ! systemctl is-active --quiet systemd-resolved; then
echo "restarting resolved"
sudo systemctl start systemd-resolved
sleep 3
fi
fi
if [ -f /data/openpilot/launch_env.sh ]; then
source /data/openpilot/launch_env.sh
@ -128,6 +134,28 @@ pipeline {
}
*/
stage('scons build test') {
agent {
dockerfile {
filename 'Dockerfile.openpilot_base'
args '--user=root'
}
}
steps {
sh "git config --global --add safe.directory '*'"
sh "git submodule update --init --depth=1 --recursive"
sh "scons --clean && scons --no-cache -j42"
sh "scons --clean && scons --no-cache --random -j42"
}
post {
always {
sh "rm -rf ${WORKSPACE}/* || true"
sh "rm -rf .* || true"
}
}
}
stage('tizi-tests') {
agent { docker { image 'ghcr.io/commaai/alpine-ssh'; args '--user=root' } }
steps {
@ -138,8 +166,9 @@ pipeline {
["test sensord", "cd system/sensord/tests && python -m unittest test_sensord.py"],
["test camerad", "python system/camerad/test/test_camerad.py"],
["test exposure", "python system/camerad/test/test_exposure.py"],
["test amp", "python system/hardware/tici/tests/test_amplifier.py"],
["test rawgpsd", "python system/sensord/rawgps/test_rawgps.py"],
["test amp", "pytest system/hardware/tici/tests/test_amplifier.py"],
["test hw", "pytest system/hardware/tici/tests/test_hardware.py"],
["test rawgpsd", "pytest system/sensord/rawgps/test_rawgps.py"],
])
}
}

@ -1,14 +1,14 @@
Version 0.9.4 (2023-XX-XX)
========================
* Navigate on openpilot
* When navigation has a destination openpilot will input the map information into the model, generally improving behavior
* When navigation has a destination, openpilot will input the map information into the model, generally improving behavior
* When navigating on openpilot, openpilot will keep left or right appropriately at forks/exits and take turns
* When navigating on openpilot, lane change behavior is unchanged and still activated by the driver
* When navigating on openpilot, lane change behavior is unchanged and still activated by the driver
* When navigate on openpilot is active, the path on the map is green
* UI updates
* Navigation settings moved to home screen and map
* UI alerts rework
* Border color always shows engagement status. Blue means disengaged, green means engaged, and grey means engaged with human overriding
* Alerts are shown inside the border. Black/grey means info, orange means warning, and red means critical alert
* Alerts are shown inside the border. Black means info, orange means warning, and red means critical alert
* Bookmarked segments are preserved on the device's storage
* Ford Focus 2018 support
* Kia Carnival 2023 support thanks to sunnyhaibin!

@ -1 +1 @@
Subproject commit 5f5b8a9dff671cbf9369eb10e18b41ca619566ba
Subproject commit 05021c559e78fd7c539abceeedcc47f981b05455

@ -1,4 +1,4 @@
import glob
from functools import lru_cache
from typing import Optional, List
def gpio_init(pin: int, output: bool) -> None:
@ -25,12 +25,20 @@ def gpio_read(pin: int) -> Optional[bool]:
return val
def get_irq_for_action(action: str) -> List[int]:
ret = []
for fn in glob.glob('/sys/kernel/irq/*/actions'):
with open(fn) as f:
@lru_cache(maxsize=None)
def get_irq_action(irq: int) -> List[str]:
try:
with open(f"/sys/kernel/irq/{irq}/actions") as f:
actions = f.read().strip().split(',')
if action in actions:
irq = int(fn.split('/')[-2])
return actions
except FileNotFoundError:
return []
def get_irqs_for_action(action: str) -> List[str]:
ret = []
with open("/proc/interrupts") as f:
for l in f.readlines():
irq = l.split(':')[0].strip()
if irq.isdigit() and action in get_irq_action(irq):
ret.append(irq)
return ret

@ -107,6 +107,7 @@ std::unordered_map<std::string, uint32_t> keys = {
{"DisablePowerDown", PERSISTENT},
{"DisableUpdates", PERSISTENT},
{"DisengageOnAccelerator", PERSISTENT},
{"DmModelInitialized", CLEAR_ON_ONROAD_TRANSITION},
{"DongleId", PERSISTENT},
{"DoReboot", CLEAR_ON_MANAGER_START},
{"DoShutdown", CLEAR_ON_MANAGER_START},

@ -153,7 +153,7 @@ A supported vehicle is one that just works when you install a comma three. All s
|Lexus|RX 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|<details><summary>View</summary><sub>- 1 RJ45 cable (7 ft)<br>- 1 Toyota connector<br>- 1 comma power v2<br>- 1 comma three<br>- 1 harness box<br>- 1 mount<br>- 1 right angle OBD-C cable (1.5 ft)<br><a href="https://comma.ai/shop/comma-three.html?make=Lexus&model=RX 2020-22">Buy Here</a></sub></details>||
|Lexus|RX Hybrid 2016|Lexus Safety System+|openpilot available[<sup>2</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|<details><summary>View</summary><sub>- 1 RJ45 cable (7 ft)<br>- 1 Toyota connector<br>- 1 comma power v2<br>- 1 comma three<br>- 1 harness box<br>- 1 mount<br>- 1 right angle OBD-C cable (1.5 ft)<br><a href="https://comma.ai/shop/comma-three.html?make=Lexus&model=RX Hybrid 2016">Buy Here</a></sub></details>||
|Lexus|RX Hybrid 2017-19|All|openpilot available[<sup>2</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|<details><summary>View</summary><sub>- 1 RJ45 cable (7 ft)<br>- 1 Toyota connector<br>- 1 comma power v2<br>- 1 comma three<br>- 1 harness box<br>- 1 mount<br>- 1 right angle OBD-C cable (1.5 ft)<br><a href="https://comma.ai/shop/comma-three.html?make=Lexus&model=RX Hybrid 2017-19">Buy Here</a></sub></details>||
|Lexus|RX Hybrid 2020-21|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|<details><summary>View</summary><sub>- 1 RJ45 cable (7 ft)<br>- 1 Toyota connector<br>- 1 comma power v2<br>- 1 comma three<br>- 1 harness box<br>- 1 mount<br>- 1 right angle OBD-C cable (1.5 ft)<br><a href="https://comma.ai/shop/comma-three.html?make=Lexus&model=RX Hybrid 2020-21">Buy Here</a></sub></details>||
|Lexus|RX Hybrid 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|<details><summary>View</summary><sub>- 1 RJ45 cable (7 ft)<br>- 1 Toyota connector<br>- 1 comma power v2<br>- 1 comma three<br>- 1 harness box<br>- 1 mount<br>- 1 right angle OBD-C cable (1.5 ft)<br><a href="https://comma.ai/shop/comma-three.html?make=Lexus&model=RX Hybrid 2020-22">Buy Here</a></sub></details>||
|Lexus|UX Hybrid 2019-23|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|<details><summary>View</summary><sub>- 1 RJ45 cable (7 ft)<br>- 1 Toyota connector<br>- 1 comma power v2<br>- 1 comma three<br>- 1 harness box<br>- 1 mount<br>- 1 right angle OBD-C cable (1.5 ft)<br><a href="https://comma.ai/shop/comma-three.html?make=Lexus&model=UX Hybrid 2019-23">Buy Here</a></sub></details>||
|Lincoln|Aviator 2020-21|Co-Pilot360 Plus|openpilot available[<sup>1</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|<details><summary>View</summary><sub>- 1 Ford Q3 connector<br>- 1 RJ45 cable (7 ft)<br>- 1 comma power v2<br>- 1 comma three<br>- 1 harness box<br>- 1 mount<br>- 1 right angle OBD-C cable (1.5 ft)<br><a href="https://comma.ai/shop/comma-three.html?make=Lincoln&model=Aviator 2020-21">Buy Here</a></sub></details>||
|MAN|eTGE 2020-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,12</sup>](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|<details><summary>View</summary><sub>- 1 J533 connector<br>- 1 USB-C coupler<br>- 1 angled mount (8 degrees)<br>- 1 comma three<br>- 1 harness box<br>- 1 long OBD-C cable<br>- 1 right angle OBD-C cable (1.5 ft)<br><a href="https://comma.ai/shop/comma-three.html?make=MAN&model=eTGE 2020-23">Buy Here</a></sub></details>|<a href="https://youtu.be/4100gLeabmo" target="_blank"><img height="18px" src="assets/icon-youtube.svg"></img></a>|

24
poetry.lock generated

@ -2668,14 +2668,6 @@ python-versions = ">=2.7,!=3.0.*,!=3.1.*,!=3.2.*,!=3.3.*,!=3.4.*,!=3.5.*,!=3.6.*
[package.dependencies]
setuptools = "*"
[[package]]
name = "nose"
version = "1.3.7"
description = "nose extends unittest to make testing easier"
category = "main"
optional = false
python-versions = "*"
[[package]]
name = "notebook"
version = "6.5.4"
@ -5148,7 +5140,7 @@ testing = ["coverage (>=5.0.3)", "zope.event", "zope.testing"]
[metadata]
lock-version = "1.1"
python-versions = "~3.11"
content-hash = "571bb6cff08ad22a78f005a7635909a399a495596ca387d59dfc4d8028f7484c"
content-hash = "4d0cc4b21d5c400e874754367d7dcf9ada3b39c94cbafa27984d695daae5ee84"
[metadata.files]
adal = [
@ -6180,6 +6172,14 @@ fastcluster = [
{file = "fastcluster-1.2.6-cp310-cp310-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:9020899b67fe492d0ed87a3e993ec9962c5a0b51ea2df71d86b1766f065f1cef"},
{file = "fastcluster-1.2.6-cp310-cp310-win32.whl", hash = "sha256:6cf156d4203708348522393c523c2e61c81f5a6a500e0411dcba2b064551ea2f"},
{file = "fastcluster-1.2.6-cp310-cp310-win_amd64.whl", hash = "sha256:1801c9daa9aa5bbbb0830efe8bd3034b4b7a417e4b8dd353683999be29797df2"},
{file = "fastcluster-1.2.6-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:ce70c743490f6778b463524d1767a9ecccd31c8bd2dbb5739bb2174168c15d39"},
{file = "fastcluster-1.2.6-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:ac1b84d4b28456a379a71451d13995eb3242143452ce9c861f8913360de842a3"},
{file = "fastcluster-1.2.6-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:55b49f6033c45a28f93540847b495ed0f718b5c3f4fef446cf77e3726662e1d5"},
{file = "fastcluster-1.2.6-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:c1c776a4ec7594f47cd2e1e2da73a30134f1d402d7c93a81e3cb7c3d8e191173"},
{file = "fastcluster-1.2.6-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:aca61d16435bb7aea3901939d7d7d7e36aff9bb538123e649166a3014b280054"},
{file = "fastcluster-1.2.6-cp311-cp311-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:04ea4a68e0675072ca761bad33322a0e998cb43693fd41165bc420d7db40429a"},
{file = "fastcluster-1.2.6-cp311-cp311-win32.whl", hash = "sha256:773043d5db2790e1ff2a4e1eae0b6a60afb2a93ad2c74897a56c80bc800db04f"},
{file = "fastcluster-1.2.6-cp311-cp311-win_amd64.whl", hash = "sha256:841d128daa6597d13781793eb482b0b566bbd58d2a9d1e2cf1b58838773beb14"},
{file = "fastcluster-1.2.6-cp36-cp36m-macosx_10_9_x86_64.whl", hash = "sha256:cf5acfe1156849279ebd44a8d1fbcbe8b8e21334f7538eda782ae31e7dade9e2"},
{file = "fastcluster-1.2.6-cp36-cp36m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:cb27c13225f5f77f3c5986a27ca27277cce7db12844330cf535019cd38021257"},
{file = "fastcluster-1.2.6-cp36-cp36m-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:5fe543b6d45da27e84e5af6248722475b88943d8ef40d835cbabbb0ba5ee786b"},
@ -7629,11 +7629,6 @@ nodeenv = [
{file = "nodeenv-1.8.0-py2.py3-none-any.whl", hash = "sha256:df865724bb3c3adc86b3876fa209771517b0cfe596beff01a92700e0e8be4cec"},
{file = "nodeenv-1.8.0.tar.gz", hash = "sha256:d51e0c37e64fbf47d017feac3145cdbb58836d7eee8c6f6d3b6880c5456227d2"},
]
nose = [
{file = "nose-1.3.7-py2-none-any.whl", hash = "sha256:dadcddc0aefbf99eea214e0f1232b94f2fa9bd98fa8353711dacb112bfcbbb2a"},
{file = "nose-1.3.7-py3-none-any.whl", hash = "sha256:9ff7c6cc443f8c51994b34a667bbcf45afd6d945be7477b52e97516fd17c53ac"},
{file = "nose-1.3.7.tar.gz", hash = "sha256:f1bffef9cbc82628f6e7d7b40d7e255aefaa1adb6a1b1d26c69a8b79e6208a98"},
]
notebook = [
{file = "notebook-6.5.4-py3-none-any.whl", hash = "sha256:dd17e78aefe64c768737b32bf171c1c766666a21cc79a44d37a1700771cab56f"},
{file = "notebook-6.5.4.tar.gz", hash = "sha256:517209568bd47261e2def27a140e97d49070602eea0d226a696f42a7f16c9a4e"},
@ -7977,6 +7972,7 @@ pillow-avif-plugin = [
{file = "pillow_avif_plugin-1.3.1-cp311-cp311-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:7a9b8e8943a8b9f860d2b03e0b9c9839bc59db22c5a0a55d66a534a3d4cea00b"},
{file = "pillow_avif_plugin-1.3.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:98dbb6b21ab5b7e0d80134721e756c956d4de2c6cb5c48bb32f78f97339425cb"},
{file = "pillow_avif_plugin-1.3.1-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:c4d0b80ff0819de1ba6d401796bc900be252468621b6e734560eee2ea154dbb4"},
{file = "pillow_avif_plugin-1.3.1-cp311-cp311-win_amd64.whl", hash = "sha256:c4ff1d331df8ca0f0c5c90d3f05b3a05325c40c9f330e0ad58eb70f7ede20157"},
{file = "pillow_avif_plugin-1.3.1-cp37-cp37m-macosx_10_10_x86_64.whl", hash = "sha256:0a02a436494e380fc99d5ff48be2ef15d42ce655614b9ebd80e106615eb3a594"},
{file = "pillow_avif_plugin-1.3.1-cp37-cp37m-macosx_11_0_arm64.whl", hash = "sha256:fe8250efd581e362a135d63bbca62b0c78ef1e474582da4013c3a995bc1f40c2"},
{file = "pillow_avif_plugin-1.3.1-cp37-cp37m-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:39e93224a3d0132a64e7d978e48b74f020c65fcb3a141641084d2a4357ed6ceb"},

@ -26,13 +26,11 @@ hexdump = "^3.3"
Jinja2 = "^3.1.2"
json-rpc = "^1.13.0"
libusb1 = "^3.0.0"
nose = "^1.3.7"
numpy = "==1.23.0" # locked pending deprecation fixes in xx
onnx = "^1.14.0"
onnxruntime-gpu = { version = "^1.15.1", platform = "linux", markers = "platform_machine == 'x86_64'" }
pillow = "^9.2.0"
poetry = "==1.2.2"
protobuf = "==3.20.3"
psutil = "^5.9.1"
pycapnp = "^1.3.0"
pycryptodome = "^3.15.0"
@ -46,7 +44,6 @@ requests = "^2.28.1"
scons = "^4.5.2"
sentry-sdk = "^1.6.0"
setproctitle = "^1.2.3"
six = "^1.16.0"
smbus2 = "^0.4.2"
sounddevice = "^0.4.5"
spidev = { version = "^3.6", platform = "linux" }

@ -42,6 +42,10 @@ from selfdrive.statsd import STATS_DIR
from system.swaglog import SWAGLOG_DIR, cloudlog
from system.version import get_commit, get_origin, get_short_branch, get_version
# missing in pysocket
TCP_USER_TIMEOUT = 18
ATHENA_HOST = os.getenv('ATHENA_HOST', 'wss://athena.comma.ai')
HANDLER_THREADS = int(os.getenv('HANDLER_THREADS', "4"))
LOCAL_PORT_WHITELIST = {8022}
@ -141,6 +145,7 @@ def handle_long_poll(ws: WebSocket, exit_event: Optional[threading.Event]) -> No
end_event = threading.Event()
threads = [
threading.Thread(target=ws_manage, args=(ws, end_event), name='ws_manage'),
threading.Thread(target=ws_recv, args=(ws, end_event), name='ws_recv'),
threading.Thread(target=ws_send, args=(ws, end_event), name='ws_send'),
threading.Thread(target=upload_handler, args=(end_event,), name='upload_handler'),
@ -154,8 +159,7 @@ def handle_long_poll(ws: WebSocket, exit_event: Optional[threading.Event]) -> No
for thread in threads:
thread.start()
try:
while not end_event.is_set():
time.sleep(0.1)
while not end_event.wait(0.1):
if exit_event is not None and exit_event.is_set():
end_event.set()
except (KeyboardInterrupt, SystemExit):
@ -756,6 +760,25 @@ def ws_send(ws: WebSocket, end_event: threading.Event) -> None:
end_event.set()
def ws_manage(ws: WebSocket, end_event: threading.Event) -> None:
params = Params()
onroad_prev = None
sock = ws.sock
while True:
onroad = params.get_bool("IsOnroad")
if onroad != onroad_prev:
onroad_prev = onroad
sock.setsockopt(socket.IPPROTO_TCP, TCP_USER_TIMEOUT, 16000 if onroad else 0)
sock.setsockopt(socket.IPPROTO_TCP, socket.TCP_KEEPIDLE, 7 if onroad else 30)
sock.setsockopt(socket.IPPROTO_TCP, socket.TCP_KEEPINTVL, 7 if onroad else 10)
sock.setsockopt(socket.IPPROTO_TCP, socket.TCP_KEEPCNT, 2 if onroad else 3)
if end_event.wait(5):
break
def backoff(retries: int) -> int:
return random.randrange(0, min(128, int(2 ** retries)))

@ -37,6 +37,9 @@ class TestAthenadPing(unittest.TestCase):
def _received_ping(self) -> bool:
return self._get_ping_time() is not None
def _set_onroad(self, onroad: bool) -> None:
self.params.put_bool("IsOnroad", onroad)
@classmethod
def setUpClass(cls) -> None:
cls.params = Params()
@ -63,8 +66,7 @@ class TestAthenadPing(unittest.TestCase):
self.exit_event.set()
self.athenad.join()
@unittest.skipIf(not TICI, "only run on desk")
def test_timeout(self) -> None:
def assertTimeout(self, reconnect_time: float) -> None:
self.athenad.start()
time.sleep(1)
@ -84,7 +86,7 @@ class TestAthenadPing(unittest.TestCase):
wifi_radio(False)
print("waiting for reconnect attempt")
start_time = time.monotonic()
with Timeout(180, "no reconnect attempt"):
with Timeout(reconnect_time, "no reconnect attempt"):
while not athenad.create_connection.called:
time.sleep(0.1)
print(f"reconnect attempt after {time.monotonic() - start_time:.2f}s")
@ -97,6 +99,16 @@ class TestAthenadPing(unittest.TestCase):
time.sleep(0.1)
print("ping received")
@unittest.skipIf(not TICI, "only run on desk")
def test_offroad(self) -> None:
self._set_onroad(False)
self.assertTimeout(100) # expect approx 90s
@unittest.skipIf(not TICI, "only run on desk")
def test_onroad(self) -> None:
self._set_onroad(True)
self.assertTimeout(30) # expect 20-30s
if __name__ == "__main__":
unittest.main()

@ -7,22 +7,22 @@ EXT_DIAG_RESPONSE = b'\x50\x03'
COM_CONT_RESPONSE = b''
def disable_ecu(logcan, sendcan, bus=0, addr=0x7d0, com_cont_req=b'\x28\x83\x01', timeout=0.1, retry=10, debug=False):
def disable_ecu(logcan, sendcan, bus=0, addr=0x7d0, sub_addr=None, com_cont_req=b'\x28\x83\x01', timeout=0.1, retry=10, debug=False):
"""Silence an ECU by disabling sending and receiving messages using UDS 0x28.
The ECU will stay silent as long as openpilot keeps sending Tester Present.
This is used to disable the radar in some cars. Openpilot will emulate the radar.
WARNING: THIS DISABLES AEB!"""
cloudlog.warning(f"ecu disable {hex(addr)} ...")
cloudlog.warning(f"ecu disable {hex(addr), sub_addr} ...")
for i in range(retry):
try:
query = IsoTpParallelQuery(sendcan, logcan, bus, [addr], [EXT_DIAG_REQUEST], [EXT_DIAG_RESPONSE], debug=debug)
query = IsoTpParallelQuery(sendcan, logcan, bus, [(addr, sub_addr)], [EXT_DIAG_REQUEST], [EXT_DIAG_RESPONSE], debug=debug)
for _, _ in query.get_data(timeout).items():
cloudlog.warning("communication control disable tx/rx ...")
query = IsoTpParallelQuery(sendcan, logcan, bus, [addr], [com_cont_req], [COM_CONT_RESPONSE], debug=debug)
query = IsoTpParallelQuery(sendcan, logcan, bus, [(addr, sub_addr)], [com_cont_req], [COM_CONT_RESPONSE], debug=debug)
query.get_data(0)
cloudlog.warning("ecu disabled")

@ -197,7 +197,7 @@ CAR_INFO: Dict[str, Union[ToyotaCarInfo, List[ToyotaCarInfo]]] = {
ToyotaCarInfo("Lexus RX Hybrid 2017-19"),
],
CAR.LEXUS_RX_TSS2: ToyotaCarInfo("Lexus RX 2020-22"),
CAR.LEXUS_RXH_TSS2: ToyotaCarInfo("Lexus RX Hybrid 2020-21"),
CAR.LEXUS_RXH_TSS2: ToyotaCarInfo("Lexus RX Hybrid 2020-22"),
}
# (addr, cars, bus, 1/freq*100, vl)
@ -2129,15 +2129,16 @@ FW_VERSIONS = {
b'F152648811\x00\x00\x00\x00\x00\x00',
],
(Ecu.eps, 0x7a1, None): [
b'8965B48271\x00\x00\x00\x00\x00\x00',
b'8965B48261\x00\x00\x00\x00\x00\x00',
b'8965B48271\x00\x00\x00\x00\x00\x00',
],
(Ecu.fwdRadar, 0x750, 0xf): [
b'\x018821F3301400\x00\x00\x00\x00',
],
(Ecu.fwdCamera, 0x750, 0x6d): [
b'\x028646F4810200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00',
b'\x028646F4810100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00',
b'\x028646F4810200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00',
b'\x028646F4810300\x00\x00\x00\x008646G2601400\x00\x00\x00\x00',
],
},
CAR.PRIUS_TSS2: {

@ -57,9 +57,10 @@ source_list = ['lat_mpc.py',
lenv = env.Clone()
lenv.Clean(generated_files, Dir(gen))
lenv.Command(generated_files,
source_list,
f"cd {Dir('.').abspath} && python3 lat_mpc.py")
generated_lat = lenv.Command(generated_files,
source_list,
f"cd {Dir('.').abspath} && python3 lat_mpc.py")
lenv.Depends(generated_lat, "#common")
lenv["CFLAGS"].append("-DACADOS_WITH_QPOASES")
lenv["CXXFLAGS"].append("-DACADOS_WITH_QPOASES")

@ -64,9 +64,10 @@ source_list = ['long_mpc.py',
lenv = env.Clone()
lenv.Clean(generated_files, Dir(gen))
lenv.Command(generated_files,
source_list,
f"cd {Dir('.').abspath} && python3 long_mpc.py")
generated_long = lenv.Command(generated_files,
source_list,
f"cd {Dir('.').abspath} && python3 long_mpc.py")
lenv.Depends(generated_long, "#cereal")
lenv["CFLAGS"].append("-DACADOS_WITH_QPOASES")
lenv["CXXFLAGS"].append("-DACADOS_WITH_QPOASES")

@ -5,6 +5,7 @@
#include <cstdlib>
#include "cereal/visionipc/visionipc_client.h"
#include "common/params.h"
#include "common/swaglog.h"
#include "common/util.h"
#include "selfdrive/modeld/models/dmonitoring.h"
@ -49,6 +50,8 @@ int main(int argc, char **argv) {
DMonitoringModelState model;
dmonitoring_init(&model);
Params().putBool("DmModelInitialized", true);
LOGW("connecting to driver stream");
VisionIpcClient vipc_client = VisionIpcClient("camerad", VISION_STREAM_DRIVER, true);
while (!do_exit && !vipc_client.connect(false)) {

@ -5,6 +5,7 @@
#include <cstdlib>
#include "cereal/visionipc/visionipc_client.h"
#include "common/params.h"
#include "common/swaglog.h"
#include "common/util.h"
#include "selfdrive/modeld/models/nav.h"
@ -41,6 +42,13 @@ void run_model(NavModelState &model, VisionIpcClient &vipc_client) {
int main(int argc, char **argv) {
setpriority(PRIO_PROCESS, 0, -15);
// there exists a race condition when two processes try to create a
// SNPE model runner at the same time, wait for dmonitoringmodeld to finish
LOGW("waiting for dmonitoringmodeld to initialize");
if (!Params().getBool("DmModelInitialized", true)) {
return 0;
}
// init the models
NavModelState model;
navmodel_init(&model);

@ -6,6 +6,7 @@ from collections import defaultdict
from typing import Any
import cereal.messaging as messaging
from common.params import Params
from common.spinner import Spinner
from system.hardware import PC
from selfdrive.manager.process_config import managed_processes
@ -62,6 +63,7 @@ def nav_model_replay(lr):
try:
assert "MAPBOX_TOKEN" in os.environ
os.environ['MAP_RENDER_TEST_MODE'] = '1'
Params().put_bool('DmModelInitialized', True)
managed_processes['mapsd'].start()
managed_processes['navmodeld'].start()

@ -103,6 +103,8 @@ def hw_state_thread(end_event, hw_queue):
modem_version = None
modem_nv = None
modem_configured = False
modem_restarted = False
modem_missing_count = 0
while not end_event.is_set():
# these are expensive calls. update every 10s
@ -120,6 +122,16 @@ def hw_state_thread(end_event, hw_queue):
if (modem_version is not None) and (modem_nv is not None):
cloudlog.event("modem version", version=modem_version, nv=modem_nv)
else:
if not modem_restarted:
# TODO: we may be able to remove this with a MM update
# ModemManager's probing on startup can fail
# rarely, restart the service to probe again.
modem_missing_count += 1
if modem_missing_count > 3:
modem_restarted = True
cloudlog.event("restarting ModemManager")
os.system("sudo systemctl restart --no-block ModemManager")
tx, rx = HARDWARE.get_modem_data_usage()

@ -49,8 +49,6 @@ private:
void pinchTriggered(QPinchGesture *gesture);
void setError(const QString &err_str);
bool m_sourceAdded = false;
bool loaded_once = false;
bool allow_open = true;

@ -8,7 +8,6 @@
#include "selfdrive/ui/qt/widgets/scrollview.h"
MapSettings::MapSettings(bool closeable, QWidget *parent) : QFrame(parent) {
close_icon = loadPixmap("../assets/icons/close.svg", {100, 100});
setContentsMargins(0, 0, 0, 0);
auto *frame = new QVBoxLayout(this);

@ -62,7 +62,6 @@ private:
DestinationWidget *home_widget;
DestinationWidget *work_widget;
std::vector<DestinationWidget *> widgets;
QPixmap close_icon;
signals:
void closeSettings();

@ -234,7 +234,7 @@ DevicePanel::DevicePanel(SettingsWindow *parent) : ListWidget(parent) {
QString selection = MultiOptionDialog::getSelection(tr("Select a language"), langs.keys(), langs.key(uiState()->language), this);
if (!selection.isEmpty()) {
// put language setting, exit Qt UI, and trigger fast restart
Params().put("LanguageSetting", langs[selection].toStdString());
params.put("LanguageSetting", langs[selection].toStdString());
qApp->exit(18);
watchdog_kick(0);
}
@ -278,7 +278,7 @@ void DevicePanel::updateCalibDescription() {
QString desc =
tr("openpilot requires the device to be mounted within 4° left or right and "
"within 5° up or 8° down. openpilot is continuously calibrating, resetting is rarely required.");
std::string calib_bytes = Params().get("CalibrationParams");
std::string calib_bytes = params.get("CalibrationParams");
if (!calib_bytes.empty()) {
try {
AlignedBuffer aligned_buf;
@ -303,7 +303,7 @@ void DevicePanel::reboot() {
if (ConfirmationDialog::confirm(tr("Are you sure you want to reboot?"), tr("Reboot"), this)) {
// Check engaged again in case it changed while the dialog was open
if (!uiState()->engaged()) {
Params().putBool("DoReboot", true);
params.putBool("DoReboot", true);
}
}
} else {
@ -316,7 +316,7 @@ void DevicePanel::poweroff() {
if (ConfirmationDialog::confirm(tr("Are you sure you want to power off?"), tr("Power Off"), this)) {
// Check engaged again in case it changed while the dialog was open
if (!uiState()->engaged()) {
Params().putBool("DoShutdown", true);
params.putBool("DoShutdown", true);
}
}
} else {

@ -8,7 +8,7 @@ from functools import cached_property, lru_cache
from pathlib import Path
from cereal import log
from common.gpio import gpio_set, gpio_init, get_irq_for_action
from common.gpio import gpio_set, gpio_init, get_irqs_for_action
from system.hardware.base import HardwareBase, ThermalConfig
from system.hardware.tici import iwlist
from system.hardware.tici.pins import GPIO
@ -61,17 +61,27 @@ MM_MODEM_ACCESS_TECHNOLOGY_LTE = 1 << 14
def sudo_write(val, path):
os.system(f"sudo su -c 'echo {val} > {path}'")
try:
with open(path, 'w') as f:
f.write(str(val))
except PermissionError:
os.system(f"sudo chmod a+w {path}")
try:
with open(path, 'w') as f:
f.write(str(val))
except PermissionError:
# fallback for debugfs files
os.system(f"sudo su -c 'echo {val} > {path}'")
def affine_irq(val, action):
irq = get_irq_for_action(action)
if len(irq) == 0:
irqs = get_irqs_for_action(action)
if len(irqs) == 0:
print(f"No IRQs found for '{action}'")
return
for i in irq:
sudo_write(str(val), f"/proc/irq/{i}/smp_affinity_list")
for i in irqs:
sudo_write(str(val), f"/proc/irq/{i}/smp_affinity_list")
class Tici(HardwareBase):
@cached_property
@ -438,17 +448,17 @@ class Tici(HardwareBase):
# *** IRQ config ***
# GPU
affine_irq(5, "kgsl-3d0")
# boardd core
affine_irq(4, "spi_geni") # SPI
affine_irq(4, "xhci-hcd:usb3") # aux panda USB (or potentially anything else on USB)
if "tici" in self.get_device_type():
affine_irq(4, "xhci-hcd:usb1") # internal panda USB
affine_irq(4, "xhci-hcd:usb1") # internal panda USB (also modem)
# GPU
affine_irq(5, "kgsl-3d0")
# camerad core
camera_irqs = ("cci", "cpas_camnoc", "cpas-cdm", "csid", "ife", "csid", "csid-lite", "ife-lite")
camera_irqs = ("cci", "cpas_camnoc", "cpas-cdm", "csid", "ife", "csid-lite", "ife-lite")
for n in camera_irqs:
affine_irq(5, n)
@ -472,14 +482,14 @@ class Tici(HardwareBase):
# *** IRQ config ***
# move these off the default core
affine_irq(1, "msm_drm")
affine_irq(1, "msm_vidc")
affine_irq(1, "i2c_geni")
# mask off big cluster from default affinity
sudo_write("f", "/proc/irq/default_smp_affinity")
# move these off the default core
affine_irq(1, "msm_drm") # display
affine_irq(1, "msm_vidc") # encoders
affine_irq(1, "i2c_geni") # sensors
# *** GPU config ***
# https://github.com/commaai/agnos-kernel-sdm845/blob/master/arch/arm64/boot/dts/qcom/sdm845-gpu.dtsi#L216
sudo_write("1", "/sys/class/kgsl/kgsl-3d0/min_pwrlevel")

@ -0,0 +1,31 @@
#!/usr/bin/env python3
import time
import unittest
import numpy as np
from system.hardware import TICI
from system.hardware.tici.hardware import Tici
HARDWARE = Tici()
class TestHardware(unittest.TestCase):
@classmethod
def setUpClass(cls):
if not TICI:
raise unittest.SkipTest
def test_power_save_time(self):
ts = []
for _ in range(5):
for on in (True, False):
st = time.monotonic()
HARDWARE.set_power_save(on)
ts.append(time.monotonic() - st)
assert 0.1 < np.mean(ts) < 0.2
assert max(ts) < 0.3
if __name__ == "__main__":
unittest.main()

@ -173,6 +173,9 @@ int handle_encoder_msg(LoggerdState *s, Message *msg, std::string &name, struct
}
void handle_user_flag(LoggerdState *s) {
static int prev_segment = -1;
if (s->rotate_segment == prev_segment) return;
LOGW("preserving %s", s->segment_path);
#ifdef __APPLE__
@ -183,16 +186,17 @@ void handle_user_flag(LoggerdState *s) {
if (ret) {
LOGE("setxattr %s failed for %s: %s", PRESERVE_ATTR_NAME, s->segment_path, strerror(errno));
}
prev_segment = s->rotate_segment.load();
}
void loggerd_thread() {
// setup messaging
typedef struct QlogState {
typedef struct ServiceState {
std::string name;
int counter, freq;
bool encoder;
} QlogState;
std::unordered_map<SubSocket*, QlogState> qlog_states;
bool encoder, user_flag;
} ServiceState;
std::unordered_map<SubSocket*, ServiceState> service_state;
std::unordered_map<SubSocket*, struct RemoteEncoder> remote_encoders;
std::unique_ptr<Context> ctx(Context::create());
@ -207,11 +211,12 @@ void loggerd_thread() {
SubSocket * sock = SubSocket::create(ctx.get(), it.name);
assert(sock != NULL);
poller->registerSocket(sock);
qlog_states[sock] = {
service_state[sock] = {
.name = it.name,
.counter = 0,
.freq = it.decimation,
.encoder = encoder,
.user_flag = (strcmp(it.name, "userFlag") == 0),
};
}
@ -236,20 +241,19 @@ void loggerd_thread() {
for (auto sock : poller->poll(1000)) {
if (do_exit) break;
ServiceState &service = service_state[sock];
if (service.user_flag) {
handle_user_flag(&s);
}
// drain socket
int count = 0;
QlogState &qs = qlog_states[sock];
Message *msg = nullptr;
while (!do_exit && (msg = sock->receive(true))) {
const bool in_qlog = qs.freq != -1 && (qs.counter++ % qs.freq == 0);
if (qs.name == "userFlag") {
handle_user_flag(&s);
}
if (qs.encoder) {
const bool in_qlog = service.freq != -1 && (service.counter++ % service.freq == 0);
if (service.encoder) {
s.last_camera_seen_tms = millis_since_boot();
bytes_count += handle_encoder_msg(&s, msg, qs.name, remote_encoders[sock], encoder_infos_dict[qs.name]);
bytes_count += handle_encoder_msg(&s, msg, service.name, remote_encoders[sock], encoder_infos_dict[service.name]);
} else {
logger_log(&s.logger, (uint8_t *)msg->getData(), msg->getSize(), in_qlog);
bytes_count += msg->getSize();
@ -265,7 +269,7 @@ void loggerd_thread() {
count++;
if (count >= 200) {
LOGD("large volume of '%s' messages", qs.name.c_str());
LOGD("large volume of '%s' messages", service.name.c_str());
break;
}
}
@ -282,7 +286,7 @@ void loggerd_thread() {
}
// messaging cleanup
for (auto &[sock, qs] : qlog_states) delete sock;
for (auto &[sock, service] : service_state) delete sock;
}
int main(int argc, char** argv) {

@ -149,20 +149,26 @@ def downloader_loop(event):
time.sleep(10)
def inject_assistance():
try:
cmd = f"mmcli -m any --timeout 30 --location-inject-assistance-data={ASSIST_DATA_FILE}"
subprocess.check_output(cmd, stderr=subprocess.PIPE, shell=True)
cloudlog.info("successfully loaded assistance data")
except subprocess.CalledProcessError as e:
cloudlog.event(
"rawgps.assistance_loading_failed",
error=True,
cmd=e.cmd,
output=e.output,
returncode=e.returncode
)
def setup_quectel(diag: ModemDiag):
for _ in range(5):
try:
cmd = f"mmcli -m any --timeout 30 --location-inject-assistance-data={ASSIST_DATA_FILE}"
subprocess.check_output(cmd, stderr=subprocess.PIPE, shell=True)
cloudlog.info("successfully loaded assistance data")
return
except subprocess.CalledProcessError as e:
cloudlog.event(
"rawgps.assistance_loading_failed",
error=True,
cmd=e.cmd,
output=e.output,
returncode=e.returncode
)
time.sleep(0.2)
cloudlog.error("failed to load assistance after retry")
def setup_quectel(diag: ModemDiag) -> bool:
ret = False
# enable OEMDRE in the NV
# TODO: it has to reboot for this to take effect
DIAG_NV_READ_F = 38
@ -186,7 +192,9 @@ def setup_quectel(diag: ModemDiag):
at_cmd("AT+QGPSXTRA=1")
at_cmd("AT+QGPSSUPLURL=\"NULL\"")
if os.path.exists(ASSIST_DATA_FILE):
ret = True
inject_assistance()
os.remove(ASSIST_DATA_FILE)
#at_cmd("AT+QGPSXTRADATA?")
time_str = datetime.utcnow().strftime("%Y/%m/%d,%H:%M:%S")
at_cmd(f"AT+QGPSXTRATIME=0,\"{time_str}\",1,1,1000")
@ -213,6 +221,8 @@ def setup_quectel(diag: ModemDiag):
0,0
))
return ret
def teardown_quectel(diag):
at_cmd("AT+QGPSCFG=\"outport\",\"none\"")
if gps_enabled():
@ -260,8 +270,8 @@ def main() -> NoReturn:
# connect to modem
diag = ModemDiag()
setup_quectel(diag)
want_assistance = True
r = setup_quectel(diag)
want_assistance = not r
current_gps_time = utc_to_gpst(GPSTime.from_datetime(datetime.utcnow()))
cloudlog.warning("quectel setup done")
gpio_init(GPIO.UBLOX_PWR_EN, True)
@ -270,12 +280,9 @@ def main() -> NoReturn:
pm = messaging.PubMaster(['qcomGnss', 'gpsLocation'])
while 1:
if os.path.exists(ASSIST_DATA_FILE):
if want_assistance:
setup_quectel(diag)
want_assistance = False
else:
os.remove(ASSIST_DATA_FILE)
if os.path.exists(ASSIST_DATA_FILE) and want_assistance:
setup_quectel(diag)
want_assistance = False
opcode, payload = diag.recv()
if opcode != DIAG_LOG_F:

@ -19,12 +19,12 @@ GOOD_SIGNAL = bool(int(os.getenv("GOOD_SIGNAL", '0')))
class TestRawgpsd(unittest.TestCase):
@classmethod
def setUpClass(cls):
os.system("sudo systemctl restart systemd-resolved")
os.system("sudo systemctl restart ModemManager lte")
wait_for_modem()
if not TICI:
raise unittest.SkipTest
cls.sm = messaging.SubMaster(['qcomGnss', 'gpsLocation', 'gnssMeasurements'])
os.system("sudo systemctl start systemd-resolved")
os.system("sudo systemctl restart ModemManager lte")
wait_for_modem()
@classmethod
def tearDownClass(cls):
@ -34,40 +34,44 @@ class TestRawgpsd(unittest.TestCase):
def setUp(self):
at_cmd("AT+QGPSDEL=0")
self.sm = messaging.SubMaster(['qcomGnss', 'gpsLocation', 'gnssMeasurements'])
def tearDown(self):
managed_processes['rawgpsd'].stop()
os.system("sudo systemctl restart systemd-resolved")
def _wait_for_output(self, t=10):
time.sleep(t)
self.sm.update()
def _wait_for_output(self, t):
dt = 0.1
for _ in range(t*int(1/dt)):
self.sm.update(0)
if self.sm.updated['qcomGnss']:
break
time.sleep(dt)
return self.sm.updated['qcomGnss']
def test_no_crash_double_command(self):
at_cmd("AT+QGPSDEL=0")
at_cmd("AT+QGPSDEL=0")
def test_wait_for_modem(self):
os.system("sudo systemctl stop ModemManager lte")
os.system("sudo systemctl stop ModemManager")
managed_processes['rawgpsd'].start()
self._wait_for_output(10)
assert not self.sm.updated['qcomGnss']
assert not self._wait_for_output(5)
os.system("sudo systemctl restart ModemManager lte")
self._wait_for_output(30)
assert self.sm.updated['qcomGnss']
os.system("sudo systemctl restart ModemManager")
assert self._wait_for_output(30)
def test_startup_time(self):
for i in range(2):
if i == 1:
for internet in (True, False):
if not internet:
os.system("sudo systemctl stop systemd-resolved")
managed_processes['rawgpsd'].start()
self._wait_for_output(10)
assert self.sm.updated['qcomGnss']
managed_processes['rawgpsd'].stop()
with self.subTest(internet=internet):
managed_processes['rawgpsd'].start()
assert self._wait_for_output(7)
managed_processes['rawgpsd'].stop()
def test_turns_off_gnss(self):
for s in (0.1, 0.5, 1, 5):
for s in (0.1, 1, 5):
managed_processes['rawgpsd'].start()
time.sleep(s)
managed_processes['rawgpsd'].stop()
@ -95,8 +99,7 @@ class TestRawgpsd(unittest.TestCase):
def test_assistance_loading(self):
managed_processes['rawgpsd'].start()
self._wait_for_output(10)
assert self.sm.updated['qcomGnss']
assert self._wait_for_output(10)
managed_processes['rawgpsd'].stop()
self.check_assistance(True)
@ -104,8 +107,7 @@ class TestRawgpsd(unittest.TestCase):
os.system("sudo systemctl stop systemd-resolved")
managed_processes['rawgpsd'].start()
self._wait_for_output(10)
assert self.sm.updated['qcomGnss']
assert self._wait_for_output(10)
managed_processes['rawgpsd'].stop()
self.check_assistance(False)
@ -115,8 +117,9 @@ class TestRawgpsd(unittest.TestCase):
managed_processes['rawgpsd'].start()
self._wait_for_output(17)
assert self.sm.updated['qcomGnss']
os.system("sudo systemctl restart systemd-resolved")
self._wait_for_output(15)
time.sleep(15)
managed_processes['rawgpsd'].stop()
self.check_assistance(True)

@ -7,7 +7,7 @@ from collections import namedtuple, defaultdict
import cereal.messaging as messaging
from cereal import log
from common.gpio import get_irq_for_action
from common.gpio import get_irqs_for_action
from system.hardware import TICI
from selfdrive.manager.process_config import managed_processes
@ -113,7 +113,7 @@ class TestSensord(unittest.TestCase):
cls.events = read_sensor_events(cls.sample_secs)
# determine sensord's irq
cls.sensord_irq = get_irq_for_action("sensord")[0]
cls.sensord_irq = get_irqs_for_action("sensord")[0]
finally:
# teardown won't run if this doesn't succeed
managed_processes["sensord"].stop()

@ -29,7 +29,7 @@ cabana_env.Depends(assets, Glob('/assets/*', exclude=[assets, assets_src, "asset
prev_moc_path = cabana_env['QT_MOCHPREFIX']
cabana_env['QT_MOCHPREFIX'] = os.path.dirname(prev_moc_path) + '/cabana/moc_'
cabana_lib = cabana_env.Library("cabana_lib", ['mainwin.cc', 'streams/pandastream.cc', 'streams/devicestream.cc', 'streams/livestream.cc', 'streams/abstractstream.cc', 'streams/replaystream.cc', 'binaryview.cc', 'historylog.cc', 'videowidget.cc', 'signalview.cc',
cabana_lib = cabana_env.Library("cabana_lib", ['mainwin.cc', 'streams/pandastream.cc', 'streams/devicestream.cc', 'streams/livestream.cc', 'streams/abstractstream.cc', 'streams/replaystream.cc', 'binaryview.cc', 'historylog.cc', 'videowidget.cc', 'signalview.cc',
'dbc/dbc.cc', 'dbc/dbcfile.cc', 'dbc/dbcmanager.cc',
'chart/chartswidget.cc', 'chart/chart.cc', 'chart/signalselector.cc', 'chart/tiplabel.cc', 'chart/sparkline.cc',
'commands.cc', 'messageswidget.cc', 'streamselector.cc', 'settings.cc', 'util.cc', 'detailwidget.cc', 'tools/findsimilarbits.cc', 'tools/findsignal.cc'], LIBS=cabana_libs, FRAMEWORKS=base_frameworks)
@ -38,6 +38,7 @@ cabana_env.Program('cabana', ['cabana.cc', cabana_lib, assets], LIBS=cabana_libs
if GetOption('test'):
cabana_env.Program('tests/test_cabana', ['tests/test_runner.cc', 'tests/test_cabana.cc', cabana_lib], LIBS=[cabana_libs])
def generate_dbc_json(target, source, env):
env.Execute('tools/cabana/dbc/generate_dbc_json.py --out tools/cabana/dbc/car_fingerprint_to_dbc.json')
cabana_env.Command('generate_dbc_json', [], generate_dbc_json)
generate_dbc = cabana_env.Command('generate_dbc_json',
[],
"python3 tools/cabana/dbc/generate_dbc_json.py --out tools/cabana/dbc/car_fingerprint_to_dbc.json")
cabana_env.Depends(generate_dbc, ["#common", "#selfdrive/boardd", "#opendbc", "#cereal"])

Loading…
Cancel
Save