Compare commits

..

1 Commits

Author SHA1 Message Date
Jason Wen b4259145fb Hyundai longitudinal: enable for KIA_CEED 2023-09-05 15:51:24 -04:00
138 changed files with 1899 additions and 886 deletions
Regular → Executable
View File
+1 -1
View File
@@ -18,7 +18,7 @@ jobs:
- uses: actions/checkout@v3
with:
submodules: true
- uses: ./.github/workflows/setup-with-retry
- uses: ./.github/workflows/setup
- name: Push badges
run: |
${{ env.RUN }} "scons -j$(nproc) && python selfdrive/ui/translations/create_badges.py"
+10 -10
View File
@@ -41,7 +41,7 @@ jobs:
- name: Build devel
timeout-minutes: 1
run: TARGET_DIR=$STRIPPED_DIR release/build_devel.sh
- uses: ./.github/workflows/setup-with-retry
- uses: ./.github/workflows/setup
- name: Check submodules
if: github.ref == 'refs/heads/master' && github.repository == 'commaai/openpilot'
timeout-minutes: 1
@@ -74,7 +74,7 @@ jobs:
- uses: actions/checkout@v3
with:
submodules: true
- uses: ./.github/workflows/setup-with-retry
- uses: ./.github/workflows/setup
- name: Build openpilot with all flags
timeout-minutes: ${{ ((steps.restore-scons-cache.outputs.cache-hit == 'true') && 12 || 30) }} # allow more time when we missed the scons cache
run: |
@@ -196,7 +196,7 @@ jobs:
run: |
echo "PUSH_IMAGE=true" >> "$GITHUB_ENV"
$DOCKER_LOGIN
- uses: ./.github/workflows/setup-with-retry
- uses: ./.github/workflows/setup
with:
git-lfs: false
- name: Build and push CL Docker image
@@ -223,7 +223,7 @@ jobs:
- uses: actions/checkout@v3
with:
submodules: true
- uses: ./.github/workflows/setup-with-retry
- uses: ./.github/workflows/setup
- name: Build openpilot
run: ${{ env.RUN }} "scons -j$(nproc)"
- name: Run valgrind
@@ -241,7 +241,7 @@ jobs:
- uses: actions/checkout@v3
with:
submodules: true
- uses: ./.github/workflows/setup-with-retry
- uses: ./.github/workflows/setup
- name: Build openpilot
timeout-minutes: ${{ ((steps.restore-scons-cache.outputs.cache-hit == 'true') && 10 || 30) }} # allow more time when we missed the scons cache
run: ${{ env.RUN }} "scons -j$(nproc)"
@@ -249,7 +249,7 @@ jobs:
timeout-minutes: 40
run: |
${{ env.RUN }} "export SKIP_LONG_TESTS=1 && \
$PYTEST -n auto --dist=loadscope --timeout 30 && \
$PYTEST --rootdir . -c selfdrive/test/pytest-ci.ini && \
selfdrive/locationd/test/_test_locationd_lib.py && \
./system/ubloxd/tests/test_glonass_runner && \
./selfdrive/ui/tests/create_test_translations.sh && \
@@ -273,7 +273,7 @@ jobs:
- uses: actions/checkout@v3
with:
submodules: true
- uses: ./.github/workflows/setup-with-retry
- uses: ./.github/workflows/setup
- name: Cache test routes
id: dependency-cache
uses: actions/cache@v3
@@ -313,7 +313,7 @@ jobs:
- uses: actions/checkout@v3
with:
submodules: true
- uses: ./.github/workflows/setup-with-retry
- uses: ./.github/workflows/setup
- name: Build base Docker image
run: eval "$BUILD"
- name: Build Docker image
@@ -349,7 +349,7 @@ jobs:
- uses: actions/checkout@v3
with:
submodules: true
- uses: ./.github/workflows/setup-with-retry
- uses: ./.github/workflows/setup
- name: Cache test routes
id: dependency-cache
uses: actions/cache@v3
@@ -378,7 +378,7 @@ jobs:
with:
submodules: true
ref: ${{ github.event.pull_request.base.ref }}
- uses: ./.github/workflows/setup-with-retry
- uses: ./.github/workflows/setup
- name: Get base car info
run: |
${{ env.RUN }} "scons -j$(nproc) && python selfdrive/debug/dump_car_info.py --path /tmp/openpilot_cache/base_car_info"
@@ -1,39 +0,0 @@
name: 'openpilot env setup, with retry on failure'
inputs:
git_lfs:
description: 'Whether or not to pull the git lfs'
required: false
default: 'true'
env:
SLEEP_TIME: 30 # Time to sleep between retries
runs:
using: "composite"
steps:
- id: setup1
uses: ./.github/workflows/setup
continue-on-error: true
with:
git_lfs: ${{ inputs.git_lfs }}
is_retried: true
- if: steps.setup1.outcome == 'failure'
shell: bash
run: sleep ${{ env.SLEEP_TIME }}
- id: setup2
if: steps.setup1.outcome == 'failure'
uses: ./.github/workflows/setup
continue-on-error: true
with:
git_lfs: ${{ inputs.git_lfs }}
is_retried: true
- if: steps.setup2.outcome == 'failure'
shell: bash
run: sleep ${{ env.SLEEP_TIME }}
- id: setup3
if: steps.setup2.outcome == 'failure'
uses: ./.github/workflows/setup
with:
git_lfs: ${{ inputs.git_lfs }}
is_retried: true
-11
View File
@@ -5,21 +5,10 @@ inputs:
description: 'Whether or not to pull the git lfs'
required: false
default: 'true'
is_retried:
description: 'A mock param that asserts that we use the setup-with-retry instead of this action directly'
required: false
default: 'false'
runs:
using: "composite"
steps:
# assert that this action is retried using the setup-with-retry
- shell: bash
if: ${{ inputs.is_retried == 'false' }}
run: |
echo "You should not run this action directly. Use setup-with-retry instead"
exit 1
# do this after checkout to ensure our custom LFS config is used to pull from GitLab
- shell: bash
if: ${{ inputs.git_lfs == 'true' }}
+5 -4
View File
@@ -33,10 +33,11 @@ jobs:
- uses: actions/checkout@v3
with:
submodules: true
- uses: ./.github/workflows/setup-with-retry
- name: Build Docker image
run: eval "$BUILD"
- name: Build openpilot
timeout-minutes: 5
run: ${{ env.RUN }} "scons -j$(nproc) cereal/ common/ --minimal"
run: ${{ env.RUN }} "scons -j$(nproc) --directory=/tmp/openpilot/cereal --minimal"
- name: Test PlotJuggler
timeout-minutes: 2
run: |
@@ -51,7 +52,7 @@ jobs:
- uses: actions/checkout@v3
with:
submodules: true
- uses: ./.github/workflows/setup-with-retry
- uses: ./.github/workflows/setup
- name: Build base cl image
run: eval "$BUILD_CL"
- name: Setup to push to repo
@@ -71,7 +72,7 @@ jobs:
- uses: actions/checkout@v3
with:
submodules: true
- uses: ./.github/workflows/setup-with-retry
- uses: ./.github/workflows/setup
with:
git_lfs: false
- name: Setup to push to repo
-7
View File
@@ -1,4 +1,3 @@
exclude: '^(tinygrad_repo)'
repos:
- repo: meta
hooks:
@@ -15,8 +14,6 @@ repos:
- id: check-yaml
- id: check-merge-conflict
- id: check-symlinks
- id: check-executables-have-shebangs
- id: check-shebang-scripts-are-executable
- id: check-added-large-files
args: ['--maxkb=100']
- repo: https://github.com/codespell-project/codespell
@@ -83,7 +80,3 @@ repos:
name: validate poetry lock
args:
- --check
- repo: https://github.com/python-jsonschema/check-jsonschema
rev: 0.26.3
hooks:
- id: check-github-workflows
Regular → Executable
View File
+1 -1
Submodule cereal updated: d469732b3b...82bca3a971
+1 -5
View File
@@ -15,11 +15,7 @@ enum ParamKeyType {
class Params {
public:
explicit Params(const std::string &path = {});
// Not copyable.
Params(const Params&) = delete;
Params& operator=(const Params&) = delete;
Params(const std::string &path = {});
std::vector<std::string> allKeys() const;
bool checkKey(const std::string &key);
ParamKeyType getKeyType(const std::string &key);
Regular → Executable
View File
+1 -1
View File
@@ -20,7 +20,7 @@
class SwaglogState : public LogState {
public:
SwaglogState() : LogState(Path::swaglog_ipc().c_str()) {}
SwaglogState() : LogState("ipc:///tmp/logmessage") {}
json11::Json::object ctx_j;
+12 -5
View File
@@ -1,6 +1,8 @@
import os
import threading
import time
import tempfile
import shutil
import uuid
import unittest
@@ -8,7 +10,12 @@ from openpilot.common.params import Params, ParamKeyType, UnknownKeyName, put_no
class TestParams(unittest.TestCase):
def setUp(self):
self.params = Params()
self.tmpdir = tempfile.mkdtemp()
print("using", self.tmpdir)
self.params = Params(self.tmpdir)
def tearDown(self):
shutil.rmtree(self.tmpdir)
def test_params_put_and_get(self):
self.params.put("DongleId", "cb38263377b873ee")
@@ -83,19 +90,19 @@ class TestParams(unittest.TestCase):
self.assertFalse(self.params.get_bool("IsMetric"))
def test_put_non_blocking_with_get_block(self):
q = Params()
q = Params(self.tmpdir)
def _delayed_writer():
time.sleep(0.1)
put_nonblocking("CarParams", "test")
put_nonblocking("CarParams", "test", self.tmpdir)
threading.Thread(target=_delayed_writer).start()
assert q.get("CarParams") is None
assert q.get("CarParams", True) == b"test"
def test_put_bool_non_blocking_with_get_block(self):
q = Params()
q = Params(self.tmpdir)
def _delayed_writer():
time.sleep(0.1)
put_bool_nonblocking("CarParams", True)
put_bool_nonblocking("CarParams", True, self.tmpdir)
threading.Thread(target=_delayed_writer).start()
assert q.get("CarParams") is None
assert q.get("CarParams", True) == b"1"
+2 -9
View File
@@ -6,18 +6,11 @@
TEST_CASE("RateKeeper") {
float freq = GENERATE(10, 50, 100);
RateKeeper rk("Test RateKeeper", freq);
int lags = 0;
int bad_keep_times = 0;
for (int i = 0; i < freq; ++i) {
double begin = seconds_since_boot();
util::sleep_for(util::random_int(0, 1000.0 / freq - 1));
bool lagged = rk.keepTime();
lags += lagged;
bad_keep_times += (seconds_since_boot() - begin - (1 / freq)) > 1e-3;
REQUIRE(std::abs(seconds_since_boot() - begin - (1 / freq)) < 1e-3);
REQUIRE(lagged == false);
}
// need a tolerance here due to scheduling
REQUIRE(lags < 5);
REQUIRE(bad_keep_times < 5);
}
+2 -1
View File
@@ -9,6 +9,7 @@
#include "system/hardware/hw.h"
#include "third_party/json11/json11.hpp"
const char *SWAGLOG_ADDR = "ipc:///tmp/logmessage";
std::string daemon_name = "testy";
std::string dongle_id = "test_dongle_id";
int LINE_NO = 0;
@@ -24,7 +25,7 @@ void log_thread(int thread_id, int msg_cnt) {
void recv_log(int thread_cnt, int thread_msg_cnt) {
void *zctx = zmq_ctx_new();
void *sock = zmq_socket(zctx, ZMQ_PULL);
zmq_bind(sock, Path::swaglog_ipc().c_str());
zmq_bind(sock, SWAGLOG_ADDR);
std::vector<int> thread_msgs(thread_cnt);
int total_count = 0;
+3 -3
View File
@@ -188,9 +188,9 @@ class LogState {
void *zctx = nullptr;
void *sock = nullptr;
int print_level;
std::string endpoint;
const char* endpoint;
LogState(std::string _endpoint) {
LogState(const char* _endpoint) {
endpoint = _endpoint;
}
@@ -202,7 +202,7 @@ class LogState {
int timeout = 100;
zmq_setsockopt(sock, ZMQ_LINGER, &timeout, sizeof(timeout));
zmq_connect(sock, endpoint.c_str());
zmq_connect(sock, endpoint);
initialized = true;
}
-10
View File
@@ -1,10 +0,0 @@
import pytest
from openpilot.common.prefix import OpenpilotPrefix
@pytest.fixture(scope="function", autouse=True)
def global_setup_and_teardown():
# setup a clean environment for each test
with OpenpilotPrefix():
yield
+4 -4
View File
@@ -83,13 +83,13 @@ A supported vehicle is one that just works when you install a comma device. All
|Hyundai|Ioniq 6 (with HDA II) 2023[<sup>6</sup>](#footnotes)|Highway Driving Assist II|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|<details><summary>Parts</summary><sub>- 1 Hyundai P 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-3x.html?make=Hyundai&model=Ioniq 6 (with HDA II) 2023">Buy Here</a></sub></details>||
|Hyundai|Ioniq Electric 2019|Smart Cruise Control (SCC)|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|<details><summary>Parts</summary><sub>- 1 Hyundai C 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-3x.html?make=Hyundai&model=Ioniq Electric 2019">Buy Here</a></sub></details>||
|Hyundai|Ioniq Electric 2020|All|openpilot available[<sup>1</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|<details><summary>Parts</summary><sub>- 1 Hyundai H 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-3x.html?make=Hyundai&model=Ioniq Electric 2020">Buy Here</a></sub></details>||
|Hyundai|Ioniq Hybrid 2017-19|Smart Cruise Control (SCC)|openpilot available[<sup>1</sup>](#footnotes)|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|<details><summary>Parts</summary><sub>- 1 Hyundai C 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-3x.html?make=Hyundai&model=Ioniq Hybrid 2017-19">Buy Here</a></sub></details>||
|Hyundai|Ioniq Hybrid 2017-19|Smart Cruise Control (SCC)|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|<details><summary>Parts</summary><sub>- 1 Hyundai C 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-3x.html?make=Hyundai&model=Ioniq Hybrid 2017-19">Buy Here</a></sub></details>||
|Hyundai|Ioniq Hybrid 2020-22|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|<details><summary>Parts</summary><sub>- 1 Hyundai H 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-3x.html?make=Hyundai&model=Ioniq Hybrid 2020-22">Buy Here</a></sub></details>||
|Hyundai|Ioniq Plug-in Hybrid 2019|Smart Cruise Control (SCC)|openpilot available[<sup>1</sup>](#footnotes)|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|<details><summary>Parts</summary><sub>- 1 Hyundai C 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-3x.html?make=Hyundai&model=Ioniq Plug-in Hybrid 2019">Buy Here</a></sub></details>||
|Hyundai|Ioniq Plug-in Hybrid 2020-22|All|openpilot available[<sup>1</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|<details><summary>Parts</summary><sub>- 1 Hyundai H 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-3x.html?make=Hyundai&model=Ioniq Plug-in Hybrid 2020-22">Buy Here</a></sub></details>||
|Hyundai|Ioniq Plug-in Hybrid 2020-22|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|<details><summary>Parts</summary><sub>- 1 Hyundai H 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-3x.html?make=Hyundai&model=Ioniq Plug-in Hybrid 2020-22">Buy Here</a></sub></details>||
|Hyundai|Kona 2020|Smart Cruise Control (SCC)|openpilot available[<sup>1</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|<details><summary>Parts</summary><sub>- 1 Hyundai B 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-3x.html?make=Hyundai&model=Kona 2020">Buy Here</a></sub></details>||
|Hyundai|Kona Electric 2018-21|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|<details><summary>Parts</summary><sub>- 1 Hyundai G 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-3x.html?make=Hyundai&model=Kona Electric 2018-21">Buy Here</a></sub></details>||
|Hyundai|Kona Electric 2022|Smart Cruise Control (SCC)|openpilot available[<sup>1</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|<details><summary>Parts</summary><sub>- 1 Hyundai O 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-3x.html?make=Hyundai&model=Kona Electric 2022">Buy Here</a></sub></details>||
|Hyundai|Kona Electric 2022|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|<details><summary>Parts</summary><sub>- 1 Hyundai O 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-3x.html?make=Hyundai&model=Kona Electric 2022">Buy Here</a></sub></details>||
|Hyundai|Kona Electric (with HDA II, Korea only) 2023[<sup>6</sup>](#footnotes)|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|<details><summary>Parts</summary><sub>- 1 Hyundai R 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-3x.html?make=Hyundai&model=Kona Electric (with HDA II, Korea only) 2023">Buy Here</a></sub></details>|<a href="https://www.youtube.com/watch?v=U2fOCmcQ8hw" target="_blank"><img height="18px" src="assets/icon-youtube.svg"></img></a>|
|Hyundai|Kona Hybrid 2020|Smart Cruise Control (SCC)|openpilot available[<sup>1</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|<details><summary>Parts</summary><sub>- 1 Hyundai I 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-3x.html?make=Hyundai&model=Kona Hybrid 2020">Buy Here</a></sub></details>|<a href="https://youtu.be/0dwpAHiZgFo" target="_blank"><img height="18px" src="assets/icon-youtube.svg"></img></a>|
|Hyundai|Palisade 2020-22|All|openpilot available[<sup>1</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|<details><summary>Parts</summary><sub>- 1 Hyundai H 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-3x.html?make=Hyundai&model=Palisade 2020-22">Buy Here</a></sub></details>|<a href="https://youtu.be/TAnDqjF4fDY?t=456" target="_blank"><img height="18px" src="assets/icon-youtube.svg"></img></a>|
@@ -111,7 +111,7 @@ A supported vehicle is one that just works when you install a comma device. All
|Jeep|Grand Cherokee 2019-21|Adaptive Cruise Control (ACC)|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|<details><summary>Parts</summary><sub>- 1 FCA 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-3x.html?make=Jeep&model=Grand Cherokee 2019-21">Buy Here</a></sub></details>|<a href="https://www.youtube.com/watch?v=jBe4lWnRSu4" target="_blank"><img height="18px" src="assets/icon-youtube.svg"></img></a>|
|Kia|Carnival 2023[<sup>6</sup>](#footnotes)|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|<details><summary>Parts</summary><sub>- 1 Hyundai A 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-3x.html?make=Kia&model=Carnival 2023">Buy Here</a></sub></details>||
|Kia|Carnival (China only) 2023[<sup>6</sup>](#footnotes)|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|<details><summary>Parts</summary><sub>- 1 Hyundai K 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-3x.html?make=Kia&model=Carnival (China only) 2023">Buy Here</a></sub></details>||
|Kia|Ceed 2019|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|<details><summary>Parts</summary><sub>- 1 Hyundai E 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-3x.html?make=Kia&model=Ceed 2019">Buy Here</a></sub></details>||
|Kia|Ceed 2019|Smart Cruise Control (SCC)|openpilot available[<sup>1</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|<details><summary>Parts</summary><sub>- 1 Hyundai E 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-3x.html?make=Kia&model=Ceed 2019">Buy Here</a></sub></details>||
|Kia|EV6 (Southeast Asia only) 2022-23[<sup>6</sup>](#footnotes)|All|openpilot available[<sup>1</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|<details><summary>Parts</summary><sub>- 1 Hyundai P 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-3x.html?make=Kia&model=EV6 (Southeast Asia only) 2022-23">Buy Here</a></sub></details>||
|Kia|EV6 (with HDA II) 2022-23[<sup>6</sup>](#footnotes)|Highway Driving Assist II|openpilot available[<sup>1</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|<details><summary>Parts</summary><sub>- 1 Hyundai P 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-3x.html?make=Kia&model=EV6 (with HDA II) 2022-23">Buy Here</a></sub></details>||
|Kia|EV6 (without HDA II) 2022-23[<sup>6</sup>](#footnotes)|Highway Driving Assist|openpilot available[<sup>1</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|<details><summary>Parts</summary><sub>- 1 Hyundai L 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-3x.html?make=Kia&model=EV6 (without HDA II) 2022-23">Buy Here</a></sub></details>||
+1 -1
Submodule opendbc updated: 5ebf73ebed...ef302f7183
+1 -1
Submodule panda updated: 4dcde30af0...ef1a9338a1
Generated
+4 -18
View File
@@ -1,4 +1,4 @@
# This file is automatically @generated by Poetry 1.5.1 and should not be changed by hand.
# This file is automatically @generated by Poetry 1.6.1 and should not be changed by hand.
[[package]]
name = "aiohttp"
@@ -2766,14 +2766,7 @@ files = [
]
[package.dependencies]
numpy = [
{version = ">=1.21.2", markers = "python_version >= \"3.10\""},
{version = ">=1.21.4", markers = "python_version >= \"3.10\" and platform_system == \"Darwin\""},
{version = ">=1.23.5", markers = "python_version >= \"3.11\""},
{version = ">=1.19.3", markers = "python_version >= \"3.6\" and platform_system == \"Linux\" and platform_machine == \"aarch64\" or python_version >= \"3.9\""},
{version = ">=1.17.0", markers = "python_version >= \"3.7\""},
{version = ">=1.17.3", markers = "python_version >= \"3.8\""},
]
numpy = {version = ">=1.23.5", markers = "python_version >= \"3.11\""}
[[package]]
name = "opencv-python-headless"
@@ -2792,14 +2785,7 @@ files = [
]
[package.dependencies]
numpy = [
{version = ">=1.21.2", markers = "python_version >= \"3.10\""},
{version = ">=1.21.4", markers = "python_version >= \"3.10\" and platform_system == \"Darwin\""},
{version = ">=1.23.5", markers = "python_version >= \"3.11\""},
{version = ">=1.19.3", markers = "python_version >= \"3.6\" and platform_system == \"Linux\" and platform_machine == \"aarch64\" or python_version >= \"3.9\""},
{version = ">=1.17.0", markers = "python_version >= \"3.7\""},
{version = ">=1.17.3", markers = "python_version >= \"3.8\""},
]
numpy = {version = ">=1.23.5", markers = "python_version >= \"3.11\""}
[[package]]
name = "packaging"
@@ -5049,4 +5035,4 @@ testing = ["big-O", "jaraco.functools", "jaraco.itertools", "more-itertools", "p
[metadata]
lock-version = "2.0"
python-versions = "~3.11"
content-hash = "0e7f2a907e73eaa31137d70be3a56d350d6fc6dbc54811c80d6031409fddcac1"
content-hash = "949a4c853db95a61159dc93c05d42d78a334b08f0f62b74587d77a348db9cf23"
+2 -18
View File
@@ -1,27 +1,11 @@
[tool.pytest.ini_options]
minversion = "6.0"
addopts = "--ignore=openpilot/ --ignore=cereal/ --ignore=opendbc/ --ignore=panda/ --ignore=rednose_repo/ --ignore=tinygrad_repo/ --ignore=laika_repo/ -Werror --strict-config --strict-markers"
addopts = "--ignore=openpilot/ --ignore=opendbc/ --ignore=panda/ --ignore=rednose_repo/ --ignore=tinygrad_repo/ --ignore=laika_repo/ -Werror --strict-config --strict-markers"
python_files = "test_*.py"
#timeout = "30" # you get this long by default
markers = [
"parallel: mark tests as parallelizable (tests with no global state, so can be run in parallel)"
]
testpaths = [
"common",
"selfdrive/athena",
"selfdrive/boardd",
"selfdrive/car",
"selfdrive/controls",
"selfdrive/locationd",
"selfdrive/monitoring",
"selfdrive/thermald",
"selfdrive/test/longitudinal_maneuvers",
"system/hardware/tici",
"system/loggerd",
"system/tests",
"system/ubloxd",
"tools/lib/tests"
]
[tool.mypy]
python_version = "3.11"
@@ -128,7 +112,7 @@ inputs = "*"
lru-dict = "*"
markdown-it-py = "*"
matplotlib = "*"
metadrive-simulator = { git = "https://github.com/metadriverse/metadrive.git", rev ="51d4393f3b3574fd0e79ed04eae0081f8447ca72", markers = "platform_machine != 'aarch64'" } # no linux/aarch64 wheels for certain dependencies
metadrive-simulator = { git = "https://github.com/metadriverse/metadrive.git", rev ="51d4393f3b3574fd0e79ed04eae0081f8447ca72" }
mpld3 = "*"
mypy = "*"
myst-parser = "*"
+8 -3
View File
@@ -209,7 +209,6 @@ system/hardware/__init__.py
system/hardware/base.h
system/hardware/base.py
system/hardware/hw.h
system/hardware/hw.py
system/hardware/tici/__init__.py
system/hardware/tici/hardware.h
system/hardware/tici/hardware.py
@@ -361,10 +360,12 @@ selfdrive/modeld/.gitignore
selfdrive/modeld/__init__.py
selfdrive/modeld/SConscript
selfdrive/modeld/modeld.py
selfdrive/modeld/navmodeld.py
selfdrive/modeld/dmonitoringmodeld.py
selfdrive/modeld/navmodeld.cc
selfdrive/modeld/dmonitoringmodeld.cc
selfdrive/modeld/constants.py
selfdrive/modeld/modeld
selfdrive/modeld/navmodeld
selfdrive/modeld/dmonitoringmodeld
selfdrive/modeld/models/__init__.py
selfdrive/modeld/models/*.pxd
@@ -377,8 +378,12 @@ selfdrive/modeld/models/driving.cc
selfdrive/modeld/models/driving.h
selfdrive/modeld/models/supercombo.onnx
selfdrive/modeld/models/dmonitoring.cc
selfdrive/modeld/models/dmonitoring.h
selfdrive/modeld/models/dmonitoring_model_q.dlc
selfdrive/modeld/models/nav.cc
selfdrive/modeld/models/nav.h
selfdrive/modeld/models/navmodel_q.dlc
selfdrive/modeld/transforms/loadyuv.cc
+12 -11
View File
@@ -36,11 +36,11 @@ from openpilot.common.file_helpers import CallbackReader
from openpilot.common.params import Params
from openpilot.common.realtime import set_core_affinity
from openpilot.system.hardware import HARDWARE, PC, AGNOS
from openpilot.system.loggerd.config import ROOT
from openpilot.system.loggerd.xattr_cache import getxattr, setxattr
from openpilot.selfdrive.statsd import STATS_DIR
from openpilot.system.swaglog import cloudlog
from openpilot.system.swaglog import SWAGLOG_DIR, cloudlog
from openpilot.system.version import get_commit, get_origin, get_short_branch, get_version
from selfdrive.hardware.hw import Paths
# TODO: use socket constant when mypy recognizes this as a valid attribute
@@ -119,11 +119,12 @@ class AbortTransferException(Exception):
class UploadQueueCache:
params = Params()
@staticmethod
def initialize(upload_queue: Queue[UploadItem]) -> None:
try:
upload_queue_json = Params().get("AthenadUploadQueue")
upload_queue_json = UploadQueueCache.params.get("AthenadUploadQueue")
if upload_queue_json is not None:
for item in json.loads(upload_queue_json):
upload_queue.put(UploadItem.from_dict(item))
@@ -135,7 +136,7 @@ class UploadQueueCache:
try:
queue: List[Optional[UploadItem]] = list(upload_queue.queue)
items = [asdict(i) for i in queue if i is not None and (i.id not in cancelled_uploads)]
Params().put("AthenadUploadQueue", json.dumps(items))
UploadQueueCache.params.put("AthenadUploadQueue", json.dumps(items))
except Exception:
cloudlog.exception("athena.UploadQueueCache.cache.exception")
@@ -351,7 +352,7 @@ def scan_dir(path: str, prefix: str) -> List[str]:
# (glob and friends traverse entire dir tree)
with os.scandir(path) as i:
for e in i:
rel_path = os.path.relpath(e.path, Paths.log_root())
rel_path = os.path.relpath(e.path, ROOT)
if e.is_dir(follow_symlinks=False):
# add trailing slash
rel_path = os.path.join(rel_path, '')
@@ -366,7 +367,7 @@ def scan_dir(path: str, prefix: str) -> List[str]:
@dispatcher.add_method
def listDataDirectory(prefix='') -> List[str]:
return scan_dir(Paths.log_root(), prefix)
return scan_dir(ROOT, prefix)
@dispatcher.add_method
@@ -407,7 +408,7 @@ def uploadFilesToUrls(files_data: List[UploadFileDict]) -> UploadFilesToUrlRespo
failed.append(file.fn)
continue
path = os.path.join(Paths.log_root(), file.fn)
path = os.path.join(ROOT, file.fn)
if not os.path.exists(path) and not os.path.exists(strip_bz2_extension(path)):
failed.append(file.fn)
continue
@@ -571,8 +572,8 @@ def get_logs_to_send_sorted() -> List[str]:
# TODO: scan once then use inotify to detect file creation/deletion
curr_time = int(time.time())
logs = []
for log_entry in os.listdir(Paths.swaglog_root()):
log_path = os.path.join(Paths.swaglog_root(), log_entry)
for log_entry in os.listdir(SWAGLOG_DIR):
log_path = os.path.join(SWAGLOG_DIR, log_entry)
time_sent = 0
try:
value = getxattr(log_path, LOG_ATTR_NAME)
@@ -607,7 +608,7 @@ def log_handler(end_event: threading.Event) -> None:
cloudlog.debug(f"athena.log_handler.forward_request {log_entry}")
try:
curr_time = int(time.time())
log_path = os.path.join(Paths.swaglog_root(), log_entry)
log_path = os.path.join(SWAGLOG_DIR, log_entry)
setxattr(log_path, LOG_ATTR_NAME, int.to_bytes(curr_time, 4, sys.byteorder))
with open(log_path) as f:
jsonrpc = {
@@ -634,7 +635,7 @@ def log_handler(end_event: threading.Event) -> None:
log_success = "result" in log_resp and log_resp["result"].get("success")
cloudlog.debug(f"athena.log_handler.forward_response {log_entry} {log_success}")
if log_entry and log_success:
log_path = os.path.join(Paths.swaglog_root(), log_entry)
log_path = os.path.join(SWAGLOG_DIR, log_entry)
try:
setxattr(log_path, LOG_ATTR_NAME, LOG_ATTR_VALUE_MAX_UNIX_TIME)
except OSError:
+8 -5
View File
@@ -3,6 +3,7 @@ import json
import os
import requests
import shutil
import tempfile
import time
import threading
import queue
@@ -17,11 +18,11 @@ from unittest import mock
from websocket import ABNF
from websocket._exceptions import WebSocketConnectionClosedException
from openpilot.system import swaglog
from openpilot.selfdrive.athena import athenad
from openpilot.selfdrive.athena.athenad import MAX_RETRY_COUNT, dispatcher
from openpilot.selfdrive.athena.tests.helpers import MockWebsocket, MockParams, MockApi, EchoSocket, with_http_server
from cereal import messaging
from selfdrive.hardware.hw import Paths
class TestAthenadMethods(unittest.TestCase):
@@ -29,6 +30,8 @@ class TestAthenadMethods(unittest.TestCase):
def setUpClass(cls):
cls.SOCKET_PORT = 45454
athenad.Params = MockParams
athenad.ROOT = tempfile.mkdtemp()
athenad.SWAGLOG_DIR = swaglog.SWAGLOG_DIR = tempfile.mkdtemp()
athenad.Api = MockApi
athenad.LOCAL_PORT_WHITELIST = {cls.SOCKET_PORT}
@@ -38,8 +41,8 @@ class TestAthenadMethods(unittest.TestCase):
athenad.cur_upload_items.clear()
athenad.cancelled_uploads.clear()
for i in os.listdir(Paths.log_root()):
p = os.path.join(Paths.log_root(), i)
for i in os.listdir(athenad.ROOT):
p = os.path.join(athenad.ROOT, i)
if os.path.isdir(p):
shutil.rmtree(p)
else:
@@ -58,7 +61,7 @@ class TestAthenadMethods(unittest.TestCase):
@staticmethod
def _create_file(file: str, parent: Optional[str] = None) -> str:
fn = os.path.join(Paths.log_root() if parent is None else parent, file)
fn = os.path.join(athenad.ROOT if parent is None else parent, file)
os.makedirs(os.path.dirname(fn), exist_ok=True)
Path(fn).touch()
return fn
@@ -415,7 +418,7 @@ class TestAthenadMethods(unittest.TestCase):
fl = list()
for i in range(10):
file = f'swaglog.{i:010}'
self._create_file(file, Paths.swaglog_root())
self._create_file(file, athenad.SWAGLOG_DIR)
fl.append(file)
# ensure the list is all logs except most recent
+1
View File
@@ -1,3 +1,4 @@
#!/usr/bin/env python3
import math
from cereal import car
from openpilot.common.realtime import DT_CTRL
+1
View File
@@ -1,3 +1,4 @@
#!/usr/bin/env python3
from openpilot.selfdrive.car.interfaces import RadarInterfaceBase
class RadarInterface(RadarInterfaceBase):
-1
View File
@@ -1,4 +1,3 @@
#!/usr/bin/env python3
from openpilot.selfdrive.car.isotp_parallel_query import IsoTpParallelQuery
from openpilot.system.swaglog import cloudlog
+1
View File
@@ -1,3 +1,4 @@
#!/usr/bin/env python3
from cereal import car
from panda import Panda
from openpilot.common.conversions import Conversions as CV
+1
View File
@@ -1,3 +1,4 @@
#!/usr/bin/env python3
from math import cos, sin
from cereal import car
from opendbc.can.parser import CANParser
+4 -5
View File
@@ -6,7 +6,7 @@ from opendbc.can.packer import CANPacker
from openpilot.selfdrive.car import apply_driver_steer_torque_limits, common_fault_avoidance
from openpilot.selfdrive.car.hyundai import hyundaicanfd, hyundaican
from openpilot.selfdrive.car.hyundai.hyundaicanfd import CanBus
from openpilot.selfdrive.car.hyundai.values import HyundaiFlags, Buttons, CarControllerParams, CANFD_CAR, CAR, CAMERA_SCC_CAR
from openpilot.selfdrive.car.hyundai.values import HyundaiFlags, Buttons, CarControllerParams, CANFD_CAR, CAR
VisualAlert = car.CarControl.HUDControl.VisualAlert
LongCtrlState = car.CarControl.Actuators.LongControlState
@@ -91,8 +91,7 @@ class CarController:
# *** common hyundai stuff ***
# tester present - w/ no response (keeps relevant ECU disabled)
if self.frame % 100 == 0 and not (self.CP.flags & HyundaiFlags.CANFD_CAMERA_SCC.value) and \
self.CP.carFingerprint not in CAMERA_SCC_CAR and self.CP.openpilotLongitudinalControl:
if self.frame % 100 == 0 and not (self.CP.flags & HyundaiFlags.CANFD_CAMERA_SCC.value) and self.CP.openpilotLongitudinalControl:
# for longitudinal control, either radar or ADAS driving ECU
addr, bus = 0x7d0, 0
if self.CP.flags & HyundaiFlags.CANFD_HDA2.value:
@@ -147,7 +146,7 @@ class CarController:
# TODO: unclear if this is needed
jerk = 3.0 if actuators.longControlState == LongCtrlState.pid else 1.0
use_fca = self.CP.flags & HyundaiFlags.USE_FCA.value
can_sends.extend(hyundaican.create_acc_commands(self.packer, CC.enabled, accel, jerk, int(self.frame / 2), CS, self.CP.carFingerprint,
can_sends.extend(hyundaican.create_acc_commands(self.packer, CC.enabled, accel, jerk, int(self.frame / 2),
hud_control.leadVisible, set_speed_in_units, stopping,
CC.cruiseControl.override, use_fca))
@@ -157,7 +156,7 @@ class CarController:
# 5 Hz ACC options
if self.frame % 20 == 0 and self.CP.openpilotLongitudinalControl:
can_sends.extend(hyundaican.create_acc_opt(self.packer, CS, self.CP.carFingerprint))
can_sends.extend(hyundaican.create_acc_opt(self.packer))
# 2 Hz front radar options
if self.frame % 50 == 0 and self.CP.openpilotLongitudinalControl:
+7 -18
View File
@@ -156,10 +156,6 @@ class CarState(CarStateBase):
# save the entire LKAS11 and CLU11
self.lkas11 = copy.copy(cp_cam.vl["LKAS11"])
self.clu11 = copy.copy(cp.vl["CLU11"])
# only forward FCA messages for FCW/AEB when using openpilot longitudinal on Camera SCC cars
if self.CP.openpilotLongitudinalControl and self.CP.carFingerprint in CAMERA_SCC_CAR:
self.fca11 = copy.copy(cp_cruise.vl["FCA11"])
self.fca12 = copy.copy(cp_cruise.vl["FCA12"])
self.steer_state = cp.vl["MDPS12"]["CF_Mdps_ToiActive"] # 0 NOT ACTIVE, 1 ACTIVE
self.prev_cruise_buttons = self.cruise_buttons[-1]
self.cruise_buttons.extend(cp.vl_all["CLU11"]["CF_Clu_CruiseSwState"])
@@ -300,21 +296,14 @@ class CarState(CarStateBase):
("LKAS11", 100)
]
if CP.carFingerprint in CAMERA_SCC_CAR:
if CP.openpilotLongitudinalControl:
if CP.flags & HyundaiFlags.USE_FCA.value:
messages += [
("FCA11", 50),
("FCA12", 50),
]
else:
messages += [
("SCC11", 50),
("SCC12", 50),
]
if not CP.openpilotLongitudinalControl and CP.carFingerprint in CAMERA_SCC_CAR:
messages += [
("SCC11", 50),
("SCC12", 50),
]
if CP.flags & HyundaiFlags.USE_FCA.value:
messages.append(("FCA11", 50))
if CP.flags & HyundaiFlags.USE_FCA.value:
messages.append(("FCA11", 50))
return CANParser(DBC[CP.carFingerprint]["pt"], messages, 2)
+14 -25
View File
@@ -125,7 +125,7 @@ def create_lfahda_mfc(packer, enabled, hda_set_speed=0):
}
return packer.make_can_msg("LFAHDA_MFC", 0, values)
def create_acc_commands(packer, enabled, accel, upper_jerk, idx, CS, car_fingerprint, lead_visible, set_speed, stopping, long_override, use_fca):
def create_acc_commands(packer, enabled, accel, upper_jerk, idx, lead_visible, set_speed, stopping, long_override, use_fca):
commands = []
scc11_values = {
@@ -172,27 +172,21 @@ def create_acc_commands(packer, enabled, accel, upper_jerk, idx, CS, car_fingerp
# Only send FCA11 on cars where it exists on the bus
if use_fca:
if car_fingerprint in CAMERA_SCC_CAR:
fca11_values = CS.fca11
fca11_values["PAINT1_Status"] = 1
fca11_values["FCA_DrvSetStatus"] = 1
fca11_values["FCA_Status"] = 1 # AEB disabled, until a route with AEB or FCW trigger is verified
else:
# note that some vehicles most likely have an alternate checksum/counter definition
# https://github.com/commaai/opendbc/commit/9ddcdb22c4929baf310295e832668e6e7fcfa602
fca11_values = {
"CR_FCA_Alive": idx % 0xF,
"PAINT1_Status": 1,
"FCA_DrvSetStatus": 1,
"FCA_Status": 1, # AEB disabled
}
# note that some vehicles most likely have an alternate checksum/counter definition
# https://github.com/commaai/opendbc/commit/9ddcdb22c4929baf310295e832668e6e7fcfa602
fca11_values = {
"CR_FCA_Alive": idx % 0xF,
"PAINT1_Status": 1,
"FCA_DrvSetStatus": 1,
"FCA_Status": 1, # AEB disabled
}
fca11_dat = packer.make_can_msg("FCA11", 0, fca11_values)[2]
fca11_values["CR_FCA_ChkSum"] = hyundai_checksum(fca11_dat[:7])
commands.append(packer.make_can_msg("FCA11", 0, fca11_values))
return commands
def create_acc_opt(packer, CS, car_fingerprint):
def create_acc_opt(packer):
commands = []
scc13_values = {
@@ -203,15 +197,10 @@ def create_acc_opt(packer, CS, car_fingerprint):
commands.append(packer.make_can_msg("SCC13", 0, scc13_values))
# TODO: this needs to be detected and conditionally sent on unsupported long cars
if car_fingerprint in CAMERA_SCC_CAR:
fca12_values = CS.fca12
fca12_values["FCA_DrvSetState"] = 2
fca12_values["FCA_USM"] = 1 # AEB disabled, until a route with AEB or FCW trigger is verified
else:
fca12_values = {
"FCA_DrvSetState": 2,
"FCA_USM": 1, # AEB disabled
}
fca12_values = {
"FCA_DrvSetState": 2,
"FCA_USM": 1, # AEB disabled
}
commands.append(packer.make_can_msg("FCA12", 0, fca12_values))
return commands
+3 -3
View File
@@ -1,3 +1,4 @@
#!/usr/bin/env python3
from cereal import car
from panda import Panda
from openpilot.common.conversions import Conversions as CV
@@ -252,7 +253,7 @@ class CarInterface(CarInterfaceBase):
else:
ret.longitudinalTuning.kpV = [0.5]
ret.longitudinalTuning.kiV = [0.0]
ret.experimentalLongitudinalAvailable = candidate not in UNSUPPORTED_LONGITUDINAL_CAR
ret.experimentalLongitudinalAvailable = candidate not in (UNSUPPORTED_LONGITUDINAL_CAR | CAMERA_SCC_CAR)
ret.openpilotLongitudinalControl = experimental_long and ret.experimentalLongitudinalAvailable
ret.pcmCruise = not ret.openpilotLongitudinalControl
@@ -311,8 +312,7 @@ class CarInterface(CarInterfaceBase):
@staticmethod
def init(CP, logcan, sendcan):
if CP.openpilotLongitudinalControl and not (CP.flags & HyundaiFlags.CANFD_CAMERA_SCC.value) and \
CP.carFingerprint not in CAMERA_SCC_CAR:
if CP.openpilotLongitudinalControl and not (CP.flags & HyundaiFlags.CANFD_CAMERA_SCC.value):
addr, bus = 0x7d0, 0
if CP.flags & HyundaiFlags.CANFD_HDA2.value:
addr, bus = 0x730, CanBus(CP).ECAN
+1
View File
@@ -1,3 +1,4 @@
#!/usr/bin/env python3
import math
from cereal import car
+6 -8
View File
@@ -576,13 +576,11 @@ FW_VERSIONS = {
b'\xf1\x00AE MDPS C 1.00 1.01 56310/G2510 4APHC101',
b'\xf1\x00AE MDPS C 1.00 1.01 56310/G2560 4APHC101',
b'\xf1\x00AE MDPS C 1.00 1.01 56310G2510\x00 4APHC101',
b'\xf1\x00AE MDPS C 1.00 1.01 56310/G2310 4APHC101',
],
(Ecu.fwdCamera, 0x7c4, None): [
b'\xf1\x00AEP MFC AT USA LHD 1.00 1.01 95740-G2600 190819',
b'\xf1\x00AEP MFC AT EUR RHD 1.00 1.01 95740-G2600 190819',
b'\xf1\x00AEP MFC AT USA LHD 1.00 1.00 95740-G2700 201027',
b'\xf1\x00AEP MFC AT EUR LHD 1.00 1.01 95740-G2600 190819',
],
(Ecu.engine, 0x7e0, None): [
b'\xf1\x816H6F6051\x00\x00\x00\x00\x00\x00\x00\x00',
@@ -595,7 +593,6 @@ FW_VERSIONS = {
b'\xf1\x816U3J9051\x00\x00\xf1\x006U3H1_C2\x00\x006U3J9051\x00\x00PAE0G16NL2\x00\x00\x00\x00',
b'\xf1\x006U3H1_C2\x00\x006U3J9051\x00\x00PAE0G16NL0\x00\x00\x00\x00',
b'\xf1\x006U3H1_C2\x00\x006U3J9051\x00\x00PAE0G16NL2\xad\xeb\xabt',
b'\xf1\x006U3H1_C2\x00\x006U3J8051\x00\x00PAETG16UL0\x00\x00\x00\x00',
],
},
CAR.IONIQ_EV_2020: {
@@ -1414,7 +1411,10 @@ FW_VERSIONS = {
b'\xf1\x8758520-K4010\xf1\x00OS IEB \x04 101 \x11\x13 58520-K4010',
b'\xf1\x8758520-K4010\xf1\x00OS IEB \x03 101 \x11\x13 58520-K4010',
b'\xf1\x00OS IEB \r 102"\x05\x16 58520-K4010',
b'\xf1\x00OS IEB \x02 102"\x05\x16 58520-K4010',
# TODO: these return from the MULTI request, above return from LONG
b'\x01\x04\x7f\xff\xff\xf8\xff\xff\x00\x00\x01\xd3\x00\x00\x00\x00\xff\xb7\xff\xee\xff\xe0\x00\xc0\xc0\xfc\xd5\xfc\x00\x00U\x10\xffP\xf5\xff\xfd\x00\x00\x00\x00\xfc\x00\x01',
b'\x01\x04\x7f\xff\xff\xf8\xff\xff\x00\x00\x01\xdb\x00\x00\x00\x00\xff\xb1\xff\xd9\xff\xd2\x00\xc0\xc0\xfc\xd5\xfc\x00\x00U\x10\xff\xd6\xf5\x00\x06\x00\x00\x00\x14\xfd\x00\x04',
b'\x01\x04\x7f\xff\xff\xf8\xff\xff\x00\x00\x01\xd3\x00\x00\x00\x00\xff\xb7\xff\xf4\xff\xd9\x00\xc0',
],
(Ecu.fwdCamera, 0x7C4, None): [
b'\xf1\x00OSP LKA AT CND LHD 1.00 1.02 99211-J9110 802',
@@ -1422,14 +1422,12 @@ FW_VERSIONS = {
b'\xf1\x00OSP LKA AT AUS RHD 1.00 1.04 99211-J9200 904',
b'\xf1\x00OSP LKA AT EUR LHD 1.00 1.04 99211-J9200 904',
b'\xf1\x00OSP LKA AT EUR RHD 1.00 1.04 99211-J9200 904',
b'\xf1\x00OSP LKA AT USA LHD 1.00 1.04 99211-J9200 904',
],
(Ecu.eps, 0x7D4, None): [
b'\xf1\x00OSP MDPS C 1.00 1.02 56310K4260\x00 4OEPC102',
b'\xf1\x00OSP MDPS C 1.00 1.02 56310/K4970 4OEPC102',
b'\xf1\x00OSP MDPS C 1.00 1.02 56310/K4271 4OEPC102',
b'\xf1\x00OSP MDPS C 1.00 1.02 56310K4971\x00 4OEPC102',
b'\xf1\x00OSP MDPS C 1.00 1.02 56310K4261\x00 4OEPC102',
],
(Ecu.fwdRadar, 0x7D0, None): [
b'\xf1\x00YB__ FCA ----- 1.00 1.01 99110-K4500 \x00\x00\x00',
@@ -1978,8 +1976,8 @@ EV_CAR = {CAR.IONIQ_EV_2020, CAR.IONIQ_EV_LTD, CAR.KONA_EV, CAR.KIA_NIRO_EV, CAR
CAR.KIA_EV6, CAR.IONIQ_5, CAR.IONIQ_6, CAR.GENESIS_GV60_EV_1ST_GEN, CAR.KONA_EV_2ND_GEN}
# these cars require a special panda safety mode due to missing counters and checksums in the messages
LEGACY_SAFETY_MODE_CAR = {CAR.HYUNDAI_GENESIS, CAR.IONIQ_EV_LTD, CAR.KONA_EV, CAR.KIA_OPTIMA_G4,
CAR.VELOSTER, CAR.GENESIS_G70, CAR.GENESIS_G80, CAR.KIA_CEED, CAR.ELANTRA, CAR.IONIQ_HEV_2022,
LEGACY_SAFETY_MODE_CAR = {CAR.HYUNDAI_GENESIS, CAR.IONIQ_EV_LTD, CAR.IONIQ_PHEV, CAR.IONIQ, CAR.KONA_EV, CAR.KIA_OPTIMA_G4,
CAR.VELOSTER, CAR.GENESIS_G70, CAR.GENESIS_G80, CAR.ELANTRA, CAR.IONIQ_HEV_2022,
CAR.KIA_OPTIMA_H}
# these cars have not been verified to work with longitudinal yet - radar disable, sending correct messages, etc.
+2 -2
View File
@@ -1,5 +1,5 @@
#!/usr/bin/env python3
from cereal import car
from panda import Panda
from openpilot.selfdrive.car import get_safety_config
from openpilot.selfdrive.car.interfaces import CarInterfaceBase
from openpilot.selfdrive.car.nissan.values import CAR
@@ -31,7 +31,7 @@ class CarInterface(CarInterfaceBase):
ret.centerToFront = ret.wheelbase * 0.44
elif candidate == CAR.ALTIMA:
# Altima has EPS on C-CAN unlike the others that have it on V-CAN
ret.safetyConfigs[0].safetyParam |= Panda.FLAG_NISSAN_ALT_EPS_BUS
ret.safetyConfigs[0].safetyParam = 1 # EPS is on alternate bus
ret.mass = 1492
ret.wheelbase = 2.824
ret.centerToFront = ret.wheelbase * 0.44
+1
View File
@@ -1,3 +1,4 @@
#!/usr/bin/env python3
from openpilot.selfdrive.car.interfaces import RadarInterfaceBase
class RadarInterface(RadarInterfaceBase):
+10 -25
View File
@@ -1,13 +1,8 @@
from openpilot.common.numpy_fast import clip, interp
from opendbc.can.packer import CANPacker
from openpilot.selfdrive.car import apply_driver_steer_torque_limits, common_fault_avoidance
from openpilot.selfdrive.car import apply_driver_steer_torque_limits
from openpilot.selfdrive.car.subaru import subarucan
from openpilot.selfdrive.car.subaru.values import DBC, GLOBAL_GEN2, PREGLOBAL_CARS, HYBRID_CARS, STEER_RATE_LIMITED, CanBus, CarControllerParams, SubaruFlags
# FIXME: These limits aren't exact. The real limit is more than likely over a larger time period and
# involves the total steering angle change rather than rate, but these limits work well for now
MAX_STEER_RATE = 25 # deg/s
MAX_STEER_RATE_FRAMES = 7 # tx control frames needed before torque can be cut
from openpilot.selfdrive.car.subaru.values import DBC, GLOBAL_GEN2, PREGLOBAL_CARS, HYBRID_CARS, CanBus, CarControllerParams, SubaruFlags
class CarController:
@@ -17,7 +12,6 @@ class CarController:
self.frame = 0
self.cruise_button_prev = 0
self.steer_rate_counter = 0
self.p = CarControllerParams(CP)
self.packer = CANPacker(DBC[CP.carFingerprint]['pt'])
@@ -44,15 +38,7 @@ class CarController:
if self.CP.carFingerprint in PREGLOBAL_CARS:
can_sends.append(subarucan.create_preglobal_steering_control(self.packer, self.frame // self.p.STEER_STEP, apply_steer, CC.latActive))
else:
apply_steer_req = CC.latActive
if self.CP.carFingerprint in STEER_RATE_LIMITED:
# Steering rate fault prevention
self.steer_rate_counter, apply_steer_req = \
common_fault_avoidance(abs(CS.out.steeringRateDeg) > MAX_STEER_RATE, apply_steer_req,
self.steer_rate_counter, MAX_STEER_RATE_FRAMES)
can_sends.append(subarucan.create_steering_control(self.packer, apply_steer, apply_steer_req))
can_sends.append(subarucan.create_steering_control(self.packer, apply_steer, CC.latActive))
self.apply_steer_last = apply_steer
@@ -94,30 +80,29 @@ class CarController:
else:
if self.frame % 10 == 0:
can_sends.append(subarucan.create_es_dashstatus(self.packer, self.frame // 10, CS.es_dashstatus_msg, CC.enabled, self.CP.openpilotLongitudinalControl,
can_sends.append(subarucan.create_es_dashstatus(self.packer, CS.es_dashstatus_msg, CC.enabled, self.CP.openpilotLongitudinalControl,
CC.longActive, hud_control.leadVisible))
can_sends.append(subarucan.create_es_lkas_state(self.packer, self.frame // 10, CS.es_lkas_state_msg, CC.enabled, hud_control.visualAlert,
can_sends.append(subarucan.create_es_lkas_state(self.packer, CS.es_lkas_state_msg, CC.enabled, hud_control.visualAlert,
hud_control.leftLaneVisible, hud_control.rightLaneVisible,
hud_control.leftLaneDepart, hud_control.rightLaneDepart))
if self.CP.flags & SubaruFlags.SEND_INFOTAINMENT:
can_sends.append(subarucan.create_es_infotainment(self.packer, self.frame // 10, CS.es_infotainment_msg, hud_control.visualAlert))
can_sends.append(subarucan.create_es_infotainment(self.packer, CS.es_infotainment_msg, hud_control.visualAlert))
if self.CP.openpilotLongitudinalControl:
if self.frame % 5 == 0:
can_sends.append(subarucan.create_es_status(self.packer, self.frame // 5, CS.es_status_msg,
self.CP.openpilotLongitudinalControl, CC.longActive, cruise_rpm))
can_sends.append(subarucan.create_es_status(self.packer, CS.es_status_msg, self.CP.openpilotLongitudinalControl, CC.longActive, cruise_rpm))
can_sends.append(subarucan.create_es_brake(self.packer, self.frame // 5, CS.es_brake_msg, CC.enabled, cruise_brake))
can_sends.append(subarucan.create_es_brake(self.packer, CS.es_brake_msg, CC.enabled, cruise_brake))
can_sends.append(subarucan.create_es_distance(self.packer, self.frame // 5, CS.es_distance_msg, 0, pcm_cancel_cmd,
can_sends.append(subarucan.create_es_distance(self.packer, CS.es_distance_msg, 0, pcm_cancel_cmd,
self.CP.openpilotLongitudinalControl, cruise_brake > 0, cruise_throttle))
else:
if pcm_cancel_cmd:
if self.CP.carFingerprint not in HYBRID_CARS:
bus = CanBus.alt if self.CP.carFingerprint in GLOBAL_GEN2 else CanBus.main
can_sends.append(subarucan.create_es_distance(self.packer, CS.es_distance_msg["COUNTER"] + 1, CS.es_distance_msg, bus, pcm_cancel_cmd))
can_sends.append(subarucan.create_es_distance(self.packer, CS.es_distance_msg, bus, pcm_cancel_cmd))
new_actuators = actuators.copy()
new_actuators.steer = self.apply_steer_last / self.p.STEER_MAX
+1
View File
@@ -1,3 +1,4 @@
#!/usr/bin/env python3
from cereal import car
from panda import Panda
from openpilot.selfdrive.car import get_safety_config
+1
View File
@@ -1,3 +1,4 @@
#!/usr/bin/env python3
from openpilot.selfdrive.car.interfaces import RadarInterfaceBase
class RadarInterface(RadarInterfaceBase):
+13 -19
View File
@@ -16,9 +16,10 @@ def create_steering_control(packer, apply_steer, steer_req):
def create_steering_status(packer):
return packer.make_can_msg("ES_LKAS_State", 0, {})
def create_es_distance(packer, frame, es_distance_msg, bus, pcm_cancel_cmd, long_enabled = False, brake_cmd = False, cruise_throttle = 0):
def create_es_distance(packer, es_distance_msg, bus, pcm_cancel_cmd, long_enabled = False, brake_cmd = False, cruise_throttle = 0):
values = {s: es_distance_msg[s] for s in [
"CHECKSUM",
"COUNTER",
"Signal1",
"Cruise_Fault",
"Cruise_Throttle",
@@ -38,8 +39,7 @@ def create_es_distance(packer, frame, es_distance_msg, bus, pcm_cancel_cmd, long
"Cruise_Resume",
"Signal6",
]}
values["COUNTER"] = frame % 0x10
values["COUNTER"] = (values["COUNTER"] + 1) % 0x10
if long_enabled:
values["Cruise_Throttle"] = cruise_throttle
@@ -57,9 +57,10 @@ def create_es_distance(packer, frame, es_distance_msg, bus, pcm_cancel_cmd, long
return packer.make_can_msg("ES_Distance", bus, values)
def create_es_lkas_state(packer, frame, es_lkas_state_msg, enabled, visual_alert, left_line, right_line, left_lane_depart, right_lane_depart):
def create_es_lkas_state(packer, es_lkas_state_msg, enabled, visual_alert, left_line, right_line, left_lane_depart, right_lane_depart):
values = {s: es_lkas_state_msg[s] for s in [
"CHECKSUM",
"COUNTER",
"LKAS_Alert_Msg",
"Signal1",
"LKAS_ACTIVE",
@@ -76,8 +77,6 @@ def create_es_lkas_state(packer, frame, es_lkas_state_msg, enabled, visual_alert
"Signal3",
]}
values["COUNTER"] = frame % 0x10
# Filter the stock LKAS "Keep hands on wheel" alert
if values["LKAS_Alert_Msg"] == 1:
values["LKAS_Alert_Msg"] = 0
@@ -120,9 +119,10 @@ def create_es_lkas_state(packer, frame, es_lkas_state_msg, enabled, visual_alert
return packer.make_can_msg("ES_LKAS_State", CanBus.main, values)
def create_es_dashstatus(packer, frame, dashstatus_msg, enabled, long_enabled, long_active, lead_visible):
def create_es_dashstatus(packer, dashstatus_msg, enabled, long_enabled, long_active, lead_visible):
values = {s: dashstatus_msg[s] for s in [
"CHECKSUM",
"COUNTER",
"PCB_Off",
"LDW_Off",
"Signal1",
@@ -150,8 +150,6 @@ def create_es_dashstatus(packer, frame, dashstatus_msg, enabled, long_enabled, l
"Cruise_State",
]}
values["COUNTER"] = frame % 0x10
if enabled and long_active:
values["Cruise_State"] = 0
values["Cruise_Activated"] = 1
@@ -167,9 +165,10 @@ def create_es_dashstatus(packer, frame, dashstatus_msg, enabled, long_enabled, l
return packer.make_can_msg("ES_DashStatus", CanBus.main, values)
def create_es_brake(packer, frame, es_brake_msg, enabled, brake_value):
def create_es_brake(packer, es_brake_msg, enabled, brake_value):
values = {s: es_brake_msg[s] for s in [
"CHECKSUM",
"COUNTER",
"Signal1",
"Brake_Pressure",
"AEB_Status",
@@ -180,8 +179,6 @@ def create_es_brake(packer, frame, es_brake_msg, enabled, brake_value):
"Signal3",
]}
values["COUNTER"] = frame % 0x10
if enabled:
values["Cruise_Activated"] = 1
@@ -193,9 +190,10 @@ def create_es_brake(packer, frame, es_brake_msg, enabled, brake_value):
return packer.make_can_msg("ES_Brake", CanBus.main, values)
def create_es_status(packer, frame, es_status_msg, long_enabled, long_active, cruise_rpm):
def create_es_status(packer, es_status_msg, long_enabled, long_active, cruise_rpm):
values = {s: es_status_msg[s] for s in [
"CHECKSUM",
"COUNTER",
"Signal1",
"Cruise_Fault",
"Cruise_RPM",
@@ -206,8 +204,6 @@ def create_es_status(packer, frame, es_status_msg, long_enabled, long_active, cr
"Signal3",
]}
values["COUNTER"] = frame % 0x10
if long_enabled:
values["Cruise_RPM"] = cruise_rpm
@@ -217,18 +213,16 @@ def create_es_status(packer, frame, es_status_msg, long_enabled, long_active, cr
return packer.make_can_msg("ES_Status", CanBus.main, values)
def create_es_infotainment(packer, frame, es_infotainment_msg, visual_alert):
def create_es_infotainment(packer, es_infotainment_msg, visual_alert):
# Filter stock LKAS disabled and Keep hands on steering wheel OFF alerts
values = {s: es_infotainment_msg[s] for s in [
"CHECKSUM",
"COUNTER",
"LKAS_State_Infotainment",
"LKAS_Blue_Lines",
"Signal1",
"Signal2",
]}
values["COUNTER"] = frame % 0x10
if values["LKAS_State_Infotainment"] in (3, 4):
values["LKAS_State_Infotainment"] = 0
-4
View File
@@ -707,7 +707,3 @@ LKAS_ANGLE = {CAR.FORESTER_2022, CAR.OUTBACK_2023, CAR.ASCENT_2023}
GLOBAL_GEN2 = {CAR.OUTBACK, CAR.LEGACY, CAR.OUTBACK_2023, CAR.ASCENT_2023}
PREGLOBAL_CARS = {CAR.FORESTER_PREGLOBAL, CAR.LEGACY_PREGLOBAL, CAR.OUTBACK_PREGLOBAL, CAR.OUTBACK_PREGLOBAL_2018}
HYBRID_CARS = {CAR.CROSSTREK_HYBRID, CAR.FORESTER_HYBRID}
# Cars that temporarily fault when steering angle rate is greater than some threshold.
# Appears to be all cars that started production after 2020
STEER_RATE_LIMITED = GLOBAL_GEN2 | {CAR.IMPREZA_2020}
Executable → Regular
-4
View File
@@ -126,11 +126,9 @@ routes = [
CarTestRoute("eb4eae1476647463|2023-08-26--18-07-04", HYUNDAI.IONIQ_6, segment=6), # HDA2
CarTestRoute("3f29334d6134fcd4|2022-03-30--22-00-50", HYUNDAI.IONIQ_PHEV_2019),
CarTestRoute("fa8db5869167f821|2021-06-10--22-50-10", HYUNDAI.IONIQ_PHEV),
CarTestRoute("e1107f9d04dfb1e2|2023-09-05--22-32-12", HYUNDAI.IONIQ_PHEV), # openpilot longitudinal enabled
CarTestRoute("2c5cf2dd6102e5da|2020-12-17--16-06-44", HYUNDAI.IONIQ_EV_2020),
CarTestRoute("610ebb9faaad6b43|2020-06-13--15-28-36", HYUNDAI.IONIQ_EV_LTD),
CarTestRoute("2c5cf2dd6102e5da|2020-06-26--16-00-08", HYUNDAI.IONIQ),
CarTestRoute("012c95f06918eca4|2023-01-15--11-19-36", HYUNDAI.IONIQ), # openpilot longitudinal enabled
CarTestRoute("ab59fe909f626921|2021-10-18--18-34-28", HYUNDAI.IONIQ_HEV_2022),
CarTestRoute("22d955b2cd499c22|2020-08-10--19-58-21", HYUNDAI.KONA),
CarTestRoute("efc48acf44b1e64d|2021-05-28--21-05-04", HYUNDAI.KONA_EV),
@@ -168,7 +166,6 @@ routes = [
CarTestRoute("e9966711cfb04ce3|2022-01-11--07-59-43", TOYOTA.AVALON_TSS2),
CarTestRoute("eca1080a91720a54|2022-03-17--13-32-29", TOYOTA.AVALONH_TSS2),
CarTestRoute("6cdecc4728d4af37|2020-02-23--15-44-18", TOYOTA.CAMRY),
CarTestRoute("2f37c007683e85ba|2023-09-02--14-39-44", TOYOTA.CAMRY), # openpilot longitudinal, with radar CAN filter
CarTestRoute("3456ad0cd7281b24|2020-12-13--17-45-56", TOYOTA.CAMRY_TSS2),
CarTestRoute("ffccc77938ddbc44|2021-01-04--16-55-41", TOYOTA.CAMRYH_TSS2),
CarTestRoute("54034823d30962f5|2021-05-24--06-37-34", TOYOTA.CAMRYH),
@@ -244,7 +241,6 @@ routes = [
CarTestRoute("c321c6b697c5a5ff|2020-06-23--11-04-33", SUBARU.FORESTER),
CarTestRoute("791340bc01ed993d|2019-03-10--16-28-08", SUBARU.IMPREZA),
CarTestRoute("8bf7e79a3ce64055|2021-05-24--09-36-27", SUBARU.IMPREZA_2020),
# CarTestRoute("8de015561e1ea4a0|2023-08-29--17-08-31", SUBARU.IMPREZA), # openpilot longitudinal
CarTestRoute("1bbe6bf2d62f58a8|2022-07-14--17-11-43", SUBARU.OUTBACK, segment=10),
CarTestRoute("c56e69bbc74b8fad|2022-08-18--09-43-51", SUBARU.LEGACY, segment=3),
CarTestRoute("f4e3a0c511a076f4|2022-08-04--16-16-48", SUBARU.CROSSTREK_HYBRID, segment=2),
@@ -1,5 +1,4 @@
#!/usr/bin/env python3
import pytest
import random
import time
import unittest
@@ -225,7 +224,6 @@ class TestFwFingerprintTiming(unittest.TestCase):
self._assert_timing(vin_time / self.N, vin_ref_time)
print(f'get_vin, query time={vin_time / self.N} seconds')
@pytest.mark.timeout(60)
def test_fw_query_timing(self):
total_ref_time = 6.07
brand_ref_times = {
+1 -1
View File
@@ -32,7 +32,7 @@ ABOVE_LIMITS_CARS = [
car_model_jerks: DefaultDict[str, Dict[str, float]] = defaultdict(dict)
@parameterized_class('car_model', [(c,) for c in sorted(CAR_MODELS)])
@parameterized_class('car_model', [(c,) for c in CAR_MODELS])
class TestLateralLimits(unittest.TestCase):
car_model: str
+4 -19
View File
@@ -24,7 +24,6 @@ from panda.tests.libpanda import libpanda_py
from openpilot.selfdrive.test.helpers import SKIP_ENV_VAR
PandaType = log.PandaState.PandaType
SafetyModel = car.CarParams.SafetyModel
NUM_JOBS = int(os.environ.get("NUM_JOBS", "1"))
JOB_ID = int(os.environ.get("JOB_ID", "0"))
@@ -71,7 +70,6 @@ class TestCarModelBase(unittest.TestCase):
ci: bool = True
can_msgs: List[capnp.lib.capnp._DynamicStructReader]
elm_frame: Optional[int]
@unittest.skipIf(SKIP_ENV_VAR in os.environ, f"Long running test skipped. Unset {SKIP_ENV_VAR} to run")
@classmethod
@@ -107,7 +105,6 @@ class TestCarModelBase(unittest.TestCase):
car_fw = []
can_msgs = []
cls.elm_frame = None
fingerprint = defaultdict(dict)
experimental_long = False
enabled_toggle = True
@@ -133,16 +130,6 @@ class TestCarModelBase(unittest.TestCase):
if param.key == 'OpenpilotEnabledToggle':
enabled_toggle = param.value.strip(b'\x00') == b'1'
# Log which can frame the panda safety mode left ELM327, for CAN validity checks
if msg.which() == 'pandaStates':
for ps in msg.pandaStates:
if cls.elm_frame is None and ps.safetyModel != SafetyModel.elm327:
cls.elm_frame = len(can_msgs)
elif msg.which() == 'pandaStateDEPRECATED':
if cls.elm_frame is None and msg.pandaStateDEPRECATED.safetyModel != SafetyModel.elm327:
cls.elm_frame = len(can_msgs)
if len(can_msgs) > int(50 / DT_CTRL):
break
else:
@@ -217,10 +204,8 @@ class TestCarModelBase(unittest.TestCase):
RI = RadarInterface(self.CP)
assert RI
# Since OBD port is multiplexed to bus 1 (commonly radar bus) while fingerprinting,
# start parsing CAN messages after we've left ELM mode and can expect CAN traffic
error_cnt = 0
for i, msg in enumerate(self.can_msgs[self.elm_frame:]):
for i, msg in enumerate(self.can_msgs):
rr = RI.update((msg.as_builder().to_bytes(),))
if rr is not None and i > 50:
error_cnt += car.RadarData.Error.canError in rr.errors
@@ -253,9 +238,9 @@ class TestCarModelBase(unittest.TestCase):
if t > 1e6:
self.assertTrue(self.safety.addr_checks_valid())
# No need to check relay malfunction on disabled routes (relay closed),
# or before fingerprinting is done (1s of tolerance to exit silent mode)
if self.openpilot_enabled and t / 1e4 > (self.elm_frame + 100):
# No need to check relay malfunction on disabled routes (relay closed) or for reasonable fingerprinting time
# TODO: detect when relay has flipped to properly check relay malfunction
if self.openpilot_enabled and t > 5e6:
self.assertFalse(self.safety.get_relay_malfunction())
else:
self.safety.set_relay_malfunction(False)
+5 -7
View File
@@ -1,3 +1,4 @@
#!/usr/bin/env python3
from cereal import car
from openpilot.common.conversions import Conversions as CV
from panda import Panda
@@ -204,8 +205,7 @@ class CarInterface(CarInterfaceBase):
ret.enableBsm = 0x3F6 in fingerprint[0] and candidate in TSS2_CAR
# Detect smartDSU, which intercepts ACC_CMD from the DSU (or radar) allowing openpilot to send it
# 0x2AA is sent by a similar device which intercepts the radar instead of DSU on NO_DSU_CARs
if 0x2FF in fingerprint[0] or (0x2AA in fingerprint[0] and candidate in NO_DSU_CAR):
if 0x2FF in fingerprint[0]:
ret.flags |= ToyotaFlags.SMART_DSU.value
# No radar dbc for cars without DSU which are not TSS 2.0
@@ -219,14 +219,13 @@ class CarInterface(CarInterfaceBase):
ret.enableGasInterceptor = 0x201 in fingerprint[0]
# if the smartDSU is detected, openpilot can send ACC_CONTROL and the smartDSU will block it from the DSU or radar.
# since we don't yet parse radar on TSS2/TSS-P radar-based ACC cars, gate longitudinal behind experimental toggle
# since we don't yet parse radar on TSS2 radar-based ACC cars, gate longitudinal behind experimental toggle
use_sdsu = bool(ret.flags & ToyotaFlags.SMART_DSU)
if candidate in (RADAR_ACC_CAR | NO_DSU_CAR):
if candidate in RADAR_ACC_CAR:
ret.experimentalLongitudinalAvailable = use_sdsu
if not use_sdsu:
# Disabling radar is only supported on TSS2 radar-ACC cars
if experimental_long and candidate in RADAR_ACC_CAR and False: # TODO: disabling radar isn't supported yet
if experimental_long and False: # TODO: disabling radar isn't supported yet
ret.flags |= ToyotaFlags.DISABLE_RADAR.value
else:
use_sdsu = use_sdsu and experimental_long
@@ -238,7 +237,6 @@ class CarInterface(CarInterfaceBase):
# openpilot longitudinal behind experimental long toggle:
# - TSS2 radar ACC cars w/ smartDSU installed
# - TSS2 radar ACC cars w/o smartDSU installed (disables radar)
# - TSS-P DSU-less cars w/ CAN filter installed (no radar parser yet)
ret.openpilotLongitudinalControl = use_sdsu or ret.enableDsu or candidate in (TSS2_CAR - RADAR_ACC_CAR) or bool(ret.flags & ToyotaFlags.DISABLE_RADAR.value)
ret.autoResumeSng = ret.openpilotLongitudinalControl and candidate in NO_STOP_TIMER_CAR
@@ -1,3 +1,4 @@
#!/usr/bin/env python3
from openpilot.selfdrive.car.interfaces import RadarInterfaceBase
class RadarInterface(RadarInterfaceBase):
View File
+2 -2
View File
@@ -381,8 +381,6 @@ class Controls:
if not (self.sm['liveParameters'].sensorValid or self.sm['liveLocationKalman'].sensorsOK) and not NOSENSOR:
if self.sm.frame > 5 / DT_CTRL: # Give locationd some time to receive all the inputs
self.events.add(EventName.sensorDataInvalid)
if not self.sm['liveLocationKalman'].inputsOK and not NOSENSOR:
self.events.add(EventName.localizerMalfunction)
if not self.sm['liveLocationKalman'].posenetOK:
self.events.add(EventName.posenetInvalid)
if not self.sm['liveLocationKalman'].deviceStable:
@@ -422,6 +420,8 @@ class Controls:
if self.sm['modelV2'].frameDropPerc > 20:
self.events.add(EventName.modeldLagging)
if self.sm['liveLocationKalman'].excessiveResets:
self.events.add(EventName.localizerMalfunction)
def data_sample(self):
"""Receive data from sockets and update carState"""
+4 -3
View File
@@ -1,4 +1,3 @@
#!/usr/bin/env python3
import math
import os
from enum import IntEnum
@@ -576,9 +575,11 @@ EVENTS: Dict[int, Dict[str, Union[Alert, AlertCallbackType]]] = {
ET.PERMANENT: NormalPermanentAlert("GPS Malfunction", "Likely Hardware Issue"),
},
# When the GPS position and localizer diverge the localizer is reset to the
# current GPS position. This alert is thrown when the localizer is reset
# more often than expected.
EventName.localizerMalfunction: {
ET.NO_ENTRY: NoEntryAlert("Localizer Malfunction"),
ET.SOFT_DISABLE: soft_disable_alert("Localizer Malfunction"),
# ET.PERMANENT: NormalPermanentAlert("Sensor Malfunction", "Hardware Malfunction"),
},
# ********** events that affect controls state transitions **********
View File
+4 -7
View File
@@ -50,8 +50,7 @@ class KalmanParams:
class Track:
def __init__(self, identifier: int, v_lead: float, kalman_params: KalmanParams):
self.identifier = identifier
def __init__(self, v_lead: float, kalman_params: KalmanParams):
self.cnt = 0
self.aLeadTau = _LEAD_ACCEL_TAU
self.K_A = kalman_params.A
@@ -99,12 +98,11 @@ class Track:
"vLead": float(self.vLead),
"vLeadK": float(self.vLeadK),
"aLeadK": float(self.aLeadK),
"aLeadTau": float(self.aLeadTau),
"status": True,
"fcw": self.is_potential_fcw(model_prob),
"modelProb": model_prob,
"radar": True,
"radarTrackId": self.identifier,
"aLeadTau": float(self.aLeadTau)
}
def potential_low_speed_lead(self, v_ego: float):
@@ -160,9 +158,8 @@ def get_RadarState_from_vision(lead_msg: capnp._DynamicStructReader, v_ego: floa
"aLeadTau": 0.3,
"fcw": False,
"modelProb": float(lead_msg.prob),
"status": True,
"radar": False,
"radarTrackId": -1,
"status": True
}
@@ -240,7 +237,7 @@ class RadarD:
# create the track if it doesn't exist or it's a new track
if ids not in self.tracks:
self.tracks[ids] = Track(ids, v_lead, self.kalman_params)
self.tracks[ids] = Track(v_lead, self.kalman_params)
self.tracks[ids].update(rpt[0], rpt[1], rpt[2], v_lead, rpt[3])
# *** publish radarState ***
+11 -10
View File
@@ -1,5 +1,4 @@
#!/usr/bin/env python3
import itertools
import numpy as np
import unittest
@@ -32,19 +31,21 @@ def run_cruise_simulation(cruise, e2e, t_end=20.):
return output[-1, 3]
@parameterized_class(("e2e", "personality", "speed"), itertools.product(
[True, False], # e2e
log.LongitudinalPersonality.schema.enumerants, # personality
[5,35])) # speed
class TestCruiseSpeed(unittest.TestCase):
def test_cruise_speed(self):
params = Params()
params.put("LongitudinalPersonality", str(self.personality))
print(f'Testing {self.speed} m/s')
cruise_speed = float(self.speed)
personalities = [log.LongitudinalPersonality.relaxed,
log.LongitudinalPersonality.standard,
log.LongitudinalPersonality.aggressive]
for personality in personalities:
params.put("LongitudinalPersonality", str(personality))
for e2e in [False, True]:
for speed in [5,35]:
print(f'Testing {speed} m/s')
cruise_speed = float(speed)
simulation_steady_state = run_cruise_simulation(cruise_speed, self.e2e)
self.assertAlmostEqual(simulation_steady_state, cruise_speed, delta=.01, msg=f'Did not reach {self.speed} m/s')
simulation_steady_state = run_cruise_simulation(cruise_speed, e2e)
self.assertAlmostEqual(simulation_steady_state, cruise_speed, delta=.01, msg=f'Did not reach {speed} m/s')
# TODO: test pcmCruise
View File
View File
+5 -5
View File
@@ -24,11 +24,11 @@ from laika.opt import calc_pos_fix, get_posfix_sympy_fun, calc_vel_fix, get_velf
from openpilot.selfdrive.locationd.models.constants import GENERATED_DIR, ObservationKind
from openpilot.selfdrive.locationd.models.gnss_kf import GNSSKalman
from openpilot.selfdrive.locationd.models.gnss_kf import States as GStates
from openpilot.system.hardware.hw import Paths
from openpilot.system.swaglog import cloudlog
MAX_TIME_GAP = 10
EPHEMERIS_CACHE = 'LaikadEphemerisV3'
DOWNLOADS_CACHE_FOLDER = "/tmp/comma_download_cache/"
CACHE_VERSION = 0.2
POS_FIX_RESIDUAL_THRESHOLD = 100.0
@@ -83,7 +83,7 @@ class Laikad:
save_ephemeris: If true saves and loads nav and orbit ephemeris to cache.
"""
self.astro_dog = AstroDog(valid_const=valid_const, auto_update=auto_update, valid_ephem_types=valid_ephem_types,
clear_old_ephemeris=True, cache_dir=Paths.download_cache_root())
clear_old_ephemeris=True, cache_dir=DOWNLOADS_CACHE_FOLDER)
self.gnss_kf = GNSSKalman(GENERATED_DIR, cython=True, erratic_clock=use_qcom)
self.auto_fetch_navs = auto_fetch_navs
@@ -435,9 +435,9 @@ def kf_add_observations(gnss_kf: GNSSKalman, t: float, measurements: List[GNSSMe
def clear_tmp_cache():
if os.path.exists(Paths.download_cache_root()):
shutil.rmtree(Paths.download_cache_root())
os.mkdir(Paths.download_cache_root())
if os.path.exists(DOWNLOADS_CACHE_FOLDER):
shutil.rmtree(DOWNLOADS_CACHE_FOLDER)
os.mkdir(DOWNLOADS_CACHE_FOLDER)
def main(sm=None, pm=None):
View File
Regular → Executable
+4 -13
View File
@@ -21,11 +21,9 @@ const double VALID_TIME_SINCE_RESET = 1.0; // s
const double VALID_POS_STD = 50.0; // m
const double MAX_RESET_TRACKER = 5.0;
const double SANE_GPS_UNCERTAINTY = 1500.0; // m
const double INPUT_INVALID_THRESHOLD = 0.5; // same as reset tracker
const double RESET_TRACKER_DECAY = 0.99995;
const double DECAY = 0.9993; // ~10 secs to resume after a bad input
const double INPUT_INVALID_THRESHOLD = 5.0; // same as reset tracker
const double DECAY = 0.99995; // same as reset tracker
const double MAX_FILTER_REWIND_TIME = 0.8; // s
const double YAWRATE_CROSS_ERR_CHECK_FACTOR = 30;
// TODO: GPS sensor time offsets are empirically calculated
// They should be replaced with synced time from a real clock
@@ -258,13 +256,7 @@ void Localizer::handle_sensor(double current_time, const cereal::SensorEventData
if (log.getSensor() == SENSOR_GYRO_UNCALIBRATED && log.getType() == SENSOR_TYPE_GYROSCOPE_UNCALIBRATED) {
auto v = log.getGyroUncalibrated().getV();
auto meas = Vector3d(-v[2], -v[1], -v[0]);
VectorXd gyro_bias = this->kf->get_x().segment<STATE_GYRO_BIAS_LEN>(STATE_GYRO_BIAS_START);
float gyro_camodo_yawrate_err = std::abs((meas[2] - gyro_bias[2]) - this->camodo_yawrate_distribution[0]);
float gyro_camodo_yawrate_err_threshold = YAWRATE_CROSS_ERR_CHECK_FACTOR * this->camodo_yawrate_distribution[1];
bool gyro_valid = gyro_camodo_yawrate_err < gyro_camodo_yawrate_err_threshold;
if ((meas.norm() < ROTATION_SANITY_CHECK) && gyro_valid) {
if (meas.norm() < ROTATION_SANITY_CHECK) {
this->kf->predict_and_observe(sensor_time, OBSERVATION_PHONE_GYRO, { meas });
this->observation_values_invalid["gyroscope"] *= DECAY;
} else {
@@ -491,7 +483,6 @@ void Localizer::handle_cam_odo(double current_time, const cereal::CameraOdometry
this->kf->predict_and_observe(current_time, OBSERVATION_CAMERA_ODO_TRANSLATION,
{ trans_device }, { trans_device_cov });
this->observation_values_invalid["cameraOdometry"] *= DECAY;
this->camodo_yawrate_distribution = Vector2d(rot_device[2], rotate_std(this->device_from_calib, rot_calib_std)[2]);
}
void Localizer::handle_live_calib(double current_time, const cereal::LiveCalibrationData::Reader& log) {
@@ -547,7 +538,7 @@ void Localizer::time_check(double current_time) {
void Localizer::update_reset_tracker() {
// reset tracker is tuned to trigger when over 1reset/10s over 2min period
if (this->is_gps_ok()) {
this->reset_tracker *= RESET_TRACKER_DECAY;
this->reset_tracker *= DECAY;
} else {
this->reset_tracker = 0.0;
}
Regular → Executable
-1
View File
@@ -94,7 +94,6 @@ private:
float gps_variance_factor;
float gps_vertical_variance_factor;
double gps_time_offset;
Eigen::VectorXd camodo_yawrate_distribution = Eigen::Vector2d(0.0, 10.0); // mean, std
void configure_gnss_source(const LocalizerGnssSource &source);
};
View File
View File
+1 -1
View File
@@ -80,7 +80,7 @@ class TestLocationdProc(unittest.TestCase):
for msg in sorted(msgs, key=lambda x: x.logMonoTime):
self.pm.send(msg.which(), msg)
if msg.which() == "cameraOdometry":
self.pm.wait_for_readers_to_update(msg.which(), 0.1, dt=0.005)
self.pm.wait_for_readers_to_update(msg.which(), 0.1)
time.sleep(1) # wait for async params write
lastGPS = json.loads(self.params.get('LastGPSPosition'))
+2 -2
View File
@@ -52,13 +52,13 @@ procs = [
PythonProcess("micd", "system.micd", iscar),
PythonProcess("timezoned", "system.timezoned", always_run, enabled=not PC),
PythonProcess("dmonitoringmodeld", "selfdrive.modeld.dmonitoringmodeld", driverview, enabled=(not PC or WEBCAM)),
NativeProcess("dmonitoringmodeld", "selfdrive/modeld", ["./dmonitoringmodeld"], driverview, enabled=(not PC or WEBCAM)),
NativeProcess("encoderd", "system/loggerd", ["./encoderd"], only_onroad),
NativeProcess("stream_encoderd", "system/loggerd", ["./encoderd", "--stream"], notcar),
NativeProcess("loggerd", "system/loggerd", ["./loggerd"], logging),
NativeProcess("modeld", "selfdrive/modeld", ["./modeld"], only_onroad),
NativeProcess("mapsd", "selfdrive/navd", ["./mapsd"], only_onroad),
PythonProcess("navmodeld", "selfdrive.modeld.navmodeld", only_onroad),
NativeProcess("navmodeld", "selfdrive/modeld", ["./navmodeld"], only_onroad),
NativeProcess("sensord", "system/sensord", ["./sensord"], only_onroad, enabled=not PC),
NativeProcess("ui", "selfdrive/ui", ["./ui"], always_run, watchdog_max_dt=(5 if not PC else None)),
NativeProcess("soundd", "selfdrive/ui/soundd", ["./soundd"], only_onroad),
+20
View File
@@ -32,6 +32,12 @@ if arch == "Darwin":
else:
libs += ['OpenCL']
# Use onnx on PC
if arch != "larch64" and not GetOption('snpe'):
common_src += ['runners/onnxmodel.cc']
lenv['CFLAGS'].append("-DUSE_ONNX_MODEL")
lenv['CXXFLAGS'].append("-DUSE_ONNX_MODEL")
# Set path definitions
for pathdef, fn in {'TRANSFORM': 'transforms/transform.cl', 'LOADYUV': 'transforms/loadyuv.cl', 'ONNXRUNNER': 'runners/onnx_runner.py'}.items():
for xenv in (lenv, lenvCython):
@@ -54,6 +60,20 @@ lenvCython.Program('runners/snpemodel_pyx.so', 'runners/snpemodel_pyx.pyx', LIBS
lenvCython.Program('models/commonmodel_pyx.so', 'models/commonmodel_pyx.pyx', LIBS=[commonmodel_lib, *cython_libs], FRAMEWORKS=frameworks)
lenvCython.Program('models/driving_pyx.so', 'models/driving_pyx.pyx', LIBS=[driving_lib, commonmodel_lib, *cython_libs], FRAMEWORKS=frameworks)
# Compile binaries
lenv['FRAMEWORKS'] = frameworks
common_model = lenv.Object(common_src)
lenv.Program('_dmonitoringmodeld', [
"dmonitoringmodeld.cc",
"models/dmonitoring.cc",
]+common_model, LIBS=libs + snpe_lib)
lenv.Program('_navmodeld', [
"navmodeld.cc",
"models/nav.cc",
]+common_model, LIBS=libs + snpe_lib)
# Build thneed model
if arch == "larch64" or GetOption('pc_thneed'):
fn = File("models/supercombo").abspath
+12
View File
@@ -0,0 +1,12 @@
#!/usr/bin/env bash
DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)"
cd $DIR
if [ -f /TICI ]; then
export LD_LIBRARY_PATH="/usr/lib/aarch64-linux-gnu:/data/pythonpath/third_party/snpe/larch64:$LD_LIBRARY_PATH"
export ADSP_LIBRARY_PATH="/data/pythonpath/third_party/snpe/dsp/"
else
export LD_LIBRARY_PATH="$DIR/../../third_party/snpe/x86_64-linux-clang:$DIR/../../openpilot/third_party/snpe/x86_64:$LD_LIBRARY_PATH"
fi
exec ./_dmonitoringmodeld
+69
View File
@@ -0,0 +1,69 @@
#include <sys/resource.h>
#include <limits.h>
#include <cstdio>
#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"
ExitHandler do_exit;
void run_model(DMonitoringModelState &model, VisionIpcClient &vipc_client) {
PubMaster pm({"driverStateV2"});
SubMaster sm({"liveCalibration"});
float calib[CALIB_LEN] = {0};
// double last = 0;
while (!do_exit) {
VisionIpcBufExtra extra = {};
VisionBuf *buf = vipc_client.recv(&extra);
if (buf == nullptr) continue;
sm.update(0);
if (sm.updated("liveCalibration")) {
auto calib_msg = sm["liveCalibration"].getLiveCalibration().getRpyCalib();
for (int i = 0; i < CALIB_LEN; i++) {
calib[i] = calib_msg[i];
}
}
double t1 = millis_since_boot();
DMonitoringModelResult model_res = dmonitoring_eval_frame(&model, buf->addr, buf->width, buf->height, buf->stride, buf->uv_offset, calib);
double t2 = millis_since_boot();
// send dm packet
dmonitoring_publish(pm, extra.frame_id, model_res, (t2 - t1) / 1000.0, model.output);
// printf("dmonitoring process: %.2fms, from last %.2fms\n", t2 - t1, t1 - last);
// last = t1;
}
}
int main(int argc, char **argv) {
setpriority(PRIO_PROCESS, 0, -15);
// init the models
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)) {
util::sleep_for(100);
}
// run the models
if (vipc_client.connected) {
LOGW("connected with buffer size: %zu", vipc_client.buffers[0].len);
run_model(model, vipc_client);
}
dmonitoring_free(&model);
return 0;
}
-157
View File
@@ -1,157 +0,0 @@
#!/usr/bin/env python3
import os
import gc
import math
import time
import ctypes
import numpy as np
from pathlib import Path
from typing import Tuple, Dict
from cereal import messaging
from cereal.messaging import PubMaster, SubMaster
from cereal.visionipc import VisionIpcClient, VisionStreamType, VisionBuf
from openpilot.system.swaglog import cloudlog
from openpilot.common.params import Params
from openpilot.common.realtime import set_realtime_priority
from openpilot.selfdrive.modeld.runners import ModelRunner, Runtime
from openpilot.selfdrive.modeld.models.commonmodel_pyx import sigmoid
CALIB_LEN = 3
REG_SCALE = 0.25
MODEL_WIDTH = 1440
MODEL_HEIGHT = 960
OUTPUT_SIZE = 84
SEND_RAW_PRED = os.getenv('SEND_RAW_PRED')
MODEL_PATHS = {
ModelRunner.SNPE: Path(__file__).parent / 'models/dmonitoring_model_q.dlc',
ModelRunner.ONNX: Path(__file__).parent / 'models/dmonitoring_model.onnx'}
class DriverStateResult(ctypes.Structure):
_fields_ = [
("face_orientation", ctypes.c_float*3),
("face_position", ctypes.c_float*3),
("face_orientation_std", ctypes.c_float*3),
("face_position_std", ctypes.c_float*3),
("face_prob", ctypes.c_float),
("_unused_a", ctypes.c_float*8),
("left_eye_prob", ctypes.c_float),
("_unused_b", ctypes.c_float*8),
("right_eye_prob", ctypes.c_float),
("left_blink_prob", ctypes.c_float),
("right_blink_prob", ctypes.c_float),
("sunglasses_prob", ctypes.c_float),
("occluded_prob", ctypes.c_float),
("ready_prob", ctypes.c_float*4),
("not_ready_prob", ctypes.c_float*2)]
class DMonitoringModelResult(ctypes.Structure):
_fields_ = [
("driver_state_lhd", DriverStateResult),
("driver_state_rhd", DriverStateResult),
("poor_vision_prob", ctypes.c_float),
("wheel_on_right_prob", ctypes.c_float)]
class ModelState:
inputs: Dict[str, np.ndarray]
output: np.ndarray
model: ModelRunner
def __init__(self):
assert ctypes.sizeof(DMonitoringModelResult) == OUTPUT_SIZE * ctypes.sizeof(ctypes.c_float)
self.output = np.zeros(OUTPUT_SIZE, dtype=np.float32)
self.inputs = {
'input_imgs': np.zeros(MODEL_HEIGHT * MODEL_WIDTH, dtype=np.uint8),
'calib': np.zeros(CALIB_LEN, dtype=np.float32)}
self.model = ModelRunner(MODEL_PATHS, self.output, Runtime.DSP, True, None)
self.model.addInput("input_imgs", None)
self.model.addInput("calib", self.inputs['calib'])
def run(self, buf:VisionBuf, calib:np.ndarray) -> Tuple[np.ndarray, float]:
self.inputs['calib'][:] = calib
v_offset = buf.height - MODEL_HEIGHT
h_offset = (buf.width - MODEL_WIDTH) // 2
buf_data = buf.data.reshape(-1, buf.stride)
input_data = self.inputs['input_imgs'].reshape(MODEL_HEIGHT, MODEL_WIDTH)
input_data[:] = buf_data[v_offset:v_offset+MODEL_HEIGHT, h_offset:h_offset+MODEL_WIDTH]
t1 = time.perf_counter()
self.model.setInputBuffer("input_imgs", self.inputs['input_imgs'].view(np.float32))
self.model.execute()
t2 = time.perf_counter()
return self.output, t2 - t1
def fill_driver_state(msg, ds_result: DriverStateResult):
msg.faceOrientation = [x * REG_SCALE for x in ds_result.face_orientation]
msg.faceOrientationStd = [math.exp(x) for x in ds_result.face_orientation_std]
msg.facePosition = [x * REG_SCALE for x in ds_result.face_position[:2]]
msg.facePositionStd = [math.exp(x) for x in ds_result.face_position_std[:2]]
msg.faceProb = sigmoid(ds_result.face_prob)
msg.leftEyeProb = sigmoid(ds_result.left_eye_prob)
msg.rightEyeProb = sigmoid(ds_result.right_eye_prob)
msg.leftBlinkProb = sigmoid(ds_result.left_blink_prob)
msg.rightBlinkProb = sigmoid(ds_result.right_blink_prob)
msg.sunglassesProb = sigmoid(ds_result.sunglasses_prob)
msg.occludedProb = sigmoid(ds_result.occluded_prob)
msg.readyProb = [sigmoid(x) for x in ds_result.ready_prob]
msg.notReadyProb = [sigmoid(x) for x in ds_result.not_ready_prob]
def get_driverstate_packet(model_output: np.ndarray, frame_id: int, location_ts: int, execution_time: float, dsp_execution_time: float):
model_result = ctypes.cast(model_output.ctypes.data, ctypes.POINTER(DMonitoringModelResult)).contents
msg = messaging.new_message('driverStateV2')
ds = msg.driverStateV2
ds.frameId = frame_id
ds.modelExecutionTime = execution_time
ds.dspExecutionTime = dsp_execution_time
ds.poorVisionProb = sigmoid(model_result.poor_vision_prob)
ds.wheelOnRightProb = sigmoid(model_result.wheel_on_right_prob)
ds.rawPredictions = model_output.tobytes() if SEND_RAW_PRED else b''
fill_driver_state(ds.leftDriverData, model_result.driver_state_lhd)
fill_driver_state(ds.rightDriverData, model_result.driver_state_rhd)
return msg
def main():
gc.disable()
set_realtime_priority(1)
model = ModelState()
cloudlog.warning("models loaded, dmonitoringmodeld starting")
Params().put_bool("DmModelInitialized", True)
cloudlog.warning("connecting to driver stream")
vipc_client = VisionIpcClient("camerad", VisionStreamType.VISION_STREAM_DRIVER, True)
while not vipc_client.connect(False):
time.sleep(0.1)
assert vipc_client.is_connected()
cloudlog.warning(f"connected with buffer size: {vipc_client.buffer_len}")
sm = SubMaster(["liveCalibration"])
pm = PubMaster(["driverStateV2"])
calib = np.zeros(CALIB_LEN, dtype=np.float32)
# last = 0
while True:
buf = vipc_client.recv()
if buf is None:
continue
sm.update(0)
if sm.updated["liveCalibration"]:
calib[:] = np.array(sm["liveCalibration"].rpyCalib)
t1 = time.perf_counter()
model_output, dsp_execution_time = model.run(buf, calib)
t2 = time.perf_counter()
pm.send("driverStateV2", get_driverstate_packet(model_output, vipc_client.frame_id, vipc_client.timestamp_sof, t2 - t1, dsp_execution_time))
# print("dmonitoring process: %.2fms, from last %.2fms\n" % (t2 - t1, t1 - last))
# last = t1
if __name__ == "__main__":
main()
+133
View File
@@ -0,0 +1,133 @@
#include <cstring>
#include "common/mat.h"
#include "common/modeldata.h"
#include "common/params.h"
#include "common/timing.h"
#include "system/hardware/hw.h"
#include "selfdrive/modeld/models/dmonitoring.h"
constexpr int MODEL_WIDTH = 1440;
constexpr int MODEL_HEIGHT = 960;
template <class T>
static inline T *get_buffer(std::vector<T> &buf, const size_t size) {
if (buf.size() < size) buf.resize(size);
return buf.data();
}
void dmonitoring_init(DMonitoringModelState* s) {
#ifdef USE_ONNX_MODEL
s->m = new ONNXModel("models/dmonitoring_model.onnx", &s->output[0], OUTPUT_SIZE, USE_DSP_RUNTIME, true);
#else
s->m = new SNPEModel("models/dmonitoring_model_q.dlc", &s->output[0], OUTPUT_SIZE, USE_DSP_RUNTIME, true);
#endif
s->m->addInput("input_imgs", NULL, 0);
s->m->addInput("calib", s->calib, CALIB_LEN);
}
void parse_driver_data(DriverStateResult &ds_res, const DMonitoringModelState* s, int out_idx_offset) {
for (int i = 0; i < 3; ++i) {
ds_res.face_orientation[i] = s->output[out_idx_offset+i] * REG_SCALE;
ds_res.face_orientation_std[i] = exp(s->output[out_idx_offset+6+i]);
}
for (int i = 0; i < 2; ++i) {
ds_res.face_position[i] = s->output[out_idx_offset+3+i] * REG_SCALE;
ds_res.face_position_std[i] = exp(s->output[out_idx_offset+9+i]);
}
for (int i = 0; i < 4; ++i) {
ds_res.ready_prob[i] = sigmoid(s->output[out_idx_offset+35+i]);
}
for (int i = 0; i < 2; ++i) {
ds_res.not_ready_prob[i] = sigmoid(s->output[out_idx_offset+39+i]);
}
ds_res.face_prob = sigmoid(s->output[out_idx_offset+12]);
ds_res.left_eye_prob = sigmoid(s->output[out_idx_offset+21]);
ds_res.right_eye_prob = sigmoid(s->output[out_idx_offset+30]);
ds_res.left_blink_prob = sigmoid(s->output[out_idx_offset+31]);
ds_res.right_blink_prob = sigmoid(s->output[out_idx_offset+32]);
ds_res.sunglasses_prob = sigmoid(s->output[out_idx_offset+33]);
ds_res.occluded_prob = sigmoid(s->output[out_idx_offset+34]);
}
void fill_driver_data(cereal::DriverStateV2::DriverData::Builder ddata, const DriverStateResult &ds_res) {
ddata.setFaceOrientation(ds_res.face_orientation);
ddata.setFaceOrientationStd(ds_res.face_orientation_std);
ddata.setFacePosition(ds_res.face_position);
ddata.setFacePositionStd(ds_res.face_position_std);
ddata.setFaceProb(ds_res.face_prob);
ddata.setLeftEyeProb(ds_res.left_eye_prob);
ddata.setRightEyeProb(ds_res.right_eye_prob);
ddata.setLeftBlinkProb(ds_res.left_blink_prob);
ddata.setRightBlinkProb(ds_res.right_blink_prob);
ddata.setSunglassesProb(ds_res.sunglasses_prob);
ddata.setOccludedProb(ds_res.occluded_prob);
ddata.setReadyProb(ds_res.ready_prob);
ddata.setNotReadyProb(ds_res.not_ready_prob);
}
DMonitoringModelResult dmonitoring_eval_frame(DMonitoringModelState* s, void* stream_buf, int width, int height, int stride, int uv_offset, float *calib) {
int v_off = height - MODEL_HEIGHT;
int h_off = (width - MODEL_WIDTH) / 2;
int yuv_buf_len = MODEL_WIDTH * MODEL_HEIGHT;
uint8_t *raw_buf = (uint8_t *) stream_buf;
// vertical crop free
uint8_t *raw_y_start = raw_buf + stride * v_off;
uint8_t *net_input_buf = get_buffer(s->net_input_buf, yuv_buf_len);
// here makes a uint8 copy
for (int r = 0; r < MODEL_HEIGHT; ++r) {
memcpy(net_input_buf + r * MODEL_WIDTH, raw_y_start + r * stride + h_off, MODEL_WIDTH);
}
// printf("preprocess completed. %d \n", yuv_buf_len);
// FILE *dump_yuv_file = fopen("/tmp/rawdump.yuv", "wb");
// fwrite(net_input_buf, yuv_buf_len, sizeof(uint8_t), dump_yuv_file);
// fclose(dump_yuv_file);
double t1 = millis_since_boot();
s->m->setInputBuffer("input_imgs", (float*)net_input_buf, yuv_buf_len / sizeof(float));
for (int i = 0; i < CALIB_LEN; i++) {
s->calib[i] = calib[i];
}
s->m->execute();
double t2 = millis_since_boot();
DMonitoringModelResult model_res = {0};
parse_driver_data(model_res.driver_state_lhd, s, 0);
parse_driver_data(model_res.driver_state_rhd, s, 41);
model_res.poor_vision_prob = sigmoid(s->output[82]);
model_res.wheel_on_right_prob = sigmoid(s->output[83]);
model_res.dsp_execution_time = (t2 - t1) / 1000.;
return model_res;
}
void dmonitoring_publish(PubMaster &pm, uint32_t frame_id, const DMonitoringModelResult &model_res, float execution_time, kj::ArrayPtr<const float> raw_pred) {
// make msg
MessageBuilder msg;
auto framed = msg.initEvent().initDriverStateV2();
framed.setFrameId(frame_id);
framed.setModelExecutionTime(execution_time);
framed.setDspExecutionTime(model_res.dsp_execution_time);
framed.setPoorVisionProb(model_res.poor_vision_prob);
framed.setWheelOnRightProb(model_res.wheel_on_right_prob);
fill_driver_data(framed.initLeftDriverData(), model_res.driver_state_lhd);
fill_driver_data(framed.initRightDriverData(), model_res.driver_state_rhd);
if (send_raw_pred) {
framed.setRawPredictions(raw_pred.asBytes());
}
pm.send("driverStateV2", msg);
}
void dmonitoring_free(DMonitoringModelState* s) {
delete s->m;
}
+50
View File
@@ -0,0 +1,50 @@
#pragma once
#include <vector>
#include "cereal/messaging/messaging.h"
#include "common/util.h"
#include "selfdrive/modeld/models/commonmodel.h"
#include "selfdrive/modeld/runners/run.h"
#define CALIB_LEN 3
#define OUTPUT_SIZE 84
#define REG_SCALE 0.25f
typedef struct DriverStateResult {
float face_orientation[3];
float face_orientation_std[3];
float face_position[2];
float face_position_std[2];
float face_prob;
float left_eye_prob;
float right_eye_prob;
float left_blink_prob;
float right_blink_prob;
float sunglasses_prob;
float occluded_prob;
float ready_prob[4];
float not_ready_prob[2];
} DriverStateResult;
typedef struct DMonitoringModelResult {
DriverStateResult driver_state_lhd;
DriverStateResult driver_state_rhd;
float poor_vision_prob;
float wheel_on_right_prob;
float dsp_execution_time;
} DMonitoringModelResult;
typedef struct DMonitoringModelState {
RunModel *m;
float output[OUTPUT_SIZE];
std::vector<uint8_t> net_input_buf;
float calib[CALIB_LEN];
} DMonitoringModelState;
void dmonitoring_init(DMonitoringModelState* s);
DMonitoringModelResult dmonitoring_eval_frame(DMonitoringModelState* s, void* stream_buf, int width, int height, int stride, int uv_offset, float *calib);
void dmonitoring_publish(PubMaster &pm, uint32_t frame_id, const DMonitoringModelResult &model_res, float execution_time, kj::ArrayPtr<const float> raw_pred);
void dmonitoring_free(DMonitoringModelState* s);
+1 -4
View File
@@ -6,16 +6,13 @@
#include "cereal/messaging/messaging.h"
#include "common/modeldata.h"
#include "common/util.h"
#include "selfdrive/modeld/models/commonmodel.h"
#include "selfdrive/modeld/runners/run.h"
#include "selfdrive/modeld/models/nav.h"
constexpr int FEATURE_LEN = 128;
constexpr int HISTORY_BUFFER_LEN = 99;
constexpr int DESIRE_LEN = 8;
constexpr int DESIRE_PRED_LEN = 4;
constexpr int TRAFFIC_CONVENTION_LEN = 2;
constexpr int NAV_FEATURE_LEN = 256;
constexpr int NAV_INSTRUCTION_LEN = 150;
constexpr int DRIVING_STYLE_LEN = 12;
constexpr int MODEL_FREQ = 20;
+71
View File
@@ -0,0 +1,71 @@
#include "selfdrive/modeld/models/nav.h"
#include <cstdio>
#include <cstring>
#include "common/mat.h"
#include "common/modeldata.h"
#include "common/timing.h"
void navmodel_init(NavModelState* s) {
#ifdef USE_ONNX_MODEL
s->m = new ONNXModel("models/navmodel.onnx", &s->output[0], NAV_NET_OUTPUT_SIZE, USE_DSP_RUNTIME, true);
#else
s->m = new SNPEModel("models/navmodel_q.dlc", &s->output[0], NAV_NET_OUTPUT_SIZE, USE_DSP_RUNTIME, true);
#endif
s->m->addInput("map", NULL, 0);
}
NavModelResult* navmodel_eval_frame(NavModelState* s, VisionBuf* buf) {
memcpy(s->net_input_buf, buf->addr, NAV_INPUT_SIZE);
double t1 = millis_since_boot();
s->m->setInputBuffer("map", (float*)s->net_input_buf, NAV_INPUT_SIZE/sizeof(float));
s->m->execute();
double t2 = millis_since_boot();
NavModelResult *model_res = (NavModelResult*)&s->output;
model_res->dsp_execution_time = (t2 - t1) / 1000.;
return model_res;
}
void fill_plan(cereal::NavModelData::Builder &framed, const NavModelOutputPlan &plan) {
std::array<float, TRAJECTORY_SIZE> pos_x, pos_y;
std::array<float, TRAJECTORY_SIZE> pos_x_std, pos_y_std;
for (int i=0; i<TRAJECTORY_SIZE; i++) {
pos_x[i] = plan.mean[i].x;
pos_y[i] = plan.mean[i].y;
pos_x_std[i] = exp(plan.std[i].x);
pos_y_std[i] = exp(plan.std[i].y);
}
auto position = framed.initPosition();
position.setX(to_kj_array_ptr(pos_x));
position.setY(to_kj_array_ptr(pos_y));
position.setXStd(to_kj_array_ptr(pos_x_std));
position.setYStd(to_kj_array_ptr(pos_y_std));
}
void navmodel_publish(PubMaster &pm, VisionIpcBufExtra &extra, const NavModelResult &model_res, float execution_time, bool route_valid) {
// make msg
MessageBuilder msg;
auto evt = msg.initEvent();
auto framed = evt.initNavModel();
evt.setValid(extra.valid && route_valid);
framed.setFrameId(extra.frame_id);
framed.setLocationMonoTime(extra.timestamp_sof);
framed.setModelExecutionTime(execution_time);
framed.setDspExecutionTime(model_res.dsp_execution_time);
framed.setFeatures(to_kj_array_ptr(model_res.features.values));
framed.setDesirePrediction(to_kj_array_ptr(model_res.desire_pred.values));
fill_plan(framed, model_res.plan);
pm.send("navModel", msg);
}
void navmodel_free(NavModelState* s) {
delete s->m;
}
+57
View File
@@ -0,0 +1,57 @@
#pragma once
#include "cereal/messaging/messaging.h"
#include "cereal/visionipc/visionipc_client.h"
#include "common/util.h"
#include "common/modeldata.h"
#include "selfdrive/modeld/models/commonmodel.h"
#include "selfdrive/modeld/runners/run.h"
constexpr int NAV_INPUT_SIZE = 256*256;
constexpr int NAV_FEATURE_LEN = 256;
constexpr int NAV_INSTRUCTION_LEN = 150;
constexpr int NAV_DESIRE_LEN = 32;
struct NavModelOutputXY {
float x;
float y;
};
static_assert(sizeof(NavModelOutputXY) == sizeof(float)*2);
struct NavModelOutputPlan {
std::array<NavModelOutputXY, TRAJECTORY_SIZE> mean;
std::array<NavModelOutputXY, TRAJECTORY_SIZE> std;
};
static_assert(sizeof(NavModelOutputPlan) == sizeof(NavModelOutputXY)*TRAJECTORY_SIZE*2);
struct NavModelOutputDesirePrediction {
std::array<float, NAV_DESIRE_LEN> values;
};
static_assert(sizeof(NavModelOutputDesirePrediction) == sizeof(float)*NAV_DESIRE_LEN);
struct NavModelOutputFeatures {
std::array<float, NAV_FEATURE_LEN> values;
};
static_assert(sizeof(NavModelOutputFeatures) == sizeof(float)*NAV_FEATURE_LEN);
struct NavModelResult {
const NavModelOutputPlan plan;
const NavModelOutputDesirePrediction desire_pred;
const NavModelOutputFeatures features;
float dsp_execution_time;
};
static_assert(sizeof(NavModelResult) == sizeof(NavModelOutputPlan) + sizeof(NavModelOutputDesirePrediction) + sizeof(NavModelOutputFeatures) + sizeof(float));
constexpr int NAV_OUTPUT_SIZE = sizeof(NavModelResult) / sizeof(float);
constexpr int NAV_NET_OUTPUT_SIZE = NAV_OUTPUT_SIZE - 1;
struct NavModelState {
RunModel *m;
uint8_t net_input_buf[NAV_INPUT_SIZE];
float output[NAV_OUTPUT_SIZE];
};
void navmodel_init(NavModelState* s);
NavModelResult* navmodel_eval_frame(NavModelState* s, VisionBuf* buf);
void navmodel_publish(PubMaster &pm, VisionIpcBufExtra &extra, const NavModelResult &model_res, float execution_time, bool route_valid);
void navmodel_free(NavModelState* s);
+12
View File
@@ -0,0 +1,12 @@
#!/usr/bin/env bash
DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)"
cd $DIR
if [ -f /TICI ]; then
export LD_LIBRARY_PATH="/usr/lib/aarch64-linux-gnu:/data/pythonpath/third_party/snpe/larch64:$LD_LIBRARY_PATH"
export ADSP_LIBRARY_PATH="/data/pythonpath/third_party/snpe/dsp/"
else
export LD_LIBRARY_PATH="$DIR/../../third_party/snpe/x86_64-linux-clang:$DIR/../../openpilot/third_party/snpe/x86_64:$LD_LIBRARY_PATH"
fi
exec ./_navmodeld
+70
View File
@@ -0,0 +1,70 @@
#include <sys/resource.h>
#include <limits.h>
#include <cstdio>
#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"
ExitHandler do_exit;
void run_model(NavModelState &model, VisionIpcClient &vipc_client) {
SubMaster sm({"navInstruction"});
PubMaster pm({"navModel"});
//double last_ts = 0;
//uint32_t last_frame_id = 0;
VisionIpcBufExtra extra = {};
while (!do_exit) {
VisionBuf *buf = vipc_client.recv(&extra);
if (buf == nullptr) continue;
sm.update(0);
double t1 = millis_since_boot();
NavModelResult *model_res = navmodel_eval_frame(&model, buf);
double t2 = millis_since_boot();
// send navmodel packet
navmodel_publish(pm, extra, *model_res, (t2 - t1) / 1000.0, sm["navInstruction"].getValid());
//printf("navmodel process: %.2fms, from last %.2fms\n", t2 - t1, t1 - last_ts);
//last_ts = t1;
//last_frame_id = extra.frame_id;
}
}
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);
LOGW("models loaded, navmodeld starting");
VisionIpcClient vipc_client = VisionIpcClient("navd", VISION_STREAM_MAP, true);
while (!do_exit && !vipc_client.connect(false)) {
util::sleep_for(100);
}
// run the models
if (vipc_client.connected) {
LOGW("connected with buffer size: %zu", vipc_client.buffers[0].len);
run_model(model, vipc_client);
}
navmodel_free(&model);
return 0;
}
-118
View File
@@ -1,118 +0,0 @@
#!/usr/bin/env python3
import gc
import math
import time
import ctypes
import numpy as np
from pathlib import Path
from typing import Tuple, Dict
from cereal import messaging
from cereal.messaging import PubMaster, SubMaster
from cereal.visionipc import VisionIpcClient, VisionStreamType
from openpilot.system.swaglog import cloudlog
from openpilot.common.params import Params
from openpilot.common.realtime import set_realtime_priority
from openpilot.selfdrive.modeld.constants import IDX_N
from openpilot.selfdrive.modeld.runners import ModelRunner, Runtime
NAV_INPUT_SIZE = 256*256
NAV_FEATURE_LEN = 256
NAV_DESIRE_LEN = 32
NAV_OUTPUT_SIZE = 2*2*IDX_N + NAV_DESIRE_LEN + NAV_FEATURE_LEN
MODEL_PATHS = {
ModelRunner.SNPE: Path(__file__).parent / 'models/navmodel_q.dlc',
ModelRunner.ONNX: Path(__file__).parent / 'models/navmodel.onnx'}
class NavModelOutputXY(ctypes.Structure):
_fields_ = [
("x", ctypes.c_float),
("y", ctypes.c_float)]
class NavModelOutputPlan(ctypes.Structure):
_fields_ = [
("mean", NavModelOutputXY*IDX_N),
("std", NavModelOutputXY*IDX_N)]
class NavModelResult(ctypes.Structure):
_fields_ = [
("plan", NavModelOutputPlan),
("desire_pred", ctypes.c_float*NAV_DESIRE_LEN),
("features", ctypes.c_float*NAV_FEATURE_LEN)]
class ModelState:
inputs: Dict[str, np.ndarray]
output: np.ndarray
model: ModelRunner
def __init__(self):
assert ctypes.sizeof(NavModelResult) == NAV_OUTPUT_SIZE * ctypes.sizeof(ctypes.c_float)
self.output = np.zeros(NAV_OUTPUT_SIZE, dtype=np.float32)
self.inputs = {'map': np.zeros(NAV_INPUT_SIZE, dtype=np.uint8)}
self.model = ModelRunner(MODEL_PATHS, self.output, Runtime.DSP, True, None)
self.model.addInput("map", None)
def run(self, buf:np.ndarray) -> Tuple[np.ndarray, float]:
self.inputs['map'][:] = buf
t1 = time.perf_counter()
self.model.setInputBuffer("map", self.inputs['map'].view(np.float32))
self.model.execute()
t2 = time.perf_counter()
return self.output, t2 - t1
def get_navmodel_packet(model_output: np.ndarray, valid: bool, frame_id: int, location_ts: int, execution_time: float, dsp_execution_time: float):
model_result = ctypes.cast(model_output.ctypes.data, ctypes.POINTER(NavModelResult)).contents
msg = messaging.new_message('navModel')
msg.valid = valid
msg.navModel.frameId = frame_id
msg.navModel.locationMonoTime = location_ts
msg.navModel.modelExecutionTime = execution_time
msg.navModel.dspExecutionTime = dsp_execution_time
msg.navModel.features = model_result.features[:]
msg.navModel.desirePrediction = model_result.desire_pred[:]
msg.navModel.position.x = [p.x for p in model_result.plan.mean]
msg.navModel.position.y = [p.y for p in model_result.plan.mean]
msg.navModel.position.xStd = [math.exp(p.x) for p in model_result.plan.std]
msg.navModel.position.yStd = [math.exp(p.y) for p in model_result.plan.std]
return msg
def main():
gc.disable()
set_realtime_priority(1)
# there exists a race condition when two processes try to create a
# SNPE model runner at the same time, wait for dmonitoringmodeld to finish
cloudlog.warning("waiting for dmonitoringmodeld to initialize")
if not Params().get_bool("DmModelInitialized", True):
return
model = ModelState()
cloudlog.warning("models loaded, navmodeld starting")
vipc_client = VisionIpcClient("navd", VisionStreamType.VISION_STREAM_MAP, True)
while not vipc_client.connect(False):
time.sleep(0.1)
assert vipc_client.is_connected()
cloudlog.warning(f"connected with buffer size: {vipc_client.buffer_len}")
sm = SubMaster(["navInstruction"])
pm = PubMaster(["navModel"])
while True:
buf = vipc_client.recv()
if buf is None:
continue
sm.update(0)
t1 = time.perf_counter()
model_output, dsp_execution_time = model.run(buf.data[:buf.uv_offset])
t2 = time.perf_counter()
valid = vipc_client.valid and sm.valid["navInstruction"]
pm.send("navModel", get_navmodel_packet(model_output, valid, vipc_client.frame_id, vipc_client.timestamp_sof, t2 - t1, dsp_execution_time))
if __name__ == "__main__":
main()
+4
View File
@@ -2,3 +2,7 @@
#include "selfdrive/modeld/runners/runmodel.h"
#include "selfdrive/modeld/runners/snpemodel.h"
#if defined(USE_ONNX_MODEL)
#include "selfdrive/modeld/runners/onnxmodel.h"
#endif
+15 -4
View File
@@ -5,12 +5,14 @@ import os
import threading
import requests
import numpy as np
import cereal.messaging as messaging
from cereal import log
from openpilot.common.api import Api
from openpilot.common.params import Params
from openpilot.common.realtime import Ratekeeper
from openpilot.common.transformations.coordinates import ecef2geodetic
from openpilot.selfdrive.navd.helpers import (Coordinate, coordinate_from_param,
distance_along_geometry, maxspeed_to_ms,
minimum_distance,
@@ -19,6 +21,7 @@ from openpilot.system.swaglog import cloudlog
REROUTE_DISTANCE = 25
MANEUVER_TRANSITION_THRESHOLD = 10
VALID_POS_STD = 50.0
REROUTE_COUNTER_MIN = 3
@@ -76,13 +79,21 @@ class RouteEngine:
def update_location(self):
location = self.sm['liveLocationKalman']
self.gps_ok = location.gpsOK
laikad = self.sm['gnssMeasurements']
self.localizer_valid = (location.status == log.LiveLocationKalman.Status.valid) and location.positionGeodetic.valid
locationd_valid = (location.status == log.LiveLocationKalman.Status.valid) and location.positionGeodetic.valid
laikad_valid = laikad.positionECEF.valid and np.linalg.norm(laikad.positionECEF.std) < VALID_POS_STD
if self.localizer_valid:
self.localizer_valid = locationd_valid or laikad_valid
self.gps_ok = location.gpsOK or laikad_valid
if locationd_valid:
self.last_bearing = math.degrees(location.calibratedOrientationNED.value[2])
self.last_position = Coordinate(location.positionGeodetic.value[0], location.positionGeodetic.value[1])
elif laikad_valid:
geodetic = ecef2geodetic(laikad.positionECEF.value)
self.last_position = Coordinate(geodetic[0], geodetic[1])
self.last_bearing = None
def recompute_route(self):
if self.last_position is None:
@@ -346,7 +357,7 @@ class RouteEngine:
def main(sm=None, pm=None):
if sm is None:
sm = messaging.SubMaster(['liveLocationKalman', 'managerState'])
sm = messaging.SubMaster(['liveLocationKalman', 'gnssMeasurements', 'managerState'])
if pm is None:
pm = messaging.PubMaster(['navInstruction', 'navRoute'])
+46
View File
@@ -1,6 +1,9 @@
import os
import time
import tempfile
from typing import List, Union
from unittest import mock
from functools import wraps
import cereal.messaging as messaging
@@ -69,3 +72,46 @@ def with_processes(processes, init_time=0, ignore_stopped=None):
return wrap
return wrapper
def temporary_mock_dir(mock_paths_in: Union[List[str], str], kwarg: Union[str, None] = None, generator = tempfile.TemporaryDirectory):
"""
mock_paths_in: string or string list representing the full path of the variable you want to mock.
kwarg: str or None representing the kwarg that gets passed into the test function, in case the test needs access to the temporary directory.
generator: a context to use to generate the temporary directory
"""
def wrapper(func):
@wraps(func)
def wrap(*args, **kwargs):
mock_paths = mock_paths_in if isinstance(mock_paths_in, list) else [mock_paths_in]
with generator() as temp_dir:
mocks = []
for mock_path in mock_paths:
mocks.append(mock.patch(mock_path, str(temp_dir)))
[mock.start() for mock in mocks]
try:
if kwarg is not None:
kwargs[kwarg] = temp_dir
func(*args, **kwargs)
finally:
[mock.stop() for mock in mocks]
return wrap
return wrapper
def string_context(context):
class StringContext:
def __enter__(self):
return context
def __exit__(self, *args):
pass
return StringContext
temporary_dir = temporary_mock_dir([], "temp_dir")
temporary_cache_dir = temporary_mock_dir("openpilot.tools.lib.url_file.CACHE_DIR")
temporary_swaglog_dir = temporary_mock_dir("openpilot.system.swaglog.SWAGLOG_DIR", "temp_dir")
temporary_laikad_downloads_dir = temporary_mock_dir("openpilot.selfdrive.locationd.laikad.DOWNLOADS_CACHE_FOLDER")
temporary_swaglog_ipc = temporary_mock_dir(["openpilot.system.swaglog.SWAGLOG_IPC", "system.logmessaged.SWAGLOG_IPC"],
generator=string_context("/tmp/test_swaglog_ipc"))
@@ -2,14 +2,13 @@ import os
import shutil
import uuid
from typing import Optional
from typing import List, Optional
from openpilot.common.params import Params
from openpilot.system.hardware.hw import Paths
class OpenpilotPrefix:
class OpenpilotPrefix(object):
def __init__(self, prefix: Optional[str] = None, clean_dirs_on_exit: bool = True):
self.prefix = prefix if prefix else str(uuid.uuid4().hex[0:15])
self.prefix = prefix if prefix else str(uuid.uuid4())
self.msgq_path = os.path.join('/dev/shm', self.prefix)
self.clean_dirs_on_exit = clean_dirs_on_exit
@@ -19,17 +18,13 @@ class OpenpilotPrefix:
os.mkdir(self.msgq_path)
except FileExistsError:
pass
os.makedirs(Paths.log_root(), exist_ok=True)
return self
def __exit__(self, exc_type, exc_obj, exc_tb):
if self.clean_dirs_on_exit:
self.clean_dirs()
try:
del os.environ['OPENPILOT_PREFIX']
except KeyError:
pass
del os.environ['OPENPILOT_PREFIX']
return False
def clean_dirs(self):
@@ -38,4 +33,17 @@ class OpenpilotPrefix:
shutil.rmtree(os.path.realpath(symlink_path), ignore_errors=True)
os.remove(symlink_path)
shutil.rmtree(self.msgq_path, ignore_errors=True)
shutil.rmtree(Paths.log_root(), ignore_errors=True)
class DummySocket:
def __init__(self):
self.data: List[bytes] = []
def receive(self, non_blocking: bool = False) -> Optional[bytes]:
if non_blocking:
return None
return self.data.pop()
def send(self, data: bytes):
self.data.append(data)
@@ -17,12 +17,12 @@ from cereal import car
from cereal.services import service_list
from cereal.visionipc import VisionIpcServer, get_endpoint_name as vipc_get_endpoint_name
from openpilot.common.params import Params
from openpilot.common.prefix import OpenpilotPrefix
from openpilot.common.timeout import Timeout
from openpilot.common.realtime import DT_CTRL
from panda.python import ALTERNATIVE_EXPERIENCE
from openpilot.selfdrive.car.car_helpers import get_car, interfaces
from openpilot.selfdrive.manager.process_config import managed_processes
from openpilot.selfdrive.test.process_replay.helpers import OpenpilotPrefix, DummySocket
from openpilot.selfdrive.test.process_replay.vision_meta import meta_from_camera_state, available_streams
from openpilot.selfdrive.test.process_replay.migration import migrate_all
from openpilot.selfdrive.test.process_replay.capture import ProcessOutputCapture
@@ -33,18 +33,6 @@ NUMPY_TOLERANCE = 1e-7
PROC_REPLAY_DIR = os.path.dirname(os.path.abspath(__file__))
FAKEDATA = os.path.join(PROC_REPLAY_DIR, "fakedata/")
class DummySocket:
def __init__(self):
self.data: List[bytes] = []
def receive(self, non_blocking: bool = False) -> Optional[bytes]:
if non_blocking:
return None
return self.data.pop()
def send(self, data: bytes):
self.data.append(data)
class LauncherWithCapture:
def __init__(self, capture: ProcessOutputCapture, launcher: Callable):
+1 -1
View File
@@ -1 +1 @@
98c21236f831ca3cff63939cb760b213460e84de
20022e4a1b5f5df343465180a3865b0c78890544
+1 -1
View File
@@ -6,7 +6,7 @@ import random
import traceback
from tqdm import tqdm
from openpilot.common.prefix import OpenpilotPrefix
from openpilot.selfdrive.test.process_replay.helpers import OpenpilotPrefix
from openpilot.selfdrive.test.process_replay.regen import regen_and_save
from openpilot.selfdrive.test.process_replay.test_processes import FAKEDATA, source_segments as segments
from openpilot.tools.lib.route import SegmentName
+18
View File
@@ -0,0 +1,18 @@
[pytest]
testpaths =
common
selfdrive/athena
selfdrive/boardd
selfdrive/car
selfdrive/controls
selfdrive/locationd
selfdrive/monitoring
selfdrive/thermald
selfdrive/test/longitudinal_maneuvers
system/hardware/tici
system/loggerd
system/tests
system/ubloxd
tools/lib/tests
markers =
parallel: mark tests as parallelizable (tests with no global state, so can be run in parallel)
+8 -8
View File
@@ -19,8 +19,8 @@ from openpilot.common.timeout import Timeout
from openpilot.common.params import Params
from openpilot.selfdrive.controls.lib.events import EVENTS, ET
from openpilot.system.hardware import HARDWARE
from openpilot.system.loggerd.config import ROOT
from openpilot.selfdrive.test.helpers import set_params_enabled, release_only
from openpilot.system.hardware.hw import Paths
from openpilot.tools.lib.logreader import LogReader
# Baseline CPU usage by process
@@ -37,8 +37,8 @@ PROCS = {
"./_sensord": 7.0,
"selfdrive.controls.radard": 4.5,
"selfdrive.modeld.modeld": 8.0,
"selfdrive.modeld.dmonitoringmodeld": 8.0,
"selfdrive.modeld.navmodeld": 1.0,
"./_dmonitoringmodeld": 5.0,
"./_navmodeld": 1.0,
"selfdrive.thermald.thermald": 3.87,
"selfdrive.locationd.calibrationd": 2.0,
"selfdrive.locationd.torqued": 5.0,
@@ -102,7 +102,7 @@ class TestOnroad(unittest.TestCase):
@classmethod
def setUpClass(cls):
if "DEBUG" in os.environ:
segs = filter(lambda x: os.path.exists(os.path.join(x, "rlog")), Path(Paths.log_root()).iterdir())
segs = filter(lambda x: os.path.exists(os.path.join(x, "rlog")), Path(ROOT).iterdir())
segs = sorted(segs, key=lambda x: x.stat().st_mtime)
print(segs[-3])
cls.lr = list(LogReader(os.path.join(segs[-3], "rlog")))
@@ -115,8 +115,8 @@ class TestOnroad(unittest.TestCase):
params.remove("CurrentRoute")
set_params_enabled()
os.environ['TESTING_CLOSET'] = '1'
if os.path.exists(Paths.log_root()):
shutil.rmtree(Paths.log_root())
if os.path.exists(ROOT):
shutil.rmtree(ROOT)
os.system("rm /dev/shm/*")
# Make sure athena isn't running
@@ -143,8 +143,8 @@ class TestOnroad(unittest.TestCase):
while len(cls.segments) < 3:
segs = set()
if Path(Paths.log_root()).exists():
segs = set(Path(Paths.log_root()).glob(f"{route}--*"))
if Path(ROOT).exists():
segs = set(Path(ROOT).glob(f"{route}--*"))
cls.segments = sorted(segs, key=lambda s: int(str(s).rsplit('--')[-1]))
time.sleep(2)
View File
@@ -25,9 +25,12 @@ def pm_patch(name, value, constant=False):
@patch("time.monotonic", new=mock_time_monotonic)
@patch("openpilot.selfdrive.thermald.power_monitoring.put_nonblocking", new=lambda x, y: Params().put(x, y))
class TestPowerMonitoring(unittest.TestCase):
def setUp(self):
self.params = Params()
self.params.remove("CarBatteryCapacity")
self.params.remove("DisablePowerDown")
# Test to see that it doesn't do anything when pandaState is None
def test_pandaState_present(self):
+2 -2
View File
@@ -10,8 +10,8 @@ import glob
from typing import NoReturn
from openpilot.common.file_helpers import mkdirs_exists_ok
from openpilot.system.loggerd.config import ROOT
import openpilot.selfdrive.sentry as sentry
from openpilot.system.hardware.hw import Paths
from openpilot.system.swaglog import cloudlog
from openpilot.system.version import get_commit
@@ -130,7 +130,7 @@ def report_tombstone_apport(fn):
new_fn = f"{date}_{get_commit(default='nocommit')[:8]}_{safe_fn(clean_path)}"[:MAX_TOMBSTONE_FN_LEN]
crashlog_dir = os.path.join(Paths.log_root(), "crash")
crashlog_dir = os.path.join(ROOT, "crash")
mkdirs_exists_ok(crashlog_dir)
# Files could be on different filesystems, copy, then delete
+1
View File
@@ -5,6 +5,7 @@
#include <QDebug>
#include "common/transformations/coordinates.hpp"
#include "selfdrive/ui/qt/maps/map_helpers.h"
#include "selfdrive/ui/qt/util.h"
#include "selfdrive/ui/ui.h"
+5
View File
@@ -149,3 +149,8 @@ std::pair<QString, QString> map_format_distance(float d, bool is_metric) {
: std::pair{QString::number(50 * std::nearbyint(d / 50)), QObject::tr("ft")};
}
}
double angle_difference(double angle1, double angle2) {
double diff = fmod(angle2 - angle1 + 180.0, 360.0) - 180.0;
return diff < -180.0 ? diff + 360.0 : diff;
}
+1
View File
@@ -29,3 +29,4 @@ QMapbox::CoordinatesCollections coordinate_list_to_collection(const QList<QGeoCo
QList<QGeoCoordinate> polyline_to_coordinate_list(const QString &polylineString);
std::optional<QMapbox::Coordinate> coordinate_from_param(const std::string &param);
std::pair<QString, QString> map_format_distance(float d, bool is_metric);
double angle_difference(double angle1, double angle2);
+1
View File
@@ -213,6 +213,7 @@ void OnroadAlerts::paintEvent(QPaintEvent *event) {
ExperimentalButton::ExperimentalButton(QWidget *parent) : experimental_mode(false), engageable(false), QPushButton(parent) {
setFixedSize(btn_size, btn_size);
params = Params();
engage_img = loadPixmap("../assets/img_chffr_wheel.png", {img_size, img_size});
experimental_img = loadPixmap("../assets/img_experimental.svg", {img_size, img_size});
QObject::connect(this, &QPushButton::clicked, this, &ExperimentalButton::changeMode);
+1 -3
View File
@@ -207,9 +207,7 @@ void CameraWidget::updateFrameMat() {
if (zoomed_view) {
if (active_stream_type == VISION_STREAM_DRIVER) {
if (stream_width > 0 && stream_height > 0) {
frame_mat = get_driver_view_transform(w, h, stream_width, stream_height);
}
frame_mat = get_driver_view_transform(w, h, stream_width, stream_height);
} else {
// Project point at "infinity" to compute x and y offsets
// to ensure this ends up in the middle of the screen
+1 -1
View File
@@ -65,7 +65,7 @@ protected:
bool zoomed_view;
GLuint frame_vao, frame_vbo, frame_ibo;
GLuint textures[2];
mat4 frame_mat = {};
mat4 frame_mat;
std::unique_ptr<QOpenGLShaderProgram> program;
QColor bg = QColor("#000000");
+11 -32
View File
@@ -14,37 +14,16 @@
#endif
namespace Path {
inline std::string openpilot_prefix() {
return util::getenv("OPENPILOT_PREFIX", "");
}
inline std::string comma_home() {
return util::getenv("HOME") + "/.comma" + Path::openpilot_prefix();
}
inline std::string log_root() {
if (const char *env = getenv("LOG_ROOT")) {
return env;
}
return Hardware::PC() ? Path::comma_home() + "/media/0/realdata" : "/data/media/0/realdata";
}
inline std::string params() {
return Hardware::PC() ? util::getenv("PARAMS_ROOT", Path::comma_home() + "/params") : "/data/params";
}
inline std::string rsa_file() {
return Hardware::PC() ? Path::comma_home() + "/persist/comma/id_rsa" : "/persist/comma/id_rsa";
}
inline std::string swaglog_ipc() {
return "ipc:///tmp/logmessage" + Path::openpilot_prefix();
}
inline std::string download_cache_root() {
if (const char *env = getenv("COMMA_CACHE")) {
return env;
}
return "/tmp/comma_download_cache" + Path::openpilot_prefix() + "/";
inline std::string log_root() {
if (const char *env = getenv("LOG_ROOT")) {
return env;
}
return Hardware::PC() ? util::getenv("HOME") + "/.comma/media/0/realdata" : "/data/media/0/realdata";
}
inline std::string params() {
return Hardware::PC() ? util::getenv("PARAMS_ROOT", util::getenv("HOME") + "/.comma/params") : "/data/params";
}
inline std::string rsa_file() {
return Hardware::PC() ? util::getenv("HOME") + "/.comma/persist/comma/id_rsa" : "/persist/comma/id_rsa";
}
} // namespace Path
-35
View File
@@ -1,35 +0,0 @@
import os
from pathlib import Path
from openpilot.selfdrive.hardware import PC
class Paths:
@staticmethod
def comma_home() -> str:
return os.path.join(str(Path.home()), ".comma" + os.environ.get("OPENPILOT_PREFIX", ""))
@staticmethod
def log_root() -> str:
if os.environ.get('LOG_ROOT', False):
return os.environ['LOG_ROOT']
elif PC:
return str(Path(Paths.comma_home()) / "media" / "0" / "realdata")
else:
return '/data/media/0/realdata/'
@staticmethod
def swaglog_root() -> str:
if PC:
return os.path.join(Paths.comma_home(), "log")
else:
return "/data/log/"
@staticmethod
def swaglog_ipc() -> str:
return "ipc:///tmp/logmessage" + os.environ.get("OPENPILOT_PREFIX", "")
@staticmethod
def download_cache_root() -> str:
if os.environ.get('COMMA_CACHE', False):
return os.environ['COMMA_CACHE']
return "/tmp/comma_download_cache" + os.environ.get("OPENPILOT_PREFIX", "") + "/"
-1
View File
@@ -1,4 +1,3 @@
#!/usr/bin/env python3
import time
from smbus2 import SMBus
from collections import namedtuple

Some files were not shown because too many files have changed in this diff Show More