diff --git a/.github/workflows/prebuilt.yaml b/.github/workflows/prebuilt.yaml
index c8b4c51e38..1fd093e2ac 100644
--- a/.github/workflows/prebuilt.yaml
+++ b/.github/workflows/prebuilt.yaml
@@ -16,7 +16,6 @@ jobs:
build_prebuilt:
name: build prebuilt
runs-on: ubuntu-20.04
- timeout-minutes: 60
if: github.repository == 'commaai/openpilot'
env:
IMAGE_NAME: openpilot-prebuilt
diff --git a/.github/workflows/release.yaml b/.github/workflows/release.yaml
index 8df89dcc38..7f83f61e0a 100644
--- a/.github/workflows/release.yaml
+++ b/.github/workflows/release.yaml
@@ -8,7 +8,6 @@ jobs:
build_masterci:
name: build master-ci
runs-on: ubuntu-20.04
- timeout-minutes: 60
if: github.repository == 'commaai/openpilot'
steps:
- name: Wait for green check mark
diff --git a/.github/workflows/selfdrive_tests.yaml b/.github/workflows/selfdrive_tests.yaml
index 7cc45d23b9..efddde720d 100644
--- a/.github/workflows/selfdrive_tests.yaml
+++ b/.github/workflows/selfdrive_tests.yaml
@@ -32,7 +32,6 @@ jobs:
build_release:
name: build release
runs-on: ubuntu-20.04
- timeout-minutes: 30
env:
STRIPPED_DIR: /tmp/releasepilot
steps:
@@ -61,12 +60,11 @@ jobs:
cp .pylintrc $STRIPPED_DIR
cp mypy.ini $STRIPPED_DIR
cd $STRIPPED_DIR
- ${{ env.RUN }} "SKIP=test_translations pre-commit run --all"
+ ${{ env.RUN }} "pre-commit run --all"
build_all:
name: build all
runs-on: ubuntu-20.04
- timeout-minutes: 30
steps:
- uses: actions/checkout@v3
with:
@@ -84,7 +82,6 @@ jobs:
#build_mac:
# name: build macos
# runs-on: macos-latest
- # timeout-minutes: 60
# steps:
# - uses: actions/checkout@v3
# with:
@@ -141,7 +138,6 @@ jobs:
docker_push:
name: docker push
runs-on: ubuntu-20.04
- timeout-minutes: 22
if: github.ref == 'refs/heads/master' && github.event_name != 'pull_request' && github.repository == 'commaai/openpilot'
needs: static_analysis # hack to ensure slow tests run first since this and static_analysis are fast
steps:
@@ -150,14 +146,12 @@ jobs:
submodules: true
- name: Build Docker image
run: eval "$BUILD"
- timeout-minutes: 13
- name: Push to container registry
run: |
$DOCKER_LOGIN
docker push $DOCKER_REGISTRY/$BASE_IMAGE:latest
- name: Build CL Docker image
run: eval "$BUILD_CL"
- timeout-minutes: 4
- name: Push to container registry
run: |
$DOCKER_LOGIN
@@ -166,7 +160,6 @@ jobs:
static_analysis:
name: static analysis
runs-on: ubuntu-20.04
- timeout-minutes: 20
steps:
- uses: actions/checkout@v3
with:
@@ -174,13 +167,11 @@ jobs:
- name: Build Docker image
run: eval "$BUILD"
- name: pre-commit
- timeout-minutes: 5
run: ${{ env.RUN }} "pre-commit run --all"
valgrind:
name: valgrind
runs-on: ubuntu-20.04
- timeout-minutes: 20
steps:
- uses: actions/checkout@v3
with:
@@ -198,7 +189,6 @@ jobs:
unit_tests:
name: unit tests
runs-on: ubuntu-20.04
- timeout-minutes: 30
steps:
- uses: actions/checkout@v3
with:
@@ -207,7 +197,6 @@ jobs:
- name: Build openpilot
run: ${{ env.RUN }} "scons -j$(nproc)"
- name: Run unit tests
- timeout-minutes: 15
run: |
${{ env.RUN }} "export SKIP_LONG_TESTS=1 && \
$UNIT_TEST common && \
@@ -219,6 +208,7 @@ jobs:
$UNIT_TEST selfdrive/car && \
$UNIT_TEST selfdrive/locationd && \
selfdrive/locationd/test/_test_locationd_lib.py && \
+ ./selfdrive/locationd/test/test_glonass_runner && \
$UNIT_TEST selfdrive/athena && \
$UNIT_TEST selfdrive/thermald && \
$UNIT_TEST system/hardware/tici && \
@@ -241,7 +231,6 @@ jobs:
process_replay:
name: process replay
runs-on: ubuntu-20.04
- timeout-minutes: 25
steps:
- uses: actions/checkout@v3
with:
@@ -261,6 +250,7 @@ jobs:
${{ env.RUN }} "CI=1 coverage run selfdrive/test/process_replay/test_processes.py -j$(nproc) && \
coverage xml"
- name: Print diff
+ id: print-diff
if: always()
run: cat selfdrive/test/process_replay/diff.txt
- uses: actions/upload-artifact@v2
@@ -270,7 +260,7 @@ jobs:
name: process_replay_diff.txt
path: selfdrive/test/process_replay/diff.txt
- name: Upload reference logs
- if: ${{ failure() && github.event_name == 'pull_request' && github.repository == 'commaai/openpilot' && env.AZURE_TOKEN != '' }}
+ if: ${{ failure() && steps.print-diff.outcome == 'success' && github.event_name == 'pull_request' && github.repository == 'commaai/openpilot' && env.AZURE_TOKEN != '' }}
run: |
${{ env.RUN }} "CI=1 AZURE_TOKEN='$AZURE_TOKEN' python selfdrive/test/process_replay/test_processes.py -j$(nproc) --upload-only"
- name: "Upload coverage to Codecov"
@@ -279,7 +269,6 @@ jobs:
test_modeld:
name: model tests
runs-on: ubuntu-20.04
- timeout-minutes: 20
steps:
- uses: actions/checkout@v3
with:
@@ -292,12 +281,10 @@ jobs:
run: |
${{ env.RUN }} "scons -j$(nproc)"
- name: Run model replay with ONNX
- timeout-minutes: 2
run: |
${{ env.RUN_CL }} "ONNXCPU=1 CI=1 NO_NAV=1 coverage run selfdrive/test/process_replay/model_replay.py && \
coverage xml"
- name: Run unit tests
- timeout-minutes: 5
run: |
${{ env.RUN_CL }} "$UNIT_TEST selfdrive/modeld && \
coverage xml"
@@ -307,7 +294,6 @@ jobs:
test_longitudinal:
name: longitudinal
runs-on: ubuntu-20.04
- timeout-minutes: 20
steps:
- uses: actions/checkout@v3
with:
@@ -322,7 +308,6 @@ jobs:
cd selfdrive/test/longitudinal_maneuvers && \
coverage run ./test_longitudinal.py && \
coverage xml"
- timeout-minutes: 2
- name: "Upload coverage to Codecov"
uses: codecov/codecov-action@v2
- uses: actions/upload-artifact@v2
@@ -335,7 +320,6 @@ jobs:
test_cars:
name: cars
runs-on: ubuntu-20.04
- timeout-minutes: 20
strategy:
fail-fast: false
matrix:
@@ -354,7 +338,6 @@ jobs:
- name: Build openpilot
run: ${{ env.RUN }} "scons -j$(nproc)"
- name: Test car models
- timeout-minutes: 12
run: |
${{ env.RUN }} "coverage run -m pytest selfdrive/car/tests/test_models.py && \
coverage xml && \
@@ -368,7 +351,6 @@ jobs:
car_docs_diff:
name: PR comments
runs-on: ubuntu-20.04
- timeout-minutes: 20
if: github.event_name == 'pull_request'
steps:
- uses: actions/checkout@v3
diff --git a/.github/workflows/tools_tests.yaml b/.github/workflows/tools_tests.yaml
index 94cc3c2580..3b32d3c790 100644
--- a/.github/workflows/tools_tests.yaml
+++ b/.github/workflows/tools_tests.yaml
@@ -30,7 +30,6 @@ jobs:
plotjuggler:
name: plotjuggler
runs-on: ubuntu-20.04
- timeout-minutes: 20
steps:
- uses: actions/checkout@v3
with:
@@ -38,7 +37,6 @@ jobs:
- name: Build Docker image
run: eval "$BUILD"
- name: Unit test
- timeout-minutes: 2
run: |
${{ env.RUN }} "scons -j$(nproc) --directory=/tmp/openpilot/cereal && \
apt-get update && \
@@ -49,7 +47,6 @@ jobs:
simulator:
name: simulator
runs-on: ubuntu-20.04
- timeout-minutes: 30
env:
IMAGE_NAME: openpilot-sim
if: github.repository == 'commaai/openpilot'
@@ -74,7 +71,6 @@ jobs:
docs:
name: build docs
runs-on: ubuntu-20.04
- timeout-minutes: 25
steps:
- uses: actions/checkout@v3
with:
diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml
index 91b9c61628..1779947ff9 100644
--- a/.pre-commit-config.yaml
+++ b/.pre-commit-config.yaml
@@ -7,7 +7,7 @@ repos:
rev: v4.1.0
hooks:
- id: check-ast
- exclude: '^(pyextra)/'
+ exclude: '^(third_party)/'
- id: check-json
- id: check-xml
- id: check-yaml
@@ -19,7 +19,7 @@ repos:
rev: v2.2.1
hooks:
- id: codespell
- exclude: '^(pyextra/)|(third_party/)|(body/)|(cereal/)|(rednose/)|(panda/)|(laika/)|(opendbc/)|(laika_repo/)|(rednose_repo/)|(include/)|(selfdrive/ui/translations/.*.ts)|(selfdrive/controls/lib/cluster)'
+ exclude: '^(third_party/)|(body/)|(cereal/)|(rednose/)|(panda/)|(laika/)|(opendbc/)|(laika_repo/)|(rednose_repo/)|(selfdrive/ui/translations/.*.ts)|(poetry.lock)'
args:
# if you've got a short variable name that's getting flagged, add it here
- -L bu,ro,te,ue,alo,hda,ois,nam,nams,ned,som,parm,setts,inout,warmup
@@ -31,12 +31,12 @@ repos:
entry: mypy
language: system
types: [python]
- exclude: '^(pyextra/)|(cereal/)|(opendbc/)|(panda/)|(laika/)|(laika_repo/)|(rednose/)|(rednose_repo/)|(tinygrad/)|(tinygrad_repo/)|(xx/)'
+ exclude: '^(third_party/)|(cereal/)|(opendbc/)|(panda/)|(laika/)|(laika_repo/)|(rednose/)|(rednose_repo/)|(tinygrad/)|(tinygrad_repo/)|(xx/)'
- repo: https://github.com/PyCQA/flake8
rev: 4.0.1
hooks:
- id: flake8
- exclude: '^(pyextra/)|(cereal/)|(rednose/)|(panda/)|(laika/)|(opendbc/)|(laika_repo/)|(rednose_repo/)|(tinygrad/)|(tinygrad_repo/)|(selfdrive/debug/)/'
+ exclude: '^(third_party/)|(cereal/)|(rednose/)|(panda/)|(laika/)|(opendbc/)|(laika_repo/)|(rednose_repo/)|(tinygrad/)|(tinygrad_repo/)|(selfdrive/debug/)/'
additional_dependencies: ['flake8-no-implicit-concat']
args:
- --indent-size=2
@@ -51,7 +51,7 @@ repos:
entry: pylint
language: system
types: [python]
- exclude: '^(pyextra/)|(cereal/)|(rednose/)|(panda/)|(laika/)|(laika_repo/)|(rednose_repo/)|(tinygrad/)|(tinygrad_repo/)'
+ exclude: '^(third_party/)|(cereal/)|(rednose/)|(panda/)|(laika/)|(laika_repo/)|(rednose_repo/)|(tinygrad/)|(tinygrad_repo/)'
args:
- -j0
- -rn
@@ -64,7 +64,7 @@ repos:
entry: cppcheck
language: system
types: [c++]
- exclude: '^(third_party/)|(pyextra/)|(cereal/)|(body/)|(rednose/)|(rednose_repo/)|(opendbc/)|(panda/)|(tools/)|(selfdrive/modeld/thneed/debug/)|(selfdrive/modeld/test/)|(selfdrive/camerad/test/)|(installer/)'
+ exclude: '^(third_party/)|(cereal/)|(body/)|(rednose/)|(rednose_repo/)|(opendbc/)|(panda/)|(tools/)|(selfdrive/modeld/thneed/debug/)|(selfdrive/modeld/test/)|(selfdrive/camerad/test/)|(installer/)'
args:
- --error-exitcode=1
- --language=c++
diff --git a/Dockerfile.openpilot b/Dockerfile.openpilot
index 102da78d7d..acc0fcc784 100644
--- a/Dockerfile.openpilot
+++ b/Dockerfile.openpilot
@@ -10,7 +10,6 @@ WORKDIR ${OPENPILOT_PATH}
COPY SConstruct ${OPENPILOT_PATH}
-COPY ./pyextra ${OPENPILOT_PATH}/pyextra
COPY ./third_party ${OPENPILOT_PATH}/third_party
COPY ./site_scons ${OPENPILOT_PATH}/site_scons
COPY ./laika ${OPENPILOT_PATH}/laika
diff --git a/Jenkinsfile b/Jenkinsfile
index 37621dde5c..30c045e419 100644
--- a/Jenkinsfile
+++ b/Jenkinsfile
@@ -13,6 +13,8 @@ export GIT_COMMIT=${env.GIT_COMMIT}
export AZURE_TOKEN='${env.AZURE_TOKEN}'
export MAPBOX_TOKEN='${env.MAPBOX_TOKEN}'
+export GIT_SSH_COMMAND="ssh -i /data/gitkey"
+
source ~/.bash_profile
if [ -f /TICI ]; then
source /etc/profile
@@ -56,14 +58,26 @@ pipeline {
}
stages {
- stage('build release3') {
+ stage('build release3-staging') {
agent { docker { image 'ghcr.io/commaai/alpine-ssh'; args '--user=root' } }
when {
branch 'devel-staging'
}
steps {
phone_steps("tici-needs-can", [
- ["build release3-staging & dashcam3-staging", "PUSH=1 $SOURCE_DIR/release/build_release.sh"],
+ ["build release3-staging & dashcam3-staging", "RELEASE_BRANCH=release3-staging DASHCAM_BRANCH=dashcam3-staging $SOURCE_DIR/release/build_release.sh"],
+ ])
+ }
+ }
+
+ stage('build nightly') {
+ agent { docker { image 'ghcr.io/commaai/alpine-ssh'; args '--user=root' } }
+ when {
+ branch 'master-ci'
+ }
+ steps {
+ phone_steps("tici-needs-can", [
+ ["build nightly", "RELEASE_BRANCH=nightly $SOURCE_DIR/release/build_release.sh"],
])
}
}
@@ -81,6 +95,7 @@ pipeline {
parallel {
+ /*
stage('simulator') {
agent {
dockerfile {
@@ -90,7 +105,8 @@ pipeline {
}
}
steps {
- sh "git config --global --add safe.directory ${WORKSPACE}"
+ sh "git config --global --add safe.directory '*'"
+ sh "git submodule update --init --recursive"
sh "git lfs pull"
lock(resource: "", label: "simulator", inversePrecedence: true, quantity: 1) {
sh "${WORKSPACE}/tools/sim/build_container.sh"
@@ -107,6 +123,7 @@ pipeline {
}
}
}
+ */
stage('build') {
agent { docker { image 'ghcr.io/commaai/alpine-ssh'; args '--user=root' } }
@@ -151,7 +168,7 @@ pipeline {
stage('camerad-ar') {
agent { docker { image 'ghcr.io/commaai/alpine-ssh'; args '--user=root' } }
steps {
- phone_steps("tici-ar0321", [
+ phone_steps("tici-ar0231", [
["build", "cd selfdrive/manager && ./build.py"],
["test camerad", "python system/camerad/test/test_camerad.py"],
["test exposure", "python system/camerad/test/test_exposure.py"],
@@ -189,7 +206,7 @@ pipeline {
steps {
phone_steps("tici-common", [
["build", "cd selfdrive/manager && ./build.py"],
- ["model replay", "cd selfdrive/test/process_replay && ./model_replay.py"],
+ ["model replay", "cd selfdrive/test/process_replay && NO_NAV=1 ./model_replay.py"],
])
}
}
diff --git a/README.md b/README.md
index cfeb625bfe..4896d9ff72 100755
--- a/README.md
+++ b/README.md
@@ -103,7 +103,6 @@ Directory Structure
├── opendbc # Files showing how to interpret data from cars
├── panda # Code used to communicate on CAN
├── third_party # External libraries
- ├── pyextra # Extra python packages
└── system # Generic services
├── camerad # Driver to capture images from the camera sensors
├── clocksd # Broadcasts current time
@@ -143,7 +142,4 @@ NO WARRANTY EXPRESSED OR IMPLIED.**
[](https://github.com/commaai/openpilot/actions)
-[](https://lgtm.com/projects/g/commaai/openpilot/alerts/)
-[](https://lgtm.com/projects/g/commaai/openpilot/context:python)
-[](https://lgtm.com/projects/g/commaai/openpilot/context:cpp)
[](https://codecov.io/gh/commaai/openpilot)
diff --git a/RELEASES.md b/RELEASES.md
index eea69d295f..f71810784a 100644
--- a/RELEASES.md
+++ b/RELEASES.md
@@ -1,12 +1,27 @@
-Version 0.9.1 (2022-12-XX)
+Version 0.9.2 (2023-03-XX)
========================
-* Adjust alert volume using ambient noise level
-* Removed driver monitoring timer resetting on interaction if face detected and distracted
-* New German translation thanks to Vrabetz and CzokNorris!
+* Draw MPC path instead of model predicted path, this is a more accurate representation of what the car will do.
+
+Version 0.9.1 (2023-02-28)
+========================
+* New driving model
+ * 30% improved height estimation resulting in better driving performance for tall cars
+* Driver monitoring: removed timer resetting on user interaction if distracted
+* UI updates
+ * Adjust alert volume using ambient noise level
+ * Driver monitoring icon shows driver's head pose
+ * German translation thanks to Vrabetz and CzokNorris!
+* Cadillac Escalade 2017 support thanks to rickygilleland!
* Chevrolet Bolt EV 2022-23 support thanks to JasonJShuler!
* Genesis GV60 2023 support thanks to sunnyhaibin!
* Hyundai Tucson 2022-23 support
+* Kia K5 Hybrid 2020 support thanks to sunnyhaibin!
+* Kia Niro Hybrid 2023 support thanks to sunnyhaibin!
+* Kia Sorento 2022-23 support thanks to sunnyhaibin!
* Kia Sorento Plug-in Hybrid 2022 support thanks to sunnyhaibin!
+* Toyota C-HR 2021 support thanks to eFiniLan!
+* Toyota C-HR Hybrid 2022 support thanks to Korben00!
+* Volkswagen Crafter and MAN TGE 2017-23 support thanks to jyoung8607!
Version 0.9.0 (2022-11-21)
========================
diff --git a/SConstruct b/SConstruct
index 54b008004e..007931b7f5 100644
--- a/SConstruct
+++ b/SConstruct
@@ -71,10 +71,10 @@ if arch == "aarch64" and AGNOS:
lenv = {
"PATH": os.environ['PATH'],
"LD_LIBRARY_PATH": [Dir(f"#third_party/acados/{arch}/lib").abspath],
- "PYTHONPATH": Dir("#").abspath + ":" + Dir("#pyextra/").abspath,
+ "PYTHONPATH": Dir("#").abspath,
"ACADOS_SOURCE_DIR": Dir("#third_party/acados/include/acados").abspath,
- "ACADOS_PYTHON_INTERFACE_PATH": Dir("#pyextra/acados_template").abspath,
+ "ACADOS_PYTHON_INTERFACE_PATH": Dir("#third_party/acados/acados_template").abspath,
"TERA_PATH": Dir("#").abspath + f"/third_party/acados/{arch}/t_renderer"
}
@@ -197,10 +197,6 @@ env = Environment(
"#third_party/libyuv/include",
"#third_party/json11",
"#third_party/curl/include",
- "#third_party/libgralloc/include",
- "#third_party/android_frameworks_native/include",
- "#third_party/android_hardware_libhardware/include",
- "#third_party/android_system_core/include",
"#third_party/linux/include",
"#third_party/snpe/include",
"#third_party/mapbox-gl-native-qt/include",
@@ -282,7 +278,7 @@ Export('envCython')
# Qt build environment
qt_env = env.Clone()
-qt_modules = ["Widgets", "Gui", "Core", "Network", "Concurrent", "Multimedia", "Quick", "Qml", "QuickWidgets", "Location", "Positioning", "DBus"]
+qt_modules = ["Widgets", "Gui", "Core", "Network", "Concurrent", "Multimedia", "Quick", "Qml", "QuickWidgets", "Location", "Positioning", "DBus", "Xml"]
qt_libs = []
if arch == "Darwin":
@@ -311,6 +307,7 @@ else:
qt_libs = [f"Qt5{m}" for m in qt_modules]
if arch == "larch64":
qt_libs += ["GLESv2", "wayland-client"]
+ qt_env.PrependENVPath('PATH', Dir("#third_party/qt5/larch64/bin/").abspath)
elif arch != "Darwin":
qt_libs += ["GL"]
@@ -387,10 +384,10 @@ rednose_config = {
if arch != "larch64":
rednose_config['to_build'].update({
'loc_4': ('#selfdrive/locationd/models/loc_kf.py', True, [], rednose_deps),
+ 'lane': ('#selfdrive/locationd/models/lane_kf.py', True, [], rednose_deps),
'pos_computer_4': ('#rednose/helpers/lst_sq_computer.py', False, [], []),
'pos_computer_5': ('#rednose/helpers/lst_sq_computer.py', False, [], []),
'feature_handler_5': ('#rednose/helpers/feature_handler.py', False, [], []),
- 'lane': ('#xx/pipeline/lib/ekf/lane_kf.py', True, [], rednose_deps),
})
Export('rednose_config')
@@ -422,7 +419,6 @@ SConscript(['common/transformations/SConscript'])
SConscript(['selfdrive/modeld/SConscript'])
-SConscript(['selfdrive/controls/lib/cluster/SConscript'])
SConscript(['selfdrive/controls/lib/lateral_mpc_lib/SConscript'])
SConscript(['selfdrive/controls/lib/longitudinal_mpc_lib/SConscript'])
diff --git a/body b/body
index dc780f858c..e1805f65ee 160000
--- a/body
+++ b/body
@@ -1 +1 @@
-Subproject commit dc780f858c1ef641471d09b72569e199e3e10acb
+Subproject commit e1805f65ee75fab4454c21eda8b42b49d4bdc48f
diff --git a/cereal b/cereal
index 22b1431132..b88523f05a 160000
--- a/cereal
+++ b/cereal
@@ -1 +1 @@
-Subproject commit 22b1431132b038253a24ab3fbbe3af36ef93b95b
+Subproject commit b88523f05ac958f87a8f6d57c3f4bb20da55f216
diff --git a/common/SConscript b/common/SConscript
index 8aee6f42a7..5d6170611f 100644
--- a/common/SConscript
+++ b/common/SConscript
@@ -10,11 +10,13 @@ common_libs = [
'statlog.cc',
'swaglog.cc',
'util.cc',
- 'gpio.cc',
'i2c.cc',
'watchdog.cc',
]
+if arch != "Darwin":
+ common_libs.append('gpio.cc')
+
_common = fxn('common', common_libs, LIBS="json11")
files = [
diff --git a/common/clutil.cc b/common/clutil.cc
index 9d3447d807..3cfc8a8c8c 100644
--- a/common/clutil.cc
+++ b/common/clutil.cc
@@ -5,6 +5,7 @@
#include
#include "common/util.h"
+#include "common/swaglog.h"
namespace { // helper functions
@@ -31,14 +32,14 @@ void cl_print_info(cl_platform_id platform, cl_device_id device) {
case CL_DEVICE_TYPE_ACCELERATOR: type_str = "CL_DEVICE_TYPE_ACCELERATOR"; break;
}
- std::cout << "vendor: " << get_platform_info(platform, CL_PLATFORM_VENDOR) << std::endl
- << "platform version: " << get_platform_info(platform, CL_PLATFORM_VERSION) << std::endl
- << "profile: " << get_platform_info(platform, CL_PLATFORM_PROFILE) << std::endl
- << "extensions: " << get_platform_info(platform, CL_PLATFORM_EXTENSIONS) << std::endl
- << "name :" << get_device_info(device, CL_DEVICE_NAME) << std::endl
- << "device version :" << get_device_info(device, CL_DEVICE_VERSION) << std::endl
- << "max work group size :" << work_group_size << std::endl
- << "type = " << device_type << " = " << type_str << std::endl;
+ LOGD("vendor: %s", get_platform_info(platform, CL_PLATFORM_VENDOR).c_str());
+ LOGD("platform version: %s", get_platform_info(platform, CL_PLATFORM_VERSION).c_str());
+ LOGD("profile: %s", get_platform_info(platform, CL_PLATFORM_PROFILE).c_str());
+ LOGD("extensions: %s", get_platform_info(platform, CL_PLATFORM_EXTENSIONS).c_str());
+ LOGD("name: %s", get_device_info(device, CL_DEVICE_NAME).c_str());
+ LOGD("device version: %s", get_device_info(device, CL_DEVICE_VERSION).c_str());
+ LOGD("max work group size: %d", work_group_size);
+ LOGD("type = %d = ", device_type, type_str);
}
void cl_print_build_errors(cl_program program, cl_device_id device) {
@@ -49,7 +50,7 @@ void cl_print_build_errors(cl_program program, cl_device_id device) {
std::string log(log_size, '\0');
clGetProgramBuildInfo(program, device, CL_PROGRAM_BUILD_LOG, log_size, &log[0], NULL);
- std::cout << "build failed; status=" << status << ", log:" << std::endl << log << std::endl;
+ LOGE("build failed; status=%d, log: %s", status, log.c_str());
}
} // namespace
@@ -61,14 +62,15 @@ cl_device_id cl_get_device_id(cl_device_type device_type) {
CL_CHECK(clGetPlatformIDs(num_platforms, &platform_ids[0], NULL));
for (size_t i = 0; i < num_platforms; ++i) {
- std::cout << "platform[" << i << "] CL_PLATFORM_NAME: " << get_platform_info(platform_ids[i], CL_PLATFORM_NAME) << std::endl;
+ LOGD("platform[%d] CL_PLATFORM_NAME: %s", i, get_platform_info(platform_ids[i], CL_PLATFORM_NAME).c_str());
+
// Get first device
if (cl_device_id device_id = NULL; clGetDeviceIDs(platform_ids[i], device_type, 1, &device_id, NULL) == 0 && device_id) {
cl_print_info(platform_ids[i], device_id);
return device_id;
}
}
- std::cout << "No valid openCL platform found" << std::endl;
+ LOGE("No valid openCL platform found");
assert(0);
return nullptr;
}
diff --git a/common/gpio.cc b/common/gpio.cc
index 9f5c211a4b..aa65c0bd9d 100644
--- a/common/gpio.cc
+++ b/common/gpio.cc
@@ -1,5 +1,20 @@
#include "common/gpio.h"
+#ifdef __APPLE__
+int gpio_init(int pin_nr, bool output) {
+ return 0;
+}
+
+int gpio_set(int pin_nr, bool high) {
+ return 0;
+}
+
+int gpiochip_get_ro_value_fd(const char* consumer_label, int gpiochiop_id, int pin_nr) {
+ return 0;
+}
+
+#else
+
#include
#include
@@ -63,3 +78,5 @@ int gpiochip_get_ro_value_fd(const char* consumer_label, int gpiochiop_id, int p
close(fd);
return rq.fd;
}
+
+#endif
diff --git a/common/params.cc b/common/params.cc
index 8f6532bc79..2ba4f7e8ab 100644
--- a/common/params.cc
+++ b/common/params.cc
@@ -104,13 +104,14 @@ std::unordered_map keys = {
{"DisablePowerDown", PERSISTENT},
{"ExperimentalMode", PERSISTENT},
{"ExperimentalModeConfirmed", PERSISTENT},
- {"ExperimentalLongitudinalEnabled", PERSISTENT}, // WARNING: THIS MAY DISABLE AEB
+ {"ExperimentalLongitudinalEnabled", PERSISTENT},
{"DisableUpdates", PERSISTENT},
{"DisengageOnAccelerator", PERSISTENT},
{"DongleId", PERSISTENT},
{"DoReboot", CLEAR_ON_MANAGER_START},
{"DoShutdown", CLEAR_ON_MANAGER_START},
{"DoUninstall", CLEAR_ON_MANAGER_START},
+ {"FirmwareObdQueryDone", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_ON},
{"ForcePowerDown", CLEAR_ON_MANAGER_START},
{"GitBranch", PERSISTENT},
{"GitCommit", PERSISTENT},
@@ -134,9 +135,10 @@ std::unordered_map keys = {
{"IsRhdDetected", PERSISTENT},
{"IsTakingSnapshot", CLEAR_ON_MANAGER_START},
{"IsTestedBranch", CLEAR_ON_MANAGER_START},
+ {"IsReleaseBranch", CLEAR_ON_MANAGER_START},
{"IsUpdateAvailable", CLEAR_ON_MANAGER_START},
{"JoystickDebugMode", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_OFF},
- {"LaikadEphemeris", PERSISTENT | DONT_LOG},
+ {"LaikadEphemerisV2", PERSISTENT | DONT_LOG},
{"LanguageSetting", PERSISTENT},
{"LastAthenaPingTime", CLEAR_ON_MANAGER_START},
{"LastGPSPosition", PERSISTENT},
@@ -153,6 +155,7 @@ std::unordered_map keys = {
{"NavSettingTime24h", PERSISTENT},
{"NavSettingLeftSide", PERSISTENT},
{"NavdRender", PERSISTENT},
+ {"ObdMultiplexingDisabled", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_ON},
{"OpenpilotEnabledToggle", PERSISTENT},
{"PandaHeartbeatLost", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_OFF},
{"PandaSignatures", CLEAR_ON_MANAGER_START},
@@ -169,7 +172,7 @@ std::unordered_map keys = {
{"Timezone", PERSISTENT},
{"TrainingVersion", PERSISTENT},
{"UbloxAvailable", PERSISTENT},
- {"UpdateAvailable", CLEAR_ON_MANAGER_START},
+ {"UpdateAvailable", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_ON},
{"UpdateFailedCount", CLEAR_ON_MANAGER_START},
{"UpdaterState", CLEAR_ON_MANAGER_START},
{"UpdaterFetchAvailable", CLEAR_ON_MANAGER_START},
diff --git a/common/version.h b/common/version.h
index 7b5764785a..5637029cf4 100644
--- a/common/version.h
+++ b/common/version.h
@@ -1 +1 @@
-#define COMMA_VERSION "0.9.1"
+#define COMMA_VERSION "0.9.2"
diff --git a/docs/CARS.md b/docs/CARS.md
index 4f1a7cb652..3bc918f784 100644
--- a/docs/CARS.md
+++ b/docs/CARS.md
@@ -4,239 +4,254 @@
A supported vehicle is one that just works when you install a comma three. All supported cars provide a better experience than any stock system.
-# 222 Supported Cars
+# 237 Supported Cars
-|Make|Model|Supported Package|ACC|No ACC accel below|No ALC below|Steering Torque|Resume from stop|Harness|
-|---|---|---|:---:|:---:|:---:|:---:|:---:|:---:|
-|Acura|ILX 2016-19|AcuraWatch Plus|openpilot|25 mph|25 mph|[](##)|[](##)|Honda Nidec|
-|Acura|RDX 2016-18|AcuraWatch Plus|openpilot|25 mph|12 mph|[](##)|[](##)|Honda Nidec|
-|Acura|RDX 2019-22|All|openpilot available[1](#footnotes)|0 mph|3 mph|[](##)|[](##)|Honda Bosch A|
-|Audi|A3 2014-19|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533|
-|Audi|A3 Sportback e-tron 2017-18|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533|
-|Audi|Q2 2018|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533|
-|Audi|Q3 2019-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533|
-|Audi|RS3 2018|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533|
-|Audi|S3 2015-17|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533|
-|Cadillac|Escalade ESV 2016[3](#footnotes)|Adaptive Cruise Control (ACC) & LKAS|openpilot|0 mph|6 mph|[](##)|[](##)|OBD-II|
-|Chevrolet|Bolt EUV 2022-23|Premier or Premier Redline Trim without Super Cruise Package|openpilot available[1](#footnotes)|3 mph|6 mph|[](##)|[](##)|GM|
-|Chevrolet|Bolt EV 2022-23|2LT Trim with Adaptive Cruise Control Package|openpilot available[1](#footnotes)|3 mph|6 mph|[](##)|[](##)|GM|
-|Chevrolet|Silverado 1500 2020-21|Safety Package II|openpilot available[1](#footnotes)|3 mph|6 mph|[](##)|[](##)|GM|
-|Chevrolet|Volt 2017-18[3](#footnotes)|Adaptive Cruise Control (ACC)|openpilot|0 mph|6 mph|[](##)|[](##)|OBD-II|
-|Chrysler|Pacifica 2017-18|Adaptive Cruise Control (ACC)|Stock|0 mph|9 mph|[](##)|[](##)|FCA|
-|Chrysler|Pacifica 2019-20|Adaptive Cruise Control (ACC)|Stock|0 mph|39 mph|[](##)|[](##)|FCA|
-|Chrysler|Pacifica 2021|All|Stock|0 mph|39 mph|[](##)|[](##)|FCA|
-|Chrysler|Pacifica Hybrid 2017-18|Adaptive Cruise Control (ACC)|Stock|0 mph|9 mph|[](##)|[](##)|FCA|
-|Chrysler|Pacifica Hybrid 2019-22|Adaptive Cruise Control (ACC)|Stock|0 mph|39 mph|[](##)|[](##)|FCA|
-|comma|body|All|openpilot|0 mph|0 mph|[](##)|[](##)|None|
-|Genesis|G70 2018-19|All|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai F|
-|Genesis|G70 2020|All|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai F|
-|Genesis|G80 2017-19|All|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai H|
-|Genesis|G90 2017-18|All|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai C|
-|Genesis|GV60 2023[5](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai K|
-|Genesis|GV70 2022-23[5](#footnotes)|All|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai L|
-|GMC|Acadia 2018[3](#footnotes)|Adaptive Cruise Control (ACC)|openpilot|0 mph|6 mph|[](##)|[](##)|OBD-II|
-|GMC|Sierra 1500 2020-21|Driver Alert Package II|openpilot available[1](#footnotes)|3 mph|6 mph|[](##)|[](##)|GM|
-|Honda|Accord 2018-22|All|openpilot available[1](#footnotes)|0 mph|3 mph|[](##)|[](##)|Honda Bosch A|
-|Honda|Accord Hybrid 2018-22|All|openpilot available[1](#footnotes)|0 mph|3 mph|[](##)|[](##)|Honda Bosch A|
-|Honda|Civic 2016-18|Honda Sensing|openpilot|0 mph|12 mph|[](##)|[](##)|Honda Nidec|
-|Honda|Civic 2019-21|All|openpilot available[1](#footnotes)|0 mph|2 mph[4](#footnotes)|[](##)|[](##)|Honda Bosch A|
-|Honda|Civic 2022|All|Stock|0 mph|0 mph|[](##)|[](##)|Honda Bosch B|
-|Honda|Civic Hatchback 2017-21|Honda Sensing|openpilot available[1](#footnotes)|0 mph|12 mph|[](##)|[](##)|Honda Bosch A|
-|Honda|Civic Hatchback 2022|All|Stock|0 mph|0 mph|[](##)|[](##)|Honda Bosch B|
-|Honda|CR-V 2015-16|Touring Trim|openpilot|25 mph|12 mph|[](##)|[](##)|Honda Nidec|
-|Honda|CR-V 2017-22|Honda Sensing|openpilot available[1](#footnotes)|0 mph|12 mph|[](##)|[](##)|Honda Bosch A|
-|Honda|CR-V Hybrid 2017-19|Honda Sensing|openpilot available[1](#footnotes)|0 mph|12 mph|[](##)|[](##)|Honda Bosch A|
-|Honda|e 2020|All|openpilot available[1](#footnotes)|0 mph|3 mph|[](##)|[](##)|Honda Bosch A|
-|Honda|Fit 2018-20|Honda Sensing|openpilot|25 mph|12 mph|[](##)|[](##)|Honda Nidec|
-|Honda|Freed 2020|Honda Sensing|openpilot|25 mph|12 mph|[](##)|[](##)|Honda Nidec|
-|Honda|HR-V 2019-22|Honda Sensing|openpilot|25 mph|12 mph|[](##)|[](##)|Honda Nidec|
-|Honda|Insight 2019-22|All|openpilot available[1](#footnotes)|0 mph|3 mph|[](##)|[](##)|Honda Bosch A|
-|Honda|Inspire 2018|All|openpilot available[1](#footnotes)|0 mph|3 mph|[](##)|[](##)|Honda Bosch A|
-|Honda|Odyssey 2018-20|Honda Sensing|openpilot|25 mph|0 mph|[](##)|[](##)|Honda Nidec|
-|Honda|Passport 2019-21|All|openpilot|25 mph|12 mph|[](##)|[](##)|Honda Nidec|
-|Honda|Pilot 2016-22|Honda Sensing|openpilot|25 mph|12 mph|[](##)|[](##)|Honda Nidec|
-|Honda|Ridgeline 2017-22|Honda Sensing|openpilot|25 mph|12 mph|[](##)|[](##)|Honda Nidec|
-|Hyundai|Elantra 2017-19|Smart Cruise Control (SCC)|Stock|19 mph|32 mph|[](##)|[](##)|Hyundai B|
-|Hyundai|Elantra 2021-22|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai K|
-|Hyundai|Elantra GT 2017-19|Smart Cruise Control (SCC)|Stock|0 mph|32 mph|[](##)|[](##)|Hyundai E|
-|Hyundai|Elantra Hybrid 2021-23|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai K|
-|Hyundai|Genesis 2015-16|Smart Cruise Control (SCC)|Stock|19 mph|37 mph|[](##)|[](##)|Hyundai J|
-|Hyundai|i30 2017-19|Smart Cruise Control (SCC)|Stock|0 mph|32 mph|[](##)|[](##)|Hyundai E|
-|Hyundai|Ioniq 5 (Southeast Asia only) 2022-23[5](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai Q|
-|Hyundai|Ioniq 5 (with HDA II) 2022-23[5](#footnotes)|Highway Driving Assist II|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai Q|
-|Hyundai|Ioniq 5 (without HDA II) 2022-23[5](#footnotes)|Highway Driving Assist|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai K|
-|Hyundai|Ioniq Electric 2019|Smart Cruise Control (SCC)|Stock|0 mph|32 mph|[](##)|[](##)|Hyundai C|
-|Hyundai|Ioniq Electric 2020|All|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai H|
-|Hyundai|Ioniq Hybrid 2017-19|Smart Cruise Control (SCC)|Stock|0 mph|32 mph|[](##)|[](##)|Hyundai C|
-|Hyundai|Ioniq Hybrid 2020-22|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai H|
-|Hyundai|Ioniq Plug-in Hybrid 2019|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|32 mph|[](##)|[](##)|Hyundai C|
-|Hyundai|Ioniq Plug-in Hybrid 2020-21|All|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai H|
-|Hyundai|Kona 2020|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai B|
-|Hyundai|Kona Electric 2018-21|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai G|
-|Hyundai|Kona Electric 2022|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai O|
-|Hyundai|Kona Hybrid 2020|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai I|
-|Hyundai|Palisade 2020-22|All|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai H|
-|Hyundai|Santa Cruz 2021-22[5](#footnotes)|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai N|
-|Hyundai|Santa Fe 2019-20|All|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai D|
-|Hyundai|Santa Fe 2021-22|All|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai L|
-|Hyundai|Santa Fe Hybrid 2022|All|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai L|
-|Hyundai|Santa Fe Plug-in Hybrid 2022|All|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai L|
-|Hyundai|Sonata 2018-19|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai E|
-|Hyundai|Sonata 2020-22|All|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai A|
-|Hyundai|Sonata Hybrid 2020-22|All|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai A|
-|Hyundai|Tucson 2021|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|19 mph|0 mph|[](##)|[](##)|Hyundai L|
-|Hyundai|Tucson 2022[5](#footnotes)|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai N|
-|Hyundai|Tucson 2023[5](#footnotes)|All|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai N|
-|Hyundai|Tucson Diesel 2019|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai L|
-|Hyundai|Tucson Hybrid 2022[5](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai N|
-|Hyundai|Veloster 2019-20|Smart Cruise Control (SCC)|Stock|5 mph|0 mph|[](##)|[](##)|Hyundai E|
-|Jeep|Grand Cherokee 2016-18|Adaptive Cruise Control (ACC)|Stock|0 mph|9 mph|[](##)|[](##)|FCA|
-|Jeep|Grand Cherokee 2019-21|Adaptive Cruise Control (ACC)|Stock|0 mph|39 mph|[](##)|[](##)|FCA|
-|Kia|Ceed 2019|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai E|
-|Kia|EV6 (Southeast Asia only) 2022-23[5](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai P|
-|Kia|EV6 (with HDA II) 2022[5](#footnotes)|Highway Driving Assist II|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai P|
-|Kia|EV6 (without HDA II) 2022[5](#footnotes)|Highway Driving Assist|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai L|
-|Kia|Forte 2019-21|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai G|
-|Kia|K5 2021-22|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai A|
-|Kia|Niro EV 2019|All|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai H|
-|Kia|Niro EV 2020|All|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai F|
-|Kia|Niro EV 2021|All|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai C|
-|Kia|Niro EV 2022|All|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai H|
-|Kia|Niro Hybrid 2021|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai F|
-|Kia|Niro Hybrid 2022|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai H|
-|Kia|Niro Plug-in Hybrid 2018-19|All|openpilot available[1](#footnotes)|10 mph|32 mph|[](##)|[](##)|Hyundai C|
-|Kia|Optima 2017|Advanced Smart Cruise Control|Stock|0 mph|32 mph|[](##)|[](##)|Hyundai B|
-|Kia|Optima 2019-20|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai G|
-|Kia|Seltos 2021|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai A|
-|Kia|Sorento 2018|Advanced Smart Cruise Control|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai C|
-|Kia|Sorento 2019|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai E|
-|Kia|Sorento Plug-in Hybrid 2022-23[5](#footnotes)|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai A|
-|Kia|Sportage 2023[5](#footnotes)|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai N|
-|Kia|Sportage Hybrid 2023[5](#footnotes)|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai N|
-|Kia|Stinger 2018-20|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai C|
-|Kia|Stinger 2022|All|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai K|
-|Kia|Telluride 2020-22|All|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai H|
-|Lexus|CT Hybrid 2017-18|Lexus Safety System+|openpilot available[2](#footnotes)|0 mph|0 mph|[](##)|[](##)|Toyota|
-|Lexus|ES 2019-22|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota|
-|Lexus|ES Hybrid 2017-18|Lexus Safety System+|openpilot available[2](#footnotes)|0 mph|0 mph|[](##)|[](##)|Toyota|
-|Lexus|ES Hybrid 2019-22|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota|
-|Lexus|IS 2017-19|All|Stock|19 mph|0 mph|[](##)|[](##)|Toyota|
-|Lexus|NX 2018-19|All|openpilot available[2](#footnotes)|0 mph|0 mph|[](##)|[](##)|Toyota|
-|Lexus|NX 2020-21|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota|
-|Lexus|NX Hybrid 2018-19|All|openpilot available[2](#footnotes)|0 mph|0 mph|[](##)|[](##)|Toyota|
-|Lexus|NX Hybrid 2020-21|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota|
-|Lexus|RC 2017-20|All|Stock|19 mph|0 mph|[](##)|[](##)|Toyota|
-|Lexus|RX 2016|Lexus Safety System+|openpilot available[2](#footnotes)|0 mph|0 mph|[](##)|[](##)|Toyota|
-|Lexus|RX 2017-19|All|openpilot available[2](#footnotes)|0 mph|0 mph|[](##)|[](##)|Toyota|
-|Lexus|RX 2020-22|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota|
-|Lexus|RX Hybrid 2016|Lexus Safety System+|openpilot available[2](#footnotes)|0 mph|0 mph|[](##)|[](##)|Toyota|
-|Lexus|RX Hybrid 2017-19|All|openpilot available[2](#footnotes)|0 mph|0 mph|[](##)|[](##)|Toyota|
-|Lexus|RX Hybrid 2020-21|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota|
-|Lexus|UX Hybrid 2019-22|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota|
-|Mazda|CX-5 2022-23|All|Stock|0 mph|0 mph|[](##)|[](##)|Mazda|
-|Mazda|CX-9 2021-23|All|Stock|0 mph|28 mph|[](##)|[](##)|Mazda|
-|Nissan|Altima 2019-20|ProPILOT Assist|Stock|0 mph|0 mph|[](##)|[](##)|Nissan B|
-|Nissan|Leaf 2018-22|ProPILOT Assist|Stock|0 mph|0 mph|[](##)|[](##)|Nissan A|
-|Nissan|Rogue 2018-20|ProPILOT Assist|Stock|0 mph|0 mph|[](##)|[](##)|Nissan A|
-|Nissan|X-Trail 2017|ProPILOT Assist|Stock|0 mph|0 mph|[](##)|[](##)|Nissan A|
-|Ram|1500 2019-22|Adaptive Cruise Control (ACC)|Stock|0 mph|32 mph|[](##)|[](##)|Ram|
-|SEAT|Ateca 2018|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533|
-|SEAT|Leon 2014-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533|
-|Subaru|Ascent 2019-21|All|Stock|0 mph|0 mph|[](##)|[](##)|Subaru A|
-|Subaru|Crosstrek 2018-19|EyeSight Driver Assistance|Stock|0 mph|0 mph|[](##)|[](##)|Subaru A|
-|Subaru|Crosstrek 2020-23|EyeSight Driver Assistance|Stock|0 mph|0 mph|[](##)|[](##)|Subaru A|
-|Subaru|Forester 2019-21|All|Stock|0 mph|0 mph|[](##)|[](##)|Subaru A|
-|Subaru|Impreza 2017-19|EyeSight Driver Assistance|Stock|0 mph|0 mph|[](##)|[](##)|Subaru A|
-|Subaru|Impreza 2020-22|EyeSight Driver Assistance|Stock|0 mph|0 mph|[](##)|[](##)|Subaru A|
-|Subaru|Legacy 2020-22|All|Stock|0 mph|0 mph|[](##)|[](##)|Subaru B|
-|Subaru|Outback 2020-22|All|Stock|0 mph|0 mph|[](##)|[](##)|Subaru B|
-|Subaru|XV 2018-19|EyeSight Driver Assistance|Stock|0 mph|0 mph|[](##)|[](##)|Subaru A|
-|Subaru|XV 2020-21|EyeSight Driver Assistance|Stock|0 mph|0 mph|[](##)|[](##)|Subaru A|
-|Škoda|Kamiq 2021[7](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533[10](#footnotes)|
-|Škoda|Karoq 2019-21|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533|
-|Škoda|Kodiaq 2018-19|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533|
-|Škoda|Octavia 2015, 2018-19|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533|
-|Škoda|Octavia RS 2016|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533|
-|Škoda|Scala 2020|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533[10](#footnotes)|
-|Škoda|Superb 2015-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533|
-|Toyota|Alphard 2019-20|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota|
-|Toyota|Alphard Hybrid 2021|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota|
-|Toyota|Avalon 2016|Toyota Safety Sense P|openpilot available[2](#footnotes)|19 mph|0 mph|[](##)|[](##)|Toyota|
-|Toyota|Avalon 2017-18|All|openpilot available[2](#footnotes)|19 mph|0 mph|[](##)|[](##)|Toyota|
-|Toyota|Avalon 2019-21|All|openpilot available[2](#footnotes)|0 mph|0 mph|[](##)|[](##)|Toyota|
-|Toyota|Avalon 2022|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota|
-|Toyota|Avalon Hybrid 2019-21|All|openpilot available[2](#footnotes)|0 mph|0 mph|[](##)|[](##)|Toyota|
-|Toyota|Avalon Hybrid 2022|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota|
-|Toyota|C-HR 2017-21|All|Stock|0 mph|0 mph|[](##)|[](##)|Toyota|
-|Toyota|C-HR Hybrid 2017-19|All|Stock|0 mph|0 mph|[](##)|[](##)|Toyota|
-|Toyota|Camry 2018-20|All|Stock|0 mph[6](#footnotes)|0 mph|[](##)|[](##)|Toyota|
-|Toyota|Camry 2021-22|All|openpilot|0 mph[6](#footnotes)|0 mph|[](##)|[](##)|Toyota|
-|Toyota|Camry Hybrid 2018-20|All|Stock|0 mph|0 mph|[](##)|[](##)|Toyota|
-|Toyota|Camry Hybrid 2021-23|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota|
-|Toyota|Corolla 2017-19|All|openpilot available[2](#footnotes)|19 mph|0 mph|[](##)|[](##)|Toyota|
-|Toyota|Corolla 2020-22|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota|
-|Toyota|Corolla Cross (Non-US only) 2020-23|All|openpilot|17 mph|0 mph|[](##)|[](##)|Toyota|
-|Toyota|Corolla Cross Hybrid (Non-US only) 2020-22|All|openpilot|17 mph|0 mph|[](##)|[](##)|Toyota|
-|Toyota|Corolla Hatchback 2019-22|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota|
-|Toyota|Corolla Hybrid 2020-22|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota|
-|Toyota|Highlander 2017-19|All|openpilot available[2](#footnotes)|0 mph|0 mph|[](##)|[](##)|Toyota|
-|Toyota|Highlander 2020-22|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota|
-|Toyota|Highlander Hybrid 2017-19|All|openpilot available[2](#footnotes)|0 mph|0 mph|[](##)|[](##)|Toyota|
-|Toyota|Highlander Hybrid 2020-22|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota|
-|Toyota|Mirai 2021|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota|
-|Toyota|Prius 2016|Toyota Safety Sense P|openpilot available[2](#footnotes)|0 mph|0 mph|[](##)|[](##)|Toyota|
-|Toyota|Prius 2017-20|All|openpilot available[2](#footnotes)|0 mph|0 mph|[](##)|[](##)|Toyota|
-|Toyota|Prius 2021-22|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota|
-|Toyota|Prius Prime 2017-20|All|openpilot available[2](#footnotes)|0 mph|0 mph|[](##)|[](##)|Toyota|
-|Toyota|Prius Prime 2021-22|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota|
-|Toyota|Prius v 2017|Toyota Safety Sense P|openpilot available[2](#footnotes)|19 mph|0 mph|[](##)|[](##)|Toyota|
-|Toyota|RAV4 2016|Toyota Safety Sense P|openpilot available[2](#footnotes)|19 mph|0 mph|[](##)|[](##)|Toyota|
-|Toyota|RAV4 2017-18|All|openpilot available[2](#footnotes)|19 mph|0 mph|[](##)|[](##)|Toyota|
-|Toyota|RAV4 2019-21|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota|
-|Toyota|RAV4 2022|All|Stock|0 mph|0 mph|[](##)|[](##)|Toyota|
-|Toyota|RAV4 Hybrid 2016|Toyota Safety Sense P|openpilot available[2](#footnotes)|0 mph|0 mph|[](##)|[](##)|Toyota|
-|Toyota|RAV4 Hybrid 2017-18|All|openpilot available[2](#footnotes)|0 mph|0 mph|[](##)|[](##)|Toyota|
-|Toyota|RAV4 Hybrid 2019-21|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota|
-|Toyota|RAV4 Hybrid 2022|All|Stock|0 mph|0 mph|[](##)|[](##)|Toyota|
-|Toyota|Sienna 2018-20|All|openpilot available[2](#footnotes)|19 mph|0 mph|[](##)|[](##)|Toyota|
-|Volkswagen|Arteon 2018-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533|
-|Volkswagen|Arteon eHybrid 2020-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533|
-|Volkswagen|Arteon R 2020-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533|
-|Volkswagen|Atlas 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533|
-|Volkswagen|Atlas Cross Sport 2021-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533|
-|Volkswagen|California 2021|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|31 mph|[](##)|[](##)|J533|
-|Volkswagen|Caravelle 2020|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|31 mph|[](##)|[](##)|J533|
-|Volkswagen|CC 2018-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533|
-|Volkswagen|e-Golf 2014-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533|
-|Volkswagen|Golf 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533|
-|Volkswagen|Golf Alltrack 2015-19|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533|
-|Volkswagen|Golf GTD 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533|
-|Volkswagen|Golf GTE 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533|
-|Volkswagen|Golf GTI 2015-21|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533|
-|Volkswagen|Golf R 2015-19|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533|
-|Volkswagen|Golf SportsVan 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533|
-|Volkswagen|Jetta 2018-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533|
-|Volkswagen|Jetta GLI 2021-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533|
-|Volkswagen|Passat 2015-22[8](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533|
-|Volkswagen|Passat Alltrack 2015-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533|
-|Volkswagen|Passat GTE 2015-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533|
-|Volkswagen|Polo 2020-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533[10](#footnotes)|
-|Volkswagen|Polo GTI 2020-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533[10](#footnotes)|
-|Volkswagen|T-Cross 2021|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533[10](#footnotes)|
-|Volkswagen|T-Roc 2021|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533[10](#footnotes)|
-|Volkswagen|Taos 2022|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533|
-|Volkswagen|Teramont 2018-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533|
-|Volkswagen|Teramont Cross Sport 2021-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533|
-|Volkswagen|Teramont X 2021-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533|
-|Volkswagen|Tiguan 2019-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533|
-|Volkswagen|Touran 2017|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533|
+|Make|Model|Supported Package|ACC|No ACC accel below|No ALC below|Steering Torque|Resume from stop|Harness|Video|
+|---|---|---|:---:|:---:|:---:|:---:|:---:|:---:|:---:|
+|Acura|ILX 2016-19|AcuraWatch Plus|openpilot|25 mph|25 mph|[](##)|[](##)|Honda Nidec||
+|Acura|RDX 2016-18|AcuraWatch Plus|openpilot|25 mph|12 mph|[](##)|[](##)|Honda Nidec||
+|Acura|RDX 2019-22|All|openpilot available[1](#footnotes)|0 mph|3 mph|[](##)|[](##)|Honda Bosch A||
+|Audi|A3 2014-19|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533||
+|Audi|A3 Sportback e-tron 2017-18|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533||
+|Audi|Q2 2018|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533||
+|Audi|Q3 2019-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533||
+|Audi|RS3 2018|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533||
+|Audi|S3 2015-17|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533||
+|Cadillac|Escalade 2017[3](#footnotes)|Driver Assist Package|openpilot|0 mph|7 mph|[](##)|[](##)|OBD-II||
+|Cadillac|Escalade ESV 2016[3](#footnotes)|Adaptive Cruise Control (ACC) & LKAS|openpilot|0 mph|7 mph|[](##)|[](##)|OBD-II||
+|Chevrolet|Bolt EUV 2022-23|Premier or Premier Redline Trim without Super Cruise Package|openpilot available[1](#footnotes)|3 mph|6 mph|[](##)|[](##)|GM||
+|Chevrolet|Bolt EV 2022-23|2LT Trim with Adaptive Cruise Control Package|openpilot available[1](#footnotes)|3 mph|6 mph|[](##)|[](##)|GM||
+|Chevrolet|Silverado 1500 2020-21|Safety Package II|openpilot available[1](#footnotes)|3 mph|6 mph|[](##)|[](##)|GM||
+|Chevrolet|Volt 2017-18[3](#footnotes)|Adaptive Cruise Control (ACC)|openpilot|0 mph|7 mph|[](##)|[](##)|OBD-II||
+|Chrysler|Pacifica 2017-18|Adaptive Cruise Control (ACC)|Stock|0 mph|9 mph|[](##)|[](##)|FCA||
+|Chrysler|Pacifica 2019-20|Adaptive Cruise Control (ACC)|Stock|0 mph|39 mph|[](##)|[](##)|FCA||
+|Chrysler|Pacifica 2021|All|Stock|0 mph|39 mph|[](##)|[](##)|FCA||
+|Chrysler|Pacifica Hybrid 2017-18|Adaptive Cruise Control (ACC)|Stock|0 mph|9 mph|[](##)|[](##)|FCA||
+|Chrysler|Pacifica Hybrid 2019-22|Adaptive Cruise Control (ACC)|Stock|0 mph|39 mph|[](##)|[](##)|FCA||
+|comma|body|All|openpilot|0 mph|0 mph|[](##)|[](##)|None||
+|Genesis|G70 2018-19|All|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai F||
+|Genesis|G70 2020|All|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai F||
+|Genesis|G80 2017|All|Stock|19 mph|37 mph|[](##)|[](##)|Hyundai J||
+|Genesis|G80 2018-19|All|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai H||
+|Genesis|G90 2017-18|All|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai C||
+|Genesis|GV60 (Advanced Trim) 2023[5](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai A||
+|Genesis|GV60 (Performance Trim) 2023[5](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai K||
+|Genesis|GV70 2022-23[5](#footnotes)|All|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai L||
+|GMC|Acadia 2018[3](#footnotes)|Adaptive Cruise Control (ACC)|openpilot|0 mph|7 mph|[](##)|[](##)|OBD-II||
+|GMC|Sierra 1500 2020-21|Driver Alert Package II|openpilot available[1](#footnotes)|3 mph|6 mph|[](##)|[](##)|GM||
+|Honda|Accord 2018-22|All|openpilot available[1](#footnotes)|0 mph|3 mph|[](##)|[](##)|Honda Bosch A||
+|Honda|Accord Hybrid 2018-22|All|openpilot available[1](#footnotes)|0 mph|3 mph|[](##)|[](##)|Honda Bosch A||
+|Honda|Civic 2016-18|Honda Sensing|openpilot|0 mph|12 mph|[](##)|[](##)|Honda Nidec||
+|Honda|Civic 2019-21|All|openpilot available[1](#footnotes)|0 mph|2 mph[4](#footnotes)|[](##)|[](##)|Honda Bosch A||
+|Honda|Civic 2022|All|Stock|0 mph|0 mph|[](##)|[](##)|Honda Bosch B||
+|Honda|Civic Hatchback 2017-21|Honda Sensing|openpilot available[1](#footnotes)|0 mph|12 mph|[](##)|[](##)|Honda Bosch A||
+|Honda|Civic Hatchback 2022|All|Stock|0 mph|0 mph|[](##)|[](##)|Honda Bosch B||
+|Honda|CR-V 2015-16|Touring Trim|openpilot|25 mph|12 mph|[](##)|[](##)|Honda Nidec||
+|Honda|CR-V 2017-22|Honda Sensing|openpilot available[1](#footnotes)|0 mph|12 mph|[](##)|[](##)|Honda Bosch A||
+|Honda|CR-V Hybrid 2017-19|Honda Sensing|openpilot available[1](#footnotes)|0 mph|12 mph|[](##)|[](##)|Honda Bosch A||
+|Honda|e 2020|All|openpilot available[1](#footnotes)|0 mph|3 mph|[](##)|[](##)|Honda Bosch A||
+|Honda|Fit 2018-20|Honda Sensing|openpilot|25 mph|12 mph|[](##)|[](##)|Honda Nidec||
+|Honda|Freed 2020|Honda Sensing|openpilot|25 mph|12 mph|[](##)|[](##)|Honda Nidec||
+|Honda|HR-V 2019-22|Honda Sensing|openpilot|25 mph|12 mph|[](##)|[](##)|Honda Nidec||
+|Honda|Insight 2019-22|All|openpilot available[1](#footnotes)|0 mph|3 mph|[](##)|[](##)|Honda Bosch A||
+|Honda|Inspire 2018|All|openpilot available[1](#footnotes)|0 mph|3 mph|[](##)|[](##)|Honda Bosch A||
+|Honda|Odyssey 2018-20|Honda Sensing|openpilot|25 mph|0 mph|[](##)|[](##)|Honda Nidec||
+|Honda|Passport 2019-21|All|openpilot|25 mph|12 mph|[](##)|[](##)|Honda Nidec||
+|Honda|Pilot 2016-22|Honda Sensing|openpilot|25 mph|12 mph|[](##)|[](##)|Honda Nidec||
+|Honda|Ridgeline 2017-22|Honda Sensing|openpilot|25 mph|12 mph|[](##)|[](##)|Honda Nidec||
+|Hyundai|Elantra 2017-19|Smart Cruise Control (SCC)|Stock|19 mph|32 mph|[](##)|[](##)|Hyundai B||
+|Hyundai|Elantra 2021-23|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai K||
+|Hyundai|Elantra GT 2017-19|Smart Cruise Control (SCC)|Stock|0 mph|32 mph|[](##)|[](##)|Hyundai E||
+|Hyundai|Elantra Hybrid 2021-23|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai K||
+|Hyundai|Genesis 2015-16|Smart Cruise Control (SCC)|Stock|19 mph|37 mph|[](##)|[](##)|Hyundai J||
+|Hyundai|i30 2017-19|Smart Cruise Control (SCC)|Stock|0 mph|32 mph|[](##)|[](##)|Hyundai E||
+|Hyundai|Ioniq 5 (Southeast Asia only) 2022-23[5](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai Q||
+|Hyundai|Ioniq 5 (with HDA II) 2022-23[5](#footnotes)|Highway Driving Assist II|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai Q||
+|Hyundai|Ioniq 5 (without HDA II) 2022-23[5](#footnotes)|Highway Driving Assist|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai K||
+|Hyundai|Ioniq Electric 2019|Smart Cruise Control (SCC)|Stock|0 mph|32 mph|[](##)|[](##)|Hyundai C||
+|Hyundai|Ioniq Electric 2020|All|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai H||
+|Hyundai|Ioniq Hybrid 2017-19|Smart Cruise Control (SCC)|Stock|0 mph|32 mph|[](##)|[](##)|Hyundai C||
+|Hyundai|Ioniq Hybrid 2020-22|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai H||
+|Hyundai|Ioniq Plug-in Hybrid 2019|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|32 mph|[](##)|[](##)|Hyundai C||
+|Hyundai|Ioniq Plug-in Hybrid 2020-21|All|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai H||
+|Hyundai|Kona 2020|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai B||
+|Hyundai|Kona Electric 2018-21|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai G||
+|Hyundai|Kona Electric 2022|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai O||
+|Hyundai|Kona Hybrid 2020|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai I||
+|Hyundai|Palisade 2020-22|All|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai H||
+|Hyundai|Santa Cruz 2022-23[5](#footnotes)|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai N||
+|Hyundai|Santa Fe 2019-20|All|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai D||
+|Hyundai|Santa Fe 2021-22|All|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai L||
+|Hyundai|Santa Fe Hybrid 2022|All|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai L||
+|Hyundai|Santa Fe Plug-in Hybrid 2022|All|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai L||
+|Hyundai|Sonata 2018-19|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai E||
+|Hyundai|Sonata 2020-23|All|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai A||
+|Hyundai|Sonata Hybrid 2020-22|All|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai A||
+|Hyundai|Tucson 2021|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|19 mph|0 mph|[](##)|[](##)|Hyundai L||
+|Hyundai|Tucson 2022[5](#footnotes)|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai N||
+|Hyundai|Tucson 2023[5](#footnotes)|All|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai N||
+|Hyundai|Tucson Diesel 2019|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai L||
+|Hyundai|Tucson Hybrid 2022[5](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai N||
+|Hyundai|Veloster 2019-20|Smart Cruise Control (SCC)|Stock|5 mph|0 mph|[](##)|[](##)|Hyundai E||
+|Jeep|Grand Cherokee 2016-18|Adaptive Cruise Control (ACC)|Stock|0 mph|9 mph|[](##)|[](##)|FCA||
+|Jeep|Grand Cherokee 2019-21|Adaptive Cruise Control (ACC)|Stock|0 mph|39 mph|[](##)|[](##)|FCA||
+|Kia|Ceed 2019|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai E||
+|Kia|EV6 (Southeast Asia only) 2022-23[5](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai P||
+|Kia|EV6 (with HDA II) 2022[5](#footnotes)|Highway Driving Assist II|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai P||
+|Kia|EV6 (without HDA II) 2022[5](#footnotes)|Highway Driving Assist|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai L||
+|Kia|Forte 2019-21|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai G||
+|Kia|K5 2021-22|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai A||
+|Kia|K5 Hybrid 2020|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai A||
+|Kia|Niro EV 2019|All|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai H||
+|Kia|Niro EV 2020|All|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai F||
+|Kia|Niro EV 2021|All|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai C||
+|Kia|Niro EV 2022|All|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai H||
+|Kia|Niro Hybrid 2021|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai F||
+|Kia|Niro Hybrid 2022|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai H||
+|Kia|Niro Hybrid 2023[5](#footnotes)|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai A||
+|Kia|Niro Plug-in Hybrid 2018-19|All|openpilot available[1](#footnotes)|10 mph|32 mph|[](##)|[](##)|Hyundai C||
+|Kia|Niro Plug-in Hybrid 2020|All|openpilot available[1](#footnotes)|0 mph|32 mph|[](##)|[](##)|Hyundai D||
+|Kia|Optima 2017|Advanced Smart Cruise Control|Stock|0 mph|32 mph|[](##)|[](##)|Hyundai B||
+|Kia|Optima 2019-20|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai G||
+|Kia|Seltos 2021|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai A||
+|Kia|Sorento 2018|Advanced Smart Cruise Control|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai C||
+|Kia|Sorento 2019|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai E||
+|Kia|Sorento 2022-23[5](#footnotes)|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai K||
+|Kia|Sorento Plug-in Hybrid 2022-23[5](#footnotes)|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai A||
+|Kia|Sportage 2023[5](#footnotes)|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai N||
+|Kia|Sportage Hybrid 2023[5](#footnotes)|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai N||
+|Kia|Stinger 2018-20|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai C||
+|Kia|Stinger 2022|All|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai K||
+|Kia|Telluride 2020-22|All|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai H||
+|Lexus|CT Hybrid 2017-18|Lexus Safety System+|openpilot available[2](#footnotes)|0 mph|0 mph|[](##)|[](##)|Toyota||
+|Lexus|ES 2019-22|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota||
+|Lexus|ES Hybrid 2017-18|Lexus Safety System+|openpilot available[2](#footnotes)|0 mph|0 mph|[](##)|[](##)|Toyota||
+|Lexus|ES Hybrid 2019-23|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota||
+|Lexus|IS 2017-19|All|Stock|19 mph|0 mph|[](##)|[](##)|Toyota||
+|Lexus|NX 2018-19|All|openpilot available[2](#footnotes)|0 mph|0 mph|[](##)|[](##)|Toyota||
+|Lexus|NX 2020-21|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota||
+|Lexus|NX Hybrid 2018-19|All|openpilot available[2](#footnotes)|0 mph|0 mph|[](##)|[](##)|Toyota||
+|Lexus|NX Hybrid 2020-21|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota||
+|Lexus|RC 2017-20|All|Stock|19 mph|0 mph|[](##)|[](##)|Toyota||
+|Lexus|RX 2016|Lexus Safety System+|openpilot available[2](#footnotes)|0 mph|0 mph|[](##)|[](##)|Toyota||
+|Lexus|RX 2017-19|All|openpilot available[2](#footnotes)|0 mph|0 mph|[](##)|[](##)|Toyota||
+|Lexus|RX 2020-22|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota||
+|Lexus|RX Hybrid 2016|Lexus Safety System+|openpilot available[2](#footnotes)|0 mph|0 mph|[](##)|[](##)|Toyota||
+|Lexus|RX Hybrid 2017-19|All|openpilot available[2](#footnotes)|0 mph|0 mph|[](##)|[](##)|Toyota||
+|Lexus|RX Hybrid 2020-21|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota||
+|Lexus|UX Hybrid 2019-22|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota||
+|MAN|eTGE 2020-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|31 mph|[](##)|[](##)|J533||
+|MAN|TGE 2017-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|31 mph|[](##)|[](##)|J533||
+|Mazda|CX-5 2022-23|All|Stock|0 mph|0 mph|[](##)|[](##)|Mazda||
+|Mazda|CX-9 2021-23|All|Stock|0 mph|28 mph|[](##)|[](##)|Mazda||
+|Nissan|Altima 2019-20|ProPILOT Assist|Stock|0 mph|0 mph|[](##)|[](##)|Nissan B||
+|Nissan|Leaf 2018-22|ProPILOT Assist|Stock|0 mph|0 mph|[](##)|[](##)|Nissan A||
+|Nissan|Rogue 2018-20|ProPILOT Assist|Stock|0 mph|0 mph|[](##)|[](##)|Nissan A||
+|Nissan|X-Trail 2017|ProPILOT Assist|Stock|0 mph|0 mph|[](##)|[](##)|Nissan A||
+|Ram|1500 2019-22|Adaptive Cruise Control (ACC)|Stock|0 mph|32 mph|[](##)|[](##)|Ram||
+|SEAT|Ateca 2018|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533||
+|SEAT|Leon 2014-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533||
+|Subaru|Ascent 2019-21|All|Stock|0 mph|0 mph|[](##)|[](##)|Subaru A||
+|Subaru|Crosstrek 2018-19|EyeSight Driver Assistance|Stock|0 mph|0 mph|[](##)|[](##)|Subaru A||
+|Subaru|Crosstrek 2020-23|EyeSight Driver Assistance|Stock|0 mph|0 mph|[](##)|[](##)|Subaru A||
+|Subaru|Forester 2019-21|All|Stock|0 mph|0 mph|[](##)|[](##)|Subaru A||
+|Subaru|Impreza 2017-19|EyeSight Driver Assistance|Stock|0 mph|0 mph|[](##)|[](##)|Subaru A||
+|Subaru|Impreza 2020-22|EyeSight Driver Assistance|Stock|0 mph|0 mph|[](##)|[](##)|Subaru A||
+|Subaru|Legacy 2020-22|All|Stock|0 mph|0 mph|[](##)|[](##)|Subaru B||
+|Subaru|Outback 2020-22|All|Stock|0 mph|0 mph|[](##)|[](##)|Subaru B||
+|Subaru|XV 2018-19|EyeSight Driver Assistance|Stock|0 mph|0 mph|[](##)|[](##)|Subaru A||
+|Subaru|XV 2020-21|EyeSight Driver Assistance|Stock|0 mph|0 mph|[](##)|[](##)|Subaru A||
+|Škoda|Kamiq 2021[7](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533[10](#footnotes)||
+|Škoda|Karoq 2019-21|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533||
+|Škoda|Kodiaq 2018-19|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533||
+|Škoda|Octavia 2015, 2018-19|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533||
+|Škoda|Octavia RS 2016|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533||
+|Škoda|Scala 2020|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533[10](#footnotes)||
+|Škoda|Superb 2015-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533||
+|Toyota|Alphard 2019-20|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota||
+|Toyota|Alphard Hybrid 2021|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota||
+|Toyota|Avalon 2016|Toyota Safety Sense P|openpilot available[2](#footnotes)|19 mph|0 mph|[](##)|[](##)|Toyota||
+|Toyota|Avalon 2017-18|All|openpilot available[2](#footnotes)|19 mph|0 mph|[](##)|[](##)|Toyota||
+|Toyota|Avalon 2019-21|All|openpilot available[2](#footnotes)|0 mph|0 mph|[](##)|[](##)|Toyota||
+|Toyota|Avalon 2022|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota||
+|Toyota|Avalon Hybrid 2019-21|All|openpilot available[2](#footnotes)|0 mph|0 mph|[](##)|[](##)|Toyota||
+|Toyota|Avalon Hybrid 2022|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota||
+|Toyota|C-HR 2017-20|All|Stock|0 mph|0 mph|[](##)|[](##)|Toyota||
+|Toyota|C-HR 2021|All|Stock|0 mph|0 mph|[](##)|[](##)|Toyota||
+|Toyota|C-HR Hybrid 2017-20|All|Stock|0 mph|0 mph|[](##)|[](##)|Toyota||
+|Toyota|C-HR Hybrid 2021-22|All|Stock|0 mph|0 mph|[](##)|[](##)|Toyota||
+|Toyota|Camry 2018-20|All|Stock|0 mph[6](#footnotes)|0 mph|[](##)|[](##)|Toyota||
+|Toyota|Camry 2021-22|All|openpilot|0 mph[6](#footnotes)|0 mph|[](##)|[](##)|Toyota||
+|Toyota|Camry Hybrid 2018-20|All|Stock|0 mph|0 mph|[](##)|[](##)|Toyota||
+|Toyota|Camry Hybrid 2021-23|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota||
+|Toyota|Corolla 2017-19|All|openpilot available[2](#footnotes)|19 mph|0 mph|[](##)|[](##)|Toyota||
+|Toyota|Corolla 2020-22|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota||
+|Toyota|Corolla Cross (Non-US only) 2020-23|All|openpilot|17 mph|0 mph|[](##)|[](##)|Toyota||
+|Toyota|Corolla Cross Hybrid (Non-US only) 2020-22|All|openpilot|17 mph|0 mph|[](##)|[](##)|Toyota||
+|Toyota|Corolla Hatchback 2019-22|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota||
+|Toyota|Corolla Hybrid 2020-22|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota||
+|Toyota|Corolla Hybrid (Non-US only) 2020-23|All|openpilot|17 mph|0 mph|[](##)|[](##)|Toyota||
+|Toyota|Highlander 2017-19|All|openpilot available[2](#footnotes)|0 mph|0 mph|[](##)|[](##)|Toyota||
+|Toyota|Highlander 2020-23|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota||
+|Toyota|Highlander Hybrid 2017-19|All|openpilot available[2](#footnotes)|0 mph|0 mph|[](##)|[](##)|Toyota||
+|Toyota|Highlander Hybrid 2020-23|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota||
+|Toyota|Mirai 2021|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota||
+|Toyota|Prius 2016|Toyota Safety Sense P|openpilot available[2](#footnotes)|0 mph|0 mph|[](##)|[](##)|Toyota||
+|Toyota|Prius 2017-20|All|openpilot available[2](#footnotes)|0 mph|0 mph|[](##)|[](##)|Toyota||
+|Toyota|Prius 2021-22|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota||
+|Toyota|Prius Prime 2017-20|All|openpilot available[2](#footnotes)|0 mph|0 mph|[](##)|[](##)|Toyota||
+|Toyota|Prius Prime 2021-22|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota||
+|Toyota|Prius v 2017|Toyota Safety Sense P|openpilot available[2](#footnotes)|19 mph|0 mph|[](##)|[](##)|Toyota||
+|Toyota|RAV4 2016|Toyota Safety Sense P|openpilot available[2](#footnotes)|19 mph|0 mph|[](##)|[](##)|Toyota||
+|Toyota|RAV4 2017-18|All|openpilot available[2](#footnotes)|19 mph|0 mph|[](##)|[](##)|Toyota||
+|Toyota|RAV4 2019-21|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota||
+|Toyota|RAV4 2022|All|Stock|0 mph|0 mph|[](##)|[](##)|Toyota||
+|Toyota|RAV4 Hybrid 2016|Toyota Safety Sense P|openpilot available[2](#footnotes)|0 mph|0 mph|[](##)|[](##)|Toyota||
+|Toyota|RAV4 Hybrid 2017-18|All|openpilot available[2](#footnotes)|0 mph|0 mph|[](##)|[](##)|Toyota||
+|Toyota|RAV4 Hybrid 2019-21|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota||
+|Toyota|RAV4 Hybrid 2022|All|Stock|0 mph|0 mph|[](##)|[](##)|Toyota||
+|Toyota|Sienna 2018-20|All|openpilot available[2](#footnotes)|19 mph|0 mph|[](##)|[](##)|Toyota||
+|Volkswagen|Arteon 2018-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533||
+|Volkswagen|Arteon eHybrid 2020-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533||
+|Volkswagen|Arteon R 2020-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533||
+|Volkswagen|Atlas 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533||
+|Volkswagen|Atlas Cross Sport 2021-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533||
+|Volkswagen|California 2021|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|31 mph|[](##)|[](##)|J533||
+|Volkswagen|Caravelle 2020|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|31 mph|[](##)|[](##)|J533||
+|Volkswagen|CC 2018-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533||
+|Volkswagen|Crafter 2017-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|31 mph|[](##)|[](##)|J533||
+|Volkswagen|e-Crafter 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|31 mph|[](##)|[](##)|J533||
+|Volkswagen|e-Golf 2014-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533||
+|Volkswagen|Golf 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533||
+|Volkswagen|Golf Alltrack 2015-19|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533||
+|Volkswagen|Golf GTD 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533||
+|Volkswagen|Golf GTE 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533||
+|Volkswagen|Golf GTI 2015-21|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533||
+|Volkswagen|Golf R 2015-19|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533||
+|Volkswagen|Golf SportsVan 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533||
+|Volkswagen|Grand California 2019-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|31 mph|[](##)|[](##)|J533||
+|Volkswagen|Jetta 2018-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533||
+|Volkswagen|Jetta GLI 2021-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533||
+|Volkswagen|Passat 2015-22[8](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533||
+|Volkswagen|Passat Alltrack 2015-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533||
+|Volkswagen|Passat GTE 2015-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533||
+|Volkswagen|Polo 2020-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533[10](#footnotes)||
+|Volkswagen|Polo GTI 2020-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533[10](#footnotes)||
+|Volkswagen|T-Cross 2021|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533[10](#footnotes)||
+|Volkswagen|T-Roc 2021|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533[10](#footnotes)||
+|Volkswagen|Taos 2022|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533||
+|Volkswagen|Teramont 2018-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533||
+|Volkswagen|Teramont Cross Sport 2021-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533||
+|Volkswagen|Teramont X 2021-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533||
+|Volkswagen|Tiguan 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533||
+|Volkswagen|Touran 2017|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,9](#footnotes)|0 mph|0 mph|[](##)|[](##)|J533||
1Experimental openpilot longitudinal control is available behind a toggle; the toggle is only available in non-release branches such as `devel` or `master-ci`. 2By default, this car will use the stock Adaptive Cruise Control (ACC) for longitudinal control. If the Driver Support Unit (DSU) is disconnected, openpilot ACC will replace stock ACC. NOTE: disconnecting the DSU disables Automatic Emergency Braking (AEB).
-3Requires a community built ASCM harness. NOTE: disconnecting the ASCM disables Automatic Emergency Braking (AEB).
+3Requires a community built ASCM harness. NOTE: disconnecting the ASCM disables Automatic Emergency Braking (AEB). 42019 Honda Civic 1.6L Diesel Sedan does not have ALC below 12mph.
-5Requires a red panda, additional harness box, additional OBD-C cable, USB-A to USB-A cable, and a USB-A to USB-C OTG dongle.
+5Requires a red panda for this CAN FD car. All the hardware needed is sold in the CAN FD kit. 6openpilot operates above 28mph for Camry 4CYL L, 4CYL LE and 4CYL SE which don't have Full-Speed Range Dynamic Radar Cruise Control. 7Not including the China market Kamiq, which is based on the (currently) unsupported PQ34 platform. 8Refers only to the MQB-based European B8 Passat, not the NMS Passat in the USA/China/Mideast markets.
diff --git a/docs/Makefile b/docs/Makefile
index d0aa841c4d..dee660f770 100644
--- a/docs/Makefile
+++ b/docs/Makefile
@@ -41,7 +41,7 @@ clean:
@echo "Building rst files..."
sphinx-apidoc -o "$(DOCSBUILDDIR)" ../ \
- ../xx ../laika_repo ../rednose_repo ../pyextra ../notebooks ../panda_jungle \
+ ../xx ../laika_repo ../rednose_repo ../notebooks ../panda_jungle \
../third_party \
../panda/examples \
../scripts \
diff --git a/docs/assets/icon-youtube.svg b/docs/assets/icon-youtube.svg
new file mode 100644
index 0000000000..4e2c9fdfa9
--- /dev/null
+++ b/docs/assets/icon-youtube.svg
@@ -0,0 +1,12 @@
+
+
\ No newline at end of file
diff --git a/docs/docker/Dockerfile b/docs/docker/Dockerfile
index 0d5883f566..a1cdbbeaf0 100644
--- a/docs/docker/Dockerfile
+++ b/docs/docker/Dockerfile
@@ -11,7 +11,6 @@ WORKDIR ${OPENPILOT_PATH}
COPY SConstruct ${OPENPILOT_PATH}
-COPY ./pyextra ${OPENPILOT_PATH}/pyextra
COPY ./third_party ${OPENPILOT_PATH}/third_party
COPY ./site_scons ${OPENPILOT_PATH}/site_scons
COPY ./laika ${OPENPILOT_PATH}/laika
diff --git a/docs/overview.rst b/docs/overview.rst
index cda51ba3d4..cc4c582155 100644
--- a/docs/overview.rst
+++ b/docs/overview.rst
@@ -77,3 +77,4 @@ tools
Simulator
tools/ssh/README.md
Webcam
+ tools/cabana/README.md
diff --git a/laika_repo b/laika_repo
index e1049cde0a..b740b71c82 160000
--- a/laika_repo
+++ b/laika_repo
@@ -1 +1 @@
-Subproject commit e1049cde0a68f7d4a70b1ebd76befdc0e163ad55
+Subproject commit b740b71c82a748e3520b1599487d9a7aaf728670
diff --git a/launch_chffrplus.sh b/launch_chffrplus.sh
index 911774a4eb..9fe9b1bd15 100755
--- a/launch_chffrplus.sh
+++ b/launch_chffrplus.sh
@@ -74,7 +74,7 @@ function launch {
# handle pythonpath
ln -sfn $(pwd) /data/pythonpath
- export PYTHONPATH="$PWD:$PWD/pyextra"
+ export PYTHONPATH="$PWD"
# hardware specific init
agnos_init
diff --git a/lgtm.yml b/lgtm.yml
deleted file mode 100644
index 6ce9353562..0000000000
--- a/lgtm.yml
+++ /dev/null
@@ -1,19 +0,0 @@
-path_classifiers:
- library:
- - external
- - third_party
- - pyextra
- - tools/lib/mkvparse
-extraction:
- cpp:
- after_prepare:
- - "pip3 install --upgrade --user pkgconfig cython setuptools wheel"
- - "pip3 install --upgrade --user jinja2 pyyaml cython pycapnp numpy sympy tqdm\
- \ cffi logentries zmq scons"
- - "export PATH=/opt/work/.local/bin:$PATH"
- index:
- build_command: "scons"
- javascript:
- index:
- filters:
- - exclude: "*"
diff --git a/mypy.ini b/mypy.ini
index 39b1b007a7..9b6d00d2c4 100644
--- a/mypy.ini
+++ b/mypy.ini
@@ -2,7 +2,7 @@
python_version = 3.8
plugins = numpy.typing.mypy_plugin
files = body, common, docs, scripts, selfdrive, site_scons, system, tools
-exclude = ^(pyextra/)|(cereal/)|(opendbc/)|(panda/)|(laika/)|(laika_repo/)|(rednose/)|(rednose_repo/)|(tinygrad/)|(tinygrad_repo/)|(xx/)
+exclude = ^(cereal/)|(opendbc/)|(panda/)|(laika/)|(laika_repo/)|(rednose/)|(rednose_repo/)|(tinygrad/)|(tinygrad_repo/)|(xx/)
; third-party packages
ignore_missing_imports = True
diff --git a/opendbc b/opendbc
index 4a7ad636ff..510bfc0695 160000
--- a/opendbc
+++ b/opendbc
@@ -1 +1 @@
-Subproject commit 4a7ad636ff806146a93f7ae541e463a7dfa5696d
+Subproject commit 510bfc06954e31257f8d8de17adf92f9a68a1b71
diff --git a/panda b/panda
index 5bd4c1dfd9..78b76e5463 160000
--- a/panda
+++ b/panda
@@ -1 +1 @@
-Subproject commit 5bd4c1dfd91991777ba3a3bd7444165afed3f09b
+Subproject commit 78b76e5463f8bd6077f100d84c44ce6b6b047c27
diff --git a/poetry.lock b/poetry.lock
index f7bc4669a3..91e1b5c826 100644
--- a/poetry.lock
+++ b/poetry.lock
@@ -80,6 +80,14 @@ develop = ["imgaug (>=0.4.0)", "pytest"]
imgaug = ["imgaug (>=0.4.0)"]
tests = ["pytest"]
+[[package]]
+name = "antlr4-python3-runtime"
+version = "4.9.3"
+description = "ANTLR 4.9.3 runtime for Python 3.7"
+category = "dev"
+optional = false
+python-versions = "*"
+
[[package]]
name = "anyio"
version = "3.6.2"
@@ -556,6 +564,34 @@ python-versions = ">=3.7"
[package.dependencies]
colorama = {version = "*", markers = "platform_system == \"Windows\""}
+[[package]]
+name = "click-plugins"
+version = "1.1.1"
+description = "An extension module for click to enable registering CLI commands via setuptools entry-points."
+category = "dev"
+optional = false
+python-versions = "*"
+
+[package.dependencies]
+click = ">=4.0"
+
+[package.extras]
+dev = ["coveralls", "pytest (>=3.6)", "pytest-cov", "wheel"]
+
+[[package]]
+name = "cligj"
+version = "0.7.2"
+description = "Click params for commmand line interfaces to GeoJSON"
+category = "dev"
+optional = false
+python-versions = ">=2.7, !=3.0.*, !=3.1.*, !=3.2.*, <4"
+
+[package.dependencies]
+click = ">=4.0"
+
+[package.extras]
+test = ["pytest-cov"]
+
[[package]]
name = "cloudpickle"
version = "2.2.0"
@@ -951,6 +987,29 @@ python-versions = ">=3.7"
docs = ["furo (>=2022.6.21)", "sphinx (>=5.1.1)", "sphinx-autodoc-typehints (>=1.19.1)"]
testing = ["covdefaults (>=2.2)", "coverage (>=6.4.2)", "pytest (>=7.1.2)", "pytest-cov (>=3)", "pytest-timeout (>=2.1)"]
+[[package]]
+name = "fiona"
+version = "1.9.1"
+description = "Fiona reads and writes spatial data files"
+category = "dev"
+optional = false
+python-versions = ">=3.7"
+
+[package.dependencies]
+attrs = ">=19.2.0"
+certifi = "*"
+click = ">=8.0,<9.0"
+click-plugins = ">=1.0"
+cligj = ">=0.5"
+munch = ">=2.3.2"
+setuptools = "*"
+
+[package.extras]
+all = ["Fiona[calc,s3,test]"]
+calc = ["shapely"]
+s3 = ["boto3 (>=1.3.1)"]
+test = ["Fiona[s3]", "pytest (>=7)", "pytest-cov", "pytz"]
+
[[package]]
name = "flake8"
version = "4.0.1"
@@ -1084,6 +1143,21 @@ python-versions = ">=3.7"
packaging = "*"
SQLAlchemy = ">=1.4"
+[[package]]
+name = "geopandas"
+version = "0.12.2"
+description = "Geographic pandas extensions"
+category = "dev"
+optional = false
+python-versions = ">=3.8"
+
+[package.dependencies]
+fiona = ">=1.8"
+packaging = "*"
+pandas = ">=1.0.0"
+pyproj = ">=2.6.1.post1"
+shapely = ">=1.7"
+
[[package]]
name = "gevent"
version = "22.10.1"
@@ -1352,6 +1426,14 @@ category = "dev"
optional = false
python-versions = "*"
+[[package]]
+name = "ioctl-opt"
+version = "1.2.2"
+description = "Functions to compute fnctl.ioctl's opt argument"
+category = "main"
+optional = false
+python-versions = "*"
+
[[package]]
name = "ipykernel"
version = "6.16.1"
@@ -2309,27 +2391,18 @@ python-versions = ">=3.5"
[[package]]
name = "networkx"
-version = "2.3"
+version = "2.8.8"
description = "Python package for creating and manipulating graphs and networks"
category = "dev"
optional = false
-python-versions = ">=3.5"
-
-[package.dependencies]
-decorator = ">=4.3.0"
+python-versions = ">=3.8"
[package.extras]
-all = ["gdal", "lxml", "matplotlib", "nose", "numpy", "pandas", "pydot", "pygraphviz", "pyyaml", "scipy"]
-gdal = ["gdal"]
-lxml = ["lxml"]
-matplotlib = ["matplotlib"]
-nose = ["nose"]
-numpy = ["numpy"]
-pandas = ["pandas"]
-pydot = ["pydot"]
-pygraphviz = ["pygraphviz"]
-pyyaml = ["pyyaml"]
-scipy = ["scipy"]
+default = ["matplotlib (>=3.4)", "numpy (>=1.19)", "pandas (>=1.3)", "scipy (>=1.8)"]
+developer = ["mypy (>=0.982)", "pre-commit (>=2.20)"]
+doc = ["nb2plots (>=0.6)", "numpydoc (>=1.5)", "pillow (>=9.2)", "pydata-sphinx-theme (>=0.11)", "sphinx (>=5.2)", "sphinx-gallery (>=0.11)", "texext (>=0.6.6)"]
+extra = ["lxml (>=4.6)", "pydot (>=1.4.2)", "pygraphviz (>=1.9)", "sympy (>=1.10)"]
+test = ["codecov (>=2.1)", "pytest (>=7.2)", "pytest-cov (>=4.0)"]
[[package]]
name = "nodeenv"
@@ -2423,6 +2496,18 @@ rsa = ["cryptography (>=3.0.0)"]
signals = ["blinker (>=1.4.0)"]
signedtoken = ["cryptography (>=3.0.0)", "pyjwt (>=2.0.0,<3)"]
+[[package]]
+name = "omegaconf"
+version = "2.3.0"
+description = "A flexible configuration library"
+category = "dev"
+optional = false
+python-versions = ">=3.6"
+
+[package.dependencies]
+antlr4-python3-runtime = ">=4.9.0,<4.10.0"
+PyYAML = ">=5.1.0"
+
[[package]]
name = "onnx"
version = "1.12.0"
@@ -2514,6 +2599,31 @@ python-versions = ">=3.6"
[package.dependencies]
requests = "*"
+[[package]]
+name = "osmnx"
+version = "1.2.2"
+description = "Retrieve, model, analyze, and visualize OpenStreetMap street networks and other spatial data"
+category = "dev"
+optional = false
+python-versions = ">=3.8"
+
+[package.dependencies]
+geopandas = ">=0.11"
+matplotlib = ">=3.5"
+networkx = ">=2.8"
+numpy = ">=1.22"
+pandas = ">=1.4"
+pyproj = ">=3.3"
+requests = ">=2.28"
+Rtree = ">=1.0"
+Shapely = ">=1.8,<2.0"
+
+[package.extras]
+entropy = ["scipy"]
+nearest-neighbor = ["scikit-learn", "scipy"]
+raster = ["gdal", "rasterio"]
+web-map = ["folium"]
+
[[package]]
name = "packaging"
version = "21.3"
@@ -3458,6 +3568,14 @@ python-versions = "*"
numpy = ">=1.11.0"
scipy = ">=0.17.1"
+[[package]]
+name = "rtree"
+version = "1.0.1"
+description = "R-Tree spatial index for Python GIS"
+category = "dev"
+optional = false
+python-versions = ">=3.7"
+
[[package]]
name = "s2sphere"
version = "0.2.5"
@@ -3660,6 +3778,19 @@ typing-extensions = "*"
test = ["pytest (>=6.2)", "virtualenv (>20)"]
toml = ["setuptools (>=42)"]
+[[package]]
+name = "shapely"
+version = "1.8.5.post1"
+description = "Geometric objects, predicates, and operations"
+category = "dev"
+optional = false
+python-versions = ">=3.6"
+
+[package.extras]
+all = ["numpy", "pytest", "pytest-cov"]
+test = ["pytest", "pytest-cov"]
+vectorized = ["numpy"]
+
[[package]]
name = "shellingham"
version = "1.5.0"
@@ -3881,6 +4012,17 @@ category = "main"
optional = false
python-versions = "*"
+[[package]]
+name = "spidev2"
+version = "0.9.0"
+description = "Pure-python interface to Linux spidev."
+category = "main"
+optional = false
+python-versions = "*"
+
+[package.dependencies]
+ioctl-opt = "*"
+
[[package]]
name = "sqlalchemy"
version = "1.4.42"
@@ -4425,7 +4567,7 @@ testing = ["coverage (>=5.0.3)", "zope.event", "zope.testing"]
[metadata]
lock-version = "1.1"
python-versions = "~3.8"
-content-hash = "d894380c87f5558e032708cc1230aed172ad3e1db9aa112e2e105bebefff4e20"
+content-hash = "9e9495c896e6fd0855803aeaf46513c6c22424b86be820759a8baf27d44e73ee"
[metadata.files]
adal = [
@@ -4538,6 +4680,9 @@ albumentations = [
{file = "albumentations-1.3.0-py3-none-any.whl", hash = "sha256:294165d87d03bc8323e484927f0a5c1a3c64b0e7b9c32a979582a6c93c363bdf"},
{file = "albumentations-1.3.0.tar.gz", hash = "sha256:be1af36832c8893314f2a5550e8ac19801e04770734c1b70fa3c996b41f37bed"},
]
+antlr4-python3-runtime = [
+ {file = "antlr4-python3-runtime-4.9.3.tar.gz", hash = "sha256:f224469b4168294902bb1efa80a8bf7855f24c99aef99cbefc1bcd3cce77881b"},
+]
anyio = [
{file = "anyio-3.6.2-py3-none-any.whl", hash = "sha256:fbbe32bd270d2a2ef3ed1c5d45041250284e31fc0a4df4a5a6071842051a51e3"},
{file = "anyio-3.6.2.tar.gz", hash = "sha256:25ea0d673ae30af41a0c442f81cf3b38c7e79fdc7b60335a4c14e05eb0947421"},
@@ -4875,6 +5020,14 @@ click = [
{file = "click-8.1.3-py3-none-any.whl", hash = "sha256:bb4d8133cb15a609f44e8213d9b391b0809795062913b383c62be0ee95b1db48"},
{file = "click-8.1.3.tar.gz", hash = "sha256:7682dc8afb30297001674575ea00d1814d808d6a36af415a82bd481d37ba7b8e"},
]
+click-plugins = [
+ {file = "click-plugins-1.1.1.tar.gz", hash = "sha256:46ab999744a9d831159c3411bb0c79346d94a444df9a3a3742e9ed63645f264b"},
+ {file = "click_plugins-1.1.1-py2.py3-none-any.whl", hash = "sha256:5d262006d3222f5057fd81e1623d4443e41dcda5dc815c06b442aa3c02889fc8"},
+]
+cligj = [
+ {file = "cligj-0.7.2-py3-none-any.whl", hash = "sha256:c1ca117dbce1fe20a5809dc96f01e1c2840f6dcc939b3ddbb1111bf330ba82df"},
+ {file = "cligj-0.7.2.tar.gz", hash = "sha256:a4bc13d623356b373c2c27c53dbd9c68cae5d526270bfa71f6c6fa69669c6b27"},
+]
cloudpickle = [
{file = "cloudpickle-2.2.0-py3-none-any.whl", hash = "sha256:7428798d5926d8fcbfd092d18d01a2a03daf8237d8fcdc8095d256b8490796f0"},
{file = "cloudpickle-2.2.0.tar.gz", hash = "sha256:3f4219469c55453cfe4737e564b67c2a149109dabf7f242478948b895f61106f"},
@@ -5297,6 +5450,28 @@ filelock = [
{file = "filelock-3.8.0-py3-none-any.whl", hash = "sha256:617eb4e5eedc82fc5f47b6d61e4d11cb837c56cb4544e39081099fa17ad109d4"},
{file = "filelock-3.8.0.tar.gz", hash = "sha256:55447caa666f2198c5b6b13a26d2084d26fa5b115c00d065664b2124680c4edc"},
]
+fiona = [
+ {file = "Fiona-1.9.1-cp310-cp310-macosx_10_15_x86_64.whl", hash = "sha256:902b67b2d012c5797b5d7d3cb3b46dcf9a342cf90a7f7e53fb12c83738d19926"},
+ {file = "Fiona-1.9.1-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:e2f4535ae2c8446e6b328745a44567478d5a077ed63c888b8c212dddb1e11925"},
+ {file = "Fiona-1.9.1-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:c3d7f3286fb59b93cefefb89014b6fa8413126e180e15c576db859ba936cf334"},
+ {file = "Fiona-1.9.1-cp310-cp310-win_amd64.whl", hash = "sha256:692fe64c0f3a39742d6f7a8e420a8387f6aec3b6818b727d2dfc98a0c40e992d"},
+ {file = "Fiona-1.9.1-cp311-cp311-macosx_10_15_x86_64.whl", hash = "sha256:a017a39650df0cc541c57cf7de450bb4cee6fd9760eb716323b594c1074634a2"},
+ {file = "Fiona-1.9.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:c3b52d49bc379fdcfd1250b38e7e00ab24ee14eb765376c793bbe251ffd09d6a"},
+ {file = "Fiona-1.9.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:5dbb0ae851cd4417104c469335a01f938251a8639317f93d422c5c808150bd27"},
+ {file = "Fiona-1.9.1-cp311-cp311-win_amd64.whl", hash = "sha256:4a6d8fcbbdafa8af8ac1904628b0267382ed9f9921933d061d7bfc5d3f3daf99"},
+ {file = "Fiona-1.9.1-cp37-cp37m-macosx_10_15_x86_64.whl", hash = "sha256:74f056a84dc52a0b21a2cf024601a69105596f06f28d40b45049948be17b4df2"},
+ {file = "Fiona-1.9.1-cp37-cp37m-manylinux2014_x86_64.whl", hash = "sha256:5b9f3f6c782bb4ae2c924eefd373cabdeaaa99f86477b9c7c71eb20c052ee7c5"},
+ {file = "Fiona-1.9.1-cp37-cp37m-win_amd64.whl", hash = "sha256:5d6183189a7e05e2498d38a1df3ab07e1353fa48e977cbc3a31203927bd06bca"},
+ {file = "Fiona-1.9.1-cp38-cp38-macosx_10_15_x86_64.whl", hash = "sha256:5f2c14beec98a330aee1fd81fa0447a6aa1d5e0a75d000c0052dbe1f23dd6cfd"},
+ {file = "Fiona-1.9.1-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:585a47ec21f2d198abc112158eaf12a6587a272beb7f001162d8c3b262676666"},
+ {file = "Fiona-1.9.1-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:dd4368b4054f21518a19dea54ce9ac445c40418c6331c0c99d1531c3ddff05da"},
+ {file = "Fiona-1.9.1-cp38-cp38-win_amd64.whl", hash = "sha256:839ed0db23198bb754f0d655d4eeaf5f9c141bef734557e77e95e4dc83e42e7f"},
+ {file = "Fiona-1.9.1-cp39-cp39-macosx_10_15_x86_64.whl", hash = "sha256:decca3956032ae2d2c19d2f7fa8a4553c43a6e66eb5abe9a05f6ddadcb1bfe5c"},
+ {file = "Fiona-1.9.1-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:cb827fa0030d03d8080723137c74b865ec18dbade87c02ed60215491a315c6be"},
+ {file = "Fiona-1.9.1-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:d7e0f36484757baa8cd1c0602941e029ff992282776f9afae4c5b90f501ff005"},
+ {file = "Fiona-1.9.1-cp39-cp39-win_amd64.whl", hash = "sha256:f98933b552adf0506799097934a6950de412288e7a50466144d04874d6f63fbc"},
+ {file = "Fiona-1.9.1.tar.gz", hash = "sha256:3a3725e94840a387fef48726d60db6a6791563f366939d22378a4661f8941be7"},
+]
flake8 = [
{file = "flake8-4.0.1-py2.py3-none-any.whl", hash = "sha256:479b1304f72536a55948cb40a32dce8bb0ffe3501e26eaf292c7e60eb5e0428d"},
{file = "flake8-4.0.1.tar.gz", hash = "sha256:806e034dda44114815e23c16ef92f95c91e4c71100ff52813adf7132a6ad870d"},
@@ -5421,6 +5596,10 @@ geoalchemy2 = [
{file = "GeoAlchemy2-0.12.5-py2.py3-none-any.whl", hash = "sha256:3a59eb651df95b3dfee8e1d82f4d18c80b75f712860a0a3080defc6b0435070d"},
{file = "GeoAlchemy2-0.12.5.tar.gz", hash = "sha256:31c2502dce317b57b335e4eb87562d501fa39e46c728be514d9b86091e08dd67"},
]
+geopandas = [
+ {file = "geopandas-0.12.2-py3-none-any.whl", hash = "sha256:0a470e4bf6f5367e6fd83ab6b40405e0b805c8174665bbcb7c4077ed90202912"},
+ {file = "geopandas-0.12.2.tar.gz", hash = "sha256:0acdacddefa176525e4da6d9aeeece225da26055c4becdc6e97cf40fa97c27f4"},
+]
gevent = [
{file = "gevent-22.10.1-cp27-cp27m-win32.whl", hash = "sha256:702a51b8f21bad1976b0893f90ade466e8c27039b846b611ad2beb8c6e6ac701"},
{file = "gevent-22.10.1-cp27-cp27m-win_amd64.whl", hash = "sha256:af7baec79a5f8ad1cc132d3b14edd12661c628d8094e501b089b1fe2d3df7f6e"},
@@ -5624,6 +5803,9 @@ inputs = [
{file = "inputs-0.5-py2.py3-none-any.whl", hash = "sha256:13f894564e52134cf1e3862b1811da034875eb1f2b62e6021e3776e9669a96ec"},
{file = "inputs-0.5.tar.gz", hash = "sha256:a31d5b96a3525f1232f326be9e7ce8ccaf873c6b1fb84d9f3c9bc3d79b23eae4"},
]
+ioctl-opt = [
+ {file = "ioctl-opt-1.2.2.tar.gz", hash = "sha256:9628bbd6728f90d019759f54d20b741ddbf9f8db8d41976da4332492f669d643"},
+]
ipykernel = [
{file = "ipykernel-6.16.1-py3-none-any.whl", hash = "sha256:32eb7bdc5af57185e9a42b0dcef66413ef91a0490b378eae46cbdf0d4e0b5912"},
{file = "ipykernel-6.16.1.tar.gz", hash = "sha256:3a27a550c1d682e7825f0f7732b0142b79ef1b21cd2e713cacac0c9847535f13"},
@@ -6348,7 +6530,8 @@ nest-asyncio = [
{file = "nest_asyncio-1.5.6.tar.gz", hash = "sha256:d267cc1ff794403f7df692964d1d2a3fa9418ffea2a3f6859a439ff482fef290"},
]
networkx = [
- {file = "networkx-2.3.zip", hash = "sha256:8311ddef63cf5c5c5e7c1d0212dd141d9a1fe3f474915281b73597ed5f1d4e3d"},
+ {file = "networkx-2.8.8-py3-none-any.whl", hash = "sha256:e435dfa75b1d7195c7b8378c3859f0445cd88c6b0375c181ed66823a9ceb7524"},
+ {file = "networkx-2.8.8.tar.gz", hash = "sha256:230d388117af870fce5647a3c52401fcf753e94720e6ea6b4197a5355648885e"},
]
nodeenv = [
{file = "nodeenv-1.7.0-py2.py3-none-any.whl", hash = "sha256:27083a7b96a25f2f5e1d8cb4b6317ee8aeda3bdd121394e5ac54e498028a042e"},
@@ -6404,6 +6587,10 @@ oauthlib = [
{file = "oauthlib-3.2.2-py3-none-any.whl", hash = "sha256:8139f29aac13e25d502680e9e19963e83f16838d48a0d71c287fe40e7067fbca"},
{file = "oauthlib-3.2.2.tar.gz", hash = "sha256:9859c40929662bec5d64f34d01c99e093149682a3f38915dc0655d5a633dd918"},
]
+omegaconf = [
+ {file = "omegaconf-2.3.0-py3-none-any.whl", hash = "sha256:7b4df175cdb08ba400f45cae3bdcae7ba8365db4d165fc65fd04b050ab63b46b"},
+ {file = "omegaconf-2.3.0.tar.gz", hash = "sha256:d5d4b6d29955cc50ad50c46dc269bcd92c6e00f5f90d23ab5fee7bfca4ba4cc7"},
+]
onnx = [
{file = "onnx-1.12.0-cp310-cp310-macosx_10_12_x86_64.whl", hash = "sha256:bdbd2578424c70836f4d0f9dda16c21868ddb07cc8192f9e8a176908b43d694b"},
{file = "onnx-1.12.0-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:213e73610173f6b2e99f99a4b0636f80b379c417312079d603806e48ada4ca8b"},
@@ -6429,6 +6616,7 @@ onnx = [
]
onnx2torch = [
{file = "onnx2torch-1.5.4-py3-none-any.whl", hash = "sha256:fd1a0fe05072bfb9f3d86d9330299b130b41f11bd4ae634db17078974e711725"},
+ {file = "onnx2torch-1.5.4.tar.gz", hash = "sha256:df837b557a63540223d85fde4a1d679fde0ca8d8bb89d5379c030b01eddc9c24"},
]
onnxoptimizer = [
{file = "onnxoptimizer-0.3.1-cp37-cp37m-macosx_10_15_x86_64.whl", hash = "sha256:e73a5e2e3ca4db9bff54f7131768749c861677b97ee811a136fcf1a52783cf6e"},
@@ -6471,6 +6659,10 @@ osmium = [
{file = "osmium-3.4.1-cp39-cp39-win_amd64.whl", hash = "sha256:e45b7c54ac756e9cb40e2ba68691df635804eb6aa2023088af66936a9c8e3782"},
{file = "osmium-3.4.1.tar.gz", hash = "sha256:575dad72ab169cf585b9aeefb4f5f99ac250bf7da1986992afcbf169dc70c381"},
]
+osmnx = [
+ {file = "osmnx-1.2.2-py2.py3-none-any.whl", hash = "sha256:94f2a3929e857d8c0da39ae552c6da3b1a3f4bcfea6de108696bda5ee3a7689d"},
+ {file = "osmnx-1.2.2.tar.gz", hash = "sha256:30924452ca02758ece3301f9fcfb1b80edf31e2be7abe7fa7e0fefddb5050408"},
+]
packaging = [
{file = "packaging-21.3-py3-none-any.whl", hash = "sha256:ef103e05f519cdc783ae24ea4e2e0f508a9c99b2d4969652eed6a2e1ea5bd522"},
{file = "packaging-21.3.tar.gz", hash = "sha256:dd47c42927d89ab911e606518907cc2d3a1f38bbd026385970643f9c5b8ecfeb"},
@@ -6810,6 +7002,7 @@ pycryptodome = [
{file = "pycryptodome-3.15.0-cp27-cp27m-manylinux2010_i686.whl", hash = "sha256:7c9ed8aa31c146bef65d89a1b655f5f4eab5e1120f55fc297713c89c9e56ff0b"},
{file = "pycryptodome-3.15.0-cp27-cp27m-manylinux2010_x86_64.whl", hash = "sha256:5099c9ca345b2f252f0c28e96904643153bae9258647585e5e6f649bb7a1844a"},
{file = "pycryptodome-3.15.0-cp27-cp27m-manylinux2014_aarch64.whl", hash = "sha256:2ec709b0a58b539a4f9d33fb8508264c3678d7edb33a68b8906ba914f71e8c13"},
+ {file = "pycryptodome-3.15.0-cp27-cp27m-musllinux_1_1_aarch64.whl", hash = "sha256:2ae53125de5b0d2c95194d957db9bb2681da8c24d0fb0fe3b056de2bcaf5d837"},
{file = "pycryptodome-3.15.0-cp27-cp27m-win32.whl", hash = "sha256:fd2184aae6ee2a944aaa49113e6f5787cdc5e4db1eb8edb1aea914bd75f33a0c"},
{file = "pycryptodome-3.15.0-cp27-cp27m-win_amd64.whl", hash = "sha256:7e3a8f6ee405b3bd1c4da371b93c31f7027944b2bcce0697022801db93120d83"},
{file = "pycryptodome-3.15.0-cp27-cp27mu-manylinux1_i686.whl", hash = "sha256:b9c5b1a1977491533dfd31e01550ee36ae0249d78aae7f632590db833a5012b8"},
@@ -6817,12 +7010,14 @@ pycryptodome = [
{file = "pycryptodome-3.15.0-cp27-cp27mu-manylinux2010_i686.whl", hash = "sha256:2aa55aae81f935a08d5a3c2042eb81741a43e044bd8a81ea7239448ad751f763"},
{file = "pycryptodome-3.15.0-cp27-cp27mu-manylinux2010_x86_64.whl", hash = "sha256:c3640deff4197fa064295aaac10ab49a0d55ef3d6a54ae1499c40d646655c89f"},
{file = "pycryptodome-3.15.0-cp27-cp27mu-manylinux2014_aarch64.whl", hash = "sha256:045d75527241d17e6ef13636d845a12e54660aa82e823b3b3341bcf5af03fa79"},
+ {file = "pycryptodome-3.15.0-cp27-cp27mu-musllinux_1_1_aarch64.whl", hash = "sha256:eb6fce570869e70cc8ebe68eaa1c26bed56d40ad0f93431ee61d400525433c54"},
{file = "pycryptodome-3.15.0-cp35-abi3-macosx_10_9_x86_64.whl", hash = "sha256:9ee40e2168f1348ae476676a2e938ca80a2f57b14a249d8fe0d3cdf803e5a676"},
{file = "pycryptodome-3.15.0-cp35-abi3-manylinux1_i686.whl", hash = "sha256:4c3ccad74eeb7b001f3538643c4225eac398c77d617ebb3e57571a897943c667"},
{file = "pycryptodome-3.15.0-cp35-abi3-manylinux1_x86_64.whl", hash = "sha256:1b22bcd9ec55e9c74927f6b1f69843cb256fb5a465088ce62837f793d9ffea88"},
{file = "pycryptodome-3.15.0-cp35-abi3-manylinux2010_i686.whl", hash = "sha256:57f565acd2f0cf6fb3e1ba553d0cb1f33405ec1f9c5ded9b9a0a5320f2c0bd3d"},
{file = "pycryptodome-3.15.0-cp35-abi3-manylinux2010_x86_64.whl", hash = "sha256:4b52cb18b0ad46087caeb37a15e08040f3b4c2d444d58371b6f5d786d95534c2"},
{file = "pycryptodome-3.15.0-cp35-abi3-manylinux2014_aarch64.whl", hash = "sha256:092a26e78b73f2530b8bd6b3898e7453ab2f36e42fd85097d705d6aba2ec3e5e"},
+ {file = "pycryptodome-3.15.0-cp35-abi3-musllinux_1_1_aarch64.whl", hash = "sha256:50ca7e587b8e541eb6c192acf92449d95377d1f88908c0a32ac5ac2703ebe28b"},
{file = "pycryptodome-3.15.0-cp35-abi3-win32.whl", hash = "sha256:e244ab85c422260de91cda6379e8e986405b4f13dc97d2876497178707f87fc1"},
{file = "pycryptodome-3.15.0-cp35-abi3-win_amd64.whl", hash = "sha256:c77126899c4b9c9827ddf50565e93955cb3996813c18900c16b2ea0474e130e9"},
{file = "pycryptodome-3.15.0-pp27-pypy_73-macosx_10_9_x86_64.whl", hash = "sha256:9eaadc058106344a566dc51d3d3a758ab07f8edde013712bc8d22032a86b264f"},
@@ -7309,6 +7504,53 @@ requests-toolbelt = [
reverse-geocoder = [
{file = "reverse_geocoder-1.5.1.tar.gz", hash = "sha256:2a2e781b5f69376d922b78fe8978f1350c84fce0ddb07e02c834ecf98b57c75c"},
]
+rtree = [
+ {file = "Rtree-1.0.1-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:9855b8f11cdad99c56eb361b7b632a4fbd3d8cbe3f2081426b445f0cfb7fdca9"},
+ {file = "Rtree-1.0.1-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:18ce7e4d04b85c48f2d364835620b3b20e38e199639746e7b12f07a2303e18ff"},
+ {file = "Rtree-1.0.1-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:784efa6b7be9e99b33613ae8495931032689441eabb6120c9b3eb91188c33794"},
+ {file = "Rtree-1.0.1-cp310-cp310-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:157207191aebdacbbdbb369e698cfbfebce53bc97114e96c8af5bed3126475f1"},
+ {file = "Rtree-1.0.1-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:c5fb3671a8d440c24b1dd29ec621d4345ced7185e26f02abe98e85a6629fcb50"},
+ {file = "Rtree-1.0.1-cp310-cp310-musllinux_1_1_aarch64.whl", hash = "sha256:11d16f51cf9205cd6995af36e24efe8f184270f667fb49bb69b09fc46b97e7d4"},
+ {file = "Rtree-1.0.1-cp310-cp310-musllinux_1_1_i686.whl", hash = "sha256:6db6a0a93e41594ffc14b053f386dd414ab5a82535bbd9aedafa6ac8dc0650d8"},
+ {file = "Rtree-1.0.1-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:c6e29e5eb3083ad12ac5c1ce6e37465ea3428d894d3466cc9c9e2ee4bf768e53"},
+ {file = "Rtree-1.0.1-cp310-cp310-win_amd64.whl", hash = "sha256:656b148589c0b5bab4a7db4d033634329f42a5feaac10ca40aceeca109d83c1f"},
+ {file = "Rtree-1.0.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:7b2c15f9373ba314c83a8df5cb6d99b4e3af23c376c6b1317add995432dd0970"},
+ {file = "Rtree-1.0.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:93c5e0bf31e76b4f92a6eec3d2891e938408774c75a8ed6ac3d2c8db04a2be33"},
+ {file = "Rtree-1.0.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:6792de0e3c2fd3ad7e069445027603bec7a47000432f49c80246886311f4f152"},
+ {file = "Rtree-1.0.1-cp311-cp311-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:004e131b570dc360a49e7f3b60e7bc6517943a54df056587964d1cb903889e7e"},
+ {file = "Rtree-1.0.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:becd711fe97c2e09b1b7969e83080a3c8012bce2d30f6db879aade255fcba5c1"},
+ {file = "Rtree-1.0.1-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:015df09e1bc55ddf7c88799bf1515d058cd0ee78eacf4cd443a32876d3b3a863"},
+ {file = "Rtree-1.0.1-cp311-cp311-musllinux_1_1_i686.whl", hash = "sha256:c2973b76f61669a85e160b4ad09879c4089fc0e3f20fd99adf161ca298fe8374"},
+ {file = "Rtree-1.0.1-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:e4335e131a58952635560a003458011d97f9ea6f3c010dc24906050b42ee2c03"},
+ {file = "Rtree-1.0.1-cp311-cp311-win_amd64.whl", hash = "sha256:e7ca5d743f6a1dc62653dfac8ee7ce2e1ba91be7cf97916a7f60b7cbe48fb48d"},
+ {file = "Rtree-1.0.1-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:2ee7165e9872a026ccb868c021711eba39cedf7d1820763c9de52d5324691a92"},
+ {file = "Rtree-1.0.1-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:8de99f28af0f1783eefb80918959903b4b18112f6a12b48f296ecb162804e69d"},
+ {file = "Rtree-1.0.1-cp37-cp37m-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:1a94e2f4bf74bd202ea8b67ea3d7c71e763ad41f79be1d6b72aa2c8d5a8e92c4"},
+ {file = "Rtree-1.0.1-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f5120da3a1b96f3a7a17dd6af0afdd4e6f3cc9baa87e9ee0a272882f01f980bb"},
+ {file = "Rtree-1.0.1-cp37-cp37m-musllinux_1_1_aarch64.whl", hash = "sha256:7e3d5f0e7b28250afbb290ab88b49aa0f121c9714d0da2080581783690347507"},
+ {file = "Rtree-1.0.1-cp37-cp37m-musllinux_1_1_i686.whl", hash = "sha256:296203e933b6ec0dd07f6a7456c4f1492def95b6993f20cc61c92b0fee0aecc5"},
+ {file = "Rtree-1.0.1-cp37-cp37m-musllinux_1_1_x86_64.whl", hash = "sha256:77908cd7acdd519a731979ebf5baff8afd102109c2f52864c1e6ee75d3ea2d87"},
+ {file = "Rtree-1.0.1-cp37-cp37m-win_amd64.whl", hash = "sha256:1a213e5d385278ca7668bc5b27083f8d6e39996a9bd59b6528f3a30009dae4ed"},
+ {file = "Rtree-1.0.1-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:cfa8cffec5cb9fed494c4bb335ebdb69b3c26178b0b685f67f79296c6b3d800c"},
+ {file = "Rtree-1.0.1-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:b31fd22d214160859d038da7cb2aaa27acb71efc24a7bcc75c84b5e502721549"},
+ {file = "Rtree-1.0.1-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:0d68a81ad419d5c2ea5fecc677e6c178666c057e2c7b24100a6c48392196f1e9"},
+ {file = "Rtree-1.0.1-cp38-cp38-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:62f38020af47b765adc6b0bc7c4e810c6c3d1eab44ba339b592ff25a4c0dc0a7"},
+ {file = "Rtree-1.0.1-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:50b658a6707f215a0056d52e9f83a97148c0af62dea07cf29b3789a2c429e78a"},
+ {file = "Rtree-1.0.1-cp38-cp38-musllinux_1_1_aarch64.whl", hash = "sha256:3573cbb0de872f54d0a0c29596a84e8ac3939c47ca3bece4a82e92775730a0d0"},
+ {file = "Rtree-1.0.1-cp38-cp38-musllinux_1_1_i686.whl", hash = "sha256:d5abe5a19d943a88bea14901970e4c53e4579fc2662404cdea6163bf4c04d49a"},
+ {file = "Rtree-1.0.1-cp38-cp38-musllinux_1_1_x86_64.whl", hash = "sha256:1e894112cef4de6c518bdea0b43eada65f12888c3645cc437c3a677aa023039f"},
+ {file = "Rtree-1.0.1-cp38-cp38-win_amd64.whl", hash = "sha256:582854252b8fd5c8472478af060635434931fb55edd269bac128cbf2eef43620"},
+ {file = "Rtree-1.0.1-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:b54057e8a8ad92c1d8e9eaa5cf32aad70dde454abbf9b638e9d6024520a52c02"},
+ {file = "Rtree-1.0.1-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:698de8ce6c62e159d93b35bacf64bcf3619077b5367bc88cd2cff5e0bc36169b"},
+ {file = "Rtree-1.0.1-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:273ee61783de3a1664e5f868feebf5eea4629447137751bfa4087b0f82093082"},
+ {file = "Rtree-1.0.1-cp39-cp39-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:16900ee02cf5c198a42b03635268a80f606aa102f3f7618b89f75023d406da1c"},
+ {file = "Rtree-1.0.1-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:6ce4a6fdb63254a4c1efebe7a4f7a59b1c333c703bde4ae715d9ad88c833e10b"},
+ {file = "Rtree-1.0.1-cp39-cp39-musllinux_1_1_aarch64.whl", hash = "sha256:5b20f69e040a05503b22297af223f336fe7047909b57e4b207b98292f33a229f"},
+ {file = "Rtree-1.0.1-cp39-cp39-musllinux_1_1_i686.whl", hash = "sha256:57128293dd625cb1f07726f32208097953e8854d70ab1fc55d6858733618b9ed"},
+ {file = "Rtree-1.0.1-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:e898d7409ab645c25e06d4e058f99271182601d70b2887aba3351bf08e09a0c6"},
+ {file = "Rtree-1.0.1-cp39-cp39-win_amd64.whl", hash = "sha256:ad9912faeddb1ddcec5e26b33089166d58a107af6862d8b7f1bb2b7c0002ab39"},
+ {file = "Rtree-1.0.1.tar.gz", hash = "sha256:222121699c303a64065d849bf7038b1ecabc37b65c7fa340bedb38ef0e805429"},
+]
s2sphere = [
{file = "s2sphere-0.2.5-py2.py3-none-any.whl", hash = "sha256:d2340c9cf458ddc9a89afd1d8048a4195ce6fa6b0095ab900d4be5271e537401"},
{file = "s2sphere-0.2.5.tar.gz", hash = "sha256:c2478c1ff7c601a59a7151a57b605435897514578fa6bdb8730721c182adbbaf"},
@@ -7417,6 +7659,18 @@ setproctitle = [
{file = "setproctitle-1.3.2-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:7f2719a398e1a2c01c2a63bf30377a34d0b6ef61946ab9cf4d550733af8f1ef1"},
{file = "setproctitle-1.3.2-cp310-cp310-win32.whl", hash = "sha256:e425be62524dc0c593985da794ee73eb8a17abb10fe692ee43bb39e201d7a099"},
{file = "setproctitle-1.3.2-cp310-cp310-win_amd64.whl", hash = "sha256:e85e50b9c67854f89635a86247412f3ad66b132a4d8534ac017547197c88f27d"},
+ {file = "setproctitle-1.3.2-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:2a97d51c17d438cf5be284775a322d57b7ca9505bb7e118c28b1824ecaf8aeaa"},
+ {file = "setproctitle-1.3.2-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:587c7d6780109fbd8a627758063d08ab0421377c0853780e5c356873cdf0f077"},
+ {file = "setproctitle-1.3.2-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d7d17c8bd073cbf8d141993db45145a70b307385b69171d6b54bcf23e5d644de"},
+ {file = "setproctitle-1.3.2-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:e932089c35a396dc31a5a1fc49889dd559548d14cb2237adae260382a090382e"},
+ {file = "setproctitle-1.3.2-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:8e4f8f12258a8739c565292a551c3db62cca4ed4f6b6126664e2381acb4931bf"},
+ {file = "setproctitle-1.3.2-cp311-cp311-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:570d255fd99c7f14d8f91363c3ea96bd54f8742275796bca67e1414aeca7d8c3"},
+ {file = "setproctitle-1.3.2-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:a8e0881568c5e6beff91ef73c0ec8ac2a9d3ecc9edd6bd83c31ca34f770910c4"},
+ {file = "setproctitle-1.3.2-cp311-cp311-musllinux_1_1_i686.whl", hash = "sha256:4bba3be4c1fabf170595b71f3af46c6d482fbe7d9e0563999b49999a31876f77"},
+ {file = "setproctitle-1.3.2-cp311-cp311-musllinux_1_1_ppc64le.whl", hash = "sha256:37ece938110cab2bb3957e3910af8152ca15f2b6efdf4f2612e3f6b7e5459b80"},
+ {file = "setproctitle-1.3.2-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:db684d6bbb735a80bcbc3737856385b55d53f8a44ce9b46e9a5682c5133a9bf7"},
+ {file = "setproctitle-1.3.2-cp311-cp311-win32.whl", hash = "sha256:ca58cd260ea02759238d994cfae844fc8b1e206c684beb8f38877dcab8451dfc"},
+ {file = "setproctitle-1.3.2-cp311-cp311-win_amd64.whl", hash = "sha256:88486e6cce2a18a033013d17b30a594f1c5cb42520c49c19e6ade40b864bb7ff"},
{file = "setproctitle-1.3.2-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:92c626edc66169a1b09e9541b9c0c9f10488447d8a2b1d87c8f0672e771bc927"},
{file = "setproctitle-1.3.2-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:710e16fa3bade3b026907e4a5e841124983620046166f355bbb84be364bf2a02"},
{file = "setproctitle-1.3.2-cp37-cp37m-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:1f29b75e86260b0ab59adb12661ef9f113d2f93a59951373eb6d68a852b13e83"},
@@ -7474,6 +7728,50 @@ setuptools-scm = [
{file = "setuptools_scm-7.0.5-py3-none-any.whl", hash = "sha256:7930f720905e03ccd1e1d821db521bff7ec2ac9cf0ceb6552dd73d24a45d3b02"},
{file = "setuptools_scm-7.0.5.tar.gz", hash = "sha256:031e13af771d6f892b941adb6ea04545bbf91ebc5ce68c78aaf3fff6e1fb4844"},
]
+shapely = [
+ {file = "Shapely-1.8.5.post1-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:d048f93e42ba578b82758c15d8ae037d08e69d91d9872bca5a1895b118f4e2b0"},
+ {file = "Shapely-1.8.5.post1-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:99ab0ddc05e44acabdbe657c599fdb9b2d82e86c5493bdae216c0c4018a82dee"},
+ {file = "Shapely-1.8.5.post1-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:99a2f0da0109e81e0c101a2b4cd8412f73f5f299e7b5b2deaf64cd2a100ac118"},
+ {file = "Shapely-1.8.5.post1-cp310-cp310-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:6fe855e7d45685926b6ba00aaeb5eba5862611f7465775dacd527e081a8ced6d"},
+ {file = "Shapely-1.8.5.post1-cp310-cp310-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:ec14ceca36f67cb48b34d02d7f65a9acae15cd72b48e303531893ba4a960f3ea"},
+ {file = "Shapely-1.8.5.post1-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d8a2b2a65fa7f97115c1cd989fe9d6f39281ca2a8a014f1d4904c1a6e34d7f25"},
+ {file = "Shapely-1.8.5.post1-cp310-cp310-win32.whl", hash = "sha256:21776184516a16bf82a0c3d6d6a312b3cd15a4cabafc61ee01cf2714a82e8396"},
+ {file = "Shapely-1.8.5.post1-cp310-cp310-win_amd64.whl", hash = "sha256:a354199219c8d836f280b88f2c5102c81bb044ccea45bd361dc38a79f3873714"},
+ {file = "Shapely-1.8.5.post1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:783bad5f48e2708a0e2f695a34ed382e4162c795cb2f0368b39528ac1d6db7ed"},
+ {file = "Shapely-1.8.5.post1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:a23ef3882d6aa203dd3623a3d55d698f59bfbd9f8a3bfed52c2da05a7f0f8640"},
+ {file = "Shapely-1.8.5.post1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:ab38f7b5196ace05725e407cb8cab9ff66edb8e6f7bb36a398e8f73f52a7aaa2"},
+ {file = "Shapely-1.8.5.post1-cp311-cp311-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:8d086591f744be483b34628b391d741e46f2645fe37594319e0a673cc2c26bcf"},
+ {file = "Shapely-1.8.5.post1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4728666fff8cccc65a07448cae72c75a8773fea061c3f4f139c44adc429b18c3"},
+ {file = "Shapely-1.8.5.post1-cp311-cp311-win32.whl", hash = "sha256:84010db15eb364a52b74ea8804ef92a6a930dfc1981d17a369444b6ddec66efd"},
+ {file = "Shapely-1.8.5.post1-cp311-cp311-win_amd64.whl", hash = "sha256:48dcfffb9e225c0481120f4bdf622131c8c95f342b00b158cdbe220edbbe20b6"},
+ {file = "Shapely-1.8.5.post1-cp36-cp36m-macosx_10_9_x86_64.whl", hash = "sha256:2fd15397638df291c427a53d641d3e6fd60458128029c8c4f487190473a69a91"},
+ {file = "Shapely-1.8.5.post1-cp36-cp36m-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:a74631e511153366c6dbe3229fa93f877e3c87ea8369cd00f1d38c76b0ed9ace"},
+ {file = "Shapely-1.8.5.post1-cp36-cp36m-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:66bdac74fbd1d3458fa787191a90fa0ae610f09e2a5ec398c36f968cc0ed743f"},
+ {file = "Shapely-1.8.5.post1-cp36-cp36m-win32.whl", hash = "sha256:6d388c0c1bd878ed1af4583695690aa52234b02ed35f93a1c8486ff52a555838"},
+ {file = "Shapely-1.8.5.post1-cp36-cp36m-win_amd64.whl", hash = "sha256:be9423d5a3577ac2e92c7e758bd8a2b205f5e51a012177a590bc46fc51eb4834"},
+ {file = "Shapely-1.8.5.post1-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:5d7f85c2d35d39ff53c9216bc76b7641c52326f7e09aaad1789a3611a0f812f2"},
+ {file = "Shapely-1.8.5.post1-cp37-cp37m-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:adcf8a11b98af9375e32bff91de184f33a68dc48b9cb9becad4f132fa25cfa3c"},
+ {file = "Shapely-1.8.5.post1-cp37-cp37m-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:753ed0e21ab108bd4282405b9b659f2e985e8502b1a72b978eaa51d3496dee19"},
+ {file = "Shapely-1.8.5.post1-cp37-cp37m-win32.whl", hash = "sha256:65b21243d8f6bcd421210daf1fabb9de84de2c04353c5b026173b88d17c1a581"},
+ {file = "Shapely-1.8.5.post1-cp37-cp37m-win_amd64.whl", hash = "sha256:370b574c78dc5af3a198a6da5d9b3d7c04654bd2ef7e80e80a3a0992dfb2d9cd"},
+ {file = "Shapely-1.8.5.post1-cp38-cp38-macosx_10_9_universal2.whl", hash = "sha256:532a55ee2a6c52d23d6f7d1567c8f0473635f3b270262c44e1b0c88096827e22"},
+ {file = "Shapely-1.8.5.post1-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:3480657460e939f45a7d359ef0e172a081f249312557fe9aa78c4fd3a362d993"},
+ {file = "Shapely-1.8.5.post1-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:b65f5d530ba91e49ffc7c589255e878d2506a8b96ffce69d3b7c4500a9a9eaf8"},
+ {file = "Shapely-1.8.5.post1-cp38-cp38-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:147066da0be41b147a61f8eb805dea3b13709dbc873a431ccd7306e24d712bc0"},
+ {file = "Shapely-1.8.5.post1-cp38-cp38-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:c2822111ddc5bcfb116e6c663e403579d0fe3f147d2a97426011a191c43a7458"},
+ {file = "Shapely-1.8.5.post1-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:4b47bb6f9369e8bf3e6dbd33e6a25a47ee02b2874792a529fe04a49bf8bc0df6"},
+ {file = "Shapely-1.8.5.post1-cp38-cp38-win32.whl", hash = "sha256:2e0a8c2e55f1be1312b51c92b06462ea89e6bb703fab4b114e7a846d941cfc40"},
+ {file = "Shapely-1.8.5.post1-cp38-cp38-win_amd64.whl", hash = "sha256:0d885cb0cf670c1c834df3f371de8726efdf711f18e2a75da5cfa82843a7ab65"},
+ {file = "Shapely-1.8.5.post1-cp39-cp39-macosx_10_9_universal2.whl", hash = "sha256:0b4ee3132ee90f07d63db3aea316c4c065ed7a26231458dda0874414a09d6ba3"},
+ {file = "Shapely-1.8.5.post1-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:02dd5d7dc6e46515d88874134dc8fcdc65826bca93c3eecee59d1910c42c1b17"},
+ {file = "Shapely-1.8.5.post1-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:c6a9a4a31cd6e86d0fbe8473ceed83d4fe760b19d949fb557ef668defafea0f6"},
+ {file = "Shapely-1.8.5.post1-cp39-cp39-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:38f0fbbcb8ca20c16451c966c1f527cc43968e121c8a048af19ed3e339a921cd"},
+ {file = "Shapely-1.8.5.post1-cp39-cp39-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:78fb9d929b8ee15cfd424b6c10879ce1907f24e05fb83310fc47d2cd27088e40"},
+ {file = "Shapely-1.8.5.post1-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:89164e7a9776a19e29f01369a98529321994e2e4d852b92b7e01d4d9804c55bf"},
+ {file = "Shapely-1.8.5.post1-cp39-cp39-win32.whl", hash = "sha256:8e59817b0fe63d34baedaabba8c393c0090f061917d18fc0bcc2f621937a8f73"},
+ {file = "Shapely-1.8.5.post1-cp39-cp39-win_amd64.whl", hash = "sha256:e9c30b311de2513555ab02464ebb76115d242842b29c412f5a9aa0cac57be9f6"},
+ {file = "Shapely-1.8.5.post1.tar.gz", hash = "sha256:ef3be705c3eac282a28058e6c6e5503419b250f482320df2172abcbea642c831"},
+]
shellingham = [
{file = "shellingham-1.5.0-py2.py3-none-any.whl", hash = "sha256:a8f02ba61b69baaa13facdba62908ca8690a94b8119b69f5ec5873ea85f7391b"},
{file = "shellingham-1.5.0.tar.gz", hash = "sha256:72fb7f5c63103ca2cb91b23dee0c71fe8ad6fbfd46418ef17dbe40db51592dad"},
@@ -7611,6 +7909,9 @@ spidev = [
{file = "spidev-3.6-cp39-cp39-linux_armv7l.whl", hash = "sha256:280abc00a1ef7780ef62c3f294f52a2527b6c47d8c269fea98664970bcaf6da5"},
{file = "spidev-3.6.tar.gz", hash = "sha256:14dbc37594a4aaef85403ab617985d3c3ef464d62bc9b769ef552db53701115b"},
]
+spidev2 = [
+ {file = "spidev2-0.9.0.tar.gz", hash = "sha256:152da2911a8660283ceac3a75dd869953379bcbcf079e5436af5aae736876086"},
+]
sqlalchemy = [
{file = "SQLAlchemy-1.4.42-cp27-cp27m-macosx_10_14_x86_64.whl", hash = "sha256:28e881266a172a4d3c5929182fde6bb6fba22ac93f137d5380cc78a11a9dd124"},
{file = "SQLAlchemy-1.4.42-cp27-cp27m-manylinux_2_5_x86_64.manylinux1_x86_64.whl", hash = "sha256:ca9389a00f639383c93ed00333ed763812f80b5ae9e772ea32f627043f8c9c88"},
diff --git a/pyproject.toml b/pyproject.toml
index e99b278341..6b4b0bb5fa 100644
--- a/pyproject.toml
+++ b/pyproject.toml
@@ -51,6 +51,7 @@ six = "^1.16.0"
smbus2 = "^0.4.2"
sounddevice = "^0.4.5"
spidev = { version = "^3.6", platform = "linux" }
+spidev2 = { version = "^0.9.0", platform = "linux" }
sympy = "^1.10.1"
timezonefinder = "^6.0.1"
tqdm = "^4.64.0"
@@ -144,7 +145,7 @@ jupyterlab = "^3.4.4"
jupyterlab-vim = "^0.15.1"
Markdown = "^3.4.1"
msgpack-python = "^0.5.6"
-networkx = "~2.3"
+networkx = "~2.8"
nvidia-ml-py3 = "^7.352.0"
onnx2torch = "^1.5.4"
onnxoptimizer = "^0.3.1"
@@ -170,6 +171,8 @@ torchvision = { url = "https://download.pytorch.org/whl/cu113/torchvision-0.12.0
triton = "^1.1.1"
Werkzeug = "^2.1.2"
zerorpc = { git = "https://github.com/commaai/zerorpc-python.git", branch = "master" }
+omegaconf = "^2.3.0"
+osmnx = "==1.2.2"
[build-system]
diff --git a/release/build_release.sh b/release/build_release.sh
index 80106eefb2..60f81fce06 100755
--- a/release/build_release.sh
+++ b/release/build_release.sh
@@ -11,15 +11,19 @@ SOURCE_DIR="$(git rev-parse --show-toplevel)"
if [ -f /TICI ]; then
FILES_SRC="release/files_tici"
- RELEASE_BRANCH=release3-staging
- DASHCAM_BRANCH=dashcam3-staging
else
- exit 0
+ echo "no release files set"
+ exit 1
+fi
+
+if [ -z "$RELEASE_BRANCH" ]; then
+ echo "RELEASE_BRANCH is not set"
+ exit 1
fi
+
# set git identity
source $DIR/identity.sh
-export GIT_SSH_COMMAND="ssh -i /data/gitkey"
echo "[-] Setting up repo T=$SECONDS"
rm -rf $BUILD_DIR
@@ -27,7 +31,6 @@ mkdir -p $BUILD_DIR
cd $BUILD_DIR
git init
git remote add origin git@github.com:commaai/openpilot.git
-git fetch origin $RELEASE_BRANCH
git checkout --orphan $RELEASE_BRANCH
# do the files copy
@@ -48,7 +51,6 @@ echo "#define COMMA_VERSION \"$VERSION-release\"" > common/version.h
echo "[-] committing version $VERSION T=$SECONDS"
git add -f .
git commit -a -m "openpilot v$VERSION release"
-git branch --set-upstream-to=origin/$RELEASE_BRANCH
# Build panda firmware
pushd panda/
@@ -105,10 +107,12 @@ RELEASE=1 selfdrive/test/test_onroad.py
selfdrive/car/tests/test_car_interfaces.py
rm -rf $TEST_FILES
-if [ ! -z "$PUSH" ]; then
- echo "[-] pushing T=$SECONDS"
- git push -f origin $RELEASE_BRANCH
+if [ ! -z "$RELEASE_BRANCH" ]; then
+ echo "[-] pushing release T=$SECONDS"
+ git push -f origin $RELEASE_BRANCH:$RELEASE_BRANCH
+fi
+if [ ! -z "$DASHCAM_BRANCH" ]; then
# Create dashcam
git rm selfdrive/car/*/carcontroller.py
git commit -m "create dashcam release from release"
diff --git a/release/check-submodules.sh b/release/check-submodules.sh
index 182042e6b4..5f4e307e49 100755
--- a/release/check-submodules.sh
+++ b/release/check-submodules.sh
@@ -1,7 +1,7 @@
#!/bin/bash
while read hash submodule ref; do
- git -C $submodule fetch --depth 100 origin master
+ git -C $submodule fetch --depth 1000 origin master
git -C $submodule branch -r --contains $hash | grep "origin/master"
if [ "$?" -eq 0 ]; then
echo "$submodule ok"
diff --git a/release/files_common b/release/files_common
index 2d9be1ee41..7f746959c8 100644
--- a/release/files_common
+++ b/release/files_common
@@ -195,8 +195,6 @@ selfdrive/controls/lib/pid.py
selfdrive/controls/lib/radar_helpers.py
selfdrive/controls/lib/vehicle_model.py
-selfdrive/controls/lib/cluster/*
-
selfdrive/controls/lib/lateral_mpc_lib/.gitignore
selfdrive/controls/lib/longitudinal_mpc_lib/.gitignore
selfdrive/controls/lib/lateral_mpc_lib/*
@@ -230,13 +228,9 @@ selfdrive/locationd/SConscript
selfdrive/locationd/ubloxd.cc
selfdrive/locationd/ublox_msg.cc
selfdrive/locationd/ublox_msg.h
-selfdrive/locationd/generated/ubx.cpp
-selfdrive/locationd/generated/ubx.h
-selfdrive/locationd/generated/gps.cpp
-selfdrive/locationd/generated/gps.h
+selfdrive/locationd/generated/*
selfdrive/locationd/laikad.py
-selfdrive/locationd/laikad_helpers.py
selfdrive/locationd/locationd.h
selfdrive/locationd/locationd.cc
selfdrive/locationd/paramsd.py
@@ -286,7 +280,6 @@ selfdrive/loggerd/deleter.py
selfdrive/loggerd/xattr_cache.py
selfdrive/sensord/SConscript
-selfdrive/sensord/libdiag.h
selfdrive/sensord/sensors_qcom2.cc
selfdrive/sensord/sensors/*.cc
selfdrive/sensord/sensors/*.h
@@ -327,12 +320,17 @@ selfdrive/ui/qt/widgets/*.cc
selfdrive/ui/qt/widgets/*.h
selfdrive/ui/qt/maps/*.cc
selfdrive/ui/qt/maps/*.h
+selfdrive/ui/qt/setup/*.cc
+selfdrive/ui/qt/setup/*.h
+
+selfdrive/ui/installer/*.cc
+selfdrive/ui/installer/*.h
+selfdrive/ui/installer/*.cc
system/camerad/SConscript
system/camerad/main.cc
system/camerad/snapshot/*
-system/camerad/include/*
system/camerad/cameras/camera_common.h
system/camerad/cameras/camera_common.cc
system/camerad/cameras/sensor2_i2c.h
@@ -388,7 +386,6 @@ selfdrive/modeld/thneed/thneed.h
selfdrive/modeld/thneed/thneed_common.cc
selfdrive/modeld/thneed/thneed_qcom2.cc
selfdrive/modeld/thneed/serialize.cc
-selfdrive/modeld/thneed/include/*
selfdrive/modeld/runners/snpemodel.cc
selfdrive/modeld/runners/snpemodel.h
@@ -416,8 +413,11 @@ selfdrive/assets/offroad/*
selfdrive/assets/sounds/*
selfdrive/assets/training/*
+third_party/.gitignore
third_party/SConscript
+third_party/cluster/*
+
third_party/linux/**
third_party/opencl/**
@@ -440,15 +440,14 @@ third_party/snpe/dsp**
third_party/acados/x86_64/**
third_party/acados/larch64/**
third_party/acados/include/**
+third_party/acados/acados_template/**
+third_party/bootstrap/**
third_party/qt5/larch64/bin/**
scripts/update_now.sh
scripts/stop_updater.sh
-pyextra/.gitignore
-pyextra/acados_template/**
-
rednose/.gitignore
rednose/**
laika/**
@@ -581,17 +580,13 @@ opendbc/tesla_can.dbc
opendbc/tesla_radar.dbc
opendbc/tesla_powertrain.dbc
-tinygrad_repo/openpilot/compile.py
tinygrad_repo/accel/opencl/*
+tinygrad_repo/tinygrad/llops/ops_opencl.py
+tinygrad_repo/openpilot/compile.py
tinygrad_repo/extra/onnx.py
tinygrad_repo/extra/thneed.py
tinygrad_repo/extra/utils.py
tinygrad_repo/tinygrad/llops/ops_gpu.py
-tinygrad_repo/tinygrad/llops/ops_opencl.py
-tinygrad_repo/tinygrad/helpers.py
-tinygrad_repo/tinygrad/mlops.py
-tinygrad_repo/tinygrad/ops.py
-tinygrad_repo/tinygrad/shapetracker.py
-tinygrad_repo/tinygrad/tensor.py
-tinygrad_repo/tinygrad/nn/__init__.py
-tinygrad_repo/tinygrad/nn/optim.py
+tinygrad_repo/tinygrad/shape/*
+tinygrad_repo/tinygrad/nn/*
+tinygrad_repo/tinygrad/*.py
diff --git a/scripts/cell.sh b/scripts/cell.sh
index cae701eccc..3623fe5b16 100755
--- a/scripts/cell.sh
+++ b/scripts/cell.sh
@@ -1,5 +1,3 @@
#!/usr/bin/bash
-
-nmcli connection modify --temporary lte ipv4.route-metric 1
-nmcli connection modify --temporary lte ipv6.route-metric 1
-nmcli con up lte
+nmcli connection modify --temporary lte ipv4.route-metric 1 ipv6.route-metric 1
+nmcli con up --wait --ask lte
diff --git a/selfdrive/assets/assets.qrc b/selfdrive/assets/assets.qrc
index 39be41aa65..79a1a1e272 100644
--- a/selfdrive/assets/assets.qrc
+++ b/selfdrive/assets/assets.qrc
@@ -1,5 +1,6 @@
+ ../../third_party/bootstrap/bootstrap-icons.svgimg_continue_triangle.svgimg_circled_check.svgimg_circled_slash.svg
diff --git a/selfdrive/assets/img_driver_face.png b/selfdrive/assets/img_driver_face.png
index ddde478cd7..e2d943e537 100644
Binary files a/selfdrive/assets/img_driver_face.png and b/selfdrive/assets/img_driver_face.png differ
diff --git a/selfdrive/assets/img_driver_face_static.png b/selfdrive/assets/img_driver_face_static.png
new file mode 100644
index 0000000000..d8bc5f1371
Binary files /dev/null and b/selfdrive/assets/img_driver_face_static.png differ
diff --git a/selfdrive/assets/navigation/default_marker.svg b/selfdrive/assets/navigation/default_marker.svg
new file mode 100644
index 0000000000..43d5290a96
--- /dev/null
+++ b/selfdrive/assets/navigation/default_marker.svg
@@ -0,0 +1,5 @@
+
+
diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc
index 1f1249194d..5d885c2c79 100644
--- a/selfdrive/boardd/boardd.cc
+++ b/selfdrive/boardd/boardd.cc
@@ -7,6 +7,7 @@
#include
#include
+#include
#include
#include
#include
@@ -48,8 +49,8 @@
#define MAX_IR_POWER 0.5f
#define MIN_IR_POWER 0.0f
-#define CUTOFF_IL 200
-#define SATURATE_IL 1600
+#define CUTOFF_IL 400
+#define SATURATE_IL 1000
#define NIBBLE_TO_HEX(n) ((n) < 10 ? (n) + '0' : ((n) - 10) + 'a')
using namespace std::chrono_literals;
@@ -105,6 +106,8 @@ void sync_time(Panda *panda, SyncTimeDir dir) {
bool safety_setter_thread(std::vector pandas) {
LOGD("Starting safety setter thread");
+ Params p;
+
// there should be at least one panda connected
if (pandas.size() == 0) {
return false;
@@ -116,29 +119,26 @@ bool safety_setter_thread(std::vector pandas) {
pandas[i]->set_safety_model(cereal::CarParams::SafetyModel::ELM327, safety_param);
}
- Params p = Params();
-
- // wait for VIN to be read
+ // wait for FW query at OBD port to finish
while (true) {
if (do_exit || !check_all_connected(pandas) || !ignition) {
return false;
}
- std::string value_vin = p.get("CarVin");
- if (value_vin.size() > 0) {
- // sanity check VIN format
- assert(value_vin.size() == 17);
- LOGW("got CarVin %s", value_vin.c_str());
+ if (p.getBool("FirmwareObdQueryDone")) {
+ LOGW("finished FW query at OBD port");
break;
}
util::sleep_for(20);
}
- // set to ELM327 for ECU knockouts
+ // set to ELM327 to finish fingerprinting and for potential ECU knockouts
for (Panda *panda : pandas) {
panda->set_safety_model(cereal::CarParams::SafetyModel::ELM327, 1U);
}
+ p.putBool("ObdMultiplexingDisabled", true);
+
std::string params;
LOGW("waiting for params to set safety model");
while (true) {
@@ -225,9 +225,9 @@ void can_send_thread(std::vector pandas, bool fake_send) {
//Dont send if older than 1 second
if ((nanos_since_boot() - event.getLogMonoTime() < 1e9) && !fake_send) {
for (const auto& panda : pandas) {
- LOGT("sending sendcan to panda: %s", (panda->hw_serial).c_str());
+ LOGT("sending sendcan to panda: %s", (panda->hw_serial()).c_str());
panda->can_send(event.getSendcan());
- LOGT("sendcan sent to panda: %s", (panda->hw_serial).c_str());
+ LOGT("sendcan sent to panda: %s", (panda->hw_serial()).c_str());
}
}
}
@@ -540,9 +540,8 @@ void peripheral_control_thread(Panda *panda, bool no_fan_control) {
if (sm.updated("driverCameraState")) {
auto event = sm["driverCameraState"];
int cur_integ_lines = event.getDriverCameraState().getIntegLines();
- float cur_gain = event.getDriverCameraState().getGain();
- cur_integ_lines = integ_lines_filter.update(cur_integ_lines * cur_gain);
+ cur_integ_lines = integ_lines_filter.update(cur_integ_lines);
last_front_frame_t = event.getLogMonoTime();
if (cur_integ_lines <= CUTOFF_IL) {
diff --git a/selfdrive/boardd/panda.cc b/selfdrive/boardd/panda.cc
index 3e447c830e..647a0d9c78 100644
--- a/selfdrive/boardd/panda.cc
+++ b/selfdrive/boardd/panda.cc
@@ -10,11 +10,13 @@
#include "common/util.h"
Panda::Panda(std::string serial, uint32_t bus_offset) : bus_offset(bus_offset) {
- // TODO: support SPI here one day...
- if (serial.find("spi") != std::string::npos) {
- handle = std::make_unique(serial);
- } else {
+ // try USB first, then SPI
+ try {
handle = std::make_unique(serial);
+ } catch (std::exception &e) {
+#ifndef __APPLE__
+ handle = std::make_unique(serial);
+#endif
}
hw_type = get_hw_type();
@@ -26,6 +28,8 @@ Panda::Panda(std::string serial, uint32_t bus_offset) : bus_offset(bus_offset) {
(hw_type == cereal::PandaState::PandaType::DOS) ||
(hw_type == cereal::PandaState::PandaType::TRES);
+ can_reset_communications();
+
return;
}
@@ -37,8 +41,22 @@ bool Panda::comms_healthy() {
return handle->comms_healthy;
}
+std::string Panda::hw_serial() {
+ return handle->hw_serial;
+}
+
std::vector Panda::list() {
- return PandaUsbHandle::list();
+ std::vector serials = PandaUsbHandle::list();
+
+#ifndef __APPLE__
+ for (auto s : PandaSpiHandle::list()) {
+ if (std::find(serials.begin(), serials.end(), s) == serials.end()) {
+ serials.push_back(s);
+ }
+ }
+#endif
+
+ return serials;
}
void Panda::set_safety_model(cereal::CarParams::SafetyModel safety_model, uint16_t safety_param) {
@@ -174,10 +192,6 @@ void Panda::pack_can_buffer(const capnp::List::Reader &can_data
int32_t pos = 0;
uint8_t send_buf[2 * USB_TX_SOFT_LIMIT];
- uint32_t magic = CAN_TRANSACTION_MAGIC;
- memcpy(&send_buf[0], &magic, sizeof(uint32_t));
- pos += sizeof(uint32_t);
-
for (auto cmsg : can_data_list) {
// check if the message is intended for this panda
uint8_t bus = cmsg.getSrc();
@@ -194,20 +208,25 @@ void Panda::pack_can_buffer(const capnp::List::Reader &can_data
header.extended = (cmsg.getAddress() >= 0x800) ? 1 : 0;
header.data_len_code = data_len_code;
header.bus = bus - bus_offset;
+ header.checksum = 0;
memcpy(&send_buf[pos], (uint8_t *)&header, sizeof(can_header));
- pos += sizeof(can_header);
- memcpy(&send_buf[pos], (uint8_t *)can_data.begin(), can_data.size());
- pos += can_data.size();
+ memcpy(&send_buf[pos + sizeof(can_header)], (uint8_t *)can_data.begin(), can_data.size());
+ uint32_t msg_size = sizeof(can_header) + can_data.size();
+
+ // set checksum
+ ((can_header *) &send_buf[pos])->checksum = calculate_checksum(&send_buf[pos], msg_size);
+
+ pos += msg_size;
if (pos >= USB_TX_SOFT_LIMIT) {
write_func(send_buf, pos);
- pos = sizeof(uint32_t);
+ pos = 0;
}
}
// send remaining packets
- if (pos > sizeof(uint32_t)) write_func(send_buf, pos);
+ if (pos > 0) write_func(send_buf, pos);
}
void Panda::can_send(capnp::List::Reader can_data_list) {
@@ -217,36 +236,38 @@ void Panda::can_send(capnp::List::Reader can_data_list) {
}
bool Panda::can_receive(std::vector& out_vec) {
- uint8_t data[RECV_SIZE];
- int recv = handle->bulk_read(0x81, (uint8_t*)data, RECV_SIZE);
+ // Check if enough space left in buffer to store RECV_SIZE data
+ assert(receive_buffer_size + RECV_SIZE <= sizeof(receive_buffer));
+
+ int recv = handle->bulk_read(0x81, &receive_buffer[receive_buffer_size], RECV_SIZE);
if (!comms_healthy()) {
return false;
}
if (recv == RECV_SIZE) {
LOGW("Panda receive buffer full");
}
+ receive_buffer_size += recv;
- return (recv <= 0) ? true : unpack_can_buffer(data, recv, out_vec);
+ return (recv <= 0) ? true : unpack_can_buffer(receive_buffer, receive_buffer_size, out_vec);
}
-bool Panda::unpack_can_buffer(uint8_t *data, int size, std::vector &out_vec) {
- if (size < sizeof(uint32_t)) {
- return true;
- }
+void Panda::can_reset_communications() {
+ handle->control_write(0xc0, 0, 0);
+}
- uint32_t magic;
- memcpy(&magic, &data[0], sizeof(uint32_t));
- if (magic != CAN_TRANSACTION_MAGIC) {
- LOGE("CAN recv: buffer didn't start with magic");
- handle->comms_healthy = false;
- return false;
- }
+bool Panda::unpack_can_buffer(uint8_t *data, uint32_t &size, std::vector &out_vec) {
+ int pos = 0;
- int pos = sizeof(uint32_t);
- while (pos < size) {
+ while (pos <= size - sizeof(can_header)) {
can_header header;
memcpy(&header, &data[pos], sizeof(can_header));
+ const uint8_t data_len = dlc_to_len[header.data_len_code];
+ if (pos + sizeof(can_header) + data_len > size) {
+ // we don't have all the data for this message yet
+ break;
+ }
+
can_frame &canData = out_vec.emplace_back();
canData.busTime = 0;
canData.address = header.addr;
@@ -258,10 +279,28 @@ bool Panda::unpack_can_buffer(uint8_t *data, int size, std::vector &o
canData.src += CAN_RETURNED_BUS_OFFSET;
}
- const uint8_t data_len = dlc_to_len[header.data_len_code];
+ if (calculate_checksum(&data[pos], sizeof(can_header) + data_len) != 0) {
+ LOGE("Panda CAN checksum failed");
+ size = 0;
+ return false;
+ }
+
canData.dat.assign((char *)&data[pos + sizeof(can_header)], data_len);
pos += sizeof(can_header) + data_len;
}
+
+ // move the overflowing data to the beginning of the buffer for the next round
+ memmove(data, &data[pos], size - pos);
+ size -= pos;
+
return true;
}
+
+uint8_t Panda::calculate_checksum(uint8_t *data, uint32_t len) {
+ uint8_t checksum = 0U;
+ for (uint32_t i = 0U; i < len; i++) {
+ checksum ^= data[i];
+ }
+ return checksum;
+}
diff --git a/selfdrive/boardd/panda.h b/selfdrive/boardd/panda.h
index 75fec57a3e..69df2e2b66 100644
--- a/selfdrive/boardd/panda.h
+++ b/selfdrive/boardd/panda.h
@@ -30,6 +30,7 @@ struct __attribute__((packed)) can_header {
uint8_t returned : 1;
uint8_t extended : 1;
uint32_t addr : 29;
+ uint8_t checksum : 8;
};
struct can_frame {
@@ -47,13 +48,13 @@ private:
public:
Panda(std::string serial="", uint32_t bus_offset=0);
- std::string hw_serial;
cereal::PandaState::PandaType hw_type = cereal::PandaState::PandaType::UNKNOWN;
bool has_rtc = false;
const uint32_t bus_offset;
bool connected();
bool comms_healthy();
+ std::string hw_serial();
// Static functions
static std::vector list();
@@ -80,11 +81,16 @@ public:
void set_canfd_non_iso(uint16_t bus, bool non_iso);
void can_send(capnp::List::Reader can_data_list);
bool can_receive(std::vector& out_vec);
+ void can_reset_communications();
protected:
// for unit tests
+ uint8_t receive_buffer[RECV_SIZE + sizeof(can_header) + 64];
+ uint32_t receive_buffer_size = 0;
+
Panda(uint32_t bus_offset) : bus_offset(bus_offset) {}
void pack_can_buffer(const capnp::List::Reader &can_data_list,
std::function write_func);
- bool unpack_can_buffer(uint8_t *data, int size, std::vector &out_vec);
+ bool unpack_can_buffer(uint8_t *data, uint32_t &size, std::vector &out_vec);
+ uint8_t calculate_checksum(uint8_t *data, uint32_t len);
};
diff --git a/selfdrive/boardd/panda_comms.cc b/selfdrive/boardd/panda_comms.cc
index e73cb69318..120d2f67d5 100644
--- a/selfdrive/boardd/panda_comms.cc
+++ b/selfdrive/boardd/panda_comms.cc
@@ -44,7 +44,7 @@ PandaUsbHandle::PandaUsbHandle(std::string serial) : PandaCommsHandle(serial) {
ret = libusb_get_string_descriptor_ascii(dev_handle, desc.iSerialNumber, desc_serial, std::size(desc_serial));
if (ret < 0) { goto fail; }
- auto hw_serial = std::string((char *)desc_serial, ret);
+ hw_serial = std::string((char *)desc_serial, ret);
if (serial.empty() || serial == hw_serial) {
break;
}
diff --git a/selfdrive/boardd/panda_comms.h b/selfdrive/boardd/panda_comms.h
index bd262dfa0e..506b96b372 100644
--- a/selfdrive/boardd/panda_comms.h
+++ b/selfdrive/boardd/panda_comms.h
@@ -5,7 +5,9 @@
#include
#include
+#ifndef __APPLE__
#include
+#endif
#include
@@ -21,6 +23,7 @@ public:
virtual ~PandaCommsHandle() {};
virtual void cleanup() = 0;
+ std::string hw_serial;
std::atomic connected = true;
std::atomic comms_healthy = true;
static std::vector list();
@@ -30,9 +33,6 @@ public:
virtual int control_read(uint8_t request, uint16_t param1, uint16_t param2, unsigned char *data, uint16_t length, unsigned int timeout=TIMEOUT) = 0;
virtual int bulk_write(unsigned char endpoint, unsigned char* data, int length, unsigned int timeout=TIMEOUT) = 0;
virtual int bulk_read(unsigned char endpoint, unsigned char* data, int length, unsigned int timeout=TIMEOUT) = 0;
-
-protected:
- std::recursive_mutex hw_lock;
};
class PandaUsbHandle : public PandaCommsHandle {
@@ -50,9 +50,11 @@ public:
private:
libusb_context *ctx = NULL;
libusb_device_handle *dev_handle = NULL;
+ std::recursive_mutex hw_lock;
void handle_usb_issue(int err, const char func[]);
};
+#ifndef __APPLE__
class PandaSpiHandle : public PandaCommsHandle {
public:
PandaSpiHandle(std::string serial);
@@ -69,9 +71,11 @@ private:
int spi_fd = -1;
uint8_t tx_buf[SPI_BUF_SIZE];
uint8_t rx_buf[SPI_BUF_SIZE];
+ inline static std::recursive_mutex hw_lock;
int wait_for_ack(spi_ioc_transfer &transfer, uint8_t ack);
int bulk_transfer(uint8_t endpoint, uint8_t *tx_data, uint16_t tx_len, uint8_t *rx_data, uint16_t rx_len);
int spi_transfer(uint8_t endpoint, uint8_t *tx_data, uint16_t tx_len, uint8_t *rx_data, uint16_t max_rx_len);
int spi_transfer_retry(uint8_t endpoint, uint8_t *tx_data, uint16_t tx_len, uint8_t *rx_data, uint16_t max_rx_len);
};
+#endif
diff --git a/selfdrive/boardd/pandad.py b/selfdrive/boardd/pandad.py
index 971756002b..f61d9ee1a6 100755
--- a/selfdrive/boardd/pandad.py
+++ b/selfdrive/boardd/pandad.py
@@ -7,7 +7,7 @@ import subprocess
from typing import List, NoReturn
from functools import cmp_to_key
-from panda import DEFAULT_FW_FN, DEFAULT_H7_FW_FN, MCU_TYPE_H7, Panda, PandaDFU
+from panda import Panda, PandaDFU
from common.basedir import BASEDIR
from common.params import Params
from system.hardware import HARDWARE
@@ -15,10 +15,8 @@ from system.swaglog import cloudlog
def get_expected_signature(panda: Panda) -> bytes:
- fn = DEFAULT_H7_FW_FN if (panda.get_mcu_type() == MCU_TYPE_H7) else DEFAULT_FW_FN
-
try:
- return Panda.get_signature_from_firmware(fn)
+ return Panda.get_signature_from_firmware(panda.get_mcu_type().config.app_path)
except Exception:
cloudlog.exception("Error computing expected signature")
return b""
diff --git a/selfdrive/boardd/spi.cc b/selfdrive/boardd/spi.cc
index 717b6ce820..9a10e30f95 100644
--- a/selfdrive/boardd/spi.cc
+++ b/selfdrive/boardd/spi.cc
@@ -1,9 +1,13 @@
+#ifndef __APPLE__
+#include
#include
#include
#include
#include
#include
+#include
+#include
#include "common/util.h"
#include "common/timing.h"
@@ -27,41 +31,77 @@ struct __attribute__((packed)) spi_header {
const int SPI_MAX_RETRIES = 5;
const int SPI_ACK_TIMEOUT = 50; // milliseconds
+const std::string SPI_DEVICE = "/dev/spidev0.0";
+
+class LockEx {
+public:
+ LockEx(int fd, std::recursive_mutex &m) : fd(fd), m(m) {
+ m.lock();
+ flock(fd, LOCK_EX);
+ };
+
+ ~LockEx() {
+ m.unlock();
+ flock(fd, LOCK_UN);
+ }
+
+private:
+ int fd;
+ std::recursive_mutex &m;
+};
PandaSpiHandle::PandaSpiHandle(std::string serial) : PandaCommsHandle(serial) {
- LOGD("opening SPI panda: %s", serial.c_str());
+ int ret;
+ const int uid_len = 12;
+ uint8_t uid[uid_len] = {0};
- int err;
uint32_t spi_mode = SPI_MODE_0;
uint32_t spi_speed = 30000000;
uint8_t spi_bits_per_word = 8;
- spi_fd = open(serial.c_str(), O_RDWR);
+ spi_fd = open(SPI_DEVICE.c_str(), O_RDWR);
if (spi_fd < 0) {
- LOGE("failed opening SPI device %d", err);
+ LOGE("failed opening SPI device %d", spi_fd);
goto fail;
}
// SPI settings
- err = util::safe_ioctl(spi_fd, SPI_IOC_WR_MODE, &spi_mode);
- if (err < 0) {
- LOGE("failed setting SPI mode %d", err);
+ ret = util::safe_ioctl(spi_fd, SPI_IOC_WR_MODE, &spi_mode);
+ if (ret < 0) {
+ LOGE("failed setting SPI mode %d", ret);
goto fail;
}
- err = util::safe_ioctl(spi_fd, SPI_IOC_WR_MAX_SPEED_HZ, &spi_speed);
- if (err < 0) {
+ ret = util::safe_ioctl(spi_fd, SPI_IOC_WR_MAX_SPEED_HZ, &spi_speed);
+ if (ret < 0) {
LOGE("failed setting SPI speed");
goto fail;
}
- err = util::safe_ioctl(spi_fd, SPI_IOC_WR_BITS_PER_WORD, &spi_bits_per_word);
- if (err < 0) {
+ ret = util::safe_ioctl(spi_fd, SPI_IOC_WR_BITS_PER_WORD, &spi_bits_per_word);
+ if (ret < 0) {
LOGE("failed setting SPI bits per word");
goto fail;
}
+ // get hw UID/serial
+ ret = control_read(0xc3, 0, 0, uid, uid_len);
+ if (ret == uid_len) {
+ std::stringstream stream;
+ for (int i = 0; i < uid_len; i++) {
+ stream << std::hex << std::setw(2) << std::setfill('0') << int(uid[i]);
+ }
+ hw_serial = stream.str();
+ } else {
+ LOGD("failed to get serial %d", ret);
+ goto fail;
+ }
+
+ if (!serial.empty() && (serial != hw_serial)) {
+ goto fail;
+ }
+
return;
fail:
@@ -84,6 +124,7 @@ void PandaSpiHandle::cleanup() {
int PandaSpiHandle::control_write(uint8_t request, uint16_t param1, uint16_t param2, unsigned int timeout) {
+ LockEx lock(spi_fd, hw_lock);
ControlPacket_t packet = {
.request = request,
.param1 = param1,
@@ -94,6 +135,7 @@ int PandaSpiHandle::control_write(uint8_t request, uint16_t param1, uint16_t par
}
int PandaSpiHandle::control_read(uint8_t request, uint16_t param1, uint16_t param2, unsigned char *data, uint16_t length, unsigned int timeout) {
+ LockEx lock(spi_fd, hw_lock);
ControlPacket_t packet = {
.request = request,
.param1 = param1,
@@ -104,15 +146,15 @@ int PandaSpiHandle::control_read(uint8_t request, uint16_t param1, uint16_t para
}
int PandaSpiHandle::bulk_write(unsigned char endpoint, unsigned char* data, int length, unsigned int timeout) {
+ LockEx lock(spi_fd, hw_lock);
return bulk_transfer(endpoint, data, length, NULL, 0);
}
int PandaSpiHandle::bulk_read(unsigned char endpoint, unsigned char* data, int length, unsigned int timeout) {
+ LockEx lock(spi_fd, hw_lock);
return bulk_transfer(endpoint, NULL, 0, data, length);
}
int PandaSpiHandle::bulk_transfer(uint8_t endpoint, uint8_t *tx_data, uint16_t tx_len, uint8_t *rx_data, uint16_t rx_len) {
- std::lock_guard lk(hw_lock);
-
const int xfer_size = 0x40 * 15;
int ret = 0;
@@ -143,7 +185,12 @@ int PandaSpiHandle::bulk_transfer(uint8_t endpoint, uint8_t *tx_data, uint16_t t
}
std::vector PandaSpiHandle::list() {
- // TODO: list all pandas available over SPI
+ try {
+ PandaSpiHandle sh("");
+ return {sh.hw_serial};
+ } catch (std::exception &e) {
+ // no panda on SPI
+ }
return {};
}
@@ -167,7 +214,6 @@ int PandaSpiHandle::spi_transfer_retry(uint8_t endpoint, uint8_t *tx_data, uint1
int ret;
int count = SPI_MAX_RETRIES;
- std::lock_guard lk(hw_lock);
do {
// TODO: handle error
ret = spi_transfer(endpoint, tx_data, tx_len, rx_data, max_rx_len);
@@ -195,7 +241,7 @@ int PandaSpiHandle::wait_for_ack(spi_ioc_transfer &transfer, uint8_t ack) {
// handle timeout
if (millis_since_boot() - start_millis > SPI_ACK_TIMEOUT) {
- LOGE("SPI: timed out waiting for ACK");
+ LOGD("SPI: timed out waiting for ACK");
return -1;
}
}
@@ -270,7 +316,10 @@ int PandaSpiHandle::spi_transfer(uint8_t endpoint, uint8_t *tx_data, uint16_t tx
goto transfer_fail;
}
rx_data_len = *(uint16_t *)(rx_buf+1);
- assert(rx_data_len < SPI_BUF_SIZE);
+ if (rx_data_len >= SPI_BUF_SIZE) {
+ LOGE("SPI: RX data len larger than buf size %d", rx_data_len);
+ goto transfer_fail;
+ }
// Read data
transfer.len = rx_data_len + 1;
@@ -294,3 +343,4 @@ int PandaSpiHandle::spi_transfer(uint8_t endpoint, uint8_t *tx_data, uint16_t tx
transfer_fail:
return ret;
}
+#endif
diff --git a/selfdrive/boardd/tests/test_boardd_loopback.py b/selfdrive/boardd/tests/test_boardd_loopback.py
index e9bbcb4586..b8ebbd88a3 100755
--- a/selfdrive/boardd/tests/test_boardd_loopback.py
+++ b/selfdrive/boardd/tests/test_boardd_loopback.py
@@ -51,7 +51,7 @@ class TestBoardd(unittest.TestCase):
cp.safetyConfigs = [safety_config]*num_pandas
params = Params()
- params.put("CarVin", b"0"*17)
+ params.put_bool("FirmwareObdQueryDone", True)
params.put_bool("ControlsReady", True)
params.put("CarParams", cp.to_bytes())
diff --git a/selfdrive/boardd/tests/test_boardd_usbprotocol.cc b/selfdrive/boardd/tests/test_boardd_usbprotocol.cc
index cc3b4bce9a..3b78eb7bd2 100644
--- a/selfdrive/boardd/tests/test_boardd_usbprotocol.cc
+++ b/selfdrive/boardd/tests/test_boardd_usbprotocol.cc
@@ -16,7 +16,8 @@ int random_int(int min, int max) {
struct PandaTest : public Panda {
PandaTest(uint32_t bus_offset, int can_list_size, cereal::PandaState::PandaType hw_type);
void test_can_send();
- void test_can_recv();
+ void test_can_recv(uint32_t chunk_size = 0);
+ void test_chunked_can_recv();
std::map test_data;
int can_list_size = 0;
@@ -58,11 +59,7 @@ PandaTest::PandaTest(uint32_t bus_offset_, int can_list_size, cereal::PandaState
void PandaTest::test_can_send() {
std::vector unpacked_data;
this->pack_can_buffer(can_data_list, [&](uint8_t *chunk, size_t size) {
- uint32_t magic;
- memcpy(&magic, &chunk[0], sizeof(uint32_t));
-
- REQUIRE(magic == CAN_TRANSACTION_MAGIC);
- unpacked_data.insert(unpacked_data.end(), &chunk[sizeof(uint32_t)], &chunk[size]);
+ unpacked_data.insert(unpacked_data.end(), chunk, &chunk[size]);
});
REQUIRE(unpacked_data.size() == total_pakets_size);
@@ -77,16 +74,30 @@ void PandaTest::test_can_send() {
REQUIRE(header.addr == cnt);
REQUIRE(test_data.find(data_len) != test_data.end());
const std::string &dat = test_data[data_len];
- REQUIRE(memcmp(dat.data(), &unpacked_data[pos + 5], dat.size()) == 0);
+ REQUIRE(memcmp(dat.data(), &unpacked_data[pos + sizeof(can_header)], dat.size()) == 0);
++cnt;
}
REQUIRE(cnt == can_list_size);
}
-void PandaTest::test_can_recv() {
+void PandaTest::test_can_recv(uint32_t rx_chunk_size) {
std::vector frames;
- this->pack_can_buffer(can_data_list, [&](uint8_t *data, size_t size) {
- this->unpack_can_buffer(data, size, frames);
+ this->pack_can_buffer(can_data_list, [&](uint8_t *data, uint32_t size) {
+ if (rx_chunk_size == 0) {
+ REQUIRE(this->unpack_can_buffer(data, size, frames));
+ } else {
+ this->receive_buffer_size = 0;
+ uint32_t pos = 0;
+
+ while(pos < size) {
+ uint32_t chunk_size = std::min(rx_chunk_size, size - pos);
+ memcpy(&this->receive_buffer[this->receive_buffer_size], &data[pos], chunk_size);
+ this->receive_buffer_size += chunk_size;
+ pos += chunk_size;
+
+ REQUIRE(this->unpack_can_buffer(this->receive_buffer, this->receive_buffer_size, frames));
+ }
+ }
});
REQUIRE(frames.size() == can_list_size);
@@ -109,6 +120,9 @@ TEST_CASE("send/recv CAN 2.0 packets") {
SECTION("can_receive") {
test.test_can_recv();
}
+ SECTION("chunked_can_receive") {
+ test.test_can_recv(0x40);
+ }
}
TEST_CASE("send/recv CAN FD packets") {
@@ -122,4 +136,7 @@ TEST_CASE("send/recv CAN FD packets") {
SECTION("can_receive") {
test.test_can_recv();
}
+ SECTION("chunked_can_receive") {
+ test.test_can_recv(0x40);
+ }
}
diff --git a/selfdrive/car/CARS_template.md b/selfdrive/car/CARS_template.md
index 2fce0f9036..1c80ea3d93 100644
--- a/selfdrive/car/CARS_template.md
+++ b/selfdrive/car/CARS_template.md
@@ -1,5 +1,6 @@
{% set footnote_tag = '[{}](#footnotes)' -%}
{% set star_icon = '[](##)' -%}
+{% set video_icon = '' -%}
@@ -12,7 +13,7 @@ A supported vehicle is one that just works when you install a comma three. All s
|{{Column | map(attribute='value') | join('|')}}|
|---|---|---|{% for _ in range((Column | length) - 3) %}{{':---:|'}}{% endfor +%}
{% for car_info in all_car_info %}
-|{% for column in Column %}{{car_info.get_column(column, star_icon, footnote_tag)}}|{% endfor %}
+|{% for column in Column %}{{car_info.get_column(column, star_icon, video_icon, footnote_tag)}}|{% endfor %}
{% endfor %}
diff --git a/selfdrive/car/__init__.py b/selfdrive/car/__init__.py
index c056f7ca3d..58cde85817 100644
--- a/selfdrive/car/__init__.py
+++ b/selfdrive/car/__init__.py
@@ -73,7 +73,7 @@ def dbc_dict(pt_dbc, radar_dbc, chassis_dbc=None, body_dbc=None) -> Dict[str, st
return {'pt': pt_dbc, 'radar': radar_dbc, 'chassis': chassis_dbc, 'body': body_dbc}
-def apply_std_steer_torque_limits(apply_torque, apply_torque_last, driver_torque, LIMITS):
+def apply_driver_steer_torque_limits(apply_torque, apply_torque_last, driver_torque, LIMITS):
# limits due to driver torque
driver_max_torque = LIMITS.STEER_MAX + (LIMITS.STEER_DRIVER_ALLOWANCE + driver_torque * LIMITS.STEER_DRIVER_FACTOR) * LIMITS.STEER_DRIVER_MULTIPLIER
@@ -93,29 +93,37 @@ def apply_std_steer_torque_limits(apply_torque, apply_torque_last, driver_torque
return int(round(float(apply_torque)))
-def apply_toyota_steer_torque_limits(apply_torque, apply_torque_last, motor_torque, LIMITS):
- # limits due to comparison of commanded torque VS motor reported torque
- max_lim = min(max(motor_torque + LIMITS.STEER_ERROR_MAX, LIMITS.STEER_ERROR_MAX), LIMITS.STEER_MAX)
- min_lim = max(min(motor_torque - LIMITS.STEER_ERROR_MAX, -LIMITS.STEER_ERROR_MAX), -LIMITS.STEER_MAX)
+def apply_dist_to_meas_limits(val, val_last, val_meas,
+ STEER_DELTA_UP, STEER_DELTA_DOWN,
+ STEER_ERROR_MAX, STEER_MAX):
+ # limits due to comparison of commanded val VS measured val (torque/angle/curvature)
+ max_lim = min(max(val_meas + STEER_ERROR_MAX, STEER_ERROR_MAX), STEER_MAX)
+ min_lim = max(min(val_meas - STEER_ERROR_MAX, -STEER_ERROR_MAX), -STEER_MAX)
- apply_torque = clip(apply_torque, min_lim, max_lim)
+ val = clip(val, min_lim, max_lim)
- # slow rate if steer torque increases in magnitude
- if apply_torque_last > 0:
- apply_torque = clip(apply_torque,
- max(apply_torque_last - LIMITS.STEER_DELTA_DOWN, -LIMITS.STEER_DELTA_UP),
- apply_torque_last + LIMITS.STEER_DELTA_UP)
+ # slow rate if val increases in magnitude
+ if val_last > 0:
+ val = clip(val,
+ max(val_last - STEER_DELTA_DOWN, -STEER_DELTA_UP),
+ val_last + STEER_DELTA_UP)
else:
- apply_torque = clip(apply_torque,
- apply_torque_last - LIMITS.STEER_DELTA_UP,
- min(apply_torque_last + LIMITS.STEER_DELTA_DOWN, LIMITS.STEER_DELTA_UP))
+ val = clip(val,
+ val_last - STEER_DELTA_UP,
+ min(val_last + STEER_DELTA_DOWN, STEER_DELTA_UP))
- return int(round(float(apply_torque)))
+ return float(val)
+
+
+def apply_meas_steer_torque_limits(apply_torque, apply_torque_last, motor_torque, LIMITS):
+ return int(round(apply_dist_to_meas_limits(apply_torque, apply_torque_last, motor_torque,
+ LIMITS.STEER_DELTA_UP, LIMITS.STEER_DELTA_DOWN,
+ LIMITS.STEER_ERROR_MAX, LIMITS.STEER_MAX)))
def apply_std_steer_angle_limits(apply_angle, apply_angle_last, v_ego, LIMITS):
# pick angle rate limits based on wind up/down
- steer_up = apply_angle_last * apply_angle > 0. and abs(apply_angle) > abs(apply_angle_last)
+ steer_up = apply_angle_last * apply_angle >= 0. and abs(apply_angle) > abs(apply_angle_last)
rate_limits = LIMITS.ANGLE_RATE_LIMIT_UP if steer_up else LIMITS.ANGLE_RATE_LIMIT_DOWN
angle_rate_lim = interp(v_ego, rate_limits.speed_bp, rate_limits.angle_v)
diff --git a/selfdrive/car/body/carcontroller.py b/selfdrive/car/body/carcontroller.py
index 00673a7e28..bcaf6f6f93 100644
--- a/selfdrive/car/body/carcontroller.py
+++ b/selfdrive/car/body/carcontroller.py
@@ -35,7 +35,7 @@ class CarController:
torque -= deadband
return torque
- def update(self, CC, CS):
+ def update(self, CC, CS, now_nanos):
torque_l = 0
torque_r = 0
diff --git a/selfdrive/car/body/interface.py b/selfdrive/car/body/interface.py
index bc5b36e2ee..850a3538ad 100644
--- a/selfdrive/car/body/interface.py
+++ b/selfdrive/car/body/interface.py
@@ -24,7 +24,7 @@ class CarInterface(CarInterfaceBase):
ret.wheelSpeedFactor = SPEED_FROM_RPM
ret.centerToFront = ret.wheelbase * 0.44
- ret.radarOffCan = True
+ ret.radarUnavailable = True
ret.openpilotLongitudinalControl = True
ret.steerControlType = car.CarParams.SteerControlType.angle
@@ -43,5 +43,5 @@ class CarInterface(CarInterfaceBase):
return ret
- def apply(self, c):
- return self.CC.update(c, self.CS)
+ def apply(self, c, now_nanos):
+ return self.CC.update(c, self.CS, now_nanos)
diff --git a/selfdrive/car/car_helpers.py b/selfdrive/car/car_helpers.py
index 61e7a3d55d..370772c902 100644
--- a/selfdrive/car/car_helpers.py
+++ b/selfdrive/car/car_helpers.py
@@ -8,7 +8,7 @@ from system.version import is_comma_remote, is_tested_branch
from selfdrive.car.interfaces import get_interface_attr
from selfdrive.car.fingerprints import eliminate_incompatible_cars, all_legacy_fingerprint_cars
from selfdrive.car.vin import get_vin, is_valid_vin, VIN_UNKNOWN
-from selfdrive.car.fw_versions import get_fw_versions_ordered, match_fw_to_car, get_present_ecus
+from selfdrive.car.fw_versions import disable_obd_multiplexing, get_fw_versions_ordered, match_fw_to_car, get_present_ecus
from system.swaglog import cloudlog
import cereal.messaging as messaging
from selfdrive.car import gen_empty_fingerprint
@@ -99,7 +99,7 @@ def fingerprint(logcan, sendcan, num_pandas):
else:
cloudlog.warning("Getting VIN & FW versions")
vin_rx_addr, vin = get_vin(logcan, sendcan, bus)
- ecu_rx_addrs = get_present_ecus(logcan, sendcan)
+ ecu_rx_addrs = get_present_ecus(logcan, sendcan, num_pandas=num_pandas)
car_fw = get_fw_versions_ordered(logcan, sendcan, ecu_rx_addrs, num_pandas=num_pandas)
cached = False
@@ -113,7 +113,10 @@ def fingerprint(logcan, sendcan, num_pandas):
cloudlog.event("Malformed VIN", vin=vin, error=True)
vin = VIN_UNKNOWN
cloudlog.warning("VIN %s", vin)
- Params().put("CarVin", vin)
+
+ params = Params()
+ params.put("CarVin", vin)
+ disable_obd_multiplexing(params)
finger = gen_empty_fingerprint()
candidate_cars = {i: all_legacy_fingerprint_cars() for i in [0, 1]} # attempt fingerprint on both bus 0 and 1
@@ -173,17 +176,15 @@ def fingerprint(logcan, sendcan, num_pandas):
return car_fingerprint, finger, vin, car_fw, source, exact_match
-def get_car(logcan, sendcan, num_pandas=1):
+def get_car(logcan, sendcan, experimental_long_allowed, num_pandas=1):
candidate, fingerprints, vin, car_fw, source, exact_match = fingerprint(logcan, sendcan, num_pandas)
if candidate is None:
cloudlog.warning("car doesn't match any fingerprints: %r", fingerprints)
candidate = "mock"
- experimental_long = Params().get_bool("ExperimentalLongitudinalEnabled")
-
CarInterface, CarController, CarState = interfaces[candidate]
- CP = CarInterface.get_params(candidate, fingerprints, car_fw, experimental_long)
+ CP = CarInterface.get_params(candidate, fingerprints, car_fw, experimental_long_allowed)
CP.carVin = vin
CP.carFw = car_fw
CP.fingerprintSource = source
diff --git a/selfdrive/car/chrysler/carcontroller.py b/selfdrive/car/chrysler/carcontroller.py
index ba6aaf8250..b418179e0e 100644
--- a/selfdrive/car/chrysler/carcontroller.py
+++ b/selfdrive/car/chrysler/carcontroller.py
@@ -1,6 +1,6 @@
from opendbc.can.packer import CANPacker
from common.realtime import DT_CTRL
-from selfdrive.car import apply_toyota_steer_torque_limits
+from selfdrive.car import apply_meas_steer_torque_limits
from selfdrive.car.chrysler.chryslercan import create_lkas_hud, create_lkas_command, create_cruise_buttons
from selfdrive.car.chrysler.values import RAM_CARS, CarControllerParams, ChryslerFlags
@@ -19,7 +19,7 @@ class CarController:
self.packer = CANPacker(dbc_name)
self.params = CarControllerParams(CP)
- def update(self, CC, CS):
+ def update(self, CC, CS, now_nanos):
can_sends = []
lkas_active = CC.latActive and self.lkas_control_bit_prev
@@ -67,7 +67,7 @@ class CarController:
# steer torque
new_steer = int(round(CC.actuators.steer * self.params.STEER_MAX))
- apply_steer = apply_toyota_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorqueEps, self.params)
+ apply_steer = apply_meas_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorqueEps, self.params)
if not lkas_active or not lkas_control_bit:
apply_steer = 0
self.apply_steer_last = apply_steer
diff --git a/selfdrive/car/chrysler/carstate.py b/selfdrive/car/chrysler/carstate.py
index 0f0d30782a..fdc5aa338a 100644
--- a/selfdrive/car/chrysler/carstate.py
+++ b/selfdrive/car/chrysler/carstate.py
@@ -81,8 +81,9 @@ class CarState(CarStateBase):
if self.CP.carFingerprint in RAM_CARS:
self.auto_high_beam = cp_cam.vl["DAS_6"]['AUTO_HIGH_BEAM_ON'] # Auto High Beam isn't Located in this message on chrysler or jeep currently located in 729 message
- ret.steerFaultTemporary = cp.vl["EPS_3"]["DASM_FAULT"] == 1
+ ret.steerFaultTemporary = cp.vl["EPS_3"]["DASM_FAULT"] == 1
else:
+ ret.steerFaultTemporary = cp.vl["EPS_2"]["LKAS_TEMPORARY_FAULT"] == 1
ret.steerFaultPermanent = cp.vl["EPS_2"]["LKAS_STATE"] == 4
# blindspot sensors
@@ -135,6 +136,7 @@ class CarState(CarStateBase):
("COUNTER", "EPS_2",),
("COLUMN_TORQUE", "EPS_2"),
("EPS_TORQUE_MOTOR", "EPS_2"),
+ ("LKAS_TEMPORARY_FAULT", "EPS_2"),
("LKAS_STATE", "EPS_2"),
("COUNTER", "CRUISE_BUTTONS"),
]
diff --git a/selfdrive/car/chrysler/interface.py b/selfdrive/car/chrysler/interface.py
index 2f058165ac..303f563c90 100755
--- a/selfdrive/car/chrysler/interface.py
+++ b/selfdrive/car/chrysler/interface.py
@@ -2,7 +2,7 @@
from cereal import car
from panda import Panda
from selfdrive.car import STD_CARGO_KG, get_safety_config
-from selfdrive.car.chrysler.values import CAR, DBC, RAM_HD, RAM_DT, RAM_CARS, ChryslerFlags
+from selfdrive.car.chrysler.values import CAR, RAM_HD, RAM_DT, RAM_CARS, ChryslerFlags
from selfdrive.car.interfaces import CarInterfaceBase
@@ -12,7 +12,8 @@ class CarInterface(CarInterfaceBase):
ret.carName = "chrysler"
ret.dashcamOnly = candidate in RAM_HD
- ret.radarOffCan = DBC[candidate]['radar'] is None
+ # radar parsing needs some work, see https://github.com/commaai/openpilot/issues/26842
+ ret.radarUnavailable = True # DBC[candidate]['radar'] is None
ret.steerActuatorDelay = 0.1
ret.steerLimitTimer = 0.4
@@ -24,6 +25,7 @@ class CarInterface(CarInterfaceBase):
ret.safetyConfigs[0].safetyParam |= Panda.FLAG_CHRYSLER_RAM_DT
ret.minSteerSpeed = 3.8 # m/s
+ CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning)
if candidate not in RAM_CARS:
# Newer FW versions standard on the following platforms, or flashed by a dealer onto older platforms have a higher minimum steering speed.
new_eps_platform = candidate in (CAR.PACIFICA_2019_HYBRID, CAR.PACIFICA_2020, CAR.JEEP_CHEROKEE_2019)
@@ -36,6 +38,8 @@ class CarInterface(CarInterfaceBase):
ret.mass = 2242. + STD_CARGO_KG
ret.wheelbase = 3.089
ret.steerRatio = 16.2 # Pacifica Hybrid 2017
+
+ ret.lateralTuning.init('pid')
ret.lateralTuning.pid.kpBP, ret.lateralTuning.pid.kiBP = [[9., 20.], [9., 20.]]
ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.15, 0.30], [0.03, 0.05]]
ret.lateralTuning.pid.kf = 0.00006
@@ -46,6 +50,8 @@ class CarInterface(CarInterfaceBase):
ret.wheelbase = 2.71
ret.steerRatio = 16.7
ret.steerActuatorDelay = 0.2
+
+ ret.lateralTuning.init('pid')
ret.lateralTuning.pid.kpBP, ret.lateralTuning.pid.kiBP = [[9., 20.], [9., 20.]]
ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.15, 0.30], [0.03, 0.05]]
ret.lateralTuning.pid.kf = 0.00006
@@ -56,11 +62,10 @@ class CarInterface(CarInterfaceBase):
ret.wheelbase = 3.88
ret.steerRatio = 16.3
ret.mass = 2493. + STD_CARGO_KG
- CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning)
ret.minSteerSpeed = 14.5
- for fw in car_fw:
- if fw.ecu == 'eps' and fw.fwVersion.startswith((b"68312176", b"68273275")):
- ret.minSteerSpeed = 0.
+ # Older EPS FW allow steer to zero
+ if any(fw.ecu == 'eps' and fw.fwVersion[:4] <= b"6831" for fw in car_fw):
+ ret.minSteerSpeed = 0.
elif candidate == CAR.RAM_HD:
ret.steerActuatorDelay = 0.2
@@ -100,5 +105,5 @@ class CarInterface(CarInterfaceBase):
return ret
- def apply(self, c):
- return self.CC.update(c, self.CS)
+ def apply(self, c, now_nanos):
+ return self.CC.update(c, self.CS, now_nanos)
diff --git a/selfdrive/car/chrysler/radar_interface.py b/selfdrive/car/chrysler/radar_interface.py
index 348e3c3632..0ab8c10b44 100755
--- a/selfdrive/car/chrysler/radar_interface.py
+++ b/selfdrive/car/chrysler/radar_interface.py
@@ -45,12 +45,13 @@ def _address_to_track(address):
class RadarInterface(RadarInterfaceBase):
def __init__(self, CP):
super().__init__(CP)
+ self.CP = CP
self.rcp = _create_radar_can_parser(CP.carFingerprint)
self.updated_messages = set()
self.trigger_msg = LAST_MSG
def update(self, can_strings):
- if self.rcp is None:
+ if self.rcp is None or self.CP.radarUnavailable:
return super().update(None)
vls = self.rcp.update_strings(can_strings)
diff --git a/selfdrive/car/chrysler/values.py b/selfdrive/car/chrysler/values.py
index 7629a2f086..2a5daf440c 100644
--- a/selfdrive/car/chrysler/values.py
+++ b/selfdrive/car/chrysler/values.py
@@ -56,6 +56,7 @@ RAM_DT = {CAR.RAM_1500, }
RAM_HD = {CAR.RAM_HD, }
RAM_CARS = RAM_DT | RAM_HD
+
@dataclass
class ChryslerCarInfo(CarInfo):
package: str = "Adaptive Cruise Control (ACC)"
@@ -92,7 +93,7 @@ CAR_INFO: Dict[str, Optional[Union[ChryslerCarInfo, List[ChryslerCarInfo]]]] = {
FINGERPRINTS = {
CAR.PACIFICA_2017_HYBRID: [{
- 168: 8, 257: 5, 258: 8, 264: 8, 268: 8, 270: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 291: 8, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 515: 7, 516: 7, 517: 7, 518: 7, 520: 8, 528: 8, 532: 8, 542: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 4, 571: 3, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 653: 8, 654: 8, 655: 8, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 678: 8, 680: 8, 701: 8, 704: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 746: 5, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 782: 8, 784: 8, 788:3, 792: 8, 799: 8, 800: 8, 804: 8, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 878: 8, 882: 8, 897: 8, 908: 8, 924: 3, 926: 3, 929: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 956: 8, 958: 8, 959: 8, 969: 4, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1082: 8, 1083: 8, 1098: 8, 1100: 8, 1216: 8, 1218: 8, 1220: 8, 1225: 8, 1235: 8, 1242: 8, 1246: 8, 1250: 8, 1284: 8, 1537: 8, 1538: 8, 1562: 8, 1568: 8, 1856: 8, 1858: 8, 1860: 8, 1865: 8, 1875: 8, 1882: 8, 1886: 8, 1890: 8, 1892: 8, 2016: 8, 2024: 8
+ 168: 8, 257: 5, 258: 8, 264: 8, 268: 8, 270: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 291: 8, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 515: 7, 516: 7, 517: 7, 518: 7, 520: 8, 528: 8, 532: 8, 542: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 4, 571: 3, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 653: 8, 654: 8, 655: 8, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 678: 8, 680: 8, 701: 8, 704: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 746: 5, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 782: 8, 784: 8, 788: 3, 792: 8, 799: 8, 800: 8, 804: 8, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 840: 8, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 878: 8, 882: 8, 897: 8, 908: 8, 924: 3, 926: 3, 929: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 956: 8, 958: 8, 959: 8, 969: 4, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1082: 8, 1083: 8, 1098: 8, 1100: 8, 1216: 8, 1218: 8, 1220: 8, 1225: 8, 1235: 8, 1242: 8, 1246: 8, 1250: 8, 1284: 8, 1537: 8, 1538: 8, 1562: 8, 1568: 8, 1856: 8, 1858: 8, 1860: 8, 1865: 8, 1875: 8, 1882: 8, 1886: 8, 1890: 8, 1892: 8, 2016: 8, 2024: 8
}],
CAR.PACIFICA_2018: [{
55: 8, 257: 5, 258: 8, 264: 8, 268: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 516: 7, 517: 7, 520: 8, 524: 8, 526: 6, 528: 8, 532: 8, 542: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 656: 4, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 678: 8, 680: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 746: 5, 752: 2, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 882: 8, 897: 8, 924: 8, 926: 3, 937: 8, 947: 8, 948: 8, 969: 4, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1098: 8, 1100: 8, 1537: 8, 1538: 8, 1562: 8
@@ -134,7 +135,7 @@ FINGERPRINTS = {
}],
CAR.JEEP_CHEROKEE_2019: [{
# Jeep Grand Cherokee 2019, including most 2020 models
- 55: 8, 168: 8, 179: 8, 181: 8, 256: 4, 257: 5, 258: 8, 264: 8, 268: 8, 272: 6, 273: 6, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 341: 8, 344: 8, 352: 8, 362: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 530: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 8, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 618: 8, 624: 8, 625: 8, 632: 8, 639: 8, 640: 1, 656: 4, 658: 6, 660: 8, 671: 8, 672: 8, 676: 8, 678: 8, 680: 8, 683: 8, 684: 8, 703: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 738: 8, 746: 5, 752: 2, 754: 8, 760: 8, 761: 8, 764: 8, 766: 8, 773: 8, 776: 8, 779: 8, 782: 8, 783: 8, 784: 8, 785: 8, 792: 8, 799: 8, 800: 8, 804: 8, 806: 2, 808: 8, 810: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 831: 6, 832: 8, 838: 2, 840: 8, 844: 5, 847: 1, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 882: 8, 897: 8, 906: 8, 924: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 960: 4, 968: 8, 969: 4, 970: 8, 973: 8, 974: 5, 976: 8, 977: 4, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1062: 8, 1098: 8, 1100: 8, 1216: 8, 1218: 8, 1220: 8, 1223: 8, 1225: 8, 1227: 8, 1235: 8, 1242: 8, 1250: 8, 1251: 8, 1252: 8, 1254: 8, 1264: 8, 1284: 8, 1536: 8, 1537: 8, 1543: 8, 1545: 8, 1562: 8, 1568: 8, 1570: 8, 1572: 8, 1593: 8, 1856: 8, 1858: 8, 1860: 8, 1863: 8, 1865: 8, 1867: 8, 1875: 8, 1882: 8, 1890: 8, 1891: 8, 1892: 8, 1894: 8, 1896: 8, 1904: 8, 2015: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8
+ 55: 8, 168: 8, 179: 8, 181: 8, 256: 4, 257: 5, 258: 8, 264: 8, 268: 8, 272: 6, 273: 6, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 341: 8, 344: 8, 352: 8, 362: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 530: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 8, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 618: 8, 624: 8, 625: 8, 632: 8, 639: 8, 640: 1, 656: 4, 658: 6, 660: 8, 671: 8, 672: 8, 676: 8, 678: 8, 680: 8, 683: 8, 684: 8, 703: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 738: 8, 746: 5, 752: 2, 754: 8, 760: 8, 761: 8, 764: 8, 766: 8, 773: 8, 776: 8, 779: 8, 782: 8, 783: 8, 784: 8, 785: 8, 792: 8, 799: 8, 800: 8, 804: 8, 806: 2, 808: 8, 810: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 831: 6, 832: 8, 838: 2, 840: 8, 844: 5, 847: 1, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 874: 2, 882: 8, 897: 8, 906: 8, 924: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 960: 4, 968: 8, 969: 4, 970: 8, 973: 8, 974: 5, 976: 8, 977: 4, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1062: 8, 1098: 8, 1100: 8, 1216: 8, 1218: 8, 1220: 8, 1223: 8, 1225: 8, 1227: 8, 1235: 8, 1242: 8, 1250: 8, 1251: 8, 1252: 8, 1254: 8, 1264: 8, 1284: 8, 1536: 8, 1537: 8, 1543: 8, 1545: 8, 1562: 8, 1568: 8, 1570: 8, 1572: 8, 1593: 8, 1856: 8, 1858: 8, 1860: 8, 1863: 8, 1865: 8, 1867: 8, 1875: 8, 1882: 8, 1890: 8, 1891: 8, 1892: 8, 1894: 8, 1896: 8, 1904: 8, 2015: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8
}],
}
diff --git a/selfdrive/car/docs.py b/selfdrive/car/docs.py
index 03313e2ff6..bc03619d0d 100755
--- a/selfdrive/car/docs.py
+++ b/selfdrive/car/docs.py
@@ -29,7 +29,7 @@ def get_all_car_info() -> List[CarInfo]:
all_car_info: List[CarInfo] = []
footnotes = get_all_footnotes()
for model, car_info in get_interface_attr("CAR_INFO", combine_brands=True).items():
- CP = interfaces[model][0].get_params(model, fingerprint=gen_empty_fingerprint(), car_fw=[car.CarParams.CarFw(ecu="unknown")])
+ CP = interfaces[model][0].get_params(model, fingerprint=gen_empty_fingerprint(), car_fw=[car.CarParams.CarFw(ecu="unknown")], experimental_long=False)
if CP.dashcamOnly or car_info is None:
continue
diff --git a/selfdrive/car/docs_definitions.py b/selfdrive/car/docs_definitions.py
index 03e9e721b5..c0fb4420df 100644
--- a/selfdrive/car/docs_definitions.py
+++ b/selfdrive/car/docs_definitions.py
@@ -21,6 +21,7 @@ class Column(Enum):
STEERING_TORQUE = "Steering Torque"
AUTO_RESUME = "Resume from stop"
HARNESS = "Harness"
+ VIDEO = "Video"
class Star(Enum):
@@ -125,20 +126,11 @@ class CarInfo:
harness: Enum = Harness.none
def init(self, CP: car.CarParams, all_footnotes: Dict[Enum, int]):
- # TODO: set all the min steer speeds in carParams and remove this
- if self.min_steer_speed is not None:
- assert CP.minSteerSpeed == 0, f"{CP.carFingerprint}: Minimum steer speed set in both CarInfo and CarParams"
- else:
- self.min_steer_speed = CP.minSteerSpeed
-
- # TODO: set all the min enable speeds in carParams correctly and remove this
- if self.min_enable_speed is None:
- self.min_enable_speed = CP.minEnableSpeed
-
self.car_name = CP.carName
self.car_fingerprint = CP.carFingerprint
self.make, self.model, self.years = split_name(self.name)
+ # longitudinal column
op_long = "Stock"
if CP.openpilotLongitudinalControl and not CP.enableDsu:
op_long = "openpilot"
@@ -149,6 +141,23 @@ class CarInfo:
else:
self.footnotes.append(CommonFootnote.EXP_LONG_AVAIL)
+ # min steer & enable speed columns
+ # TODO: set all the min steer speeds in carParams and remove this
+ if self.min_steer_speed is not None:
+ assert CP.minSteerSpeed == 0, f"{CP.carFingerprint}: Minimum steer speed set in both CarInfo and CarParams"
+ else:
+ self.min_steer_speed = CP.minSteerSpeed
+
+ # TODO: set all the min enable speeds in carParams correctly and remove this
+ if self.min_enable_speed is None:
+ self.min_enable_speed = CP.minEnableSpeed
+
+ # harness column
+ harness_col = self.harness.value
+ if self.harness is not Harness.none:
+ model_years = self.model + (' ' + self.years if self.years else '')
+ harness_col = f'{harness_col}'
+
self.row = {
Column.MAKE: self.make,
Column.MODEL: self.model,
@@ -158,7 +167,8 @@ class CarInfo:
Column.FSR_STEERING: f"{max(self.min_steer_speed * CV.MS_TO_MPH, 0):.0f} mph",
Column.STEERING_TORQUE: Star.EMPTY,
Column.AUTO_RESUME: Star.FULL if CP.autoResumeSng else Star.EMPTY,
- Column.HARNESS: self.harness.value,
+ Column.HARNESS: harness_col,
+ Column.VIDEO: self.video_link if self.video_link is not None else "", # replaced with an image and link from template in get_column
}
# Set steering torque star from max lateral acceleration
@@ -194,6 +204,13 @@ class CarInfo:
if self.row[Column.STEERING_TORQUE] != Star.FULL:
sentence_builder += " This car may not be able to take tight turns on its own."
+ # experimental mode
+ exp_link = "Experimental mode"
+ if CP.openpilotLongitudinalControl or CP.experimentalLongitudinalAvailable:
+ sentence_builder += f" Traffic light and stop sign handling is also available in {exp_link}."
+ else:
+ sentence_builder += f" {exp_link}, with traffic light and stop sign handling, is not currently available for this car, but may be added in a future software update."
+
return sentence_builder.format(car_model=f"{self.make} {self.model}", alc=alc, acc=acc)
else:
@@ -202,12 +219,14 @@ class CarInfo:
else:
raise Exception(f"This notCar does not have a detail sentence: {CP.carFingerprint}")
- def get_column(self, column: Column, star_icon: str, footnote_tag: str) -> str:
+ def get_column(self, column: Column, star_icon: str, video_icon: str, footnote_tag: str) -> str:
item: Union[str, Star] = self.row[column]
if isinstance(item, Star):
item = star_icon.format(item.value)
elif column == Column.MODEL and len(self.years):
item += f" {self.years}"
+ elif column == Column.VIDEO and len(item) > 0:
+ item = video_icon.format(item)
footnotes = get_footnotes(self.footnotes, column)
if len(footnotes):
diff --git a/selfdrive/car/ecu_addrs.py b/selfdrive/car/ecu_addrs.py
index 9f6ace2b5f..e5d550fac8 100755
--- a/selfdrive/car/ecu_addrs.py
+++ b/selfdrive/car/ecu_addrs.py
@@ -87,5 +87,5 @@ if __name__ == "__main__":
for addr, subaddr, bus in ecu_addrs:
msg = f" 0x{hex(addr)}"
if subaddr is not None:
- msg += f" (sub-address: 0x{hex(subaddr)})"
+ msg += f" (sub-address: {hex(subaddr)})"
print(msg)
diff --git a/selfdrive/car/ford/carcontroller.py b/selfdrive/car/ford/carcontroller.py
index 8c391bb276..99072ae975 100644
--- a/selfdrive/car/ford/carcontroller.py
+++ b/selfdrive/car/ford/carcontroller.py
@@ -1,28 +1,14 @@
-import math
from cereal import car
-from common.numpy_fast import clip, interp
+from common.numpy_fast import clip
from opendbc.can.packer import CANPacker
-from selfdrive.car.ford import fordcan
-from selfdrive.car.ford.values import CANBUS, CarControllerParams
+from selfdrive.car import apply_std_steer_angle_limits
+from selfdrive.car.ford.fordcan import create_acc_command, create_acc_ui_msg, create_button_msg, create_lat_ctl_msg, \
+ create_lat_ctl2_msg, create_lka_msg, create_lkas_ui_msg
+from selfdrive.car.ford.values import CANBUS, CANFD_CARS, CarControllerParams
VisualAlert = car.CarControl.HUDControl.VisualAlert
-def apply_ford_steer_angle_limits(apply_angle, apply_angle_last, vEgo):
- # rate limit
- steer_up = apply_angle_last * apply_angle > 0. and abs(apply_angle) > abs(apply_angle_last)
- rate_limit = CarControllerParams.RATE_LIMIT_UP if steer_up else CarControllerParams.RATE_LIMIT_DOWN
- max_angle_diff = interp(vEgo, rate_limit.speed_points, rate_limit.max_angle_diff_points)
- apply_angle = clip(apply_angle, (apply_angle_last - max_angle_diff), (apply_angle_last + max_angle_diff))
-
- # absolute limit (LatCtlPath_An_Actl)
- apply_path_angle = math.radians(apply_angle) / CarControllerParams.LKAS_STEER_RATIO
- apply_path_angle = clip(apply_path_angle, -0.5, 0.5235)
- apply_angle = math.degrees(apply_path_angle) * CarControllerParams.LKAS_STEER_RATIO
-
- return apply_angle
-
-
class CarController:
def __init__(self, dbc_name, CP, VM):
self.CP = CP
@@ -30,12 +16,12 @@ class CarController:
self.packer = CANPacker(dbc_name)
self.frame = 0
- self.apply_angle_last = 0
+ self.apply_curvature_last = 0
self.main_on_last = False
self.lkas_enabled_last = False
self.steer_alert_last = False
- def update(self, CC, CS):
+ def update(self, CC, CS, now_nanos):
can_sends = []
actuators = CC.actuators
@@ -46,66 +32,69 @@ class CarController:
### acc buttons ###
if CC.cruiseControl.cancel:
- can_sends.append(fordcan.create_button_command(self.packer, CS.buttons_stock_values, cancel=True))
- can_sends.append(fordcan.create_button_command(self.packer, CS.buttons_stock_values, cancel=True, bus=CANBUS.main))
+ can_sends.append(create_button_msg(self.packer, CS.buttons_stock_values, cancel=True))
+ can_sends.append(create_button_msg(self.packer, CS.buttons_stock_values, cancel=True, bus=CANBUS.main))
elif CC.cruiseControl.resume and (self.frame % CarControllerParams.BUTTONS_STEP) == 0:
- can_sends.append(fordcan.create_button_command(self.packer, CS.buttons_stock_values, resume=True))
- can_sends.append(fordcan.create_button_command(self.packer, CS.buttons_stock_values, resume=True, bus=CANBUS.main))
+ can_sends.append(create_button_msg(self.packer, CS.buttons_stock_values, resume=True))
+ can_sends.append(create_button_msg(self.packer, CS.buttons_stock_values, resume=True, bus=CANBUS.main))
# if stock lane centering isn't off, send a button press to toggle it off
# the stock system checks for steering pressed, and eventually disengages cruise control
elif CS.acc_tja_status_stock_values["Tja_D_Stat"] != 0 and (self.frame % CarControllerParams.ACC_UI_STEP) == 0:
- can_sends.append(fordcan.create_button_command(self.packer, CS.buttons_stock_values, tja_toggle=True))
-
+ can_sends.append(create_button_msg(self.packer, CS.buttons_stock_values, tja_toggle=True))
### lateral control ###
- if CC.latActive:
- lca_rq = 1
- apply_angle = apply_ford_steer_angle_limits(actuators.steeringAngleDeg, self.apply_angle_last, CS.out.vEgo)
- else:
- lca_rq = 0
- apply_angle = 0.
-
# send steering commands at 20Hz
if (self.frame % CarControllerParams.STEER_STEP) == 0:
- # use LatCtlPath_An_Actl to actuate steering
- path_angle = math.radians(apply_angle) / CarControllerParams.LKAS_STEER_RATIO
-
- # set slower ramp type when small steering angle change
- # 0=Slow, 1=Medium, 2=Fast, 3=Immediately
- steer_change = abs(CS.out.steeringAngleDeg - actuators.steeringAngleDeg)
- if steer_change < 2.0:
- ramp_type = 0
- elif steer_change < 4.0:
- ramp_type = 1
- elif steer_change < 6.0:
- ramp_type = 2
+ if CC.latActive:
+ # apply limits to curvature and clip to signal range
+ apply_curvature = apply_std_steer_angle_limits(actuators.curvature, self.apply_curvature_last, CS.out.vEgo, CarControllerParams)
+ apply_curvature = clip(apply_curvature, -CarControllerParams.CURVATURE_MAX, CarControllerParams.CURVATURE_MAX)
else:
- ramp_type = 3
- precision = 1 # 0=Comfortable, 1=Precise (the stock system always uses comfortable)
+ apply_curvature = 0.
- self.apply_angle_last = apply_angle
- can_sends.append(fordcan.create_lka_command(self.packer, 0, 0))
- can_sends.append(fordcan.create_tja_command(self.packer, lca_rq, ramp_type, precision,
- 0, path_angle, 0, 0))
+ self.apply_curvature_last = apply_curvature
+ can_sends.append(create_lka_msg(self.packer))
+
+ if self.CP.carFingerprint in CANFD_CARS:
+ # TODO: extended mode
+ mode = 1 if CC.latActive else 0
+ counter = self.frame // CarControllerParams.STEER_STEP
+ can_sends.append(create_lat_ctl2_msg(self.packer, mode, 0., 0., -apply_curvature, 0., counter))
+ else:
+ can_sends.append(create_lat_ctl_msg(self.packer, CC.latActive, 0., 0., -apply_curvature, 0.))
+
+ ### longitudinal control ###
+ # send acc command at 50Hz
+ if self.CP.openpilotLongitudinalControl and (self.frame % CarControllerParams.ACC_CONTROL_STEP) == 0:
+ accel = clip(actuators.accel, CarControllerParams.ACCEL_MIN, CarControllerParams.ACCEL_MAX)
+
+ precharge_brake = accel < -0.1
+ if accel > -0.5:
+ gas = accel
+ decel = False
+ else:
+ gas = -5.0
+ decel = True
+ can_sends.append(create_acc_command(self.packer, CC.longActive, gas, accel, precharge_brake, decel))
### ui ###
send_ui = (self.main_on_last != main_on) or (self.lkas_enabled_last != CC.latActive) or (self.steer_alert_last != steer_alert)
# send lkas ui command at 1Hz or if ui state changes
if (self.frame % CarControllerParams.LKAS_UI_STEP) == 0 or send_ui:
- can_sends.append(fordcan.create_lkas_ui_command(self.packer, main_on, CC.latActive, steer_alert, hud_control, CS.lkas_status_stock_values))
+ can_sends.append(create_lkas_ui_msg(self.packer, main_on, CC.latActive, steer_alert, hud_control, CS.lkas_status_stock_values))
# send acc ui command at 20Hz or if ui state changes
if (self.frame % CarControllerParams.ACC_UI_STEP) == 0 or send_ui:
- can_sends.append(fordcan.create_acc_ui_command(self.packer, main_on, CC.latActive, hud_control, CS.acc_tja_status_stock_values))
+ can_sends.append(create_acc_ui_msg(self.packer, main_on, CC.latActive, hud_control, CS.acc_tja_status_stock_values))
self.main_on_last = main_on
self.lkas_enabled_last = CC.latActive
self.steer_alert_last = steer_alert
new_actuators = actuators.copy()
- new_actuators.steeringAngleDeg = self.apply_angle_last
+ new_actuators.curvature = self.apply_curvature_last
self.frame += 1
return new_actuators, can_sends
diff --git a/selfdrive/car/ford/carstate.py b/selfdrive/car/ford/carstate.py
index 2276b1208a..21af1062f3 100644
--- a/selfdrive/car/ford/carstate.py
+++ b/selfdrive/car/ford/carstate.py
@@ -14,7 +14,7 @@ class CarState(CarStateBase):
super().__init__(CP)
can_define = CANDefine(DBC[CP.carFingerprint]["pt"])
if CP.transmissionType == TransmissionType.automatic:
- self.shifter_values = can_define.dv["Gear_Shift_by_Wire_FD1"]["TrnGear_D_RqDrv"]
+ self.shifter_values = can_define.dv["Gear_Shift_by_Wire_FD1"]["TrnRng_D_RqGsm"]
def update(self, cp, cp_cam):
ret = car.CarState.new_message()
@@ -37,7 +37,7 @@ class CarState(CarStateBase):
# steering wheel
ret.steeringAngleDeg = cp.vl["SteeringPinion_Data"]["StePinComp_An_Est"]
ret.steeringTorque = cp.vl["EPAS_INFO"]["SteeringColumnTorque"]
- ret.steeringPressed = abs(ret.steeringTorque) > CarControllerParams.STEER_DRIVER_ALLOWANCE
+ ret.steeringPressed = self.update_steering_pressed(abs(ret.steeringTorque) > CarControllerParams.STEER_DRIVER_ALLOWANCE, 5)
ret.steerFaultTemporary = cp.vl["EPAS_INFO"]["EPAS_Failure"] == 1
ret.steerFaultPermanent = cp.vl["EPAS_INFO"]["EPAS_Failure"] in (2, 3)
# ret.espDisabled = False # TODO: find traction control signal
@@ -51,7 +51,7 @@ class CarState(CarStateBase):
# gear
if self.CP.transmissionType == TransmissionType.automatic:
- gear = self.shifter_values.get(cp.vl["Gear_Shift_by_Wire_FD1"]["TrnGear_D_RqDrv"], None)
+ gear = self.shifter_values.get(cp.vl["Gear_Shift_by_Wire_FD1"]["TrnRng_D_RqGsm"])
ret.gearShifter = self.parse_gear_shifter(gear)
elif self.CP.transmissionType == TransmissionType.manual:
ret.clutchPressed = cp.vl["Engine_Clutch_Data"]["CluPdlPos_Pc_Meas"] > 0
@@ -118,7 +118,7 @@ class CarState(CarStateBase):
("DrStatRl_B_Actl", "BodyInfo_3_FD1"), # BCM Door open, rear left
("DrStatRr_B_Actl", "BodyInfo_3_FD1"), # BCM Door open, rear right
("FirstRowBuckleDriver", "RCMStatusMessage2_FD1"), # RCM Seatbelt status, driver
- ("HeadLghtHiFlash_D_Stat", "Steering_Data_FD1"), # SCCM Passthru the remaining buttons
+ ("HeadLghtHiFlash_D_Stat", "Steering_Data_FD1"), # SCCM Passthrough the remaining buttons
("WiprFront_D_Stat", "Steering_Data_FD1"),
("LghtAmb_D_Sns", "Steering_Data_FD1"),
("AccButtnGapDecPress", "Steering_Data_FD1"),
@@ -171,7 +171,7 @@ class CarState(CarStateBase):
if CP.transmissionType == TransmissionType.automatic:
signals += [
- ("TrnGear_D_RqDrv", "Gear_Shift_by_Wire_FD1"), # GWM transmission gear position
+ ("TrnRng_D_RqGsm", "Gear_Shift_by_Wire_FD1"), # GWM transmission gear position
]
checks += [
("Gear_Shift_by_Wire_FD1", 10),
diff --git a/selfdrive/car/ford/fordcan.py b/selfdrive/car/ford/fordcan.py
index 373ce096c6..594d50f59f 100644
--- a/selfdrive/car/ford/fordcan.py
+++ b/selfdrive/car/ford/fordcan.py
@@ -4,64 +4,120 @@ from selfdrive.car.ford.values import CANBUS
HUDControl = car.CarControl.HUDControl
-def create_lka_command(packer, angle_deg: float, curvature: float):
+def calculate_lat_ctl2_checksum(mode: int, counter: int, dat: bytearray):
+ checksum = mode + counter
+ checksum += dat[2] + ((dat[3] & 0xE0) >> 5) # curvature
+ checksum += dat[6] + ((dat[7] & 0xE0) >> 5) # curvature rate
+ checksum += (dat[3] & 0x1F) + ((dat[4] & 0xFC) >> 2) # path angle
+ checksum += (dat[4] & 0x3) + dat[5] # path offset
+ return 0xFF - (checksum & 0xFF)
+
+
+def create_lka_msg(packer):
"""
- Creates a CAN message for the Ford LKAS Command.
+ Creates an empty CAN message for the Ford LKA Command.
This command can apply "Lane Keeping Aid" manoeuvres, which are subject to the PSCM lockout.
Frequency is 20Hz.
"""
- values = {
- "LkaDrvOvrrd_D_Rq": 0, # driver override level? [0|3]
- "LkaActvStats_D2_Req": 0, # action [0|7]
- "LaRefAng_No_Req": angle_deg, # angle [-102.4|102.3] degrees
- "LaRampType_B_Req": 0, # Ramp speed: 0=Smooth, 1=Quick
- "LaCurvature_No_Calc": curvature, # curvature [-0.01024|0.01023] 1/meter
- "LdwActvStats_D_Req": 0, # LDW status [0|7]
- "LdwActvIntns_D_Req": 0, # LDW intensity [0|3], shake alert strength
- }
- return packer.make_can_msg("Lane_Assist_Data1", CANBUS.main, values)
+ return packer.make_can_msg("Lane_Assist_Data1", CANBUS.main, {})
-def create_tja_command(packer, lca_rq: int, ramp_type: int, precision: int, path_offset: float, path_angle: float, curvature_rate: float, curvature: float):
+def create_lat_ctl_msg(packer, lat_active: bool, path_offset: float, path_angle: float, curvature: float,
+ curvature_rate: float):
"""
Creates a CAN message for the Ford TJA/LCA Command.
- This command can apply "Lane Centering" manoeuvres: continuous lane centering for traffic jam
- assist and highway driving. It is not subject to the PSCM lockout.
+ This command can apply "Lane Centering" manoeuvres: continuous lane centering for traffic jam assist and highway
+ driving. It is not subject to the PSCM lockout.
- Ford lane centering command uses a third order polynomial to describe the road centerline. The
- polynomial is defined by the following coefficients:
- c0: lateral offset between the vehicle and the centerline
- c1: heading angle between the vehicle and the centerline
- c2: curvature of the centerline
+ Ford lane centering command uses a third order polynomial to describe the road centerline. The polynomial is defined
+ by the following coefficients:
+ c0: lateral offset between the vehicle and the centerline (positive is right)
+ c1: heading angle between the vehicle and the centerline (positive is right)
+ c2: curvature of the centerline (positive is left)
c3: rate of change of curvature of the centerline
- As the PSCM combines this information with other sensor data, such as the vehicle's yaw rate and
- speed, the steering angle cannot be easily controlled.
+ As the PSCM combines this information with other sensor data, such as the vehicle's yaw rate and speed, the steering
+ angle cannot be easily controlled.
- The PSCM should be configured to accept TJA/LCA commands before these commands will be processed.
- This can be done using tools such as Forscan.
+ The PSCM should be configured to accept TJA/LCA commands before these commands will be processed. This can be done
+ using tools such as Forscan.
Frequency is 20Hz.
"""
values = {
- "LatCtlRng_L_Max": 0, # Unknown [0|126] meter
- "HandsOffCnfm_B_Rq": 0, # Unknown: 0=Inactive, 1=Active [0|1]
- "LatCtl_D_Rq": lca_rq, # Mode: 0=None, 1=ContinuousPathFollowing, 2=InterventionLeft, 3=InterventionRight, 4-7=NotUsed [0|7]
- "LatCtlRampType_D_Rq": ramp_type, # Ramp speed: 0=Slow, 1=Medium, 2=Fast, 3=Immediate [0|3]
- "LatCtlPrecision_D_Rq": precision, # Precision: 0=Comfortable, 1=Precise, 2/3=NotUsed [0|3]
- "LatCtlPathOffst_L_Actl": path_offset, # Path offset [-5.12|5.11] meter
- "LatCtlPath_An_Actl": path_angle, # Path angle [-0.5|0.5235] radians
- "LatCtlCurv_NoRate_Actl": curvature_rate, # Curvature rate [-0.001024|0.00102375] 1/meter^2
- "LatCtlCurv_No_Actl": curvature, # Curvature [-0.02|0.02094] 1/meter
+ "LatCtlRng_L_Max": 0, # Unknown [0|126] meter
+ "HandsOffCnfm_B_Rq": 0, # Unknown: 0=Inactive, 1=Active [0|1]
+ "LatCtl_D_Rq": 1 if lat_active else 0, # Mode: 0=None, 1=ContinuousPathFollowing, 2=InterventionLeft,
+ # 3=InterventionRight, 4-7=NotUsed [0|7]
+ "LatCtlRampType_D_Rq": 0, # Ramp speed: 0=Slow, 1=Medium, 2=Fast, 3=Immediate [0|3]
+ # Makes no difference with curvature control
+ "LatCtlPrecision_D_Rq": 1, # Precision: 0=Comfortable, 1=Precise, 2/3=NotUsed [0|3]
+ # The stock system always uses comfortable
+ "LatCtlPathOffst_L_Actl": path_offset, # Path offset [-5.12|5.11] meter
+ "LatCtlPath_An_Actl": path_angle, # Path angle [-0.5|0.5235] radians
+ "LatCtlCurv_NoRate_Actl": curvature_rate, # Curvature rate [-0.001024|0.00102375] 1/meter^2
+ "LatCtlCurv_No_Actl": curvature, # Curvature [-0.02|0.02094] 1/meter
}
return packer.make_can_msg("LateralMotionControl", CANBUS.main, values)
-def create_lkas_ui_command(packer, main_on: bool, enabled: bool, steer_alert: bool, hud_control, stock_values: dict):
+def create_lat_ctl2_msg(packer, mode: int, path_offset: float, path_angle: float, curvature: float,
+ curvature_rate: float, counter: int):
+ """
+ Create a CAN message for the new Ford Lane Centering command.
+
+ This message is used on the CAN FD platform and replaces the old LateralMotionControl message. It is similar but has
+ additional signals for a counter and checksum.
+
+ Frequency is 20Hz.
+ """
+
+ values = {
+ "LatCtl_D2_Rq": mode, # Mode: 0=None, 1=PathFollowingLimitedMode, 2=PathFollowingExtendedMode,
+ # 3=SafeRampOut, 4-7=NotUsed [0|7]
+ "LatCtlRampType_D_Rq": 0, # 0=Slow, 1=Medium, 2=Fast, 3=Immediate [0|3]
+ "LatCtlPrecision_D_Rq": 1, # 0=Comfortable, 1=Precise, 2/3=NotUsed [0|3]
+ "LatCtlPathOffst_L_Actl": path_offset, # [-5.12|5.11] meter
+ "LatCtlPath_An_Actl": path_angle, # [-0.5|0.5235] radians
+ "LatCtlCurv_No_Actl": curvature, # [-0.02|0.02094] 1/meter
+ "LatCtlCrv_NoRate2_Actl": curvature_rate, # [-0.001024|0.001023] 1/meter^2
+ "HandsOffCnfm_B_Rq": 0, # 0=Inactive, 1=Active [0|1]
+ "LatCtlPath_No_Cnt": counter, # [0|15]
+ "LatCtlPath_No_Cs": 0, # [0|255]
+ }
+
+ # calculate checksum
+ dat = packer.make_can_msg("LateralMotionControl2", CANBUS.main, values)[2]
+ values["LatCtlPath_No_Cs"] = calculate_lat_ctl2_checksum(mode, counter, dat)
+
+ return packer.make_can_msg("LateralMotionControl2", CANBUS.main, values)
+
+
+def create_acc_command(packer, long_active: bool, gas: float, accel: float, precharge_brake: bool, decel: bool):
+ """
+ Creates a CAN message for the Ford ACC Command.
+
+ This command can be used to enable ACC, to set the ACC gas/brake/decel values
+ and to disable ACC.
+
+ Frequency is 50Hz.
+ """
+
+ values = {
+ "AccBrkTot_A_Rq": accel, # Brake total accel request: [-20|11.9449] m/s^2
+ "Cmbb_B_Enbl": 1 if long_active else 0, # Enabled: 0=No, 1=Yes
+ "AccPrpl_A_Rq": gas, # Acceleration request: [-5|5.23] m/s^2
+ "AccBrkPrchg_B_Rq": 1 if precharge_brake else 0, # Pre-charge brake request: 0=No, 1=Yes
+ "AccBrkDecel_B_Rq": 1 if decel else 0, # Deceleration request: 0=Inactive, 1=Active
+ }
+ return packer.make_can_msg("ACCDATA", CANBUS.main, values)
+
+
+def create_lkas_ui_msg(packer, main_on: bool, enabled: bool, steer_alert: bool, hud_control, stock_values: dict):
"""
Creates a CAN message for the Ford IPC IPMA/LKAS status.
@@ -107,16 +163,15 @@ def create_lkas_ui_command(packer, main_on: bool, enabled: bool, steer_alert: bo
values = {
**stock_values,
- "LaActvStats_D_Dsply": lines, # LKAS status (lines) [0|31]
- "LaHandsOff_D_Dsply": hands_on_wheel_dsply, # 0=HandsOn, 1=Level1 (w/o chime), 2=Level2 (w/ chime), 3=Suppressed
+ "LaActvStats_D_Dsply": lines, # LKAS status (lines) [0|31]
+ "LaHandsOff_D_Dsply": hands_on_wheel_dsply, # 0=HandsOn, 1=Level1 (w/o chime), 2=Level2 (w/ chime), 3=Suppressed
}
return packer.make_can_msg("IPMA_Data", CANBUS.main, values)
-def create_acc_ui_command(packer, main_on: bool, enabled: bool, hud_control, stock_values: dict):
+def create_acc_ui_msg(packer, main_on: bool, enabled: bool, hud_control, stock_values: dict):
"""
- Creates a CAN message for the Ford IPC adaptive cruise, forward collision warning and traffic jam
- assist status.
+ Creates a CAN message for the Ford IPC adaptive cruise, forward collision warning and traffic jam assist status.
Stock functionality is maintained by passing through unmodified signals.
@@ -148,7 +203,8 @@ def create_acc_ui_command(packer, main_on: bool, enabled: bool, hud_control, sto
return packer.make_can_msg("ACCDATA_3", CANBUS.main, values)
-def create_button_command(packer, stock_values: dict, cancel = False, resume = False, tja_toggle = False, bus: int = CANBUS.camera):
+def create_button_msg(packer, stock_values: dict, cancel=False, resume=False, tja_toggle=False,
+ bus: int = CANBUS.camera):
"""
Creates a CAN message for the Ford SCCM buttons/switches.
diff --git a/selfdrive/car/ford/interface.py b/selfdrive/car/ford/interface.py
index f3d77bc05a..9e1366618c 100644
--- a/selfdrive/car/ford/interface.py
+++ b/selfdrive/car/ford/interface.py
@@ -2,39 +2,52 @@
from cereal import car
from common.conversions import Conversions as CV
from selfdrive.car import STD_CARGO_KG, get_safety_config
-from selfdrive.car.ford.values import CAR, Ecu, TransmissionType, GearShifter
+from selfdrive.car.ford.values import CAR, Ecu
from selfdrive.car.interfaces import CarInterfaceBase
-CarParams = car.CarParams
+TransmissionType = car.CarParams.TransmissionType
+GearShifter = car.CarState.GearShifter
class CarInterface(CarInterfaceBase):
@staticmethod
def _get_params(ret, candidate, fingerprint, car_fw, experimental_long):
ret.carName = "ford"
+ ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.ford)]
+
+ # These cars are dashcam only until the port is finished
ret.dashcamOnly = True
- ret.safetyConfigs = [get_safety_config(CarParams.SafetyModel.ford)]
- # Angle-based steering
- ret.steerControlType = CarParams.SteerControlType.angle
- ret.steerActuatorDelay = 0.4
+ ret.radarUnavailable = True
+ ret.steerControlType = car.CarParams.SteerControlType.angle
+ ret.steerActuatorDelay = 0.2
ret.steerLimitTimer = 1.0
- if candidate == CAR.ESCAPE_MK4:
+ if candidate == CAR.BRONCO_SPORT_MK1:
+ ret.wheelbase = 2.67
+ ret.steerRatio = 17.7
+ ret.mass = 1625 + STD_CARGO_KG
+
+ elif candidate == CAR.ESCAPE_MK4:
ret.wheelbase = 2.71
- ret.steerRatio = 14.3 # Copied from Focus
+ ret.steerRatio = 16.7
ret.mass = 1750 + STD_CARGO_KG
elif candidate == CAR.EXPLORER_MK6:
ret.wheelbase = 3.025
- ret.steerRatio = 16.8 # learned
+ ret.steerRatio = 16.8
ret.mass = 2050 + STD_CARGO_KG
elif candidate == CAR.FOCUS_MK4:
ret.wheelbase = 2.7
- ret.steerRatio = 13.8 # learned
+ ret.steerRatio = 15.0
ret.mass = 1350 + STD_CARGO_KG
+ elif candidate == CAR.MAVERICK_MK1:
+ ret.wheelbase = 3.076
+ ret.steerRatio = 17.0
+ ret.mass = 1650 + STD_CARGO_KG
+
else:
raise ValueError(f"Unsupported car: {candidate}")
@@ -65,5 +78,5 @@ class CarInterface(CarInterfaceBase):
return ret
- def apply(self, c):
- return self.CC.update(c, self.CS)
+ def apply(self, c, now_nanos):
+ return self.CC.update(c, self.CS, now_nanos)
diff --git a/selfdrive/car/ford/radar_interface.py b/selfdrive/car/ford/radar_interface.py
index c942703002..ee4efb311d 100644
--- a/selfdrive/car/ford/radar_interface.py
+++ b/selfdrive/car/ford/radar_interface.py
@@ -47,7 +47,7 @@ class RadarInterface(RadarInterfaceBase):
self.updated_messages = set()
self.track_id = 0
self.radar = DBC[CP.carFingerprint]['radar']
- if self.radar is None:
+ if self.radar is None or CP.radarUnavailable:
self.rcp = None
elif self.radar == RADAR.DELPHI_ESR:
self.rcp = _create_delphi_esr_radar_can_parser()
diff --git a/selfdrive/car/ford/values.py b/selfdrive/car/ford/values.py
index 0e6ef464b3..3bc56eb9dd 100644
--- a/selfdrive/car/ford/values.py
+++ b/selfdrive/car/ford/values.py
@@ -1,23 +1,21 @@
-from collections import defaultdict, namedtuple
+from collections import defaultdict
from dataclasses import dataclass
from enum import Enum
-from typing import Dict, List, Union
+from typing import Dict, List, Set, Union
from cereal import car
-from selfdrive.car import dbc_dict
+from selfdrive.car import AngleRateLimit, dbc_dict
from selfdrive.car.docs_definitions import CarInfo, Harness
from selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries
Ecu = car.CarParams.Ecu
-TransmissionType = car.CarParams.TransmissionType
-GearShifter = car.CarState.GearShifter
-
-AngleRateLimit = namedtuple('AngleRateLimit', ['speed_points', 'max_angle_diff_points'])
class CarControllerParams:
# Messages: Lane_Assist_Data1, LateralMotionControl
STEER_STEP = 5
+ # Message: ACCDATA
+ ACC_CONTROL_STEP = 2
# Message: IPMA_Data
LKAS_UI_STEP = 100
# Message: ACCDATA_3
@@ -25,12 +23,17 @@ class CarControllerParams:
# Message: Steering_Data_FD1, but send twice as fast
BUTTONS_STEP = 10 / 2
- LKAS_STEER_RATIO = 2.75 # Approximate ratio between LatCtlPath_An_Actl and steering angle in radians
- # TODO: remove this once we understand how the EPS calculates the steering angle better
- STEER_DRIVER_ALLOWANCE = 0.8 # Driver intervention threshold in Nm
+ CURVATURE_MAX = 0.02 # Max curvature for steering command, m^-1
+ STEER_DRIVER_ALLOWANCE = 1.0 # Driver intervention threshold, Nm
+
+ # Curvature rate limits
+ # TODO: unify field names used by curvature and angle control cars
+ # ~2 m/s^3 up, ~-3 m/s^3 down
+ ANGLE_RATE_LIMIT_UP = AngleRateLimit(speed_bp=[5, 15, 25], angle_v=[0.004, 0.00044, 0.00016])
+ ANGLE_RATE_LIMIT_DOWN = AngleRateLimit(speed_bp=[5, 15, 25], angle_v=[0.006, 0.00066, 0.00024])
- RATE_LIMIT_UP = AngleRateLimit(speed_points=[0., 5., 15.], max_angle_diff_points=[5., .8, .15])
- RATE_LIMIT_DOWN = AngleRateLimit(speed_points=[0., 5., 15.], max_angle_diff_points=[5., 3.5, 0.4])
+ ACCEL_MAX = 2.0 # m/s^s max acceleration
+ ACCEL_MIN = -3.5 # m/s^s max deceleration
def __init__(self, CP):
pass
@@ -43,9 +46,14 @@ class CANBUS:
class CAR:
+ BRONCO_SPORT_MK1 = "FORD BRONCO SPORT 1ST GEN"
ESCAPE_MK4 = "FORD ESCAPE 4TH GEN"
EXPLORER_MK6 = "FORD EXPLORER 6TH GEN"
FOCUS_MK4 = "FORD FOCUS 4TH GEN"
+ MAVERICK_MK1 = "FORD MAVERICK 1ST GEN"
+
+
+CANFD_CARS: Set[str] = set()
class RADAR:
@@ -63,12 +71,20 @@ class FordCarInfo(CarInfo):
CAR_INFO: Dict[str, Union[CarInfo, List[CarInfo]]] = {
+ CAR.BRONCO_SPORT_MK1: FordCarInfo("Ford Bronco Sport 2021-22"),
CAR.ESCAPE_MK4: [
- FordCarInfo("Ford Escape 2020-21"),
+ FordCarInfo("Ford Escape 2020-22"),
+ FordCarInfo("Ford Escape Plug-in Hybrid 2020-22"),
FordCarInfo("Ford Kuga 2020-21", "Driver Assistance Pack"),
+ FordCarInfo("Ford Kuga Plug-in Hybrid 2020-22", "Driver Assistance Pack"),
+ ],
+ CAR.EXPLORER_MK6: [
+ FordCarInfo("Ford Explorer 2020-22"),
+ FordCarInfo("Lincoln Aviator 2021", "Co-Pilot360 Plus"),
+ FordCarInfo("Lincoln Aviator Plug-in Hybrid 2021", "Co-Pilot360 Plus"),
],
- CAR.EXPLORER_MK6: FordCarInfo("Ford Explorer 2020-22"),
CAR.FOCUS_MK4: FordCarInfo("Ford Focus EU 2019", "Driver Assistance Pack"),
+ CAR.MAVERICK_MK1: FordCarInfo("Ford Maverick 2022", "Co-Pilot360 Assist"),
}
FW_QUERY_CONFIG = FwQueryConfig(
@@ -88,10 +104,35 @@ FW_QUERY_CONFIG = FwQueryConfig(
)
FW_VERSIONS = {
+ CAR.BRONCO_SPORT_MK1: {
+ (Ecu.eps, 0x730, None): [
+ b'LX6C-14D003-AH\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ b'LX6C-14D003-AK\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ ],
+ (Ecu.abs, 0x760, None): [
+ b'LX6C-2D053-RD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ b'LX6C-2D053-RE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ ],
+ (Ecu.fwdRadar, 0x764, None): [
+ b'LB5T-14D049-AB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ ],
+ (Ecu.fwdCamera, 0x706, None): [
+ b'M1PT-14F397-AC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ ],
+ (Ecu.engine, 0x7E0, None): [
+ b'M1PA-14C204-GF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ b'N1PA-14C204-AC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ ],
+ (Ecu.shiftByWire, 0x732, None): [
+ b'LX6P-14G395-AD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ b'PZ1P-14G395-AB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ ],
+ },
CAR.ESCAPE_MK4: {
(Ecu.eps, 0x730, None): [
b'LX6C-14D003-AF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
b'LX6C-14D003-AH\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ b'LX6C-14D003-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
],
(Ecu.abs, 0x760, None): [
b'LX6C-2D053-NS\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
@@ -109,10 +150,12 @@ FW_VERSIONS = {
b'LX6A-14C204-BJV\x00\x00\x00\x00\x00\x00\x00\x00\x00',
b'LX6A-14C204-ESG\x00\x00\x00\x00\x00\x00\x00\x00\x00',
b'MX6A-14C204-BEF\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ b'NX6A-14C204-BLE\x00\x00\x00\x00\x00\x00\x00\x00\x00',
],
(Ecu.shiftByWire, 0x732, None): [
b'LX6P-14G395-AB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
b'LX6P-14G395-AD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ b'PZ1P-14G395-AC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
],
},
CAR.EXPLORER_MK6: {
@@ -132,13 +175,16 @@ FW_VERSIONS = {
(Ecu.fwdCamera, 0x706, None): [
b'LB5T-14F397-AE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
b'LB5T-14F397-AF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ b'LC5T-14F397-AH\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
],
(Ecu.engine, 0x7E0, None): [
b'LB5A-14C204-EAC\x00\x00\x00\x00\x00\x00\x00\x00\x00',
b'MB5A-14C204-MD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ b'MB5A-14C204-RC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
b'NB5A-14C204-HB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
],
(Ecu.shiftByWire, 0x732, None): [
+ b'L1MP-14C561-AB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
b'L1MP-14G395-AD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
b'L1MP-14G395-AE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
b'L1MP-14G395-JB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
@@ -163,4 +209,26 @@ FW_VERSIONS = {
(Ecu.shiftByWire, 0x732, None): [
],
},
+ CAR.MAVERICK_MK1: {
+ (Ecu.eps, 0x730, None): [
+ b'NZ6C-14D003-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ ],
+ (Ecu.abs, 0x760, None): [
+ b'NZ6C-2D053-AG\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ ],
+ (Ecu.fwdRadar, 0x764, None): [
+ b'NZ6T-14D049-AA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ ],
+ (Ecu.fwdCamera, 0x706, None): [
+ b'NZ6T-14F397-AC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ ],
+ (Ecu.engine, 0x7E0, None): [
+ b'NZ6A-14C204-AAA\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ b'NZ6A-14C204-PA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ b'NZ6A-14C204-ZA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ ],
+ (Ecu.shiftByWire, 0x732, None): [
+ b'NZ6P-14G395-AD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ ],
+ },
}
diff --git a/selfdrive/car/fw_query_definitions.py b/selfdrive/car/fw_query_definitions.py
index c7e4d4eb30..dd3b19f6de 100755
--- a/selfdrive/car/fw_query_definitions.py
+++ b/selfdrive/car/fw_query_definitions.py
@@ -57,11 +57,16 @@ class Request:
whitelist_ecus: List[int] = field(default_factory=list)
rx_offset: int = 0x8
bus: int = 1
+ # FW responses from these queries will not be used for fingerprinting
+ logging: bool = False
+ # These requests are done once OBD multiplexing is disabled, after all others
+ non_obd: bool = False
@dataclass
class FwQueryConfig:
requests: List[Request]
+ # TODO: make this automatic and remove hardcoded lists, or do fingerprinting with ecus
# Overrides and removes from essential ecus for specific models and ecus (exact matching)
non_essential_ecus: Dict[capnp.lib.capnp._EnumModule, List[str]] = field(default_factory=dict)
# Ecus added for data collection, not to be fingerprinted on
diff --git a/selfdrive/car/fw_versions.py b/selfdrive/car/fw_versions.py
index f4d92ab960..8092ac0b76 100755
--- a/selfdrive/car/fw_versions.py
+++ b/selfdrive/car/fw_versions.py
@@ -5,6 +5,7 @@ from tqdm import tqdm
import panda.python.uds as uds
from cereal import car
+from common.params import Params
from selfdrive.car.ecu_addrs import get_ecu_addrs
from selfdrive.car.interfaces import get_interface_attr
from selfdrive.car.fingerprints import FW_VERSIONS
@@ -29,10 +30,9 @@ def chunks(l, n=128):
def build_fw_dict(fw_versions, filter_brand=None):
fw_versions_dict = defaultdict(set)
for fw in fw_versions:
- if filter_brand is None or fw.brand == filter_brand:
- addr = fw.address
+ if (filter_brand is None or fw.brand == filter_brand) and not fw.logging:
sub_addr = fw.subAddress if fw.subAddress != 0 else None
- fw_versions_dict[(addr, sub_addr)].add(fw.fwVersion)
+ fw_versions_dict[(fw.address, sub_addr)].add(fw.fwVersion)
return dict(fw_versions_dict)
@@ -90,7 +90,7 @@ def match_fw_to_car_fuzzy(fw_versions_dict, log=True, exclude=None):
return set()
-def match_fw_to_car_exact(fw_versions_dict):
+def match_fw_to_car_exact(fw_versions_dict) -> Set[str]:
"""Do an exact FW match. Returns all cars that match the given
FW versions for a list of "essential" ECUs. If an ECU is not considered
essential the FW version can be missing to get a fingerprint, but if it's present it
@@ -146,12 +146,16 @@ def match_fw_to_car(fw_versions, allow_exact=True, allow_fuzzy=True):
return True, set()
-def get_present_ecus(logcan, sendcan):
+def get_present_ecus(logcan, sendcan, num_pandas=1) -> Set[Tuple[int, Optional[int], int]]:
queries = list()
parallel_queries = list()
responses = set()
for brand, r in REQUESTS:
+ # Skip query if no panda available
+ if r.bus > num_pandas * 4 - 1:
+ continue
+
for brand_versions in VERSIONS[brand].values():
for ecu_type, addr, sub_addr in brand_versions:
# Only query ecus in whitelist if whitelist is not empty
@@ -171,7 +175,7 @@ def get_present_ecus(logcan, sendcan):
queries.insert(0, parallel_queries)
- ecu_responses: Set[Tuple[int, Optional[int], int]] = set()
+ ecu_responses = set()
for query in queries:
ecu_responses.update(get_ecu_addrs(logcan, sendcan, set(query), responses, timeout=0.1))
return ecu_responses
@@ -194,11 +198,21 @@ def get_brand_ecu_matches(ecu_rx_addrs):
return brand_matches
+def disable_obd_multiplexing(params):
+ if not params.get_bool("ObdMultiplexingDisabled"):
+ params.put_bool("FirmwareObdQueryDone", True)
+
+ cloudlog.warning("Waiting for OBD multiplexing to be disabled")
+ params.get_bool("ObdMultiplexingDisabled", block=True)
+ cloudlog.warning("OBD multiplexing disabled")
+
+
def get_fw_versions_ordered(logcan, sendcan, ecu_rx_addrs, timeout=0.1, num_pandas=1, debug=False, progress=False):
"""Queries for FW versions ordering brands by likelihood, breaks when exact match is found"""
all_car_fw = []
brand_matches = get_brand_ecu_matches(ecu_rx_addrs)
+ matched_brand: Optional[str] = None
for brand in sorted(brand_matches, key=lambda b: len(brand_matches[b]), reverse=True):
car_fw = get_fw_versions(logcan, sendcan, query_brand=brand, timeout=timeout, num_pandas=num_pandas, debug=debug, progress=progress)
@@ -206,12 +220,20 @@ def get_fw_versions_ordered(logcan, sendcan, ecu_rx_addrs, timeout=0.1, num_pand
# Try to match using FW returned from this brand only
matches = match_fw_to_car_exact(build_fw_dict(car_fw))
if len(matches) == 1:
+ matched_brand = brand
break
+ disable_obd_multiplexing(Params())
+
+ # Do non-OBD queries for matched brand, or all if no match is found
+ for brand in FW_QUERY_CONFIGS.keys():
+ if brand == matched_brand or matched_brand is None:
+ all_car_fw.extend(get_fw_versions(logcan, sendcan, query_brand=brand, timeout=timeout, num_pandas=num_pandas, obd_multiplexed=False, debug=debug, progress=progress))
+
return all_car_fw
-def get_fw_versions(logcan, sendcan, query_brand=None, extra=None, timeout=0.1, num_pandas=1, debug=False, progress=False):
+def get_fw_versions(logcan, sendcan, query_brand=None, extra=None, timeout=0.1, num_pandas=1, obd_multiplexed=True, debug=False, progress=False):
versions = VERSIONS.copy()
# Each brand can define extra ECUs to query for data collection
@@ -228,15 +250,19 @@ def get_fw_versions(logcan, sendcan, query_brand=None, extra=None, timeout=0.1,
# ECUs using a subaddress need be queried one by one, the rest can be done in parallel
addrs = []
parallel_addrs = []
+ logging_addrs = []
ecu_types = {}
for brand, brand_versions in versions.items():
- for c in brand_versions.values():
- for ecu_type, addr, sub_addr in c.keys():
+ for candidate, ecu in brand_versions.items():
+ for ecu_type, addr, sub_addr in ecu.keys():
a = (brand, addr, sub_addr)
if a not in ecu_types:
ecu_types[a] = ecu_type
+ if a not in logging_addrs and candidate == "debug":
+ logging_addrs.append(a)
+
if sub_addr is None:
if a not in parallel_addrs:
parallel_addrs.append(a)
@@ -255,6 +281,9 @@ def get_fw_versions(logcan, sendcan, query_brand=None, extra=None, timeout=0.1,
# Skip query if no panda available
if r.bus > num_pandas * 4 - 1:
continue
+ # Or if request is not designated for current multiplexing mode
+ elif r.non_obd == obd_multiplexed:
+ continue
try:
addrs = [(a, s) for (b, a, s) in addr_chunk if b in (brand, 'any') and
@@ -265,13 +294,15 @@ def get_fw_versions(logcan, sendcan, query_brand=None, extra=None, timeout=0.1,
for (tx_addr, sub_addr), version in query.get_data(timeout).items():
f = car.CarParams.CarFw.new_message()
- f.ecu = ecu_types.get((brand, tx_addr, sub_addr), Ecu.unknown)
+ ecu_key = (brand, tx_addr, sub_addr)
+ f.ecu = ecu_types.get(ecu_key, Ecu.unknown)
f.fwVersion = version
f.address = tx_addr
f.responseAddress = uds.get_rx_addr_for_tx_addr(tx_addr, r.rx_offset)
f.request = r.request
f.brand = brand
f.bus = r.bus
+ f.logging = r.logging or ecu_key in logging_addrs
if sub_addr is not None:
f.subAddress = sub_addr
diff --git a/selfdrive/car/gm/carcontroller.py b/selfdrive/car/gm/carcontroller.py
index b4a79d10a6..2a996c0ff6 100644
--- a/selfdrive/car/gm/carcontroller.py
+++ b/selfdrive/car/gm/carcontroller.py
@@ -3,7 +3,7 @@ from common.conversions import Conversions as CV
from common.numpy_fast import interp
from common.realtime import DT_CTRL
from opendbc.can.packer import CANPacker
-from selfdrive.car import apply_std_steer_torque_limits
+from selfdrive.car import apply_driver_steer_torque_limits
from selfdrive.car.gm import gmcan
from selfdrive.car.gm.values import DBC, CanBus, CarControllerParams, CruiseButtons
@@ -13,6 +13,8 @@ LongCtrlState = car.CarControl.Actuators.LongControlState
# Camera cancels up to 0.1s after brake is pressed, ECM allows 0.5s
CAMERA_CANCEL_DELAY_FRAMES = 10
+# Enforce a minimum interval between steering messages to avoid a fault
+MIN_STEER_MSG_INTERVAL_MS = 15
class CarController:
@@ -28,7 +30,6 @@ class CarController:
self.cancel_counter = 0
self.lka_steering_cmd_counter = 0
- self.sent_lka_steering_cmd = False
self.lka_icon_status_last = (False, False)
self.params = CarControllerParams(self.CP)
@@ -37,7 +38,7 @@ class CarController:
self.packer_obj = CANPacker(DBC[self.CP.carFingerprint]['radar'])
self.packer_ch = CANPacker(DBC[self.CP.carFingerprint]['chassis'])
- def update(self, CC, CS):
+ def update(self, CC, CS, now_nanos):
actuators = CC.actuators
hud_control = CC.hudControl
hud_alert = hud_control.visualAlert
@@ -49,25 +50,30 @@ class CarController:
can_sends = []
# Steering (Active: 50Hz, inactive: 10Hz)
- # Attempt to sync with camera on startup at 50Hz, first few msgs are blocked
- init_lka_counter = not self.sent_lka_steering_cmd and self.CP.networkLocation == NetworkLocation.fwdCamera
- steer_step = self.params.INACTIVE_STEER_STEP
- if CC.latActive or init_lka_counter:
- steer_step = self.params.STEER_STEP
-
- # Avoid GM EPS faults when transmitting messages too close together: skip this transmit if we just received the
- # next Panda loopback confirmation in the current CS frame.
- if CS.loopback_lka_steering_cmd_updated:
- self.lka_steering_cmd_counter += 1
- self.sent_lka_steering_cmd = True
- elif (self.frame - self.last_steer_frame) >= steer_step:
+ steer_step = self.params.STEER_STEP if CC.latActive else self.params.INACTIVE_STEER_STEP
+
+ if self.CP.networkLocation == NetworkLocation.fwdCamera:
+ # Also send at 50Hz:
+ # - on startup, first few msgs are blocked
+ # - until we're in sync with camera so counters align when relay closes, preventing a fault.
+ # openpilot can subtly drift, so this is activated throughout a drive to stay synced
+ out_of_sync = self.lka_steering_cmd_counter % 4 != (CS.cam_lka_steering_cmd_counter + 1) % 4
+ if CS.loopback_lka_steering_cmd_ts_nanos == 0 or out_of_sync:
+ steer_step = self.params.STEER_STEP
+
+ self.lka_steering_cmd_counter += 1 if CS.loopback_lka_steering_cmd_updated else 0
+
+ # Avoid GM EPS faults when transmitting messages too close together: skip this transmit if we
+ # received the ASCMLKASteeringCmd loopback confirmation too recently
+ last_lka_steer_msg_ms = (now_nanos - CS.loopback_lka_steering_cmd_ts_nanos) * 1e-6
+ if (self.frame - self.last_steer_frame) >= steer_step and last_lka_steer_msg_ms > MIN_STEER_MSG_INTERVAL_MS:
# Initialize ASCMLKASteeringCmd counter using the camera until we get a msg on the bus
- if init_lka_counter:
- self.lka_steering_cmd_counter = CS.camera_lka_steering_cmd_counter + 1
+ if CS.loopback_lka_steering_cmd_ts_nanos == 0:
+ self.lka_steering_cmd_counter = CS.pt_lka_steering_cmd_counter + 1
if CC.latActive:
new_steer = int(round(actuators.steer * self.params.STEER_MAX))
- apply_steer = apply_std_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.params)
+ apply_steer = apply_driver_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.params)
else:
apply_steer = 0
@@ -109,7 +115,7 @@ class CarController:
# Radar needs to know current speed and yaw rate (50hz),
# and that ADAS is alive (10hz)
- if not self.CP.radarOffCan:
+ if not self.CP.radarUnavailable:
tt = self.frame * DT_CTRL
time_and_headlights_step = 10
if self.frame % time_and_headlights_step == 0:
diff --git a/selfdrive/car/gm/carstate.py b/selfdrive/car/gm/carstate.py
index de0fd2eed6..2f9c952876 100644
--- a/selfdrive/car/gm/carstate.py
+++ b/selfdrive/car/gm/carstate.py
@@ -17,8 +17,13 @@ class CarState(CarStateBase):
super().__init__(CP)
can_define = CANDefine(DBC[CP.carFingerprint]["pt"])
self.shifter_values = can_define.dv["ECMPRDNL2"]["PRNDL2"]
+ self.cluster_speed_hyst_gap = CV.KPH_TO_MS / 2.
+ self.cluster_min_speed = CV.KPH_TO_MS / 2.
+
self.loopback_lka_steering_cmd_updated = False
- self.camera_lka_steering_cmd_counter = 0
+ self.loopback_lka_steering_cmd_ts_nanos = 0
+ self.pt_lka_steering_cmd_counter = 0
+ self.cam_lka_steering_cmd_counter = 0
self.buttons_counter = 0
def update(self, pt_cp, cam_cp, loopback_cp):
@@ -32,8 +37,11 @@ class CarState(CarStateBase):
# Variables used for avoiding LKAS faults
self.loopback_lka_steering_cmd_updated = len(loopback_cp.vl_all["ASCMLKASteeringCmd"]["RollingCounter"]) > 0
+ if self.loopback_lka_steering_cmd_updated:
+ self.loopback_lka_steering_cmd_ts_nanos = loopback_cp.ts_nanos["ASCMLKASteeringCmd"]["RollingCounter"]
if self.CP.networkLocation == NetworkLocation.fwdCamera:
- self.camera_lka_steering_cmd_counter = cam_cp.vl["ASCMLKASteeringCmd"]["RollingCounter"]
+ self.pt_lka_steering_cmd_counter = pt_cp.vl["ASCMLKASteeringCmd"]["RollingCounter"]
+ self.cam_lka_steering_cmd_counter = cam_cp.vl["ASCMLKASteeringCmd"]["RollingCounter"]
ret.wheelSpeeds = self.get_wheel_speeds(
pt_cp.vl["EBCMWheelSpdFront"]["FLWheelSpd"],
@@ -93,7 +101,8 @@ class CarState(CarStateBase):
ret.parkingBrake = pt_cp.vl["VehicleIgnitionAlt"]["ParkBrake"] == 1
ret.cruiseState.available = pt_cp.vl["ECMEngineStatus"]["CruiseMainOn"] != 0
ret.espDisabled = pt_cp.vl["ESPStatus"]["TractionControlOn"] != 1
- ret.accFaulted = pt_cp.vl["AcceleratorPedal2"]["CruiseState"] == AccState.FAULTED
+ ret.accFaulted = (pt_cp.vl["AcceleratorPedal2"]["CruiseState"] == AccState.FAULTED or
+ pt_cp.vl["EBCMFrictionBrakeStatus"]["FrictionBrakeUnavailable"] == 1)
ret.cruiseState.enabled = pt_cp.vl["AcceleratorPedal2"]["CruiseState"] != AccState.OFF
ret.cruiseState.standstill = pt_cp.vl["AcceleratorPedal2"]["CruiseState"] == AccState.STANDSTILL
@@ -148,6 +157,7 @@ class CarState(CarStateBase):
("RLWheelSpd", "EBCMWheelSpdRear"),
("RRWheelSpd", "EBCMWheelSpdRear"),
("MovingBackward", "EBCMWheelSpdRear"),
+ ("FrictionBrakeUnavailable", "EBCMFrictionBrakeStatus"),
("PRNDL2", "ECMPRDNL2"),
("ManualMode", "ECMPRDNL2"),
("LKADriverAppldTrq", "PSCMStatus"),
@@ -173,6 +183,7 @@ class CarState(CarStateBase):
("VehicleIgnitionAlt", 10),
("EBCMWheelSpdFront", 20),
("EBCMWheelSpdRear", 20),
+ ("EBCMFrictionBrakeStatus", 20),
("AcceleratorPedal2", 33),
("ASCMSteeringButton", 33),
("ECMEngineStatus", 100),
@@ -180,6 +191,15 @@ class CarState(CarStateBase):
("ECMAcceleratorPos", 80),
]
+ # Used to read back last counter sent to PT by camera
+ if CP.networkLocation == NetworkLocation.fwdCamera:
+ signals += [
+ ("RollingCounter", "ASCMLKASteeringCmd"),
+ ]
+ checks += [
+ ("ASCMLKASteeringCmd", 0),
+ ]
+
if CP.transmissionType == TransmissionType.direct:
signals.append(("RegenPaddle", "EBCMRegenPaddle"))
checks.append(("EBCMRegenPaddle", 50))
diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py
index 195df36a7f..7e6e71c642 100755
--- a/selfdrive/car/gm/interface.py
+++ b/selfdrive/car/gm/interface.py
@@ -5,7 +5,8 @@ from panda import Panda
from common.conversions import Conversions as CV
from selfdrive.car import STD_CARGO_KG, create_button_event, scale_tire_stiffness, get_safety_config
-from selfdrive.car.gm.values import CAR, CruiseButtons, CarControllerParams, EV_CAR, CAMERA_ACC_CAR
+from selfdrive.car.gm.radar_interface import RADAR_HEADER_MSG
+from selfdrive.car.gm.values import CAR, CruiseButtons, CarControllerParams, EV_CAR, CAMERA_ACC_CAR, CanBus
from selfdrive.car.interfaces import CarInterfaceBase
ButtonType = car.CarState.ButtonEvent.Type
@@ -48,6 +49,7 @@ class CarInterface(CarInterfaceBase):
ret.carName = "gm"
ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.gm)]
ret.autoResumeSng = False
+ use_off_car_defaults = len(fingerprint[0]) == 0 # Pick sensible carParams during offline doc generation/CI jobs
if candidate in EV_CAR:
ret.transmissionType = TransmissionType.direct
@@ -63,32 +65,34 @@ class CarInterface(CarInterfaceBase):
if candidate in CAMERA_ACC_CAR:
ret.experimentalLongitudinalAvailable = True
ret.networkLocation = NetworkLocation.fwdCamera
- ret.radarOffCan = True # no radar
+ ret.radarUnavailable = True # no radar
ret.pcmCruise = True
ret.safetyConfigs[0].safetyParam |= Panda.FLAG_GM_HW_CAM
ret.minEnableSpeed = 5 * CV.KPH_TO_MS
+ ret.minSteerSpeed = 10 * CV.KPH_TO_MS
+
+ # Tuning for experimental long
+ ret.longitudinalTuning.kpV = [2.0, 1.5]
+ ret.longitudinalTuning.kiV = [0.72]
+ ret.stopAccel = -2.0
+ ret.stoppingDecelRate = 2.0 # reach brake quickly after enabling
+ ret.vEgoStopping = 0.25
+ ret.vEgoStarting = 0.25
+ ret.longitudinalActuatorDelayUpperBound = 0.5
if experimental_long:
ret.pcmCruise = False
ret.openpilotLongitudinalControl = True
ret.safetyConfigs[0].safetyParam |= Panda.FLAG_GM_HW_CAM_LONG
- # Tuning
- ret.longitudinalTuning.kpV = [2.0, 1.5]
- ret.longitudinalTuning.kiV = [0.72]
- ret.stopAccel = -2.0
- ret.stoppingDecelRate = 2.0 # reach brake quickly after enabling
- ret.vEgoStopping = 0.25
- ret.vEgoStarting = 0.25
- ret.longitudinalActuatorDelayUpperBound = 0.5
-
else: # ASCM, OBD-II harness
ret.openpilotLongitudinalControl = True
ret.networkLocation = NetworkLocation.gateway
- ret.radarOffCan = False
+ ret.radarUnavailable = RADAR_HEADER_MSG not in fingerprint[CanBus.OBSTACLE] and not use_off_car_defaults
ret.pcmCruise = False # stock non-adaptive cruise control is kept off
# supports stop and go, but initial engage must (conservatively) be above 18mph
ret.minEnableSpeed = 18 * CV.MPH_TO_MS
+ ret.minSteerSpeed = 7 * CV.MPH_TO_MS
# Tuning
ret.longitudinalTuning.kpV = [2.4, 1.5]
@@ -97,11 +101,10 @@ class CarInterface(CarInterfaceBase):
# These cars have been put into dashcam only due to both a lack of users and test coverage.
# These cars likely still work fine. Once a user confirms each car works and a test route is
# added to selfdrive/car/tests/routes.py, we can remove it from this list.
- ret.dashcamOnly = candidate in {CAR.CADILLAC_ATS, CAR.HOLDEN_ASTRA, CAR.MALIBU, CAR.BUICK_REGAL, CAR.EQUINOX}
+ ret.dashcamOnly = candidate in {CAR.CADILLAC_ATS, CAR.HOLDEN_ASTRA, CAR.MALIBU, CAR.BUICK_REGAL, CAR.EQUINOX} or \
+ (ret.networkLocation == NetworkLocation.gateway and ret.radarUnavailable)
# Start with a baseline tuning for all GM vehicles. Override tuning as needed in each model section below.
- # Some GMs need some tolerance above 10 kph to avoid a fault
- ret.minSteerSpeed = 10.1 * CV.KPH_TO_MS
ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]]
ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2], [0.00]]
ret.lateralTuning.pid.kf = 0.00004 # full torque for 20 deg at 80mph means 0.00007818594
@@ -159,6 +162,15 @@ class CarInterface(CarInterfaceBase):
ret.steerRatio = 15.3
ret.centerToFront = ret.wheelbase * 0.5
+ elif candidate == CAR.ESCALADE:
+ ret.minEnableSpeed = -1. # engage speed is decided by pcm
+ ret.mass = 5653. * CV.LB_TO_KG + STD_CARGO_KG # (5552+5815)/2
+ ret.wheelbase = 2.95 # 116 inches in meters
+ ret.steerRatio = 17.3
+ ret.centerToFront = ret.wheelbase * 0.5
+ ret.longitudinalActuatorDelayUpperBound = 0.5 # large delay to initially start braking
+ CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning)
+
elif candidate == CAR.ESCALADE_ESV:
ret.minEnableSpeed = -1. # engage speed is decided by pcm
ret.mass = 2739. + STD_CARGO_KG
@@ -174,7 +186,7 @@ class CarInterface(CarInterfaceBase):
ret.mass = 1669. + STD_CARGO_KG
ret.wheelbase = 2.63779
ret.steerRatio = 16.8
- ret.centerToFront = 2.15 # measured
+ ret.centerToFront = ret.wheelbase * 0.4
tire_stiffness_factor = 1.0
ret.steerActuatorDelay = 0.2
CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning)
@@ -236,5 +248,5 @@ class CarInterface(CarInterfaceBase):
return ret
- def apply(self, c):
- return self.CC.update(c, self.CS)
+ def apply(self, c, now_nanos):
+ return self.CC.update(c, self.CS, now_nanos)
diff --git a/selfdrive/car/gm/radar_interface.py b/selfdrive/car/gm/radar_interface.py
index 6904e6f899..b86a85f915 100755
--- a/selfdrive/car/gm/radar_interface.py
+++ b/selfdrive/car/gm/radar_interface.py
@@ -3,7 +3,7 @@ import math
from cereal import car
from common.conversions import Conversions as CV
from opendbc.can.parser import CANParser
-from selfdrive.car.gm.values import DBC, CAR, CanBus
+from selfdrive.car.gm.values import DBC, CanBus
from selfdrive.car.interfaces import RadarInterfaceBase
RADAR_HEADER_MSG = 1120
@@ -16,9 +16,6 @@ LAST_RADAR_MSG = RADAR_HEADER_MSG + NUM_SLOTS
def create_radar_can_parser(car_fingerprint):
- if car_fingerprint not in (CAR.VOLT, CAR.MALIBU, CAR.HOLDEN_ASTRA, CAR.ACADIA, CAR.CADILLAC_ATS, CAR.ESCALADE_ESV):
- return None
-
# C1A-ARS3-A by Continental
radar_targets = list(range(SLOT_1_MSG, SLOT_1_MSG + NUM_SLOTS))
signals = list(zip(['FLRRNumValidTargets',
@@ -34,11 +31,12 @@ def create_radar_can_parser(car_fingerprint):
return CANParser(DBC[car_fingerprint]['radar'], signals, checks, CanBus.OBSTACLE)
+
class RadarInterface(RadarInterfaceBase):
def __init__(self, CP):
super().__init__(CP)
- self.rcp = create_radar_can_parser(CP.carFingerprint)
+ self.rcp = None if CP.radarUnavailable else create_radar_can_parser(CP.carFingerprint)
self.trigger_msg = LAST_RADAR_MSG
self.updated_messages = set()
diff --git a/selfdrive/car/gm/values.py b/selfdrive/car/gm/values.py
index ece128c253..2ac418b629 100644
--- a/selfdrive/car/gm/values.py
+++ b/selfdrive/car/gm/values.py
@@ -11,10 +11,10 @@ Ecu = car.CarParams.Ecu
class CarControllerParams:
STEER_MAX = 300 # GM limit is 3Nm. Used by carcontroller to generate LKA output
- STEER_STEP = 2 # Active control frames per command (50hz)
+ STEER_STEP = 3 # Active control frames per command (~33hz)
INACTIVE_STEER_STEP = 10 # Inactive control frames per command (10hz)
- STEER_DELTA_UP = 7 # Delta rates require review due to observed EPS weakness
- STEER_DELTA_DOWN = 17
+ STEER_DELTA_UP = 10 # Delta rates require review due to observed EPS weakness
+ STEER_DELTA_DOWN = 25
STEER_DRIVER_ALLOWANCE = 50
STEER_DRIVER_MULTIPLIER = 4
STEER_DRIVER_FACTOR = 100
@@ -67,6 +67,7 @@ class CAR:
MALIBU = "CHEVROLET MALIBU PREMIER 2017"
ACADIA = "GMC ACADIA DENALI 2018"
BUICK_REGAL = "BUICK REGAL ESSENCE 2018"
+ ESCALADE = "CADILLAC ESCALADE 2017"
ESCALADE_ESV = "CADILLAC ESCALADE ESV 2016"
BOLT_EUV = "CHEVROLET BOLT EUV 2022"
SILVERADO = "CHEVROLET SILVERADO 1500 2020"
@@ -75,7 +76,7 @@ class CAR:
class Footnote(Enum):
OBD_II = CarFootnote(
- 'Requires a community built ASCM harness. ' +
+ 'Requires a community built ASCM harness. ' +
'NOTE: disconnecting the ASCM disables Automatic Emergency Braking (AEB).',
Column.MODEL)
@@ -99,6 +100,7 @@ CAR_INFO: Dict[str, Union[GMCarInfo, List[GMCarInfo]]] = {
CAR.MALIBU: GMCarInfo("Chevrolet Malibu Premier 2017"),
CAR.ACADIA: GMCarInfo("GMC Acadia 2018", video_link="https://www.youtube.com/watch?v=0ZN6DdsBUZo"),
CAR.BUICK_REGAL: GMCarInfo("Buick Regal Essence 2018"),
+ CAR.ESCALADE: GMCarInfo("Cadillac Escalade 2017", "Driver Assist Package"),
CAR.ESCALADE_ESV: GMCarInfo("Cadillac Escalade ESV 2016", "Adaptive Cruise Control (ACC) & LKAS"),
CAR.BOLT_EUV: [
GMCarInfo("Chevrolet Bolt EUV 2022-23", "Premier or Premier Redline Trim without Super Cruise Package", "https://youtu.be/xvwzGMUA210"),
@@ -149,6 +151,10 @@ FINGERPRINTS = {
# Volt Premier w/ ACC 2018
{
170: 8, 171: 8, 189: 7, 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 288: 5, 298: 8, 304: 1, 308: 4, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 389: 2, 390: 7, 417: 7, 419: 1, 426: 7, 451: 8, 452: 8, 453: 6, 454: 8, 456: 8, 479: 3, 481: 7, 485: 8, 489: 8, 493: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 528: 4, 532: 6, 546: 7, 550: 8, 554: 3, 558: 8, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 566: 5, 567: 3, 568: 1, 573: 1, 577: 8, 578: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 3, 707: 8, 711: 6, 715: 8, 717: 5, 761: 7, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 967: 4, 969: 8, 977: 8, 979: 7, 988: 6, 989: 8, 995: 7, 1001: 8, 1005: 6, 1009: 8, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1187: 4, 1217: 8, 1221: 5, 1223: 3, 1225: 7, 1227: 4, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1273: 3, 1275: 3, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1516: 8, 1601: 8, 1618: 8, 1905: 7, 1906: 7, 1907: 7, 1910: 7, 1912: 7, 1922: 7, 1927: 7, 1930: 7, 2016: 8, 2018: 8, 2020: 8, 2024: 8, 2028: 8
+ },
+ # Volt Premier 2018 w/ flashed firmware, no radar
+ {
+ 170: 8, 171: 8, 189: 7, 190: 6, 192: 5, 193: 8, 197: 8, 199: 4, 201: 6, 209: 7, 211: 2, 241: 6, 288: 5, 289: 1, 290: 1, 298: 2, 304: 1, 308: 4, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 368: 8, 381: 2, 384: 8, 386: 5, 388: 8, 389: 2, 390: 7, 417: 7, 419: 1, 426: 7, 451: 8, 452: 8, 453: 6, 454: 8, 456: 8, 458: 8, 479: 3, 481: 7, 485: 8, 489: 5, 493: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 3, 508: 8, 512: 3, 528: 4, 530: 8, 532: 6, 537: 5, 539: 8, 542: 7, 546: 7, 550: 8, 554: 3, 558: 8, 560: 6, 562: 4, 563: 5, 564: 5, 565: 5, 566: 5, 567: 3, 568: 1, 573: 1, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 3, 707: 8, 711: 6, 761: 7, 810: 8, 821: 4, 823: 7, 832: 8, 840: 5, 842: 5, 844: 8, 853: 8, 866: 4, 961: 8, 967: 4, 969: 8, 977: 8, 979: 7, 988: 6, 989: 8, 995: 7, 1001: 5, 1003: 5, 1005: 6, 1009: 8, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1187: 4, 1217: 8, 1221: 5, 1223: 3, 1225: 7, 1227: 4, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1273: 3, 1275: 3, 1280: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1905: 7, 1906: 7, 1907: 7, 1910: 7, 1912: 7, 1922: 7, 1927: 7
}],
CAR.BUICK_REGAL : [
# Regal TourX Essence w/ ACC 2018
@@ -174,6 +180,10 @@ FINGERPRINTS = {
{
190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 208: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 289: 8, 298: 8, 304: 1, 309: 8, 313: 8, 320: 3, 322: 7, 328: 1, 338: 6, 340: 6, 352: 5, 381: 8, 384: 4, 386: 8, 388: 8, 393: 8, 398: 8, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 454: 8, 455: 7, 462: 4, 463: 3, 479: 3, 481: 7, 485: 8, 489: 8, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 510: 8, 532: 6, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 567: 5, 573: 1, 577: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1017: 8, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1225: 8, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1328: 4, 1417: 8, 1601: 8, 1906: 7, 1907: 7, 1912: 7, 1914: 7, 1919: 7, 1920: 7, 1930: 7, 2016: 8, 2024: 8
}],
+ CAR.ESCALADE: [
+ {
+ 170: 8, 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 208: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 322: 7, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 393: 7, 398: 8, 407: 4, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 454: 8, 455: 7, 460: 5, 462: 4, 463: 3, 479: 3, 481: 7, 485: 8, 487: 8, 489: 8, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 510: 8, 532: 6, 534: 2, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 573: 1, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 719: 5, 761: 7, 801: 8, 804: 3, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 967: 4, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1223: 2, 1225: 7, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1609: 8, 1613: 8, 1649: 8, 1792: 8, 1798: 8, 1824: 8, 1825: 8, 1840: 8, 1842: 8, 1858: 8, 1860: 8, 1863: 8, 1872: 8, 1875: 8, 1882: 8, 1888: 8, 1889: 8, 1892: 8, 1906: 7, 1907: 7, 1912: 7, 1914: 7, 1917: 7, 1918: 7, 1919: 7, 1920: 7, 1930: 7, 1937: 8, 1953: 8, 1968: 8, 2001: 8, 2017: 8, 2018: 8, 2020: 8, 2026: 8
+ }],
CAR.ESCALADE_ESV: [
{
309: 1, 848: 8, 849: 8, 850: 8, 851: 8, 852: 8, 853: 8, 854: 3, 1056: 6, 1057: 8, 1058: 8, 1059: 8, 1060: 8, 1061: 8, 1062: 8, 1063: 8, 1064: 8, 1065: 8, 1066: 8, 1067: 8, 1068: 8, 1120: 8, 1121: 8, 1122: 8, 1123: 8, 1124: 8, 1125: 8, 1126: 8, 1127: 8, 1128: 8, 1129: 8, 1130: 8, 1131: 8, 1132: 8, 1133: 8, 1134: 8, 1135: 8, 1136: 8, 1137: 8, 1138: 8, 1139: 8, 1140: 8, 1141: 8, 1142: 8, 1143: 8, 1146: 8, 1147: 8, 1148: 8, 1149: 8, 1150: 8, 1151: 8, 1216: 8, 1217: 8, 1218: 8, 1219: 8, 1220: 8, 1221: 8, 1222: 8, 1223: 8, 1224: 8, 1225: 8, 1226: 8, 1232: 8, 1233: 8, 1234: 8, 1235: 8, 1236: 8, 1237: 8, 1238: 8, 1239: 8, 1240: 8, 1241: 8, 1242: 8, 1787: 8, 1788: 8
diff --git a/selfdrive/car/honda/carcontroller.py b/selfdrive/car/honda/carcontroller.py
index ab944a30aa..4dc1dc8131 100644
--- a/selfdrive/car/honda/carcontroller.py
+++ b/selfdrive/car/honda/carcontroller.py
@@ -124,7 +124,7 @@ class CarController:
self.brake = 0.0
self.last_steer = 0.0
- def update(self, CC, CS):
+ def update(self, CC, CS, now_nanos):
actuators = CC.actuators
hud_control = CC.hudControl
hud_v_cruise = hud_control.setSpeed * CV.MS_TO_KPH if hud_control.speedVisible else 255
diff --git a/selfdrive/car/honda/carstate.py b/selfdrive/car/honda/carstate.py
index a37667fd3a..16880d1b1f 100644
--- a/selfdrive/car/honda/carstate.py
+++ b/selfdrive/car/honda/carstate.py
@@ -274,7 +274,7 @@ class CarState(CarStateBase):
ret.cruiseState.available = bool(cp.vl[self.main_on_sig_msg]["MAIN_ON"])
# Gets rid of Pedal Grinding noise when brake is pressed at slow speeds for some models
- if self.CP.carFingerprint in (CAR.PILOT, CAR.PASSPORT, CAR.RIDGELINE):
+ if self.CP.carFingerprint in (CAR.PILOT, CAR.RIDGELINE):
if ret.brake > 0.1:
ret.brakePressed = True
diff --git a/selfdrive/car/honda/interface.py b/selfdrive/car/honda/interface.py
index 990238ae5d..d3cf9fa891 100755
--- a/selfdrive/car/honda/interface.py
+++ b/selfdrive/car/honda/interface.py
@@ -21,6 +21,8 @@ class CarInterface(CarInterfaceBase):
def get_pid_accel_limits(CP, current_speed, cruise_speed):
if CP.carFingerprint in HONDA_BOSCH:
return CarControllerParams.BOSCH_ACCEL_MIN, CarControllerParams.BOSCH_ACCEL_MAX
+ elif CP.enableGasInterceptor:
+ return CarControllerParams.NIDEC_ACCEL_MIN, CarControllerParams.NIDEC_ACCEL_MAX
else:
# NIDECs don't allow acceleration near cruise_speed,
# so limit limits of pid to prevent windup
@@ -34,7 +36,7 @@ class CarInterface(CarInterfaceBase):
if candidate in HONDA_BOSCH:
ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.hondaBosch)]
- ret.radarOffCan = True
+ ret.radarUnavailable = True
if candidate not in HONDA_BOSCH_RADARLESS:
# Disable the radar and let openpilot control longitudinal
@@ -231,11 +233,11 @@ class CarInterface(CarInterfaceBase):
else:
ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end
- elif candidate in (CAR.PILOT, CAR.PASSPORT):
- ret.mass = 4204. * CV.LB_TO_KG + STD_CARGO_KG # average weight
- ret.wheelbase = 2.82
+ elif candidate == CAR.PILOT:
+ ret.mass = 4278. * CV.LB_TO_KG + STD_CARGO_KG # average weight
+ ret.wheelbase = 2.86
ret.centerToFront = ret.wheelbase * 0.428
- ret.steerRatio = 17.25 # as spec
+ ret.steerRatio = 16.0 # as spec
ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end
tire_stiffness_factor = 0.444
ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.38], [0.11]]
@@ -348,5 +350,5 @@ class CarInterface(CarInterfaceBase):
# pass in a car.CarControl
# to be called @ 100hz
- def apply(self, c):
- return self.CC.update(c, self.CS)
+ def apply(self, c, now_nanos):
+ return self.CC.update(c, self.CS, now_nanos)
diff --git a/selfdrive/car/honda/radar_interface.py b/selfdrive/car/honda/radar_interface.py
index 629ab01d4c..660be4c449 100755
--- a/selfdrive/car/honda/radar_interface.py
+++ b/selfdrive/car/honda/radar_interface.py
@@ -21,7 +21,7 @@ class RadarInterface(RadarInterfaceBase):
self.track_id = 0
self.radar_fault = False
self.radar_wrong_config = False
- self.radar_off_can = CP.radarOffCan
+ self.radar_off_can = CP.radarUnavailable
self.radar_ts = CP.radarTimeStep
self.delay = int(round(0.1 / CP.radarTimeStep)) # 0.1s delay of radar
diff --git a/selfdrive/car/honda/tests/test_honda.py b/selfdrive/car/honda/tests/test_honda.py
new file mode 100755
index 0000000000..7a8c86fb0a
--- /dev/null
+++ b/selfdrive/car/honda/tests/test_honda.py
@@ -0,0 +1,20 @@
+#!/usr/bin/env python3
+import re
+import unittest
+
+from selfdrive.car.honda.values import FW_VERSIONS
+
+HONDA_FW_VERSION_RE = br"\d{5}-[A-Z0-9]{3}(-|,)[A-Z0-9]{4}(\x00){2}$"
+
+
+class TestHondaFingerprint(unittest.TestCase):
+ def test_fw_version_format(self):
+ # Asserts all FW versions follow an expected format
+ for fw_by_ecu in FW_VERSIONS.values():
+ for fws in fw_by_ecu.values():
+ for fw in fws:
+ self.assertTrue(re.match(HONDA_FW_VERSION_RE, fw) is not None, fw)
+
+
+if __name__ == "__main__":
+ unittest.main()
diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py
index 905c9f4b4f..c085c3fe80 100644
--- a/selfdrive/car/honda/values.py
+++ b/selfdrive/car/honda/values.py
@@ -4,9 +4,10 @@ from typing import Dict, List, Optional, Union
from cereal import car
from common.conversions import Conversions as CV
+from panda.python import uds
from selfdrive.car import dbc_dict
from selfdrive.car.docs_definitions import CarFootnote, CarInfo, Column, Harness
-from selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries
+from selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries, p16
Ecu = car.CarParams.Ecu
VisualAlert = car.CarControl.HUDControl.VisualAlert
@@ -91,7 +92,6 @@ class CAR:
ACURA_RDX = "ACURA RDX 2018"
ACURA_RDX_3G = "ACURA RDX 2020"
PILOT = "HONDA PILOT 2017"
- PASSPORT = "HONDA PASSPORT 2021"
RIDGELINE = "HONDA RIDGELINE 2017"
INSIGHT = "HONDA INSIGHT 2019"
HONDA_E = "HONDA E 2020"
@@ -142,19 +142,56 @@ CAR_INFO: Dict[str, Optional[Union[HondaCarInfo, List[HondaCarInfo]]]] = {
CAR.ODYSSEY_CHN: None, # Chinese version of Odyssey
CAR.ACURA_RDX: HondaCarInfo("Acura RDX 2016-18", "AcuraWatch Plus", min_steer_speed=12. * CV.MPH_TO_MS),
CAR.ACURA_RDX_3G: HondaCarInfo("Acura RDX 2019-22", "All", min_steer_speed=3. * CV.MPH_TO_MS),
- CAR.PILOT: HondaCarInfo("Honda Pilot 2016-22", min_steer_speed=12. * CV.MPH_TO_MS),
- CAR.PASSPORT: HondaCarInfo("Honda Passport 2019-21", "All", min_steer_speed=12. * CV.MPH_TO_MS),
+ CAR.PILOT: [
+ HondaCarInfo("Honda Pilot 2016-22", min_steer_speed=12. * CV.MPH_TO_MS),
+ HondaCarInfo("Honda Passport 2019-21", "All", min_steer_speed=12. * CV.MPH_TO_MS),
+ ],
CAR.RIDGELINE: HondaCarInfo("Honda Ridgeline 2017-22", min_steer_speed=12. * CV.MPH_TO_MS),
CAR.INSIGHT: HondaCarInfo("Honda Insight 2019-22", "All", min_steer_speed=3. * CV.MPH_TO_MS),
CAR.HONDA_E: HondaCarInfo("Honda e 2020", "All", min_steer_speed=3. * CV.MPH_TO_MS),
}
+HONDA_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \
+ p16(0xF112)
+HONDA_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \
+ p16(0xF112)
+
FW_QUERY_CONFIG = FwQueryConfig(
requests=[
+ # Currently used to fingerprint
+ Request(
+ [StdQueries.UDS_VERSION_REQUEST],
+ [StdQueries.UDS_VERSION_RESPONSE],
+ bus=1,
+ ),
+
+ # Data collection requests:
+ # Log extra identifiers for current ECUs
+ Request(
+ [HONDA_VERSION_REQUEST],
+ [HONDA_VERSION_RESPONSE],
+ bus=1,
+ logging=True,
+ ),
+ # Nidec PT bus
Request(
[StdQueries.UDS_VERSION_REQUEST],
[StdQueries.UDS_VERSION_RESPONSE],
+ bus=0,
+ logging=True,
),
+ # Bosch PT bus
+ Request(
+ [StdQueries.UDS_VERSION_REQUEST],
+ [StdQueries.UDS_VERSION_RESPONSE],
+ bus=1,
+ logging=True,
+ non_obd=True,
+ ),
+ ],
+ extra_ecus=[
+ # The only other ECU on PT bus accessible by camera on radarless Civic
+ (Ecu.unknown, 0x18DAB3F1, None),
],
)
@@ -1067,6 +1104,8 @@ FW_VERSIONS = {
b'28101-5EZ-A060\x00\x00',
b'28101-5EZ-A100\x00\x00',
b'28101-5EZ-A210\x00\x00',
+ b'28101-5EZ-A600\x00\x00',
+ b'28101-5EZ-A430\x00\x00',
],
(Ecu.programmedFuelInjection, 0x18da10f1, None): [
b'37805-RLV-4060\x00\x00',
@@ -1078,6 +1117,9 @@ FW_VERSIONS = {
b'37805-RLV-C520\x00\x00',
b'37805-RLV-C530\x00\x00',
b'37805-RLV-C910\x00\x00',
+ b'37805-RLV-B220\x00\x00',
+ b'37805-RLV-B210\x00\x00',
+ b'37805-RLV-L160\x00\x00',
],
(Ecu.gateway, 0x18daeff1, None): [
b'38897-TG7-A030\x00\x00',
@@ -1110,6 +1152,7 @@ FW_VERSIONS = {
b'36161-TGS-A130\x00\x00',
b'36161-TGT-A030\x00\x00',
b'36161-TGT-A130\x00\x00',
+ b'36161-TGS-A030\x00\x00',
],
(Ecu.srs, 0x18da53f1, None): [
b'77959-TG7-A020\x00\x00',
@@ -1147,6 +1190,9 @@ FW_VERSIONS = {
b'78109-TGS-AP20\x00\x00',
b'78109-TGT-AJ20\x00\x00',
b'78109-TGT-AK30\x00\x00',
+ b'78109-TGS-AT20\x00\x00',
+ b'78109-TGS-AX20\x00\x00',
+ b'78109-TGS-AJ20\x00\x00',
],
(Ecu.vsa, 0x18da28f1, None): [
b'57114-TG7-A130\x00\x00',
@@ -1163,38 +1209,6 @@ FW_VERSIONS = {
b'57114-TGT-A530\x00\x00',
],
},
- CAR.PASSPORT: {
- (Ecu.programmedFuelInjection, 0x18da10f1, None): [
- b'37805-RLV-B220\x00\x00',
- b'37805-RLV-B210\x00\x00',
- ],
- (Ecu.eps, 0x18da30f1, None): [
- b'39990-TGS-A230\x00\x00',
- ],
- (Ecu.fwdRadar, 0x18dab0f1, None): [
- b'36161-TGS-A030\x00\x00',
- b'36161-TGS-A130\x00\x00',
- ],
- (Ecu.gateway, 0x18daeff1, None): [
- b'38897-TG7-A040\x00\x00',
- ],
- (Ecu.srs, 0x18da53f1, None): [
- b'77959-TGS-A010\x00\x00',
- ],
- (Ecu.shiftByWire, 0x18da0bf1, None): [
- b'54008-TG7-A530\x00\x00',
- ],
- (Ecu.transmission, 0x18da1ef1, None): [
- b'28101-5EZ-A600\x00\x00',
- ],
- (Ecu.combinationMeter, 0x18da60f1, None): [
- b'78109-TGS-AT20\x00\x00',
- b'78109-TGS-AX20\x00\x00',
- ],
- (Ecu.vsa, 0x18da28f1, None): [
- b'57114-TGS-A530\x00\x00',
- ],
- },
CAR.ACURA_RDX: {
(Ecu.vsa, 0x18da28f1, None): [
b'57114-TX5-A220\x00\x00',
@@ -1436,6 +1450,7 @@ FW_VERSIONS = {
(Ecu.eps, 0x18DA30F1, None): [
b'39990-T39-A130\x00\x00',
b'39990-T43-J020\x00\x00',
+ b'39990-T24-T120\x00\x00',
],
(Ecu.gateway, 0x18DAEFF1, None): [
b'38897-T20-A020\x00\x00',
@@ -1443,11 +1458,13 @@ FW_VERSIONS = {
b'38897-T21-A010\x00\x00',
b'38897-T20-A210\x00\x00',
b'38897-T20-A310\x00\x00',
+ b'38897-T24-Z120\x00\x00',
],
(Ecu.srs, 0x18DA53F1, None): [
b'77959-T20-A970\x00\x00',
b'77959-T47-A940\x00\x00',
b'77959-T47-A950\x00\x00',
+ b'77959-T20-M820\x00\x00',
],
(Ecu.combinationMeter, 0x18DA60F1, None): [
b'78108-T21-A220\x00\x00',
@@ -1455,16 +1472,26 @@ FW_VERSIONS = {
b'78108-T23-A110\x00\x00',
b'78108-T21-A230\x00\x00',
b'78108-T22-A020\x00\x00',
+ b'78108-T21-MB10\x00\x00',
+ ],
+ (Ecu.fwdRadar, 0x18dab0f1, None): [
+ b'36161-T20-A070\x00\x00',
+ b'36161-T20-A080\x00\x00',
+ b'36161-T20-A060\x00\x00',
+ b'36161-T47-A070\x00\x00',
+ b'36161-T24-T070\x00\x00',
],
(Ecu.vsa, 0x18DA28F1, None): [
b'57114-T20-AB40\x00\x00',
b'57114-T43-JB30\x00\x00',
+ b'57114-T24-TB30\x00\x00',
],
(Ecu.transmission, 0x18da1ef1, None): [
b'28101-65D-A020\x00\x00',
b'28101-65D-A120\x00\x00',
b'28101-65H-A020\x00\x00',
b'28101-65H-A120\x00\x00',
+ b'28101-65J-N010\x00\x00',
],
(Ecu.programmedFuelInjection, 0x18da10f1, None): [
b'37805-64L-A540\x00\x00',
@@ -1472,6 +1499,7 @@ FW_VERSIONS = {
b'37805-64S-A720\x00\x00',
b'37805-64A-A540\x00\x00',
b'37805-64A-A620\x00\x00',
+ b'37805-64D-P510\x00\x00',
],
},
}
@@ -1495,7 +1523,6 @@ DBC = {
CAR.ODYSSEY: dbc_dict('honda_odyssey_exl_2018_generated', 'acura_ilx_2016_nidec'),
CAR.ODYSSEY_CHN: dbc_dict('honda_odyssey_extreme_edition_2018_china_can_generated', 'acura_ilx_2016_nidec'),
CAR.PILOT: dbc_dict('acura_ilx_2016_can_generated', 'acura_ilx_2016_nidec'),
- CAR.PASSPORT: dbc_dict('acura_ilx_2016_can_generated', 'acura_ilx_2016_nidec'),
CAR.RIDGELINE: dbc_dict('acura_ilx_2016_can_generated', 'acura_ilx_2016_nidec'),
CAR.INSIGHT: dbc_dict('honda_insight_ex_2019_can_generated', None),
CAR.HONDA_E: dbc_dict('acura_rdx_2020_can_generated', None),
@@ -1510,7 +1537,7 @@ STEER_THRESHOLD = {
HONDA_NIDEC_ALT_PCM_ACCEL = {CAR.ODYSSEY}
HONDA_NIDEC_ALT_SCM_MESSAGES = {CAR.ACURA_ILX, CAR.ACURA_RDX, CAR.CRV, CAR.CRV_EU, CAR.FIT, CAR.FREED, CAR.HRV, CAR.ODYSSEY_CHN,
- CAR.PILOT, CAR.PASSPORT, CAR.RIDGELINE}
+ CAR.PILOT, CAR.RIDGELINE}
HONDA_BOSCH = {CAR.ACCORD, CAR.ACCORDH, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_5G,
CAR.CRV_HYBRID, CAR.INSIGHT, CAR.ACURA_RDX_3G, CAR.HONDA_E, CAR.CIVIC_2022}
HONDA_BOSCH_ALT_BRAKE_SIGNAL = {CAR.ACCORD, CAR.CRV_5G, CAR.ACURA_RDX_3G}
diff --git a/selfdrive/car/hyundai/carcontroller.py b/selfdrive/car/hyundai/carcontroller.py
index b81c5e3f7d..2572038492 100644
--- a/selfdrive/car/hyundai/carcontroller.py
+++ b/selfdrive/car/hyundai/carcontroller.py
@@ -3,7 +3,7 @@ from common.conversions import Conversions as CV
from common.numpy_fast import clip
from common.realtime import DT_CTRL
from opendbc.can.packer import CANPacker
-from selfdrive.car import apply_std_steer_torque_limits
+from selfdrive.car import apply_driver_steer_torque_limits
from selfdrive.car.hyundai import hyundaicanfd, hyundaican
from selfdrive.car.hyundai.values import HyundaiFlags, Buttons, CarControllerParams, CANFD_CAR, CAR
@@ -54,13 +54,13 @@ class CarController:
self.car_fingerprint = CP.carFingerprint
self.last_button_frame = 0
- def update(self, CC, CS):
+ def update(self, CC, CS, now_nanos):
actuators = CC.actuators
hud_control = CC.hudControl
# steering torque
new_steer = int(round(actuators.steer * self.params.STEER_MAX))
- apply_steer = apply_std_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.params)
+ apply_steer = apply_driver_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.params)
if not CC.latActive:
apply_steer = 0
@@ -169,7 +169,8 @@ class CarController:
if (self.frame - self.last_button_frame) * DT_CTRL > 0.1:
# send 25 messages at a time to increases the likelihood of resume being accepted
can_sends.extend([hyundaican.create_clu11(self.packer, self.frame, CS.clu11, Buttons.RES_ACCEL, self.CP.carFingerprint)] * 25)
- self.last_button_frame = self.frame
+ if (self.frame - self.last_button_frame) * DT_CTRL >= 0.15:
+ self.last_button_frame = self.frame
if self.frame % 2 == 0 and self.CP.openpilotLongitudinalControl:
# TODO: unclear if this is needed
@@ -178,10 +179,7 @@ class CarController:
hud_control.leadVisible, set_speed_in_units, stopping, CC.cruiseControl.override))
# 20 Hz LFA MFA message
- if self.frame % 5 == 0 and self.car_fingerprint in (CAR.SONATA, CAR.PALISADE, CAR.IONIQ, CAR.KIA_NIRO_EV, CAR.KIA_NIRO_HEV_2021,
- CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.KIA_CEED, CAR.KIA_SELTOS, CAR.KONA_EV, CAR.KONA_EV_2022,
- CAR.ELANTRA_2021, CAR.ELANTRA_HEV_2021, CAR.SONATA_HYBRID, CAR.KONA_HEV, CAR.SANTA_FE_2022,
- CAR.KIA_K5_2021, CAR.IONIQ_HEV_2022, CAR.SANTA_FE_HEV_2022, CAR.GENESIS_G70_2020, CAR.SANTA_FE_PHEV_2022, CAR.KIA_STINGER_2022):
+ if self.frame % 5 == 0 and self.CP.flags & HyundaiFlags.SEND_LFA.value:
can_sends.append(hyundaican.create_lfahda_mfc(self.packer, CC.enabled))
# 5 Hz ACC options
diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py
index fc196528d7..22934c05b2 100644
--- a/selfdrive/car/hyundai/carstate.py
+++ b/selfdrive/car/hyundai/carstate.py
@@ -6,6 +6,7 @@ from cereal import car
from common.conversions import Conversions as CV
from opendbc.can.parser import CANParser
from opendbc.can.can_define import CANDefine
+from selfdrive.car.hyundai.hyundaicanfd import get_e_can_bus
from selfdrive.car.hyundai.values import HyundaiFlags, CAR, DBC, FEATURES, CAMERA_SCC_CAR, CANFD_CAR, EV_CAR, HYBRID_CAR, Buttons, CarControllerParams
from selfdrive.car.interfaces import CarStateBase
@@ -21,7 +22,9 @@ class CarState(CarStateBase):
self.cruise_buttons = deque([Buttons.NONE] * PREV_BUTTON_SAMPLES, maxlen=PREV_BUTTON_SAMPLES)
self.main_buttons = deque([Buttons.NONE] * PREV_BUTTON_SAMPLES, maxlen=PREV_BUTTON_SAMPLES)
- self.gear_msg_canfd = "GEAR_ALT" if CP.flags & HyundaiFlags.CANFD_ALT_GEARS else "GEAR_SHIFTER"
+ self.gear_msg_canfd = "GEAR_ALT_2" if CP.flags & HyundaiFlags.CANFD_ALT_GEARS_2 else \
+ "GEAR_ALT" if CP.flags & HyundaiFlags.CANFD_ALT_GEARS else \
+ "GEAR_SHIFTER"
if CP.carFingerprint in CANFD_CAR:
self.shifter_values = can_define.dv[self.gear_msg_canfd]["GEAR"]
elif self.CP.carFingerprint in FEATURES["use_cluster_gears"]:
@@ -86,7 +89,7 @@ class CarState(CarStateBase):
50, cp.vl["CGW1"]["CF_Gway_TurnSigLh"], cp.vl["CGW1"]["CF_Gway_TurnSigRh"])
ret.steeringTorque = cp.vl["MDPS12"]["CR_Mdps_StrColTq"]
ret.steeringTorqueEps = cp.vl["MDPS12"]["CR_Mdps_OutTq"]
- ret.steeringPressed = abs(ret.steeringTorque) > self.params.STEER_THRESHOLD
+ ret.steeringPressed = self.update_steering_pressed(abs(ret.steeringTorque) > self.params.STEER_THRESHOLD, 5)
ret.steerFaultTemporary = cp.vl["MDPS12"]["CF_Mdps_ToiUnavail"] != 0 or cp.vl["MDPS12"]["CF_Mdps_ToiFlt"] != 0
# cruise state
@@ -132,8 +135,8 @@ class CarState(CarStateBase):
ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(gear))
if not self.CP.openpilotLongitudinalControl:
- aeb_src = "FCA11" if self.CP.carFingerprint in FEATURES["use_fca"] else "SCC12"
- aeb_sig = "FCA_CmdAct" if self.CP.carFingerprint in FEATURES["use_fca"] else "AEB_CmdAct"
+ aeb_src = "FCA11" if self.CP.flags & HyundaiFlags.USE_FCA.value else "SCC12"
+ aeb_sig = "FCA_CmdAct" if self.CP.flags & HyundaiFlags.USE_FCA.value else "AEB_CmdAct"
aeb_warning = cp_cruise.vl[aeb_src]["CF_VSM_Warn"] != 0
aeb_braking = cp_cruise.vl[aeb_src]["CF_VSM_DecCmdAct"] != 0 or cp_cruise.vl[aeb_src][aeb_sig] != 0
ret.stockFcw = aeb_warning and not aeb_braking
@@ -156,6 +159,9 @@ class CarState(CarStateBase):
def update_canfd(self, cp, cp_cam):
ret = car.CarState.new_message()
+ self.is_metric = cp.vl["CRUISE_BUTTONS_ALT"]["DISTANCE_UNIT"] != 1
+ speed_factor = CV.KPH_TO_MS if self.is_metric else CV.MPH_TO_MS
+
if self.CP.carFingerprint in (EV_CAR | HYBRID_CAR):
if self.CP.carFingerprint in EV_CAR:
ret.gas = cp.vl["ACCELERATOR"]["ACCELERATOR_PEDAL"] / 255.
@@ -197,14 +203,18 @@ class CarState(CarStateBase):
ret.leftBlindspot = cp.vl["BLINDSPOTS_REAR_CORNERS"]["FL_INDICATOR"] != 0
ret.rightBlindspot = cp.vl["BLINDSPOTS_REAR_CORNERS"]["FR_INDICATOR"] != 0
- ret.cruiseState.available = True
- self.is_metric = cp.vl["CRUISE_BUTTONS_ALT"]["DISTANCE_UNIT"] != 1
- if not self.CP.openpilotLongitudinalControl:
- speed_factor = CV.KPH_TO_MS if self.is_metric else CV.MPH_TO_MS
+ # cruise state
+ # CAN FD cars enable on main button press, set available if no TCS faults preventing engagement
+ ret.cruiseState.available = cp.vl["TCS"]["ACCEnable"] == 0
+ if self.CP.openpilotLongitudinalControl:
+ # These are not used for engage/disengage since openpilot keeps track of state using the buttons
+ ret.cruiseState.enabled = cp.vl["TCS"]["ACC_REQ"] == 1
+ ret.cruiseState.standstill = False
+ else:
cp_cruise_info = cp_cam if self.CP.flags & HyundaiFlags.CANFD_CAMERA_SCC else cp
- ret.cruiseState.speed = cp_cruise_info.vl["SCC_CONTROL"]["VSetDis"] * speed_factor
- ret.cruiseState.standstill = cp_cruise_info.vl["SCC_CONTROL"]["CRUISE_STANDSTILL"] == 1
ret.cruiseState.enabled = cp_cruise_info.vl["SCC_CONTROL"]["ACCMode"] in (1, 2)
+ ret.cruiseState.standstill = cp_cruise_info.vl["SCC_CONTROL"]["CRUISE_STANDSTILL"] == 1
+ ret.cruiseState.speed = cp_cruise_info.vl["SCC_CONTROL"]["VSetDis"] * speed_factor
self.cruise_info = copy.copy(cp_cruise_info.vl["SCC_CONTROL"])
cruise_btn_msg = "CRUISE_BUTTONS_ALT" if self.CP.flags & HyundaiFlags.CANFD_ALT_BUTTONS else "CRUISE_BUTTONS"
@@ -307,7 +317,7 @@ class CarState(CarStateBase):
("SCC12", 50),
]
- if CP.carFingerprint in FEATURES["use_fca"]:
+ if CP.flags & HyundaiFlags.USE_FCA.value:
signals += [
("FCA_CmdAct", "FCA11"),
("CF_VSM_Warn", "FCA11"),
@@ -398,7 +408,7 @@ class CarState(CarStateBase):
("SCC12", 50),
]
- if CP.carFingerprint in FEATURES["use_fca"]:
+ if CP.flags & HyundaiFlags.USE_FCA.value:
signals += [
("FCA_CmdAct", "FCA11"),
("CF_VSM_Warn", "FCA11"),
@@ -418,7 +428,9 @@ class CarState(CarStateBase):
def get_can_parser_canfd(CP):
cruise_btn_msg = "CRUISE_BUTTONS_ALT" if CP.flags & HyundaiFlags.CANFD_ALT_BUTTONS else "CRUISE_BUTTONS"
- gear_msg = "GEAR_ALT" if CP.flags & HyundaiFlags.CANFD_ALT_GEARS else "GEAR_SHIFTER"
+ gear_msg = "GEAR_ALT_2" if CP.flags & HyundaiFlags.CANFD_ALT_GEARS_2 else \
+ "GEAR_ALT" if CP.flags & HyundaiFlags.CANFD_ALT_GEARS else \
+ "GEAR_SHIFTER"
signals = [
("WHEEL_SPEED_1", "WHEEL_SPEEDS"),
("WHEEL_SPEED_2", "WHEEL_SPEEDS"),
@@ -435,6 +447,7 @@ class CarState(CarStateBase):
("DriverBraking", "TCS"),
("ACCEnable", "TCS"),
+ ("ACC_REQ", "TCS"),
("COUNTER", cruise_btn_msg),
("CRUISE_BUTTONS", cruise_btn_msg),
@@ -503,8 +516,7 @@ class CarState(CarStateBase):
("ACCELERATOR_BRAKE_ALT", 100),
]
- bus = 5 if CP.flags & HyundaiFlags.CANFD_HDA2 else 4
- return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, bus)
+ return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, get_e_can_bus(CP))
@staticmethod
def get_cam_can_parser_canfd(CP):
diff --git a/selfdrive/car/hyundai/hyundaican.py b/selfdrive/car/hyundai/hyundaican.py
index c2ffffbf22..858f3d0876 100644
--- a/selfdrive/car/hyundai/hyundaican.py
+++ b/selfdrive/car/hyundai/hyundaican.py
@@ -21,7 +21,7 @@ def create_lkas11(packer, frame, car_fingerprint, apply_steer, steer_req,
CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.KIA_SELTOS, CAR.ELANTRA_2021, CAR.GENESIS_G70_2020,
CAR.ELANTRA_HEV_2021, CAR.SONATA_HYBRID, CAR.KONA_EV, CAR.KONA_HEV, CAR.KONA_EV_2022,
CAR.SANTA_FE_2022, CAR.KIA_K5_2021, CAR.IONIQ_HEV_2022, CAR.SANTA_FE_HEV_2022,
- CAR.SANTA_FE_PHEV_2022, CAR.KIA_STINGER_2022):
+ CAR.SANTA_FE_PHEV_2022, CAR.KIA_STINGER_2022, CAR.KIA_K5_HEV_2020):
values["CF_Lkas_LdwsActivemode"] = int(left_lane) + (int(right_lane) << 1)
values["CF_Lkas_LdwsOpt_USM"] = 2
diff --git a/selfdrive/car/hyundai/hyundaicanfd.py b/selfdrive/car/hyundai/hyundaicanfd.py
index c492e6a5ff..af7239571c 100644
--- a/selfdrive/car/hyundai/hyundaicanfd.py
+++ b/selfdrive/car/hyundai/hyundaicanfd.py
@@ -72,8 +72,6 @@ def create_acc_control(packer, CP, enabled, accel_last, accel, stopping, gas_ove
else:
a_raw = accel
a_val = clip(accel, accel_last - jn, accel_last + jn)
- if stopping:
- a_raw = 0
values = {
"ACCMode": 0 if not enabled else (2 if gas_override else 1),
@@ -83,6 +81,7 @@ def create_acc_control(packer, CP, enabled, accel_last, accel, stopping, gas_ove
"aReqRaw": a_raw,
"VSetDis": set_speed,
"JerkLowerLimit": jerk if enabled else 1,
+ "JerkUpperLimit": 3.0,
"ACC_ObjDist": 1,
"ObjValid": 0,
@@ -90,7 +89,6 @@ def create_acc_control(packer, CP, enabled, accel_last, accel, stopping, gas_ove
"SET_ME_2": 0x4,
"SET_ME_3": 0x3,
"SET_ME_TMP_64": 0x64,
- "NEW_SIGNAL_10": 4,
"DISTANCE_SETTING": 4,
}
diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py
index 6881be5a33..1dd91ac888 100644
--- a/selfdrive/car/hyundai/interface.py
+++ b/selfdrive/car/hyundai/interface.py
@@ -2,6 +2,7 @@
from cereal import car
from panda import Panda
from common.conversions import Conversions as CV
+from selfdrive.car.hyundai.hyundaicanfd import get_e_can_bus
from selfdrive.car.hyundai.values import HyundaiFlags, CAR, DBC, CANFD_CAR, CAMERA_SCC_CAR, CANFD_RADAR_SCC_CAR, EV_CAR, HYBRID_CAR, LEGACY_SAFETY_MODE_CAR, Buttons
from selfdrive.car.hyundai.radar_interface import RADAR_START_ADDR
from selfdrive.car import STD_CARGO_KG, create_button_event, scale_tire_stiffness, get_safety_config
@@ -20,7 +21,7 @@ class CarInterface(CarInterfaceBase):
@staticmethod
def _get_params(ret, candidate, fingerprint, car_fw, experimental_long):
ret.carName = "hyundai"
- ret.radarOffCan = RADAR_START_ADDR not in fingerprint[1] or DBC[ret.carFingerprint]["radar"] is None
+ ret.radarUnavailable = RADAR_START_ADDR not in fingerprint[1] or DBC[ret.carFingerprint]["radar"] is None
# These cars have been put into dashcam only due to both a lack of users and test coverage.
# These cars likely still work fine. Once a user confirms each car works and a test route is
@@ -35,11 +36,22 @@ class CarInterface(CarInterfaceBase):
# non-HDA2
if 0x1cf not in fingerprint[4]:
ret.flags |= HyundaiFlags.CANFD_ALT_BUTTONS.value
- # ICE cars do not have 0x130; GEARS message on 0x40 instead
+ # ICE cars do not have 0x130; GEARS message on 0x40 or 0x70 instead
if 0x130 not in fingerprint[4]:
- ret.flags |= HyundaiFlags.CANFD_ALT_GEARS.value
+ if 0x40 not in fingerprint[4]:
+ ret.flags |= HyundaiFlags.CANFD_ALT_GEARS_2.value
+ else:
+ ret.flags |= HyundaiFlags.CANFD_ALT_GEARS.value
if candidate not in CANFD_RADAR_SCC_CAR:
ret.flags |= HyundaiFlags.CANFD_CAMERA_SCC.value
+ else:
+ # Send LFA message on cars with HDA
+ if 0x485 in fingerprint[2]:
+ ret.flags |= HyundaiFlags.SEND_LFA.value
+
+ # These cars use the FCA11 message for the AEB and FCW signals, all others use SCC12
+ if 0x38d in fingerprint[0] or 0x38d in fingerprint[2]:
+ ret.flags |= HyundaiFlags.USE_FCA.value
ret.steerActuatorDelay = 0.1 # Default delay
ret.steerLimitTimer = 0.4
@@ -92,18 +104,13 @@ class CarInterface(CarInterfaceBase):
ret.wheelbase = 2.6
ret.steerRatio = 13.42 # Spec
tire_stiffness_factor = 0.385
- elif candidate in (CAR.IONIQ, CAR.IONIQ_EV_LTD, CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.IONIQ_HEV_2022):
+ elif candidate in (CAR.IONIQ, CAR.IONIQ_EV_LTD, CAR.IONIQ_PHEV_2019, CAR.IONIQ_HEV_2022, CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV):
ret.mass = 1490. + STD_CARGO_KG # weight per hyundai site https://www.hyundaiusa.com/ioniq-electric/specifications.aspx
ret.wheelbase = 2.7
ret.steerRatio = 13.73 # Spec
tire_stiffness_factor = 0.385
- if candidate not in (CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.IONIQ_HEV_2022):
+ if candidate in (CAR.IONIQ, CAR.IONIQ_EV_LTD, CAR.IONIQ_PHEV_2019):
ret.minSteerSpeed = 32 * CV.MPH_TO_MS
- elif candidate == CAR.IONIQ_PHEV_2019:
- ret.mass = 1550. + STD_CARGO_KG # weight per hyundai site https://www.hyundaiusa.com/us/en/vehicles/2019-ioniq-plug-in-hybrid/compare-specs
- ret.wheelbase = 2.7
- ret.steerRatio = 13.73
- ret.minSteerSpeed = 32 * CV.MPH_TO_MS
elif candidate == CAR.VELOSTER:
ret.mass = 3558. * CV.LB_TO_KG
ret.wheelbase = 2.80
@@ -129,8 +136,8 @@ class CarInterface(CarInterfaceBase):
ret.mass = 1985. + STD_CARGO_KG
ret.wheelbase = 2.78
ret.steerRatio = 14.4 * 1.1 # 10% higher at the center seems reasonable
- elif candidate in (CAR.KIA_NIRO_EV, CAR.KIA_NIRO_PHEV, CAR.KIA_NIRO_HEV_2021):
- ret.mass = 1737. + STD_CARGO_KG
+ elif candidate in (CAR.KIA_NIRO_EV, CAR.KIA_NIRO_PHEV, CAR.KIA_NIRO_HEV_2021, CAR.KIA_NIRO_HEV_2ND_GEN):
+ ret.mass = 3452. * CV.LB_TO_KG + STD_CARGO_KG # average of all the cars
ret.wheelbase = 2.7
ret.steerRatio = 13.9 if CAR.KIA_NIRO_HEV_2021 else 13.73 # Spec
tire_stiffness_factor = 0.385
@@ -166,7 +173,7 @@ class CarInterface(CarInterfaceBase):
ret.wheelbase = 2.65
ret.steerRatio = 13.75
tire_stiffness_factor = 0.5
- elif candidate == CAR.KIA_K5_2021:
+ elif candidate in (CAR.KIA_K5_2021, CAR.KIA_K5_HEV_2020):
ret.mass = 3228. * CV.LB_TO_KG
ret.wheelbase = 2.85
ret.steerRatio = 13.27 # 2021 Kia K5 Steering Ratio (all trims)
@@ -185,10 +192,13 @@ class CarInterface(CarInterfaceBase):
ret.mass = 1767. + STD_CARGO_KG # SX Prestige trim support only
ret.wheelbase = 2.756
ret.steerRatio = 13.6
- elif candidate == CAR.KIA_SORENTO_PHEV_4TH_GEN:
- ret.mass = 4095.8 * CV.LB_TO_KG + STD_CARGO_KG # weight from EX and above trims, average of FWD and AWD versions (EX, X-Line EX AWD, SX, SX Pestige, X-Line SX Prestige AWD)
+ elif candidate in (CAR.KIA_SORENTO_4TH_GEN, CAR.KIA_SORENTO_PHEV_4TH_GEN):
ret.wheelbase = 2.81
- ret.steerRatio = 13.27 # steering ratio according to Kia News https://www.kiamedia.com/us/en/models/sorento-phev/2022/specifications
+ ret.steerRatio = 13.5 # average of the platforms
+ if candidate == CAR.KIA_SORENTO_4TH_GEN:
+ ret.mass = 3957 * CV.LB_TO_KG + STD_CARGO_KG
+ else:
+ ret.mass = 4537 * CV.LB_TO_KG + STD_CARGO_KG
# Genesis
elif candidate == CAR.GENESIS_GV60_EV_1ST_GEN:
@@ -238,8 +248,7 @@ class CarInterface(CarInterfaceBase):
# *** feature detection ***
if candidate in CANFD_CAR:
- bus = 5 if ret.flags & HyundaiFlags.CANFD_HDA2 else 4
- ret.enableBsm = 0x1e5 in fingerprint[bus]
+ ret.enableBsm = 0x1e5 in fingerprint[get_e_can_bus(ret)]
else:
ret.enableBsm = 0x58b in fingerprint[0]
@@ -324,5 +333,5 @@ class CarInterface(CarInterfaceBase):
return ret
- def apply(self, c):
- return self.CC.update(c, self.CS)
+ def apply(self, c, now_nanos):
+ return self.CC.update(c, self.CS, now_nanos)
diff --git a/selfdrive/car/hyundai/radar_interface.py b/selfdrive/car/hyundai/radar_interface.py
index 0d22611fb5..4ecca542b5 100644
--- a/selfdrive/car/hyundai/radar_interface.py
+++ b/selfdrive/car/hyundai/radar_interface.py
@@ -37,7 +37,7 @@ class RadarInterface(RadarInterfaceBase):
self.trigger_msg = RADAR_START_ADDR + RADAR_MSG_COUNT - 1
self.track_id = 0
- self.radar_off_can = CP.radarOffCan
+ self.radar_off_can = CP.radarUnavailable
self.rcp = get_radar_can_parser(CP)
def update(self, can_strings):
diff --git a/selfdrive/car/hyundai/tests/test_hyundai.py b/selfdrive/car/hyundai/tests/test_hyundai.py
index a52027f448..6ecfa03796 100755
--- a/selfdrive/car/hyundai/tests/test_hyundai.py
+++ b/selfdrive/car/hyundai/tests/test_hyundai.py
@@ -2,24 +2,19 @@
import unittest
from cereal import car
-from selfdrive.car.car_helpers import get_interface_attr
-from selfdrive.car.fw_versions import FW_QUERY_CONFIGS
-from selfdrive.car.hyundai.values import CANFD_CAR
+from selfdrive.car.hyundai.values import CANFD_CAR, FW_QUERY_CONFIG, FW_VERSIONS
Ecu = car.CarParams.Ecu
-
ECU_NAME = {v: k for k, v in Ecu.schema.enumerants.items()}
-VERSIONS = get_interface_attr("FW_VERSIONS", ignore_none=True)
class TestHyundaiFingerprint(unittest.TestCase):
def test_auxiliary_request_ecu_whitelist(self):
# Asserts only auxiliary Ecus can exist in database for CAN-FD cars
- config = FW_QUERY_CONFIGS['hyundai']
- whitelisted_ecus = {ecu for r in config.requests for ecu in r.whitelist_ecus if r.bus > 3}
+ whitelisted_ecus = {ecu for r in FW_QUERY_CONFIG.requests for ecu in r.whitelist_ecus if r.bus > 3}
for car_model in CANFD_CAR:
- ecus = {fw[0] for fw in VERSIONS['hyundai'][car_model].keys()}
+ ecus = {fw[0] for fw in FW_VERSIONS[car_model].keys()}
ecus_not_in_whitelist = ecus - whitelisted_ecus
ecu_strings = ", ".join([f'Ecu.{ECU_NAME[ecu]}' for ecu in ecus_not_in_whitelist])
self.assertEqual(len(ecus_not_in_whitelist), 0, f'{car_model}: Car model has ECUs not in auxiliary request whitelists: {ecu_strings}')
diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py
index 4d3f44d65f..4b7a295246 100644
--- a/selfdrive/car/hyundai/values.py
+++ b/selfdrive/car/hyundai/values.py
@@ -35,7 +35,7 @@ class CarControllerParams:
# To determine the limit for your car, find the maximum value that the stock LKAS will request.
# If the max stock LKAS request is <384, add your car to this list.
- elif CP.carFingerprint in (CAR.GENESIS_G80, CAR.GENESIS_G90, CAR.ELANTRA, CAR.HYUNDAI_GENESIS, CAR.IONIQ,
+ elif CP.carFingerprint in (CAR.GENESIS_G80, CAR.GENESIS_G90, CAR.ELANTRA, CAR.IONIQ,
CAR.IONIQ_EV_LTD, CAR.SANTA_FE_PHEV_2022, CAR.SONATA_LF, CAR.KIA_FORTE, CAR.KIA_NIRO_PHEV,
CAR.KIA_OPTIMA_H, CAR.KIA_SORENTO):
self.STEER_MAX = 255
@@ -58,8 +58,10 @@ class HyundaiFlags(IntFlag):
CANFD_CAMERA_SCC = 8
ALT_LIMITS = 16
-
ENABLE_BLINKERS = 32
+ CANFD_ALT_GEARS_2 = 64
+ SEND_LFA = 128
+ USE_FCA = 256
class CAR:
@@ -96,15 +98,18 @@ class CAR:
# Kia
KIA_FORTE = "KIA FORTE E 2018 & GT 2021"
KIA_K5_2021 = "KIA K5 2021"
+ KIA_K5_HEV_2020 = "KIA K5 HYBRID 2020"
KIA_NIRO_EV = "KIA NIRO EV 2020"
KIA_NIRO_PHEV = "KIA NIRO HYBRID 2019"
KIA_NIRO_HEV_2021 = "KIA NIRO HYBRID 2021"
+ KIA_NIRO_HEV_2ND_GEN = "KIA NIRO HYBRID 2ND GEN"
KIA_OPTIMA_G4 = "KIA OPTIMA 4TH GEN"
KIA_OPTIMA_G4_FL = "KIA OPTIMA 4TH GEN FACELIFT"
KIA_OPTIMA_H = "KIA OPTIMA HYBRID 2017 & SPORTS 2019"
KIA_SELTOS = "KIA SELTOS 2021"
KIA_SPORTAGE_5TH_GEN = "KIA SPORTAGE 5TH GEN"
KIA_SORENTO = "KIA SORENTO GT LINE 2018"
+ KIA_SORENTO_4TH_GEN = "KIA SORENTO 4TH GEN"
KIA_SORENTO_PHEV_4TH_GEN = "KIA SORENTO PLUG-IN HYBRID 4TH GEN"
KIA_SPORTAGE_HYBRID_5TH_GEN = "KIA SPORTAGE HYBRID 5TH GEN"
KIA_STINGER = "KIA STINGER GT2 2018"
@@ -122,9 +127,10 @@ class CAR:
class Footnote(Enum):
+ # footnotes which mention "red panda" will be replaced with the CAN FD panda kit on the shop page
CANFD = CarFootnote(
- "Requires a red panda, additional harness box, " +
- "additional OBD-C cable, USB-A to USB-A cable, and a USB-A to USB-C OTG dongle.",
+ "Requires a red panda for this CAN FD car. " +
+ "All the hardware needed is sold in the CAN FD kit.",
Column.MODEL, shop_footnote=True)
@@ -143,9 +149,12 @@ CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = {
HyundaiCarInfo("Hyundai Elantra GT 2017-19", harness=Harness.hyundai_e),
HyundaiCarInfo("Hyundai i30 2017-19", harness=Harness.hyundai_e),
],
- CAR.ELANTRA_2021: HyundaiCarInfo("Hyundai Elantra 2021-22", video_link="https://youtu.be/_EdYQtV52-c", harness=Harness.hyundai_k),
+ CAR.ELANTRA_2021: HyundaiCarInfo("Hyundai Elantra 2021-23", video_link="https://youtu.be/_EdYQtV52-c", harness=Harness.hyundai_k),
CAR.ELANTRA_HEV_2021: HyundaiCarInfo("Hyundai Elantra Hybrid 2021-23", video_link="https://youtu.be/_EdYQtV52-c", harness=Harness.hyundai_k),
- CAR.HYUNDAI_GENESIS: HyundaiCarInfo("Hyundai Genesis 2015-16", min_enable_speed=19 * CV.MPH_TO_MS, harness=Harness.hyundai_j), # TODO: check 2015 packages
+ CAR.HYUNDAI_GENESIS: [
+ HyundaiCarInfo("Hyundai Genesis 2015-16", min_enable_speed=19 * CV.MPH_TO_MS, harness=Harness.hyundai_j), # TODO: check 2015 packages
+ HyundaiCarInfo("Genesis G80 2017", "All", min_enable_speed=19 * CV.MPH_TO_MS, harness=Harness.hyundai_j),
+ ],
CAR.IONIQ: HyundaiCarInfo("Hyundai Ioniq Hybrid 2017-19", harness=Harness.hyundai_c),
CAR.IONIQ_HEV_2022: HyundaiCarInfo("Hyundai Ioniq Hybrid 2020-22", harness=Harness.hyundai_h), # TODO: confirm 2020-21 harness
CAR.IONIQ_EV_LTD: HyundaiCarInfo("Hyundai Ioniq Electric 2019", harness=Harness.hyundai_c),
@@ -160,7 +169,7 @@ CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = {
CAR.SANTA_FE_2022: HyundaiCarInfo("Hyundai Santa Fe 2021-22", "All", "https://youtu.be/VnHzSTygTS4", harness=Harness.hyundai_l),
CAR.SANTA_FE_HEV_2022: HyundaiCarInfo("Hyundai Santa Fe Hybrid 2022", "All", harness=Harness.hyundai_l),
CAR.SANTA_FE_PHEV_2022: HyundaiCarInfo("Hyundai Santa Fe Plug-in Hybrid 2022", "All", harness=Harness.hyundai_l),
- CAR.SONATA: HyundaiCarInfo("Hyundai Sonata 2020-22", "All", "https://www.youtube.com/watch?v=ix63r9kE3Fw", harness=Harness.hyundai_a),
+ CAR.SONATA: HyundaiCarInfo("Hyundai Sonata 2020-23", "All", "https://www.youtube.com/watch?v=ix63r9kE3Fw", harness=Harness.hyundai_a),
CAR.SONATA_LF: HyundaiCarInfo("Hyundai Sonata 2018-19", harness=Harness.hyundai_e),
CAR.TUCSON: [
HyundaiCarInfo("Hyundai Tucson 2021", min_enable_speed=19 * CV.MPH_TO_MS, harness=Harness.hyundai_l),
@@ -182,22 +191,27 @@ CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = {
HyundaiCarInfo("Hyundai Tucson 2023", "All", harness=Harness.hyundai_n),
],
CAR.TUCSON_HYBRID_4TH_GEN: HyundaiCarInfo("Hyundai Tucson Hybrid 2022", "All", harness=Harness.hyundai_n),
- CAR.SANTA_CRUZ_1ST_GEN: HyundaiCarInfo("Hyundai Santa Cruz 2021-22", harness=Harness.hyundai_n),
+ CAR.SANTA_CRUZ_1ST_GEN: HyundaiCarInfo("Hyundai Santa Cruz 2022-23", harness=Harness.hyundai_n),
# Kia
CAR.KIA_FORTE: HyundaiCarInfo("Kia Forte 2019-21", harness=Harness.hyundai_g),
CAR.KIA_K5_2021: HyundaiCarInfo("Kia K5 2021-22", harness=Harness.hyundai_a),
+ CAR.KIA_K5_HEV_2020: HyundaiCarInfo("Kia K5 Hybrid 2020", harness=Harness.hyundai_a),
CAR.KIA_NIRO_EV: [
HyundaiCarInfo("Kia Niro EV 2019", "All", "https://www.youtube.com/watch?v=lT7zcG6ZpGo", harness=Harness.hyundai_h),
HyundaiCarInfo("Kia Niro EV 2020", "All", "https://www.youtube.com/watch?v=lT7zcG6ZpGo", harness=Harness.hyundai_f),
HyundaiCarInfo("Kia Niro EV 2021", "All", "https://www.youtube.com/watch?v=lT7zcG6ZpGo", harness=Harness.hyundai_c),
HyundaiCarInfo("Kia Niro EV 2022", "All", "https://www.youtube.com/watch?v=lT7zcG6ZpGo", harness=Harness.hyundai_h),
],
- CAR.KIA_NIRO_PHEV: HyundaiCarInfo("Kia Niro Plug-in Hybrid 2018-19", "All", min_enable_speed=10. * CV.MPH_TO_MS, harness=Harness.hyundai_c),
+ CAR.KIA_NIRO_PHEV: [
+ HyundaiCarInfo("Kia Niro Plug-in Hybrid 2018-19", "All", min_enable_speed=10. * CV.MPH_TO_MS, harness=Harness.hyundai_c),
+ HyundaiCarInfo("Kia Niro Plug-in Hybrid 2020", "All", harness=Harness.hyundai_d),
+ ],
CAR.KIA_NIRO_HEV_2021: [
HyundaiCarInfo("Kia Niro Hybrid 2021", harness=Harness.hyundai_f), # TODO: could be hyundai_d, verify
HyundaiCarInfo("Kia Niro Hybrid 2022", harness=Harness.hyundai_h),
],
+ CAR.KIA_NIRO_HEV_2ND_GEN: HyundaiCarInfo("Kia Niro Hybrid 2023", harness=Harness.hyundai_a),
CAR.KIA_OPTIMA_G4: HyundaiCarInfo("Kia Optima 2017", "Advanced Smart Cruise Control", harness=Harness.hyundai_b), # TODO: may support 2016, 2018
CAR.KIA_OPTIMA_G4_FL: HyundaiCarInfo("Kia Optima 2019-20", harness=Harness.hyundai_g),
CAR.KIA_OPTIMA_H: [
@@ -210,7 +224,8 @@ CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = {
HyundaiCarInfo("Kia Sorento 2018", "Advanced Smart Cruise Control", "https://www.youtube.com/watch?v=Fkh3s6WHJz8", harness=Harness.hyundai_c),
HyundaiCarInfo("Kia Sorento 2019", video_link="https://www.youtube.com/watch?v=Fkh3s6WHJz8", harness=Harness.hyundai_e),
],
- CAR.KIA_SORENTO_PHEV_4TH_GEN: HyundaiCarInfo("Kia Sorento Plug-in Hybrid 2022-23", "Smart Cruise Control (SCC)", harness=Harness.hyundai_a),
+ CAR.KIA_SORENTO_4TH_GEN: HyundaiCarInfo("Kia Sorento 2022-23", harness=Harness.hyundai_k),
+ CAR.KIA_SORENTO_PHEV_4TH_GEN: HyundaiCarInfo("Kia Sorento Plug-in Hybrid 2022-23", harness=Harness.hyundai_a),
CAR.KIA_SPORTAGE_HYBRID_5TH_GEN: HyundaiCarInfo("Kia Sportage Hybrid 2023", harness=Harness.hyundai_n),
CAR.KIA_STINGER: HyundaiCarInfo("Kia Stinger 2018-20", video_link="https://www.youtube.com/watch?v=MJ94qoofYw0", harness=Harness.hyundai_c),
CAR.KIA_STINGER_2022: HyundaiCarInfo("Kia Stinger 2022", "All", harness=Harness.hyundai_k),
@@ -222,11 +237,14 @@ CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = {
],
# Genesis
- CAR.GENESIS_GV60_EV_1ST_GEN: HyundaiCarInfo("Genesis GV60 2023", "All", harness=Harness.hyundai_k),
+ CAR.GENESIS_GV60_EV_1ST_GEN: [
+ HyundaiCarInfo("Genesis GV60 (Advanced Trim) 2023", "All", harness=Harness.hyundai_a),
+ HyundaiCarInfo("Genesis GV60 (Performance Trim) 2023", "All", harness=Harness.hyundai_k),
+ ],
CAR.GENESIS_G70: HyundaiCarInfo("Genesis G70 2018-19", "All", harness=Harness.hyundai_f),
CAR.GENESIS_G70_2020: HyundaiCarInfo("Genesis G70 2020", "All", harness=Harness.hyundai_f),
CAR.GENESIS_GV70_1ST_GEN: HyundaiCarInfo("Genesis GV70 2022-23", "All", harness=Harness.hyundai_l),
- CAR.GENESIS_G80: HyundaiCarInfo("Genesis G80 2017-19", "All", harness=Harness.hyundai_h),
+ CAR.GENESIS_G80: HyundaiCarInfo("Genesis G80 2018-19", "All", harness=Harness.hyundai_h),
CAR.GENESIS_G90: HyundaiCarInfo("Genesis G90 2017-18", "All", harness=Harness.hyundai_c),
}
@@ -358,6 +376,13 @@ FW_QUERY_CONFIG = FwQueryConfig(
)
FW_VERSIONS = {
+ CAR.HYUNDAI_GENESIS: {
+ (Ecu.fwdCamera, 0x7c4, None): [
+ b'\xf1\x00DH LKAS 1.1 -150210',
+ b'\xf1\x00DH LKAS 1.4 -140110',
+ b'\xf1\x00DH LKAS 1.5 -140425',
+ ],
+ },
CAR.IONIQ: {
(Ecu.fwdRadar, 0x7d0, None): [
b'\xf1\x00AEhe SCC H-CUP 1.01 1.01 96400-G2000 ',
@@ -395,29 +420,32 @@ FW_VERSIONS = {
},
CAR.IONIQ_PHEV: {
(Ecu.fwdRadar, 0x7d0, None): [
- b'\xf1\000AEhe SCC FHCUP 1.00 1.02 99110-G2100 ',
+ b'\xf1\x00AEhe SCC FHCUP 1.00 1.02 99110-G2100 ',
b'\xf1\x00AEhe SCC F-CUP 1.00 1.00 99110-G2200 ',
b'\xf1\x00AEhe SCC F-CUP 1.00 1.00 99110-G2600 ',
+ b'\xf1\x00AEhe SCC F-CUP 1.00 1.02 99110-G2100 ',
],
(Ecu.eps, 0x7d4, None): [
- b'\xf1\000AE MDPS C 1.00 1.01 56310/G2510 4APHC101',
+ 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',
],
(Ecu.fwdCamera, 0x7c4, None): [
- b'\xf1\000AEP MFC AT USA LHD 1.00 1.01 95740-G2600 190819',
+ 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',
],
(Ecu.engine, 0x7e0, None): [
b'\xf1\x816H6F6051\x00\x00\x00\x00\x00\x00\x00\x00',
b'\xf1\x816H6G6051\x00\x00\x00\x00\x00\x00\x00\x00',
+ b'\xf1\x816H6G5051\x00\x00\x00\x00\x00\x00\x00\x00',
],
(Ecu.transmission, 0x7e1, None): [
b'\xf1\x816U3J9051\000\000\xf1\0006U3H1_C2\000\0006U3J9051\000\000PAE0G16NL0\x82zT\xd2',
b'\xf1\x816U3J8051\x00\x00\xf1\x006U3H1_C2\x00\x006U3J8051\x00\x00PAETG16UL0\x00\x00\x00\x00',
- b'\xf1\x816U3J9051\x00\x00\xf1\x006U3H1_C2\x00\x006U3J9051\x00\x00PAE0G16NL2\xad\xeb\xabt',
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',
],
},
CAR.IONIQ_EV_2020: {
@@ -445,16 +473,19 @@ FW_VERSIONS = {
b'\xf1\x00AE MDPS C 1.00 1.04 56310/G7501 4AEEC104',
b'\xf1\x00AE MDPS C 1.00 1.03 56310/G7300 4AEEC103',
b'\xf1\x00AE MDPS C 1.00 1.03 56310G7300\x00 4AEEC103',
+ b'\xf1\x00AE MDPS C 1.00 1.04 56310/G7301 4AEEC104',
],
(Ecu.fwdCamera, 0x7c4, None): [
b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.00 95740-G7200 160418',
b'\xf1\x00AEE MFC AT USA LHD 1.00 1.00 95740-G2400 180222',
b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.00 95740-G2300 170703',
+ b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.00 95740-G2400 180222',
],
},
CAR.IONIQ_HEV_2022: {
(Ecu.fwdRadar, 0x7d0, None): [
b'\xf1\x00AEhe SCC F-CUP 1.00 1.00 99110-G2600 ',
+ b'\xf1\x00AEhe SCC FHCUP 1.00 1.00 99110-G2600 ',
],
(Ecu.eps, 0x7d4, None): [
b'\xf1\x00AE MDPS C 1.00 1.01 56310G2510\x00 4APHC101',
@@ -467,6 +498,7 @@ FW_VERSIONS = {
],
(Ecu.transmission, 0x7e1, None): [
b'\xf1\x816U3J9051\x00\x00\xf1\x006U3H1_C2\x00\x006U3J9051\x00\x00HAE0G16NL2\x00\x00\x00\x00',
+ b'\xf1\x006U3H1_C2\x00\x006U3J9051\x00\x00HAE0G16NL2\x96\xda\xd4\xee',
],
},
CAR.SONATA: {
@@ -512,6 +544,8 @@ FW_VERSIONS = {
b'HM6M1_0a0_G20',
b'HM6M2_0a0_BD0',
b'\xf1\x8739110-2S278\xf1\x82DNDVD5GMCCXXXL5B',
+ b'\xf1\x8739110-2S041\xf1\x81HM6M1_0a0_M00',
+ b'\xf1\x81HM6M1_0a0_G20',
],
(Ecu.eps, 0x7d4, None): [
b'\xf1\x00DN8 MDPS C 1,00 1,01 56310L0010\x00 4DNAC101', # modified firmware
@@ -529,6 +563,7 @@ FW_VERSIONS = {
b'\xf1\x8756310L0210\x00\xf1\x00DN8 MDPS C 1.00 1.01 56310L0210\x00 4DNAC101',
b'\xf1\x8757700-L0000\xf1\x00DN8 MDPS R 1.00 1.00 57700-L0000 4DNAP100',
b'\xf1\x00DN8 MDPS R 1.00 1.00 57700-L0000 4DNAP101',
+ b'\xf1\x00DN8 MDPS C 1.00 1.01 56310-L0210 4DNAC102',
],
(Ecu.fwdCamera, 0x7c4, None): [
b'\xf1\x00DN8 MFC AT KOR LHD 1.00 1.02 99211-L1000 190422',
@@ -538,6 +573,7 @@ FW_VERSIONS = {
b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.03 99211-L0000 210603',
b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.05 99211-L1000 201109',
b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.06 99211-L1000 210325',
+ b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.07 99211-L1000 211223',
],
(Ecu.transmission, 0x7e1, None): [
b'\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v',
@@ -548,6 +584,7 @@ FW_VERSIONS = {
b'\xf1\x00HT6WA250BLHT6WA910A1SDN8G25NB1\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
b'\xf1\x00HT6WA250BLHT6WA910A1SDN8G25NB1\x00\x00\x00\x00\x00\x00\x96\xa1\xf1\x92',
b'\xf1\x00HT6WA280BLHT6WAD10A1SDN8G25NB2\x00\x00\x00\x00\x00\x00\x08\xc9O:',
+ b'\xf1\x00HT6WA280BLHT6WAD10A1SDN8G25NB4\x00\x00\x00\x00\x00\x00g!l[',
b'\xf1\x00T02601BL T02730A1 VDN8T25XXX730NS5\xf7_\x92\xf5',
b'\xf1\x00T02601BL T02832A1 VDN8T25XXX832NS8G\x0e\xfeE',
b'\xf1\x87954A02N060\x00\x00\x00\x00\x00\xf1\x81T02730A1 \xf1\x00T02601BL T02730A1 VDN8T25XXX730NS5\xf7_\x92\xf5',
@@ -599,6 +636,7 @@ FW_VERSIONS = {
b'\xf1\x87SALFBA7460044GJ2gx\x87\x88Vf\x86hx\x88\x87\x88wwwwgw\x86wd?\xfa\xff\x86U_\xff\xaf\x1f\xf1\x81U913\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U913\x00\x00\x00\x00\x00\x00SDN8T16NB2\n\xdd^\xbc',
b'\xf1\x87SAMFBA8105254GJ2wx\x87\x88Vf\x86hx\x88\x87\x88wwwwwwww\x86O\xfa\xff\x99\x88\x7f\xffZG\xf1\x81U913\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U913\x00\x00\x00\x00\x00\x00SDN8T16NB2\n\xdd^\xbc',
b'\xf1\x87SANFB45889451GC7wx\x87\x88gw\x87x\x88\x88x\x88\x87wxw\x87wxw\x87\x8f\xfc\xffeU\x8f\xff+Q\xf1\x81U913\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U913\x00\x00\x00\x00\x00\x00SDN8T16NB2\n\xdd^\xbc',
+ b'\xf1\x00T02601BL T02900A1 VDN8T25XXX900NSA\xb9\x13\xf9p',
],
},
CAR.SONATA_LF: {
@@ -648,14 +686,16 @@ FW_VERSIONS = {
},
CAR.SANTA_FE: {
(Ecu.fwdRadar, 0x7d0, None): [
+ b'\xf1\x00TM__ SCC F-CUP 1.00 1.00 99110-S1210 ',
b'\xf1\x00TM__ SCC F-CUP 1.00 1.01 99110-S2000 ',
b'\xf1\x00TM__ SCC F-CUP 1.00 1.02 99110-S2000 ',
b'\xf1\x00TM__ SCC F-CUP 1.00 1.03 99110-S2000 ',
],
(Ecu.abs, 0x7d1, None): [
b'\xf1\x00TM ESC \r 100\x18\x031 58910-S2650',
+ b'\xf1\x00TM ESC \r 105\x19\x05# 58910-S1500',
b'\xf1\x00TM ESC \r 103\x18\x11\x08 58910-S2650',
- b'\xf1\x00TM ESC \r 104\x19\a\b 58910-S2650',
+ b'\xf1\x00TM ESC \r 104\x19\x07\x08 58910-S2650',
b'\xf1\x00TM ESC \x02 100\x18\x030 58910-S2600',
b'\xf1\x00TM ESC \x02 102\x18\x07\x01 58910-S2600',
b'\xf1\x00TM ESC \x02 103\x18\x11\x07 58910-S2600',
@@ -672,11 +712,15 @@ FW_VERSIONS = {
b'\xf1\x00TM MDPS C 1.00 1.00 56340-S2000 8409',
b'\xf1\x00TM MDPS C 1.00 1.00 56340-S2000 8A12',
b'\xf1\x00TM MDPS C 1.00 1.01 56340-S2000 9129',
+ b'\xf1\x00TM MDPS R 1.00 1.02 57700-S1100 4TMDP102'
],
(Ecu.fwdCamera, 0x7c4, None): [
+ b'\xf1\x00TM MFC AT EUR LHD 1.00 1.01 99211-S1010 181207',
b'\xf1\x00TM MFC AT USA LHD 1.00 1.00 99211-S2000 180409',
],
(Ecu.transmission, 0x7e1, None): [
+ b'\xf1\x00bcsh8p54 U833\x00\x00\x00\x00\x00\x00TTM4V22US3_<]\xf1',
+ b'\xf1\x006W351_C2\x00\x006W3E1051\x00\x00TTM4T20NS5\x00\x00\x00\x00',
b'\xf1\x87LBJSGA7082574HG0\x87www\x98\x88\x88\x88\x99\xaa\xb9\x9afw\x86gx\x99\xa7\x89co\xf8\xffvU_\xffR\xaf\xf1\x816W3C2051\x00\x00\xf1\x006W351_C2\x00\x006W3C2051\x00\x00TTM2T20NS1\x00\xa6\xe0\x91',
b'\xf1\x87LBKSGA0458404HG0vfvg\x87www\x89\x99\xa8\x99y\xaa\xa7\x9ax\x88\xa7\x88t_\xf9\xff\x86w\x8f\xff\x15x\xf1\x816W3C2051\x00\x00\xf1\x006W351_C2\x00\x006W3C2051\x00\x00TTM2T20NS1\x00\x00\x00\x00',
b'\xf1\x87LDJUEA6010814HG1\x87w\x87x\x86gvw\x88\x88\x98\x88gw\x86wx\x88\x97\x88\x85o\xf8\xff\x86f_\xff\xd37\xf1\x816W3C2051\x00\x00\xf1\x006W351_C2\x00\x006W3C2051\x00\x00TTM4T20NS0\xf8\x19\x92g',
@@ -707,7 +751,6 @@ FW_VERSIONS = {
(Ecu.fwdRadar, 0x7d0, None): [
b'\xf1\x00TM__ SCC F-CUP 1.00 1.00 99110-S1500 ',
b'\xf1\x8799110S1500\xf1\x00TM__ SCC F-CUP 1.00 1.00 99110-S1500 ',
- b'\xf1\x8799110S1500\xf1\x00TM__ SCC FHCUP 1.00 1.00 99110-S1500 ',
b'\xf1\x00TM__ SCC FHCUP 1.00 1.00 99110-S1500 ',
],
(Ecu.abs, 0x7d1, None): [
@@ -741,6 +784,7 @@ FW_VERSIONS = {
b'\xf1\x00TMA MFC AT USA LHD 1.00 1.01 99211-S2500 210205',
],
(Ecu.transmission, 0x7e1, None): [
+ b'\xf1\x00T02601BL T02900A1 VTMPT25XXX900NSA\xf3\xf4Uj',
b'\xf1\x87SDMXCA9087684GN1VfvgUUeVwwgwwwwwffffU?\xfb\xff\x97\x88\x7f\xff+\xa4\xf1\x89HT6WAD00A1\xf1\x82STM4G25NH1\x00\x00\x00\x00\x00\x00',
b'\xf1\x00T02601BL T02730A1 VTMPT25XXX730NS2\xa6\x06\x88\xf7',
b'\xf1\x87SDMXCA8653204GN1EVugEUuWwwwwww\x87wwwwwv/\xfb\xff\xa8\x88\x9f\xff\xa5\x9c\xf1\x89HT6WAD00A1\xf1\x82STM4G25NH1\x00\x00\x00\x00\x00\x00',
@@ -755,19 +799,23 @@ FW_VERSIONS = {
},
CAR.SANTA_FE_HEV_2022: {
(Ecu.fwdRadar, 0x7d0, None): [
- b'\xf1\x8799110CL500\xf1\x00TMhe SCC FHCUP 1.00 1.00 99110-CL500 ',
+ b'\xf1\x00TMhe SCC FHCUP 1.00 1.00 99110-CL500 ',
],
(Ecu.eps, 0x7d4, None): [
b'\xf1\x00TM MDPS C 1.00 1.02 56310-CLAC0 4TSHC102',
+ b'\xf1\x00TM MDPS R 1.00 1.05 57700-CL000 4TSHP105',
],
(Ecu.fwdCamera, 0x7c4, None): [
+ b'\xf1\x00TMH MFC AT EUR LHD 1.00 1.06 99211-S1500 220727',
b'\xf1\x00TMH MFC AT USA LHD 1.00 1.03 99211-S1500 210224',
],
(Ecu.transmission, 0x7e1, None): [
+ b'\xf1\x00PSBG2333 E16\x00\x00\x00\x00\x00\x00\x00TTM2H16UA3I\x94\xac\x8f',
b'\xf1\x87959102T250\x00\x00\x00\x00\x00\xf1\x81E14\x00\x00\x00\x00\x00\x00\x00\xf1\x00PSBG2333 E14\x00\x00\x00\x00\x00\x00\x00TTM2H16SA2\x80\xd7l\xb2',
],
(Ecu.engine, 0x7e0, None): [
b'\xf1\x87391312MTC1',
+ b'\xf1\x87391312MTE0',
],
},
CAR.SANTA_FE_PHEV_2022: {
@@ -794,6 +842,7 @@ FW_VERSIONS = {
b'\xf1\x00CK__ SCC F_CUP 1.00 1.01 96400-J5100 ',
b'\xf1\x00CK__ SCC F_CUP 1.00 1.03 96400-J5100 ',
b'\xf1\x00CK__ SCC F_CUP 1.00 1.01 96400-J5000 ',
+ b'\xf1\x00CK__ SCC F_CUP 1.00 1.02 96400-J5100 ',
],
(Ecu.engine, 0x7e0, None): [
b'\xf1\x81606DE051\x00\x00\x00\x00\x00\x00\x00\x00',
@@ -801,6 +850,7 @@ FW_VERSIONS = {
b'\xf1\x82CKJN3TMSDE0B\x00\x00\x00\x00',
b'\xf1\x82CKKN3TMD_H0A\x00\x00\x00\x00',
b'\xe0\x19\xff\xe7\xe7g\x01\xa2\x00\x0f\x00\x9e\x00\x06\x00\xff\xff\xff\xff\xff\xff\x00\x00\xff\xff\xff\xff\xff\xff\x00\x00\x0f\x0e\x0f\x0f\x0e\r\x00\x00\x7f\x02.\xff\x00\x00~p\x00\x00\x00\x00u\xff\xf9\xff\x00\x00\x00\x00V\t\xd5\x01\xc0\x00\x00\x00\x007\xfb\xfc\x0b\x8d\x00',
+ b'\xf1\x81640H0051\x00\x00\x00\x00\x00\x00\x00\x00',
],
(Ecu.eps, 0x7d4, None): [
b'\xf1\x00CK MDPS R 1.00 1.04 57700-J5200 4C2CL104',
@@ -808,6 +858,7 @@ FW_VERSIONS = {
b'\xf1\x00CK MDPS R 1.00 1.04 57700-J5420 4C4VL104',
b'\xf1\x00CK MDPS R 1.00 1.06 57700-J5420 4C4VL106',
b'\xf1\x00CK MDPS R 1.00 1.07 57700-J5220 4C2VL107',
+ b'\xf1\x00CK MDPS R 1.00 1.06 57700-J5220 4C2VL106',
],
(Ecu.fwdCamera, 0x7c4, None): [
b'\xf1\x00CK MFC AT USA LHD 1.00 1.03 95740-J5000 170822',
@@ -815,6 +866,7 @@ FW_VERSIONS = {
b'\xf1\x00CK MFC AT EUR LHD 1.00 1.03 95740-J5000 170822',
],
(Ecu.transmission, 0x7e1, None): [
+ b'\xf1\x00bcsh8p54 E25\x00\x00\x00\x00\x00\x00\x00SCK0T33NB2\xb3\xee\xba\xdc',
b'\xf1\x87VCJLE17622572DK0vd6D\x99\x98y\x97vwVffUfvfC%CuT&Dx\x87o\xff{\x1c\xf1\x81E21\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 E21\x00\x00\x00\x00\x00\x00\x00SCK0T33NB0\x88\xa2\xe6\xf0',
b'\xf1\x87VDHLG17000192DK2xdFffT\xa5VUD$DwT\x86wveVeeD&T\x99\xba\x8f\xff\xcc\x99\xf1\x81E21\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 E21\x00\x00\x00\x00\x00\x00\x00SCK0T33NB0\x88\xa2\xe6\xf0',
b'\xf1\x87VDHLG17000192DK2xdFffT\xa5VUD$DwT\x86wveVeeD&T\x99\xba\x8f\xff\xcc\x99\xf1\x89E21\x00\x00\x00\x00\x00\x00\x00\xf1\x82SCK0T33NB0',
@@ -1006,6 +1058,25 @@ FW_VERSIONS = {
b'\xf1\x81640H0051\x00\x00\x00\x00\x00\x00\x00\x00',
],
},
+ CAR.GENESIS_G80: {
+ (Ecu.fwdRadar, 0x7d0, None): [
+ b'\xf1\x00DH__ SCC F-CUP 1.00 1.01 96400-B1120 ',
+ ],
+ (Ecu.fwdCamera, 0x7c4, None): [
+ b'\xf1\x00DH LKAS AT USA LHD 1.01 1.03 95895-B1500 180713',
+ b'\xf1\x00DH LKAS AT USA LHD 1.01 1.02 95895-B1500 170810',
+ b'\xf1\x00DH LKAS AT USA LHD 1.01 1.01 95895-B1500 161014',
+ ],
+ (Ecu.transmission, 0x7e1, None): [
+ b'\xf1\x00bcsh8p54 E21\x00\x00\x00\x00\x00\x00\x00SDH0T33NH4\xd7O\x9e\xc9',
+ b'\xf1\x00bcsh8p54 E18\x00\x00\x00\x00\x00\x00\x00TDH0G38NH3:-\xa9n',
+ b'\xf1\x00bcsh8p54 E18\x00\x00\x00\x00\x00\x00\x00SDH0G38NH2j\x9dA\x1c',
+ b'\xf1\x00bcsh8p54 E18\x00\x00\x00\x00\x00\x00\x00SDH0T33NH3\x97\xe6\xbc\xb8',
+ ],
+ (Ecu.engine, 0x7e0, None): [
+ b'\xf1\x81640F0051\x00\x00\x00\x00\x00\x00\x00\x00',
+ ],
+ },
CAR.GENESIS_G90: {
(Ecu.transmission, 0x7e1, None): [b'\xf1\x87VDGMD15866192DD3x\x88x\x89wuFvvfUf\x88vWwgwwwvfVgx\x87o\xff\xbc^\xf1\x81E14\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcshcm49 E14\x00\x00\x00\x00\x00\x00\x00SHI0G50NB1tc5\xb7'],
(Ecu.fwdRadar, 0x7d0, None): [b'\xf1\x00HI__ SCC F-CUP 1.00 1.01 96400-D2100 '],
@@ -1094,6 +1165,23 @@ FW_VERSIONS = {
b'\xf1\x00bcsh8p54 U913\x00\x00\x00\x00\x00\x00TDL4T16NB05\x94t\x18',
],
},
+ CAR.KIA_K5_HEV_2020: {
+ (Ecu.fwdRadar, 0x7D0, None): [
+ b'\xf1\x00DLhe SCC FHCUP 1.00 1.02 99110-L7000 ',
+ ],
+ (Ecu.eps, 0x7D4, None): [
+ b'\xf1\x00DL3 MDPS C 1.00 1.02 56310-L7000 4DLHC102',
+ ],
+ (Ecu.fwdCamera, 0x7C4, None): [
+ b'\xf1\x00DL3HMFC AT KOR LHD 1.00 1.02 99210-L2000 200309',
+ ],
+ (Ecu.engine, 0x7E0, None): [
+ b'\xf1\x87391162JLA0',
+ ],
+ (Ecu.transmission, 0x7E1, None): [
+ b'\xf1\x00PSBG2323 E08\x00\x00\x00\x00\x00\x00\x00TDL2H20KA2\xe3\xc6cz',
+ ],
+ },
CAR.KONA_EV: {
(Ecu.abs, 0x7D1, None): [
b'\xf1\x00OS IEB \r 105\x18\t\x18 58520-K4000',
@@ -1180,22 +1268,27 @@ FW_VERSIONS = {
(Ecu.engine, 0x7e0, None): [
b'\xf1\x816H6F4051\x00\x00\x00\x00\x00\x00\x00\x00',
b'\xf1\x816H6D1051\x00\x00\x00\x00\x00\x00\x00\x00',
+ b'\xf1\x816H6F6051\x00\x00\x00\x00\x00\x00\x00\x00',
],
(Ecu.transmission, 0x7e1, None): [
b"\xf1\x816U3J2051\x00\x00\xf1\x006U3H0_C2\x00\x006U3J2051\x00\x00PDE0G16NS2\xf4'\\\x91",
b'\xf1\x816U3J2051\x00\x00\xf1\x006U3H0_C2\x00\x006U3J2051\x00\x00PDE0G16NS2\x00\x00\x00\x00',
b'\xf1\x816U3H3051\x00\x00\xf1\x006U3H0_C2\x00\x006U3H3051\x00\x00PDE0G16NS1\x00\x00\x00\x00',
b'\xf1\x816U3H3051\x00\x00\xf1\x006U3H0_C2\x00\x006U3H3051\x00\x00PDE0G16NS1\x13\xcd\x88\x92',
+ b'\xf1\x006U3H1_C2\x00\x006U3J9051\x00\x00PDE0G16NL2&[\xc3\x01',
],
(Ecu.eps, 0x7D4, None): [
b'\xf1\x00DE MDPS C 1.00 1.09 56310G5301\x00 4DEHC109',
+ b'\xf1\x00DE MDPS C 1.00 1.01 56310G5520\x00 4DEPC101',
],
(Ecu.fwdCamera, 0x7C4, None): [
b'\xf1\x00DEP MFC AT USA LHD 1.00 1.01 95740-G5010 170424',
b'\xf1\x00DEP MFC AT USA LHD 1.00 1.00 95740-G5010 170117',
+ b'\xf1\x00DEP MFC AT USA LHD 1.00 1.05 99211-G5000 190826',
],
(Ecu.fwdRadar, 0x7D0, None): [
b'\xf1\x00DEhe SCC H-CUP 1.01 1.02 96400-G5100 ',
+ b'\xf1\x00DEhe SCC F-CUP 1.00 1.02 99110-G5100 ',
],
},
CAR.KIA_NIRO_HEV_2021: {
@@ -1307,25 +1400,26 @@ FW_VERSIONS = {
(Ecu.fwdRadar, 0x7d0, None): [
b'\xf1\x00CN7_ SCC F-CUP 1.00 1.01 99110-AA000 ',
b'\xf1\x00CN7_ SCC FHCUP 1.00 1.01 99110-AA000 ',
+ b'\xf1\x00CN7_ SCC FNCUP 1.00 1.01 99110-AA000 ',
b'\xf1\x8799110AA000\xf1\x00CN7_ SCC FHCUP 1.00 1.01 99110-AA000 ',
b'\xf1\x8799110AA000\xf1\x00CN7_ SCC F-CUP 1.00 1.01 99110-AA000 ',
],
(Ecu.eps, 0x7d4, None): [
b'\xf1\x87\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\xf1\x00CN7 MDPS C 1.00 1.06 \x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00 4CNDC106',
b'\xf1\x8756310/AA070\xf1\x00CN7 MDPS C 1.00 1.06 56310/AA070 4CNDC106',
- b'\xf1\x8756310AA050\x00\xf1\x00CN7 MDPS C 1.00 1.06 56310AA050\x00 4CNDC106',
b'\xf1\x8756310AA050\x00\xf1\x00CN7 MDPS C 1.00 1.06 56310AA050\x00 4CNDC106\xf1\xa01.06',
+ b'\xf1\x00CN7 MDPS C 1.00 1.06 56310AA050\x00 4CNDC106',
],
(Ecu.fwdCamera, 0x7c4, None): [
b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.00 99210-AB000 200819',
b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.03 99210-AA000 200819',
b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.01 99210-AB000 210205',
b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.06 99210-AA000 220111',
+ b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.03 99210-AB000 220426',
],
(Ecu.abs, 0x7d1, None): [
b'\xf1\x00CN ESC \t 101 \x10\x03 58910-AB800',
b'\xf1\x8758910-AA800\xf1\x00CN ESC \t 104 \x08\x03 58910-AA800',
- b'\xf1\x8758910-AB800\xf1\x00CN ESC \t 101 \x10\x03 58910-AB800',
b'\xf1\x8758910-AA800\xf1\x00CN ESC \t 105 \x10\x03 58910-AA800',
b'\xf1\x8758910-AB800\xf1\x00CN ESC \t 101 \x10\x03 58910-AB800\xf1\xa01.01',
],
@@ -1343,6 +1437,7 @@ FW_VERSIONS = {
b'\xf1\x81HM6M2_0a0_FF0',
b'\xf1\x82CNCVD0AMFCXCSFFB',
b'\xf1\x870\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\xf1\x81HM6M2_0a0_G80',
+ b'\xf1\x870\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\xf1\x81HM6M2_0a0_HC0',
],
},
CAR.ELANTRA_HEV_2021: {
@@ -1457,6 +1552,7 @@ FW_VERSIONS = {
b'\xf1\x00CV1 MFC AT EUR LHD 1.00 1.05 99210-CV000 211027',
b'\xf1\x00CV1 MFC AT EUR LHD 1.00 1.06 99210-CV000 220328',
b'\xf1\x00CV1 MFC AT EUR RHD 1.00 1.00 99210-CV100 220630',
+ b'\xf1\x00CV1 MFC AT USA LHD 1.00 1.00 99210-CV100 220630',
],
},
CAR.IONIQ_5: {
@@ -1468,6 +1564,8 @@ FW_VERSIONS = {
b'\xf1\x00NE1 MFC AT EUR LHD 1.00 1.06 99211-GI000 210813',
b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.05 99211-GI010 220614',
b'\xf1\x00NE1 MFC AT EUR RHD 1.00 1.01 99211-GI010 211007',
+ b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.01 99211-GI010 211007',
+ b'\xf1\x00NE1 MFC AT EUR RHD 1.00 1.02 99211-GI010 211206',
],
},
CAR.TUCSON_4TH_GEN: {
@@ -1499,9 +1597,11 @@ FW_VERSIONS = {
CAR.SANTA_CRUZ_1ST_GEN: {
(Ecu.fwdCamera, 0x7c4, None): [
b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-CW000 14M',
+ b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-CW010 14X',
],
(Ecu.fwdRadar, 0x7d0, None): [
b'\xf1\x00NX4__ 1.00 1.00 99110-K5000 ',
+ b'\xf1\x00NX4__ 1.01 1.00 99110-K5000 ',
],
},
CAR.KIA_SPORTAGE_5TH_GEN: {
@@ -1517,23 +1617,42 @@ FW_VERSIONS = {
CAR.GENESIS_GV70_1ST_GEN: {
(Ecu.fwdCamera, 0x7c4, None): [
b'\xf1\x00JK1 MFC AT USA LHD 1.00 1.04 99211-AR000 210204',
+ b'\xf1\x00JK1 MFC AT USA LHD 1.00 1.01 99211-AR200 220125',
],
(Ecu.fwdRadar, 0x7d0, None): [
b'\xf1\x00JK1_ SCC FHCUP 1.00 1.02 99110-AR000 ',
+ b'\xf1\x00JK1_ SCC FHCUP 1.00 1.00 99110-AR200 ',
],
},
CAR.GENESIS_GV60_EV_1ST_GEN: {
(Ecu.fwdCamera, 0x7c4, None): [
b'\xf1\x00JW1 MFC AT USA LHD 1.00 1.02 99211-CU100 211215',
+ b'\xf1\x00JW1 MFC AT USA LHD 1.00 1.02 99211-CU000 211215',
],
(Ecu.fwdRadar, 0x7d0, None): [
b'\xf1\x00JW1_ RDR ----- 1.00 1.00 99110-CU000 ',
],
},
+ CAR.KIA_SORENTO_4TH_GEN: {
+ (Ecu.fwdCamera, 0x7c4, None): [
+ b'\xf1\x00MQ4 MFC AT USA LHD 1.00 1.05 99210-R5000 210623',
+ ],
+ (Ecu.fwdRadar, 0x7d0, None): [
+ b'\xf1\x00MQ4_ SCC FHCUP 1.00 1.06 99110-P2000 ',
+ ],
+ },
+ CAR.KIA_NIRO_HEV_2ND_GEN: {
+ (Ecu.fwdCamera, 0x7c4, None): [
+ b'\xf1\x00SG2HMFC AT USA LHD 1.01 1.08 99211-AT000 220531',
+ ],
+ (Ecu.fwdRadar, 0x7d0, None): [
+ b'\xf1\x00SG2_ RDR ----- 1.00 1.01 99110-AT000 ',
+ ],
+ },
}
CHECKSUM = {
- "crc8": [CAR.SANTA_FE, CAR.SONATA, CAR.PALISADE, CAR.KIA_SELTOS, CAR.ELANTRA_2021, CAR.ELANTRA_HEV_2021, CAR.SONATA_HYBRID, CAR.SANTA_FE_2022, CAR.KIA_K5_2021, CAR.SANTA_FE_HEV_2022, CAR.SANTA_FE_PHEV_2022],
+ "crc8": [CAR.SANTA_FE, CAR.SONATA, CAR.PALISADE, CAR.KIA_SELTOS, CAR.ELANTRA_2021, CAR.ELANTRA_HEV_2021, CAR.SONATA_HYBRID, CAR.SANTA_FE_2022, CAR.KIA_K5_2021, CAR.SANTA_FE_HEV_2022, CAR.SANTA_FE_PHEV_2022, CAR.KIA_K5_HEV_2020],
"6B": [CAR.KIA_SORENTO, CAR.HYUNDAI_GENESIS],
}
@@ -1541,25 +1660,23 @@ FEATURES = {
# which message has the gear
"use_cluster_gears": {CAR.ELANTRA, CAR.KONA},
"use_tcu_gears": {CAR.KIA_OPTIMA_G4, CAR.KIA_OPTIMA_G4_FL, CAR.SONATA_LF, CAR.VELOSTER, CAR.TUCSON},
- "use_elect_gears": {CAR.KIA_NIRO_EV, CAR.KIA_NIRO_PHEV, CAR.KIA_NIRO_HEV_2021, CAR.KIA_OPTIMA_H, CAR.IONIQ_EV_LTD, CAR.KONA_EV, CAR.IONIQ, CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.ELANTRA_HEV_2021, CAR.SONATA_HYBRID, CAR.KONA_HEV, CAR.IONIQ_HEV_2022, CAR.SANTA_FE_HEV_2022, CAR.SANTA_FE_PHEV_2022, CAR.IONIQ_PHEV_2019, CAR.KONA_EV_2022},
-
- # these cars use the FCA11 message for the AEB and FCW signals, all others use SCC12
- "use_fca": {CAR.SONATA, CAR.SONATA_HYBRID, CAR.ELANTRA, CAR.ELANTRA_2021, CAR.ELANTRA_HEV_2021, CAR.KIA_STINGER, CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.KONA_EV, CAR.KIA_FORTE, CAR.KIA_NIRO_EV, CAR.PALISADE, CAR.GENESIS_G70, CAR.GENESIS_G70_2020, CAR.KONA, CAR.SANTA_FE, CAR.KIA_SELTOS, CAR.KONA_HEV, CAR.SANTA_FE_2022, CAR.KIA_K5_2021, CAR.IONIQ_HEV_2022, CAR.SANTA_FE_HEV_2022, CAR.SANTA_FE_PHEV_2022, CAR.TUCSON, CAR.KONA_EV_2022, CAR.KIA_STINGER_2022},
+ "use_elect_gears": {CAR.KIA_NIRO_EV, CAR.KIA_NIRO_PHEV, CAR.KIA_NIRO_HEV_2021, CAR.KIA_OPTIMA_H, CAR.IONIQ_EV_LTD, CAR.KONA_EV, CAR.IONIQ, CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.ELANTRA_HEV_2021, CAR.SONATA_HYBRID, CAR.KONA_HEV, CAR.IONIQ_HEV_2022, CAR.SANTA_FE_HEV_2022, CAR.SANTA_FE_PHEV_2022, CAR.IONIQ_PHEV_2019, CAR.KONA_EV_2022, CAR.KIA_K5_HEV_2020},
}
-CANFD_CAR = {CAR.KIA_EV6, CAR.IONIQ_5, CAR.TUCSON_4TH_GEN, CAR.TUCSON_HYBRID_4TH_GEN, CAR.KIA_SPORTAGE_HYBRID_5TH_GEN, CAR.SANTA_CRUZ_1ST_GEN, CAR.KIA_SPORTAGE_5TH_GEN, CAR.GENESIS_GV70_1ST_GEN, CAR.KIA_SORENTO_PHEV_4TH_GEN, CAR.GENESIS_GV60_EV_1ST_GEN}
+CANFD_CAR = {CAR.KIA_EV6, CAR.IONIQ_5, CAR.TUCSON_4TH_GEN, CAR.TUCSON_HYBRID_4TH_GEN, CAR.KIA_SPORTAGE_HYBRID_5TH_GEN, CAR.SANTA_CRUZ_1ST_GEN, CAR.KIA_SPORTAGE_5TH_GEN, CAR.GENESIS_GV70_1ST_GEN, CAR.KIA_SORENTO_PHEV_4TH_GEN, CAR.GENESIS_GV60_EV_1ST_GEN, CAR.KIA_SORENTO_4TH_GEN, CAR.KIA_NIRO_HEV_2ND_GEN}
# The radar does SCC on these cars when HDA I, rather than the camera
-CANFD_RADAR_SCC_CAR = {CAR.GENESIS_GV70_1ST_GEN, CAR.KIA_SORENTO_PHEV_4TH_GEN}
+CANFD_RADAR_SCC_CAR = {CAR.GENESIS_GV70_1ST_GEN, CAR.KIA_SORENTO_PHEV_4TH_GEN, CAR.KIA_SORENTO_4TH_GEN}
# The camera does SCC on these cars, rather than the radar
CAMERA_SCC_CAR = {CAR.KONA_EV_2022, }
-HYBRID_CAR = {CAR.IONIQ_PHEV, CAR.ELANTRA_HEV_2021, CAR.KIA_NIRO_PHEV, CAR.KIA_NIRO_HEV_2021, CAR.SONATA_HYBRID, CAR.KONA_HEV, CAR.IONIQ, CAR.IONIQ_HEV_2022, CAR.SANTA_FE_HEV_2022, CAR.SANTA_FE_PHEV_2022, CAR.IONIQ_PHEV_2019, CAR.TUCSON_HYBRID_4TH_GEN, CAR.KIA_SPORTAGE_HYBRID_5TH_GEN, CAR.KIA_SORENTO_PHEV_4TH_GEN} # these cars use a different gas signal
+HYBRID_CAR = {CAR.IONIQ_PHEV, CAR.ELANTRA_HEV_2021, CAR.KIA_NIRO_PHEV, CAR.KIA_NIRO_HEV_2021, CAR.SONATA_HYBRID, CAR.KONA_HEV, CAR.IONIQ, CAR.IONIQ_HEV_2022, CAR.SANTA_FE_HEV_2022, CAR.SANTA_FE_PHEV_2022, CAR.IONIQ_PHEV_2019, CAR.TUCSON_HYBRID_4TH_GEN, CAR.KIA_SPORTAGE_HYBRID_5TH_GEN, CAR.KIA_SORENTO_PHEV_4TH_GEN, CAR.KIA_K5_HEV_2020, CAR.KIA_NIRO_HEV_2ND_GEN} # these cars use a different gas signal
EV_CAR = {CAR.IONIQ_EV_2020, CAR.IONIQ_EV_LTD, CAR.KONA_EV, CAR.KIA_NIRO_EV, CAR.KONA_EV_2022, CAR.KIA_EV6, CAR.IONIQ_5, CAR.GENESIS_GV60_EV_1ST_GEN}
# these cars require a special panda safety mode due to missing counters and checksums in the messages
-LEGACY_SAFETY_MODE_CAR = {CAR.HYUNDAI_GENESIS, CAR.IONIQ_EV_2020, CAR.IONIQ_EV_LTD, CAR.IONIQ_PHEV, CAR.IONIQ, CAR.KONA_EV, CAR.KIA_SORENTO, CAR.SONATA_LF, CAR.KIA_OPTIMA_G4, CAR.KIA_OPTIMA_G4_FL, CAR.VELOSTER, CAR.KIA_STINGER, 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_2020, CAR.IONIQ_EV_LTD, CAR.IONIQ_PHEV, CAR.IONIQ, CAR.KONA_EV, CAR.KIA_SORENTO, CAR.SONATA_LF, CAR.KIA_OPTIMA_G4, CAR.KIA_OPTIMA_G4_FL, CAR.VELOSTER,
+ CAR.GENESIS_G70, CAR.GENESIS_G80, CAR.KIA_CEED, CAR.ELANTRA, CAR.IONIQ_HEV_2022}
# If 0x500 is present on bus 1 it probably has a Mando radar outputting radar points.
# If no points are outputted by default it might be possible to turn it on using selfdrive/debug/hyundai_enable_radar_points.py
@@ -1580,6 +1697,7 @@ DBC = {
CAR.IONIQ_HEV_2022: dbc_dict('hyundai_kia_generic', None),
CAR.KIA_FORTE: dbc_dict('hyundai_kia_generic', None),
CAR.KIA_K5_2021: dbc_dict('hyundai_kia_generic', None),
+ CAR.KIA_K5_HEV_2020: dbc_dict('hyundai_kia_generic', 'hyundai_kia_mando_front_radar_generated'),
CAR.KIA_NIRO_EV: dbc_dict('hyundai_kia_generic', 'hyundai_kia_mando_front_radar_generated'),
CAR.KIA_NIRO_PHEV: dbc_dict('hyundai_kia_generic', 'hyundai_kia_mando_front_radar_generated'),
CAR.KIA_NIRO_HEV_2021: dbc_dict('hyundai_kia_generic', None),
@@ -1615,4 +1733,6 @@ DBC = {
CAR.GENESIS_GV70_1ST_GEN: dbc_dict('hyundai_canfd', None),
CAR.KIA_SORENTO_PHEV_4TH_GEN: dbc_dict('hyundai_canfd', None),
CAR.GENESIS_GV60_EV_1ST_GEN: dbc_dict('hyundai_canfd', None),
+ CAR.KIA_SORENTO_4TH_GEN: dbc_dict('hyundai_canfd', None),
+ CAR.KIA_NIRO_HEV_2ND_GEN: dbc_dict('hyundai_canfd', None),
}
diff --git a/selfdrive/car/interfaces.py b/selfdrive/car/interfaces.py
index ad1fd22b90..249818369c 100644
--- a/selfdrive/car/interfaces.py
+++ b/selfdrive/car/interfaces.py
@@ -88,13 +88,14 @@ class CarInterfaceBase(ABC):
return ACCEL_MIN, ACCEL_MAX
@classmethod
- def get_params(cls, candidate: str, fingerprint: Optional[Dict[int, Dict[int, int]]] = None, car_fw: Optional[List[car.CarParams.CarFw]] = None, experimental_long: bool = False):
- if fingerprint is None:
- fingerprint = gen_empty_fingerprint()
-
- if car_fw is None:
- car_fw = list()
+ def get_non_essential_params(cls, candidate: str):
+ """
+ Parameters essential to controlling the car may be incomplete or wrong without FW versions or fingerprints.
+ """
+ return cls.get_params(candidate, gen_empty_fingerprint(), list(), False)
+ @classmethod
+ def get_params(cls, candidate: str, fingerprint: Dict[int, Dict[int, int]], car_fw: List[car.CarParams.CarFw], experimental_long: bool):
ret = CarInterfaceBase.get_std_params(candidate)
ret = cls._get_params(ret, candidate, fingerprint, car_fw, experimental_long)
@@ -232,7 +233,7 @@ class CarInterfaceBase(ABC):
return reader
@abstractmethod
- def apply(self, c: car.CarControl) -> Tuple[car.CarControl.Actuators, List[bytes]]:
+ def apply(self, c: car.CarControl, now_nanos: int) -> Tuple[car.CarControl.Actuators, List[bytes]]:
pass
def create_common_events(self, cs_out, extra_gears=None, pcm_enable=True, allow_enable=True,
@@ -400,15 +401,15 @@ class CarStateBase(ABC):
return GearShifter.unknown
d: Dict[str, car.CarState.GearShifter] = {
- 'P': GearShifter.park, 'PARK': GearShifter.park,
- 'R': GearShifter.reverse, 'REVERSE': GearShifter.reverse,
- 'N': GearShifter.neutral, 'NEUTRAL': GearShifter.neutral,
- 'E': GearShifter.eco, 'ECO': GearShifter.eco,
- 'T': GearShifter.manumatic, 'MANUAL': GearShifter.manumatic,
- 'D': GearShifter.drive, 'DRIVE': GearShifter.drive,
- 'S': GearShifter.sport, 'SPORT': GearShifter.sport,
- 'L': GearShifter.low, 'LOW': GearShifter.low,
- 'B': GearShifter.brake, 'BRAKE': GearShifter.brake,
+ 'P': GearShifter.park, 'PARK': GearShifter.park,
+ 'R': GearShifter.reverse, 'REVERSE': GearShifter.reverse,
+ 'N': GearShifter.neutral, 'NEUTRAL': GearShifter.neutral,
+ 'E': GearShifter.eco, 'ECO': GearShifter.eco,
+ 'T': GearShifter.manumatic, 'MANUAL': GearShifter.manumatic,
+ 'D': GearShifter.drive, 'DRIVE': GearShifter.drive,
+ 'S': GearShifter.sport, 'SPORT': GearShifter.sport,
+ 'L': GearShifter.low, 'LOW': GearShifter.low,
+ 'B': GearShifter.brake, 'BRAKE': GearShifter.brake,
}
return d.get(gear.upper(), GearShifter.unknown)
diff --git a/selfdrive/car/mazda/carcontroller.py b/selfdrive/car/mazda/carcontroller.py
index 027822cc3f..cb401a8abd 100644
--- a/selfdrive/car/mazda/carcontroller.py
+++ b/selfdrive/car/mazda/carcontroller.py
@@ -1,6 +1,6 @@
from cereal import car
from opendbc.can.packer import CANPacker
-from selfdrive.car import apply_std_steer_torque_limits
+from selfdrive.car import apply_driver_steer_torque_limits
from selfdrive.car.mazda import mazdacan
from selfdrive.car.mazda.values import CarControllerParams, Buttons
@@ -15,7 +15,7 @@ class CarController:
self.brake_counter = 0
self.frame = 0
- def update(self, CC, CS):
+ def update(self, CC, CS, now_nanos):
can_sends = []
apply_steer = 0
@@ -23,8 +23,8 @@ class CarController:
if CC.latActive:
# calculate steer and also set limits due to driver torque
new_steer = int(round(CC.actuators.steer * CarControllerParams.STEER_MAX))
- apply_steer = apply_std_steer_torque_limits(new_steer, self.apply_steer_last,
- CS.out.steeringTorque, CarControllerParams)
+ apply_steer = apply_driver_steer_torque_limits(new_steer, self.apply_steer_last,
+ CS.out.steeringTorque, CarControllerParams)
if CC.cruiseControl.cancel:
# If brake is pressed, let us wait >70ms before trying to disable crz to avoid
diff --git a/selfdrive/car/mazda/interface.py b/selfdrive/car/mazda/interface.py
index fdd2439ff9..2930b002d4 100755
--- a/selfdrive/car/mazda/interface.py
+++ b/selfdrive/car/mazda/interface.py
@@ -14,7 +14,7 @@ class CarInterface(CarInterfaceBase):
def _get_params(ret, candidate, fingerprint, car_fw, experimental_long):
ret.carName = "mazda"
ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.mazda)]
- ret.radarOffCan = True
+ ret.radarUnavailable = True
ret.dashcamOnly = candidate not in (CAR.CX5_2022, CAR.CX9_2021)
@@ -69,5 +69,5 @@ class CarInterface(CarInterfaceBase):
return ret
- def apply(self, c):
- return self.CC.update(c, self.CS)
+ def apply(self, c, now_nanos):
+ return self.CC.update(c, self.CS, now_nanos)
diff --git a/selfdrive/car/mock/interface.py b/selfdrive/car/mock/interface.py
index 3ac487dbb7..13210c86d5 100755
--- a/selfdrive/car/mock/interface.py
+++ b/selfdrive/car/mock/interface.py
@@ -57,7 +57,7 @@ class CarInterface(CarInterfaceBase):
return ret
- def apply(self, c):
+ def apply(self, c, now_nanos):
# in mock no carcontrols
actuators = car.CarControl.Actuators.new_message()
return actuators, []
diff --git a/selfdrive/car/nissan/carcontroller.py b/selfdrive/car/nissan/carcontroller.py
index ff13812398..45c3dd720c 100644
--- a/selfdrive/car/nissan/carcontroller.py
+++ b/selfdrive/car/nissan/carcontroller.py
@@ -18,7 +18,7 @@ class CarController:
self.packer = CANPacker(dbc_name)
- def update(self, CC, CS):
+ def update(self, CC, CS, now_nanos):
actuators = CC.actuators
hud_control = CC.hudControl
pcm_cancel_cmd = CC.cruiseControl.cancel
diff --git a/selfdrive/car/nissan/interface.py b/selfdrive/car/nissan/interface.py
index 386e859089..074cd1cc57 100644
--- a/selfdrive/car/nissan/interface.py
+++ b/selfdrive/car/nissan/interface.py
@@ -19,7 +19,7 @@ class CarInterface(CarInterfaceBase):
ret.steerRatio = 17
ret.steerControlType = car.CarParams.SteerControlType.angle
- ret.radarOffCan = True
+ ret.radarUnavailable = True
if candidate in (CAR.ROGUE, CAR.XTRAIL):
ret.mass = 1610 + STD_CARGO_KG
@@ -56,5 +56,5 @@ class CarInterface(CarInterfaceBase):
return ret
- def apply(self, c):
- return self.CC.update(c, self.CS)
+ def apply(self, c, now_nanos):
+ return self.CC.update(c, self.CS, now_nanos)
diff --git a/selfdrive/car/nissan/values.py b/selfdrive/car/nissan/values.py
index 6371b56be8..e9af828e2b 100644
--- a/selfdrive/car/nissan/values.py
+++ b/selfdrive/car/nissan/values.py
@@ -39,7 +39,7 @@ class NissanCarInfo(CarInfo):
CAR_INFO: Dict[str, Optional[Union[NissanCarInfo, List[NissanCarInfo]]]] = {
CAR.XTRAIL: NissanCarInfo("Nissan X-Trail 2017"),
- CAR.LEAF: NissanCarInfo("Nissan Leaf 2018-22"),
+ CAR.LEAF: NissanCarInfo("Nissan Leaf 2018-22", video_link="https://youtu.be/vaMbtAh_0cY"),
CAR.LEAF_IC: None, # same platforms
CAR.ROGUE: NissanCarInfo("Nissan Rogue 2018-20"),
CAR.ALTIMA: NissanCarInfo("Nissan Altima 2019-20", harness=Harness.nissan_b),
diff --git a/selfdrive/car/subaru/carcontroller.py b/selfdrive/car/subaru/carcontroller.py
index a56e63408e..a6dbf4a39e 100644
--- a/selfdrive/car/subaru/carcontroller.py
+++ b/selfdrive/car/subaru/carcontroller.py
@@ -1,5 +1,5 @@
from opendbc.can.packer import CANPacker
-from selfdrive.car import apply_std_steer_torque_limits
+from selfdrive.car import apply_driver_steer_torque_limits
from selfdrive.car.subaru import subarucan
from selfdrive.car.subaru.values import DBC, GLOBAL_GEN2, PREGLOBAL_CARS, CarControllerParams
@@ -19,7 +19,7 @@ class CarController:
self.p = CarControllerParams(CP)
self.packer = CANPacker(DBC[CP.carFingerprint]['pt'])
- def update(self, CC, CS):
+ def update(self, CC, CS, now_nanos):
actuators = CC.actuators
hud_control = CC.hudControl
pcm_cancel_cmd = CC.cruiseControl.cancel
@@ -34,7 +34,7 @@ class CarController:
# limits due to driver torque
new_steer = int(round(apply_steer))
- apply_steer = apply_std_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.p)
+ apply_steer = apply_driver_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.p)
if not CC.latActive:
apply_steer = 0
diff --git a/selfdrive/car/subaru/interface.py b/selfdrive/car/subaru/interface.py
index 22468801ec..733482ef82 100644
--- a/selfdrive/car/subaru/interface.py
+++ b/selfdrive/car/subaru/interface.py
@@ -11,7 +11,7 @@ class CarInterface(CarInterfaceBase):
@staticmethod
def _get_params(ret, candidate, fingerprint, car_fw, experimental_long):
ret.carName = "subaru"
- ret.radarOffCan = True
+ ret.radarUnavailable = True
ret.dashcamOnly = candidate in PREGLOBAL_CARS
ret.autoResumeSng = False
@@ -112,5 +112,5 @@ class CarInterface(CarInterfaceBase):
return ret
- def apply(self, c):
- return self.CC.update(c, self.CS)
+ def apply(self, c, now_nanos):
+ return self.CC.update(c, self.CS, now_nanos)
diff --git a/selfdrive/car/subaru/values.py b/selfdrive/car/subaru/values.py
index 6ac2637fa2..5c7d3f5e4d 100644
--- a/selfdrive/car/subaru/values.py
+++ b/selfdrive/car/subaru/values.py
@@ -253,6 +253,7 @@ FW_VERSIONS = {
b'\xca!f@\x07',
b'\xca!fp\x07',
b'\xf3"f@\x07',
+ b'\xe6!fp\x07',
],
(Ecu.transmission, 0x7e1, None): [
b'\xe6\xf5\004\000\000',
@@ -262,6 +263,7 @@ FW_VERSIONS = {
b'\xf1\x00\xd7\x10@',
b'\xe6\xf5D0\x00',
b'\xe9\xf6F0\x00',
+ b'\xe9\xf5B0\x00',
],
},
CAR.FORESTER: {
diff --git a/selfdrive/car/tesla/carcontroller.py b/selfdrive/car/tesla/carcontroller.py
index 6e2869d1c2..1f18c3d0ea 100644
--- a/selfdrive/car/tesla/carcontroller.py
+++ b/selfdrive/car/tesla/carcontroller.py
@@ -14,7 +14,7 @@ class CarController:
self.pt_packer = CANPacker(DBC[CP.carFingerprint]['pt'])
self.tesla_can = TeslaCAN(self.packer, self.pt_packer)
- def update(self, CC, CS):
+ def update(self, CC, CS, now_nanos):
actuators = CC.actuators
pcm_cancel_cmd = CC.cruiseControl.cancel
diff --git a/selfdrive/car/tesla/interface.py b/selfdrive/car/tesla/interface.py
index 49e06d8923..70d49896cb 100755
--- a/selfdrive/car/tesla/interface.py
+++ b/selfdrive/car/tesla/interface.py
@@ -23,7 +23,6 @@ class CarInterface(CarInterfaceBase):
ret.longitudinalTuning.kpV = [0]
ret.longitudinalTuning.kiBP = [0]
ret.longitudinalTuning.kiV = [0]
- ret.stopAccel = 0.0
ret.longitudinalActuatorDelayUpperBound = 0.5 # s
ret.radarTimeStep = (1.0 / 8) # 8Hz
@@ -59,5 +58,5 @@ class CarInterface(CarInterfaceBase):
return ret
- def apply(self, c):
- return self.CC.update(c, self.CS)
+ def apply(self, c, now_nanos):
+ return self.CC.update(c, self.CS, now_nanos)
diff --git a/selfdrive/car/tests/routes.py b/selfdrive/car/tests/routes.py
index 3edc406e19..02e37492d3 100644
--- a/selfdrive/car/tests/routes.py
+++ b/selfdrive/car/tests/routes.py
@@ -18,6 +18,7 @@ from selfdrive.car.body.values import CAR as COMMA
non_tested_cars = [
FORD.ESCAPE_MK4,
FORD.FOCUS_MK4,
+ FORD.MAVERICK_MK1,
GM.CADILLAC_ATS,
GM.HOLDEN_ASTRA,
GM.MALIBU,
@@ -25,6 +26,7 @@ non_tested_cars = [
HYUNDAI.GENESIS_G90,
HYUNDAI.KIA_OPTIMA_H,
HONDA.ODYSSEY_CHN,
+ VOLKSWAGEN.CRAFTER_MK2, # need a route from an ACC-equipped Crafter
]
CarTestRoute = namedtuple('CarTestRoute', ['route', 'car_model', 'segment'], defaults=(None,))
@@ -42,11 +44,13 @@ routes = [
CarTestRoute("221c253375af4ee9|2022-06-15--18-38-24", CHRYSLER.RAM_1500),
CarTestRoute("8fb5eabf914632ae|2022-08-04--17-28-53", CHRYSLER.RAM_HD, segment=6),
+ CarTestRoute("54827bf84c38b14f|2023-01-25--14-14-11", FORD.BRONCO_SPORT_MK1),
CarTestRoute("62241b0c7fea4589|2022-09-01--15-32-49", FORD.EXPLORER_MK6),
#TestRoute("f1b4c567731f4a1b|2018-04-30--10-15-35", FORD.FUSION),
CarTestRoute("7cc2a8365b4dd8a9|2018-12-02--12-10-44", GM.ACADIA),
CarTestRoute("aa20e335f61ba898|2019-02-05--16-59-04", GM.BUICK_REGAL),
+ CarTestRoute("ef8f2185104d862e|2023-02-09--18-37-13", GM.ESCALADE),
CarTestRoute("46460f0da08e621e|2021-10-26--07-21-46", GM.ESCALADE_ESV),
CarTestRoute("c950e28c26b5b168|2018-05-30--22-03-41", GM.VOLT),
CarTestRoute("f08912a233c1584f|2022-08-11--18-02-41", GM.BOLT_EUV, segment=1),
@@ -72,7 +76,7 @@ routes = [
CarTestRoute("d83f36766f8012a5|2020-02-05--18-42-21", HONDA.CIVIC_BOSCH_DIESEL),
CarTestRoute("f0890d16a07a236b|2021-05-25--17-27-22", HONDA.INSIGHT),
CarTestRoute("07d37d27996096b6|2020-03-04--21-57-27", HONDA.PILOT),
- CarTestRoute("684e8f96bd491a0e|2021-11-03--11-08-42", HONDA.PASSPORT),
+ CarTestRoute("684e8f96bd491a0e|2021-11-03--11-08-42", HONDA.PILOT), # Passport
CarTestRoute("0a78dfbacc8504ef|2020-03-04--13-29-55", HONDA.CIVIC_BOSCH),
CarTestRoute("f34a60d68d83b1e5|2020-10-06--14-35-55", HONDA.ACURA_RDX),
CarTestRoute("54fd8451b3974762|2021-04-01--14-50-10", HONDA.RIDGELINE),
@@ -100,6 +104,7 @@ routes = [
CarTestRoute("db68bbe12250812c|2022-12-05--00-54-12", HYUNDAI.TUCSON_4TH_GEN), # 2023
CarTestRoute("36e10531feea61a4|2022-07-25--13-37-42", HYUNDAI.TUCSON_HYBRID_4TH_GEN),
CarTestRoute("5875672fc1d4bf57|2020-07-23--21-33-28", HYUNDAI.KIA_SORENTO),
+ CarTestRoute("1d0d000db3370fd0|2023-01-04--22-28-42", HYUNDAI.KIA_SORENTO_4TH_GEN, segment=5),
CarTestRoute("628935d7d3e5f4f7|2022-11-30--01-12-46", HYUNDAI.KIA_SORENTO_PHEV_4TH_GEN),
CarTestRoute("9c917ba0d42ffe78|2020-04-17--12-43-19", HYUNDAI.PALISADE),
CarTestRoute("05a8f0197fdac372|2022-10-19--14-14-09", HYUNDAI.IONIQ_5), # HDA2
@@ -119,9 +124,11 @@ routes = [
CarTestRoute("d545129f3ca90f28|2022-10-19--09-22-54", HYUNDAI.KIA_EV6), # HDA2
CarTestRoute("68d6a96e703c00c9|2022-09-10--16-09-39", HYUNDAI.KIA_EV6), # HDA1
CarTestRoute("007d5e4ad9f86d13|2021-09-30--15-09-23", HYUNDAI.KIA_K5_2021),
+ CarTestRoute("c58dfc9fc16590e0|2023-01-14--13-51-48", HYUNDAI.KIA_K5_HEV_2020),
CarTestRoute("50c6c9b85fd1ff03|2020-10-26--17-56-06", HYUNDAI.KIA_NIRO_EV),
CarTestRoute("173219cf50acdd7b|2021-07-05--10-27-41", HYUNDAI.KIA_NIRO_PHEV),
CarTestRoute("34a875f29f69841a|2021-07-29--13-02-09", HYUNDAI.KIA_NIRO_HEV_2021),
+ CarTestRoute("db04d2c63990e3ba|2023-02-08--16-52-39", HYUNDAI.KIA_NIRO_HEV_2ND_GEN),
CarTestRoute("50a2212c41f65c7b|2021-05-24--16-22-06", HYUNDAI.KIA_FORTE),
CarTestRoute("192283cdbb7a58c2|2022-10-15--01-43-18", HYUNDAI.KIA_SPORTAGE_5TH_GEN),
CarTestRoute("c5ac319aa9583f83|2021-06-01--18-18-31", HYUNDAI.ELANTRA),
@@ -174,7 +181,9 @@ routes = [
CarTestRoute("0a0de17a1e6a2d15|2020-09-21--21-24-41", TOYOTA.PRIUS_TSS2),
CarTestRoute("9b36accae406390e|2021-03-30--10-41-38", TOYOTA.MIRAI),
CarTestRoute("cd9cff4b0b26c435|2021-05-13--15-12-39", TOYOTA.CHR),
+ CarTestRoute("ea8fbe72b96a185c|2023-02-08--15-11-46", TOYOTA.CHR_TSS2),
CarTestRoute("57858ede0369a261|2021-05-18--20-34-20", TOYOTA.CHRH),
+ CarTestRoute("6719965b0e1d1737|2023-02-09--22-44-05", TOYOTA.CHRH_TSS2),
CarTestRoute("14623aae37e549f3|2021-10-24--01-20-49", TOYOTA.PRIUS_V),
CarTestRoute("202c40641158a6e5|2021-09-21--09-43-24", VOLKSWAGEN.ARTEON_MK1),
diff --git a/selfdrive/car/tests/test_car_interfaces.py b/selfdrive/car/tests/test_car_interfaces.py
index 48d85584b3..ac8213e4c1 100755
--- a/selfdrive/car/tests/test_car_interfaces.py
+++ b/selfdrive/car/tests/test_car_interfaces.py
@@ -25,16 +25,23 @@ class TestCarInterfaces(unittest.TestCase):
car_fw = []
- car_params = CarInterface.get_params(car_name, fingerprints, car_fw)
+ car_params = CarInterface.get_params(car_name, fingerprints, car_fw, experimental_long=False)
car_interface = CarInterface(car_params, CarController, CarState)
assert car_params
assert car_interface
self.assertGreater(car_params.mass, 1)
self.assertGreater(car_params.wheelbase, 0)
- self.assertGreater(car_params.centerToFront, 0)
+ # centerToFront is center of gravity to front wheels, assert a reasonable range
+ self.assertTrue(car_params.wheelbase * 0.3 < car_params.centerToFront < car_params.wheelbase * 0.7)
self.assertGreater(car_params.maxLateralAccel, 0)
+ # Longitudinal sanity checks
+ self.assertEqual(len(car_params.longitudinalTuning.kpV), len(car_params.longitudinalTuning.kpBP))
+ self.assertEqual(len(car_params.longitudinalTuning.kiV), len(car_params.longitudinalTuning.kiBP))
+ self.assertEqual(len(car_params.longitudinalTuning.deadzoneV), len(car_params.longitudinalTuning.deadzoneBP))
+
+ # Lateral sanity checks
if car_params.steerControlType != car.CarParams.SteerControlType.angle:
tune = car_params.lateralTuning
if tune.which() == 'pid':
@@ -53,15 +60,15 @@ class TestCarInterfaces(unittest.TestCase):
CC = car.CarControl.new_message()
for _ in range(10):
car_interface.update(CC, [])
- car_interface.apply(CC)
- car_interface.apply(CC)
+ car_interface.apply(CC, 0)
+ car_interface.apply(CC, 0)
CC = car.CarControl.new_message()
CC.enabled = True
for _ in range(10):
car_interface.update(CC, [])
- car_interface.apply(CC)
- car_interface.apply(CC)
+ car_interface.apply(CC, 0)
+ car_interface.apply(CC, 0)
# Test radar interface
RadarInterface = importlib.import_module(f'selfdrive.car.{car_params.carName}.radar_interface').RadarInterface
@@ -70,7 +77,7 @@ class TestCarInterfaces(unittest.TestCase):
# Run radar interface once
radar_interface.update([])
- if not car_params.radarOffCan and radar_interface.rcp is not None and \
+ if not car_params.radarUnavailable and radar_interface.rcp is not None and \
hasattr(radar_interface, '_update') and hasattr(radar_interface, 'trigger_msg'):
radar_interface._update([radar_interface.trigger_msg])
diff --git a/selfdrive/car/tests/test_fw_fingerprint.py b/selfdrive/car/tests/test_fw_fingerprint.py
index 2e43103852..e9f23145cd 100755
--- a/selfdrive/car/tests/test_fw_fingerprint.py
+++ b/selfdrive/car/tests/test_fw_fingerprint.py
@@ -67,7 +67,7 @@ class TestFwFingerprint(unittest.TestCase):
blacklisted_addrs = (0x7c4, 0x7d0) # includes A/C ecu and an unknown ecu
for car_model, ecus in FW_VERSIONS.items():
with self.subTest(car_model=car_model):
- CP = interfaces[car_model][0].get_params(car_model)
+ CP = interfaces[car_model][0].get_non_essential_params(car_model)
if CP.carName == 'subaru':
for ecu in ecus.keys():
self.assertNotIn(ecu[1], blacklisted_addrs, f'{car_model}: Blacklisted ecu: (Ecu.{ECU_NAME[ecu[0]]}, {hex(ecu[1])})')
diff --git a/selfdrive/car/tests/test_lateral_limits.py b/selfdrive/car/tests/test_lateral_limits.py
index a82c20ce01..3efdd7404e 100755
--- a/selfdrive/car/tests/test_lateral_limits.py
+++ b/selfdrive/car/tests/test_lateral_limits.py
@@ -40,7 +40,7 @@ class TestLateralLimits(unittest.TestCase):
@classmethod
def setUpClass(cls):
CarInterface, _, _ = interfaces[cls.car_model]
- CP = CarInterface.get_params(cls.car_model)
+ CP = CarInterface.get_non_essential_params(cls.car_model)
if CP.dashcamOnly:
raise unittest.SkipTest("Platform is behind dashcamOnly")
diff --git a/selfdrive/car/tests/test_models.py b/selfdrive/car/tests/test_models.py
index 641c109316..6fbe1436f1 100755
--- a/selfdrive/car/tests/test_models.py
+++ b/selfdrive/car/tests/test_models.py
@@ -149,7 +149,7 @@ class TestCarModelBase(unittest.TestCase):
for i, msg in enumerate(self.can_msgs):
CS = self.CI.update(CC, (msg.as_builder().to_bytes(),))
- self.CI.apply(CC)
+ self.CI.apply(CC, msg.logMonoTime)
if CS.canValid:
can_valid = True
@@ -238,14 +238,14 @@ class TestCarModelBase(unittest.TestCase):
# TODO: check rest of panda's carstate (steering, ACC main on, etc.)
checks['gasPressed'] += CS.gasPressed != self.safety.get_gas_pressed_prev()
- if self.CP.carName not in ("hyundai", "volkswagen", "body"):
+ if self.CP.carName not in ("hyundai", "body"):
# TODO: fix standstill mismatches for other makes
checks['standstill'] += CS.standstill == self.safety.get_vehicle_moving()
# TODO: remove this exception once this mismatch is resolved
brake_pressed = CS.brakePressed
if CS.brakePressed and not self.safety.get_brake_pressed_prev():
- if self.CP.carFingerprint in (HONDA.PILOT, HONDA.PASSPORT, HONDA.RIDGELINE) and CS.brake > 0.05:
+ if self.CP.carFingerprint in (HONDA.PILOT, HONDA.RIDGELINE) and CS.brake > 0.05:
brake_pressed = False
checks['brakePressed'] += brake_pressed != self.safety.get_brake_pressed_prev()
checks['regenBraking'] += CS.regenBraking != self.safety.get_regen_braking_prev()
diff --git a/selfdrive/car/torque_data/override.yaml b/selfdrive/car/torque_data/override.yaml
index d7b2ec4079..cc1681bce1 100644
--- a/selfdrive/car/torque_data/override.yaml
+++ b/selfdrive/car/torque_data/override.yaml
@@ -12,9 +12,11 @@ TESLA AP1 MODEL S: [.nan, 2.5, .nan]
TESLA AP2 MODEL S: [.nan, 2.5, .nan]
# Guess
+FORD BRONCO SPORT 1ST GEN: [.nan, 1.5, .nan]
FORD ESCAPE 4TH GEN: [.nan, 1.5, .nan]
FORD EXPLORER 6TH GEN: [.nan, 1.5, .nan]
FORD FOCUS 4TH GEN: [.nan, 1.5, .nan]
+FORD MAVERICK 1ST GEN: [.nan, 1.5, .nan]
###
# No steering wheel
@@ -24,7 +26,7 @@ COMMA BODY: [.nan, 1000, .nan]
RAM 1500 5TH GEN: [2.0, 2.0, 0.0]
RAM HD 5TH GEN: [1.4, 1.4, 0.0]
SUBARU OUTBACK 6TH GEN: [2.3, 2.3, 0.11]
-CHEVROLET BOLT EV 2022: [2.0, 2.0, 0.05]
+CADILLAC ESCALADE 2017: [1.899999976158142, 1.842270016670227, 0.1120000034570694]
CHEVROLET BOLT EUV 2022: [2.0, 2.0, 0.05]
CHEVROLET SILVERADO 1500 2020: [1.9, 1.9, 0.112]
CHEVROLET EQUINOX 2019: [2.0, 2.0, 0.05]
@@ -36,6 +38,8 @@ KIA SPORTAGE HYBRID 5TH GEN: [2.5, 2.5, 0.1]
GENESIS GV70 1ST GEN: [2.42, 2.42, 0.1]
KIA SORENTO PLUG-IN HYBRID 4TH GEN: [2.5, 2.5, 0.1]
GENESIS GV60 ELECTRIC 1ST GEN: [2.5, 2.5, 0.1]
+KIA SORENTO 4TH GEN: [2.5, 2.5, 0.1]
+KIA NIRO HYBRID 2ND GEN: [2.42, 2.5, 0.12]
# Dashcam or fallback configured as ideal car
mock: [10.0, 10, 0.0]
diff --git a/selfdrive/car/torque_data/params.yaml b/selfdrive/car/torque_data/params.yaml
index eb1a04cee6..6f8cfe0ce6 100644
--- a/selfdrive/car/torque_data/params.yaml
+++ b/selfdrive/car/torque_data/params.yaml
@@ -4,11 +4,11 @@ ACURA RDX 2020: [1.4314459806646749, 0.33874701282109954, 0.18048847083897598]
AUDI A3 3RD GEN: [1.5122414863077502, 1.7443517531719404, 0.15194151892450905]
AUDI Q3 2ND GEN: [1.4439223359448605, 1.2254955789112076, 0.1413798895978097]
CHEVROLET VOLT PREMIER 2017: [1.5961527626411784, 1.8422651988094612, 0.1572393918005158]
-CHRYSLER PACIFICA 2018: [1.593387270257916, 1.3366521181047952, 0.13776367250652022]
-CHRYSLER PACIFICA 2020: [1.4323553627965695, 1.509076559398423, 0.14328246159386085]
-CHRYSLER PACIFICA HYBRID 2017: [1.3032470208409048, 1.06831764583744, 0.13287170990024627]
-CHRYSLER PACIFICA HYBRID 2018: [1.6068280248761635, 1.2943025830995154, 0.1358557824293823]
-CHRYSLER PACIFICA HYBRID 2019: [1.4624643614072217, 1.1958788168371808, 0.15748488008472716]
+CHRYSLER PACIFICA 2018: [2.07140, 1.3366521181047952, 0.13776367250652022]
+CHRYSLER PACIFICA 2020: [1.86206, 1.509076559398423, 0.14328246159386085]
+CHRYSLER PACIFICA HYBRID 2017: [1.79422, 1.06831764583744, 0.116237]
+CHRYSLER PACIFICA HYBRID 2018: [2.08887, 1.2943025830995154, 0.114818]
+CHRYSLER PACIFICA HYBRID 2019: [1.90120, 1.1958788168371808, 0.131520]
GENESIS G70 2018: [3.8520195946707947, 2.354697063349854, 0.06830285485626221]
GMC ACADIA DENALI 2018: [1.3181430320331884, 1.1853735340610179, 0.3450592280031644]
HONDA ACCORD 2018: [1.7135052593468778, 0.3461280068322071, 0.21579936052863807]
@@ -22,11 +22,10 @@ HONDA FIT 2018: [1.5719981427109775, 0.5712761407108976, 0.110773383324281]
HONDA HRV 2019: [2.0661212805710205, 0.7521343418694775, 0.17760375789242094]
HONDA INSIGHT 2019: [1.5201671214069354, 0.5660229120683284, 0.25808042580281876]
HONDA ODYSSEY 2018: [1.8774809275211801, 0.8394431662987996, 0.2096978613792822]
-HONDA PASSPORT 2021: [1.5305538930036766, 0.7956063674638759, 0.19599407381531284]
HONDA PILOT 2017: [1.7262026201812795, 0.9470005614967523, 0.21351430733218763]
HONDA RIDGELINE 2017: [1.4146525028237624, 0.7356572861629564, 0.23307177552211328]
HYUNDAI ELANTRA 2021: [3.169, 2.1259108157250735, 0.0819]
-HYUNDAI GENESIS 2015-2016: [1.8466226943929824, 1.5552063647830634, 0.0984484465421171]
+HYUNDAI GENESIS 2015-2016: [2.7807965280270794, 2.325, 0.0984484465421171]
HYUNDAI IONIQ 5 2022: [3.172929, 2.713050, 0.096019]
HYUNDAI IONIQ ELECTRIC LIMITED 2019: [1.7662975472852054, 1.613755614526594, 0.17087579756306276]
HYUNDAI IONIQ PHEV 2020: [3.2928700076638537, 2.1193482926455656, 0.12463700961468778]
@@ -40,8 +39,8 @@ HYUNDAI SONATA 2019: [2.2200457811703953, 1.2967330275895228, 0.1403992098658639
HYUNDAI SONATA 2020: [2.9638737459977467, 2.1259108157250735, 0.07813665616927593]
HYUNDAI SONATA HYBRID 2021: [2.8990264092395734, 2.061410192222139, 0.0899805488717382]
HYUNDAI TUCSON HYBRID 4TH GEN: [2.035545, 2.035545, 0.110272]
-JEEP GRAND CHEROKEE 2019: [1.7321233388827006, 1.289689569171081, 0.15046331002097185]
-JEEP GRAND CHEROKEE V6 2018: [1.8776598027756923, 1.4057367824262523, 0.11725947414922003]
+JEEP GRAND CHEROKEE 2019: [2.30972, 1.289689569171081, 0.117048]
+JEEP GRAND CHEROKEE V6 2018: [2.27116, 1.4057367824262523, 0.11725947414922003]
KIA EV6 2022: [3.2, 2.093457, 0.05]
KIA K5 2021: [2.405339728085138, 1.460032270828705, 0.11650989850813716]
KIA NIRO EV 2020: [2.9215954981365337, 2.1500583840260044, 0.09236802474810267]
diff --git a/selfdrive/car/torque_data/substitute.yaml b/selfdrive/car/torque_data/substitute.yaml
index aeb2e6f280..61243424f0 100644
--- a/selfdrive/car/torque_data/substitute.yaml
+++ b/selfdrive/car/torque_data/substitute.yaml
@@ -9,6 +9,7 @@ TOYOTA ALPHARD 2020: TOYOTA SIENNA 2018
TOYOTA PRIUS v 2017 : TOYOTA PRIUS 2017
TOYOTA RAV4 2022: TOYOTA RAV4 HYBRID 2022
TOYOTA C-HR HYBRID 2018: TOYOTA C-HR 2018
+TOYOTA C-HR HYBRID 2022: TOYOTA C-HR 2021
LEXUS IS 2018: LEXUS NX 2018
LEXUS CT HYBRID 2018 : LEXUS NX 2018
LEXUS ES HYBRID 2018: TOYOTA CAMRY HYBRID 2018
@@ -37,6 +38,7 @@ HYUNDAI ELANTRA HYBRID 2021: HYUNDAI SONATA 2020
HYUNDAI TUCSON 2019: HYUNDAI SANTA FE 2019
HYUNDAI TUCSON 4TH GEN: HYUNDAI TUCSON HYBRID 4TH GEN
HYUNDAI SANTA FE 2022: HYUNDAI SANTA FE HYBRID 2022
+KIA K5 HYBRID 2020: KIA K5 2021
KIA STINGER 2022: KIA STINGER GT2 2018
GENESIS G90 2017: GENESIS G70 2018
GENESIS G80 2017: GENESIS G70 2018
@@ -59,6 +61,7 @@ SKODA SCALA 1ST GEN: SKODA SUPERB 3RD GEN
SKODA KODIAQ 1ST GEN: SKODA SUPERB 3RD GEN
SKODA KAROQ 1ST GEN: SKODA SUPERB 3RD GEN
SKODA KAMIQ 1ST GEN: SKODA SUPERB 3RD GEN
+VOLKSWAGEN CRAFTER 2ND GEN: VOLKSWAGEN TIGUAN 2ND GEN
VOLKSWAGEN T-ROC 1ST GEN: VOLKSWAGEN TIGUAN 2ND GEN
VOLKSWAGEN T-CROSS 1ST GEN: VOLKSWAGEN TIGUAN 2ND GEN
VOLKSWAGEN TOURAN 2ND GEN: VOLKSWAGEN TIGUAN 2ND GEN
diff --git a/selfdrive/car/toyota/carcontroller.py b/selfdrive/car/toyota/carcontroller.py
index c952144523..9da00f40fd 100644
--- a/selfdrive/car/toyota/carcontroller.py
+++ b/selfdrive/car/toyota/carcontroller.py
@@ -1,7 +1,6 @@
from cereal import car
from common.numpy_fast import clip, interp
-from selfdrive.car import apply_std_steer_angle_limits, apply_toyota_steer_torque_limits, \
- create_gas_interceptor_command, make_can_msg
+from selfdrive.car import apply_std_steer_angle_limits, apply_meas_steer_torque_limits, create_gas_interceptor_command, make_can_msg
from selfdrive.car.toyota.toyotacan import create_steer_command, create_ui_command, \
create_accel_command, create_acc_cancel_command, \
create_fcw_command, create_lta_steer_command
@@ -45,7 +44,7 @@ class CarController:
self.gas = 0
self.accel = 0
- def update(self, CC, CS):
+ def update(self, CC, CS, now_nanos):
actuators = CC.actuators
hud_control = CC.hudControl
pcm_cancel_cmd = CC.cruiseControl.cancel
@@ -75,7 +74,7 @@ class CarController:
if self.CP.steerControlType != SteerControlType.angle:
# - steer torque
new_steer = int(round(actuators.steer * self.params.STEER_MAX))
- apply_steer = apply_toyota_steer_torque_limits(new_steer, self.last_steer, CS.out.steeringTorqueEps, self.params)
+ apply_steer = apply_meas_steer_torque_limits(new_steer, self.last_steer, CS.out.steeringTorqueEps, self.params)
else:
# - steer angle
# angle command is in terms of the torque sensor angle (may or may not have an offset)
@@ -183,7 +182,7 @@ class CarController:
# forcing the pcm to disengage causes a bad fault sound so play a good sound instead
send_ui = True
- if self.frame % 100 == 0 or send_ui:
+ if self.frame % 20 == 0 or send_ui:
can_sends.append(create_ui_command(self.packer, steer_alert, pcm_cancel_cmd, hud_control.leftLaneVisible,
hud_control.rightLaneVisible, hud_control.leftLaneDepart,
hud_control.rightLaneDepart, CC.enabled, CS.lkas_hud))
diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py
index 4fa4d9e5d6..5dd615bf51 100644
--- a/selfdrive/car/toyota/interface.py
+++ b/selfdrive/car/toyota/interface.py
@@ -82,7 +82,7 @@ class CarInterface(CarInterfaceBase):
tire_stiffness_factor = 0.5533
ret.mass = 4481. * CV.LB_TO_KG + STD_CARGO_KG # mean between min and max
- elif candidate in (CAR.CHR, CAR.CHRH):
+ elif candidate in (CAR.CHR, CAR.CHRH, CAR.CHR_TSS2, CAR.CHRH_TSS2):
stop_and_go = True
ret.wheelbase = 2.63906
ret.steerRatio = 13.6
@@ -287,5 +287,5 @@ class CarInterface(CarInterfaceBase):
# pass in a car.CarControl
# to be called @ 100hz
- def apply(self, c):
- return self.CC.update(c, self.CS)
+ def apply(self, c, now_nanos):
+ return self.CC.update(c, self.CS, now_nanos)
diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py
index 7983f192fa..68fcbec425 100644
--- a/selfdrive/car/toyota/values.py
+++ b/selfdrive/car/toyota/values.py
@@ -57,7 +57,9 @@ class CAR:
CAMRY_TSS2 = "TOYOTA CAMRY 2021" # TSS 2.5
CAMRYH_TSS2 = "TOYOTA CAMRY HYBRID 2021"
CHR = "TOYOTA C-HR 2018"
+ CHR_TSS2 = "TOYOTA C-HR 2021"
CHRH = "TOYOTA C-HR HYBRID 2018"
+ CHRH_TSS2 = "TOYOTA C-HR HYBRID 2022"
COROLLA = "TOYOTA COROLLA 2017"
COROLLA_TSS2 = "TOYOTA COROLLA TSS2 2019"
# LSS2 Lexus UX Hybrid is same as a TSS2 Corolla Hybrid
@@ -123,8 +125,10 @@ CAR_INFO: Dict[str, Union[ToyotaCarInfo, List[ToyotaCarInfo]]] = {
CAR.CAMRYH: ToyotaCarInfo("Toyota Camry Hybrid 2018-20", video_link="https://www.youtube.com/watch?v=Q2DYY0AWKgk"),
CAR.CAMRY_TSS2: ToyotaCarInfo("Toyota Camry 2021-22", footnotes=[Footnote.CAMRY]),
CAR.CAMRYH_TSS2: ToyotaCarInfo("Toyota Camry Hybrid 2021-23"),
- CAR.CHR: ToyotaCarInfo("Toyota C-HR 2017-21"),
- CAR.CHRH: ToyotaCarInfo("Toyota C-HR Hybrid 2017-19"),
+ CAR.CHR: ToyotaCarInfo("Toyota C-HR 2017-20"),
+ CAR.CHR_TSS2: ToyotaCarInfo("Toyota C-HR 2021"),
+ CAR.CHRH: ToyotaCarInfo("Toyota C-HR Hybrid 2017-20"),
+ CAR.CHRH_TSS2: ToyotaCarInfo("Toyota C-HR Hybrid 2021-22"),
CAR.COROLLA: ToyotaCarInfo("Toyota Corolla 2017-19"),
CAR.COROLLA_TSS2: [
ToyotaCarInfo("Toyota Corolla 2020-22", video_link="https://www.youtube.com/watch?v=_66pXk0CBYA"),
@@ -133,13 +137,14 @@ CAR_INFO: Dict[str, Union[ToyotaCarInfo, List[ToyotaCarInfo]]] = {
],
CAR.COROLLAH_TSS2: [
ToyotaCarInfo("Toyota Corolla Hybrid 2020-22"),
+ ToyotaCarInfo("Toyota Corolla Hybrid (Non-US only) 2020-23", min_enable_speed=7.5),
ToyotaCarInfo("Toyota Corolla Cross Hybrid (Non-US only) 2020-22", min_enable_speed=7.5),
ToyotaCarInfo("Lexus UX Hybrid 2019-22"),
],
CAR.HIGHLANDER: ToyotaCarInfo("Toyota Highlander 2017-19", video_link="https://www.youtube.com/watch?v=0wS0wXSLzoo"),
- CAR.HIGHLANDER_TSS2: ToyotaCarInfo("Toyota Highlander 2020-22"),
+ CAR.HIGHLANDER_TSS2: ToyotaCarInfo("Toyota Highlander 2020-23"),
CAR.HIGHLANDERH: ToyotaCarInfo("Toyota Highlander Hybrid 2017-19"),
- CAR.HIGHLANDERH_TSS2: ToyotaCarInfo("Toyota Highlander Hybrid 2020-22"),
+ CAR.HIGHLANDERH_TSS2: ToyotaCarInfo("Toyota Highlander Hybrid 2020-23"),
CAR.PRIUS: [
ToyotaCarInfo("Toyota Prius 2016", "Toyota Safety Sense P", "https://www.youtube.com/watch?v=8zopPJI8XQ0"),
ToyotaCarInfo("Toyota Prius 2017-20", video_link="https://www.youtube.com/watch?v=8zopPJI8XQ0"),
@@ -169,7 +174,7 @@ CAR_INFO: Dict[str, Union[ToyotaCarInfo, List[ToyotaCarInfo]]] = {
CAR.LEXUS_CTH: ToyotaCarInfo("Lexus CT Hybrid 2017-18", "Lexus Safety System+"),
CAR.LEXUS_ESH: ToyotaCarInfo("Lexus ES Hybrid 2017-18", "Lexus Safety System+"),
CAR.LEXUS_ES_TSS2: ToyotaCarInfo("Lexus ES 2019-22"),
- CAR.LEXUS_ESH_TSS2: ToyotaCarInfo("Lexus ES Hybrid 2019-22", video_link="https://youtu.be/BZ29osRVJeg?t=12"),
+ CAR.LEXUS_ESH_TSS2: ToyotaCarInfo("Lexus ES Hybrid 2019-23", video_link="https://youtu.be/BZ29osRVJeg?t=12"),
CAR.LEXUS_IS: ToyotaCarInfo("Lexus IS 2017-19"),
CAR.LEXUS_NX: ToyotaCarInfo("Lexus NX 2018-19"),
CAR.LEXUS_NXH: ToyotaCarInfo("Lexus NX Hybrid 2018-19"),
@@ -238,7 +243,7 @@ FW_QUERY_CONFIG = FwQueryConfig(
# FIXME: On some models, abs can sometimes be missing
Ecu.abs: [CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.SIENNA, CAR.LEXUS_IS],
# On some models, the engine can show on two different addresses
- Ecu.engine: [CAR.CAMRY, CAR.COROLLA_TSS2, CAR.CHR, CAR.LEXUS_IS],
+ Ecu.engine: [CAR.CAMRY, CAR.COROLLA_TSS2, CAR.CHR, CAR.CHR_TSS2, CAR.LEXUS_IS, CAR.LEXUS_RC],
}
)
@@ -355,6 +360,7 @@ FW_VERSIONS = {
],
(Ecu.fwdRadar, 0x750, 0xf): [
b'\x018821F6201200\x00\x00\x00\x00',
+ b'\x018821F6201300\x00\x00\x00\x00',
],
(Ecu.fwdCamera, 0x750, 0x6d): [
b'\x028646F4104100\x00\x00\x00\x008646G5301200\x00\x00\x00\x00',
@@ -639,6 +645,30 @@ FW_VERSIONS = {
b'8646FF407000 ',
],
},
+ CAR.CHR_TSS2: {
+ (Ecu.abs, 0x7b0, None): [
+ b'F152610260\x00\x00\x00\x00\x00\x00',
+ b'F1526F4270\x00\x00\x00\x00\x00\x00',
+ ],
+ (Ecu.eps, 0x7a1, None): [
+ b'8965B10091\x00\x00\x00\x00\x00\x00',
+ b'8965B10110\x00\x00\x00\x00\x00\x00',
+ ],
+ (Ecu.engine, 0x700, None): [
+ b'\x0189663F459000\x00\x00\x00\x00',
+ ],
+ (Ecu.engine, 0x7e0, None): [
+ b'\x0331014000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00',
+ ],
+ (Ecu.fwdRadar, 0x750, 0xf): [
+ b'\x018821FF410200\x00\x00\x00\x00',
+ b'\x018821FF410300\x00\x00\x00\x00',
+ ],
+ (Ecu.fwdCamera, 0x750, 0x6d): [
+ b'\x028646FF410200\x00\x00\x00\x008646GF408200\x00\x00\x00\x00',
+ b'\x028646FF411100\x00\x00\x00\x008646GF409000\x00\x00\x00\x00',
+ ],
+ },
CAR.CHRH: {
(Ecu.engine, 0x700, None): [
b'\x0289663F405100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00',
@@ -690,8 +720,26 @@ FW_VERSIONS = {
b'8646FF404000 ',
b'8646FF406000 ',
b'8646FF407000 ',
+ b'8646FF407100 ',
],
},
+ CAR.CHRH_TSS2: {
+ (Ecu.eps, 0x7a1, None): [
+ b'8965B10092\x00\x00\x00\x00\x00\x00',
+ ],
+ (Ecu.abs, 0x7b0, None): [
+ b'F152610041\x00\x00\x00\x00\x00\x00',
+ ],
+ (Ecu.engine, 0x700, None): [
+ b'\x0189663F438000\x00\x00\x00\x00',
+ ],
+ (Ecu.fwdRadar, 0x750, 15): [
+ b'\x018821FF410500\x00\x00\x00\x00',
+ ],
+ (Ecu.fwdCamera, 0x750, 109): [
+ b'\x028646FF413100\x00\x00\x00\x008646GF411100\x00\x00\x00\x00',
+ ],
+ },
CAR.COROLLA: {
(Ecu.engine, 0x7e0, None): [
b'\x0230ZC2000\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00',
@@ -773,6 +821,7 @@ FW_VERSIONS = {
b'\x03312N6100\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00',
b'\x03312N6200\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00',
b'\x03312N6200\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00',
+ b'\x03312N6200\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00',
b'\x02312K4000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00',
b'\x02312U5000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00',
],
@@ -839,6 +888,7 @@ FW_VERSIONS = {
b'\x01896630ZJ1000\x00\x00\x00\x00',
b'\x01896630ZU8000\x00\x00\x00\x00',
b'\x01896637621000\x00\x00\x00\x00',
+ b'\x01896637623000\x00\x00\x00\x00',
b'\x01896637624000\x00\x00\x00\x00',
b'\x01896637626000\x00\x00\x00\x00',
b'\x01896637639000\x00\x00\x00\x00',
@@ -847,11 +897,13 @@ FW_VERSIONS = {
b'\x02896630A07000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00',
b'\x02896630A21000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00',
b'\x02896630ZJ5000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00',
+ b'\x02896630ZK8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00',
b'\x02896630ZN8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00',
b'\x02896630ZQ3000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00',
b'\x02896630ZR2000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00',
b'\x02896630ZT8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00',
b'\x02896630ZT9000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00',
+ b'\x02896630ZZ0000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00',
b'\x028966312K6000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00',
b'\x028966312L0000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00',
b'\x028966312Q3000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00',
@@ -864,6 +916,7 @@ FW_VERSIONS = {
b'8965B12361\x00\x00\x00\x00\x00\x00',
b'8965B12451\x00\x00\x00\x00\x00\x00',
b'8965B16011\x00\x00\x00\x00\x00\x00',
+ b'8965B16101\x00\x00\x00\x00\x00\x00',
b'8965B76012\x00\x00\x00\x00\x00\x00',
b'8965B76050\x00\x00\x00\x00\x00\x00',
b'\x018965B12350\x00\x00\x00\x00\x00\x00',
@@ -911,6 +964,7 @@ FW_VERSIONS = {
b'\x028646F1202100\x00\x00\x00\x008646G2601400\x00\x00\x00\x00',
b'\x028646F1202200\x00\x00\x00\x008646G2601500\x00\x00\x00\x00',
b'\x028646F1601100\x00\x00\x00\x008646G2601400\x00\x00\x00\x00',
+ b'\x028646F1601200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00',
b"\x028646F1601300\x00\x00\x00\x008646G2601400\x00\x00\x00\x00",
b'\x028646F4203400\x00\x00\x00\x008646G2601200\x00\x00\x00\x00',
b'\x028646F76020C0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00',
@@ -988,12 +1042,14 @@ FW_VERSIONS = {
b'8965B48241\x00\x00\x00\x00\x00\x00',
b'8965B48310\x00\x00\x00\x00\x00\x00',
b'8965B48320\x00\x00\x00\x00\x00\x00',
+ b'8965B48400\x00\x00\x00\x00\x00\x00',
],
(Ecu.abs, 0x7b0, None): [
b'\x01F15260E051\x00\x00\x00\x00\x00\x00',
b'\x01F15260E061\x00\x00\x00\x00\x00\x00',
b'\x01F15260E110\x00\x00\x00\x00\x00\x00',
b'\x01F15260E170\x00\x00\x00\x00\x00\x00',
+ b'\x01F15260E05300\x00\x00\x00\x00',
],
(Ecu.engine, 0x700, None): [
b'\x01896630E62100\x00\x00\x00\x00',
@@ -1011,6 +1067,8 @@ FW_VERSIONS = {
b'\x01896630ED9100\x00\x00\x00\x00',
b'\x01896630EE1000\x00\x00\x00\x00',
b'\x01896630EE1100\x00\x00\x00\x00',
+ b'\x01896630EG3000\x00\x00\x00\x00',
+ b'\x01896630EG5000\x00\x00\x00\x00',
],
(Ecu.fwdRadar, 0x750, 0xf): [
b'\x018821F3301400\x00\x00\x00\x00',
@@ -1021,17 +1079,20 @@ FW_VERSIONS = {
b'\x028646F0E02100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00',
b'\x028646F4803000\x00\x00\x00\x008646G5301200\x00\x00\x00\x00',
b'\x028646F4803000\x00\x00\x00\x008646G3304000\x00\x00\x00\x00',
+ b'\x028646F4803200\x00\x00\x00\x008646G3304000\x00\x00\x00\x00',
],
},
CAR.HIGHLANDERH_TSS2: {
(Ecu.eps, 0x7a1, None): [
b'8965B48241\x00\x00\x00\x00\x00\x00',
b'8965B48310\x00\x00\x00\x00\x00\x00',
+ b'8965B48400\x00\x00\x00\x00\x00\x00',
],
(Ecu.abs, 0x7b0, None): [
b'\x01F15264872300\x00\x00\x00\x00',
b'\x01F15264872400\x00\x00\x00\x00',
b'\x01F15264872500\x00\x00\x00\x00',
+ b'\x01F15264872600\x00\x00\x00\x00',
b'\x01F15264873500\x00\x00\x00\x00',
b'\x01F152648C6300\x00\x00\x00\x00',
b'\x01F152648J4000\x00\x00\x00\x00',
@@ -1045,6 +1106,7 @@ FW_VERSIONS = {
b'\x01896630EE4100\x00\x00\x00\x00',
b'\x01896630EE5000\x00\x00\x00\x00',
b'\x01896630EE6000\x00\x00\x00\x00',
+ b'\x01896630EF8000\x00\x00\x00\x00',
b'\x02896630E66000\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00',
b'\x02896630E66100\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00',
b'\x01896630EA1000\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00',
@@ -1060,6 +1122,7 @@ FW_VERSIONS = {
b'\x028646F0E02100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00',
b'\x028646F4803000\x00\x00\x00\x008646G5301200\x00\x00\x00\x00',
b'\x028646F4803000\x00\x00\x00\x008646G3304000\x00\x00\x00\x00',
+ b'\x028646F4803200\x00\x00\x00\x008646G3304000\x00\x00\x00\x00',
],
},
CAR.LEXUS_IS: {
@@ -1589,12 +1652,14 @@ FW_VERSIONS = {
b'\x028966333V4000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00',
b'\x02896633T09000\x00\x00\x00\x00897CF3307001\x00\x00\x00\x00',
b'\x01896633T38000\x00\x00\x00\x00',
+ b'\x01896633T58000\x00\x00\x00\x00',
],
(Ecu.abs, 0x7b0, None): [
b'F152633423\x00\x00\x00\x00\x00\x00',
b'F152633680\x00\x00\x00\x00\x00\x00',
b'F152633681\x00\x00\x00\x00\x00\x00',
b'F152633F50\x00\x00\x00\x00\x00\x00',
+ b'F152633F51\x00\x00\x00\x00\x00\x00',
],
(Ecu.eps, 0x7a1, None): [
b'8965B33252\x00\x00\x00\x00\x00\x00',
@@ -1610,6 +1675,7 @@ FW_VERSIONS = {
b'\x018821F6201300\x00\x00\x00\x00',
],
(Ecu.fwdCamera, 0x750, 0x6d): [
+ b'\x028646F0610000\x00\x00\x00\x008646G3304000\x00\x00\x00\x00',
b'\x028646F33030D0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00',
b'\x028646F3303100\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00',
b'\x028646F3303200\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00',
@@ -1674,6 +1740,7 @@ FW_VERSIONS = {
(Ecu.engine, 0x700, None): [
b'\x018966378B2100\x00\x00\x00\x00',
b'\x018966378B3000\x00\x00\x00\x00',
+ b'\x018966378B4100\x00\x00\x00\x00',
b'\x018966378G3000\x00\x00\x00\x00',
b'\x018966378B2000\x00\x00\x00\x00',
],
@@ -1742,22 +1809,29 @@ FW_VERSIONS = {
],
},
CAR.LEXUS_RC: {
+ (Ecu.engine, 0x700, None): [
+ b'\x01896632478200\x00\x00\x00\x00',
+ ],
(Ecu.engine, 0x7e0, None): [
b'\x0232484000\x00\x00\x00\x00\x00\x00\x00\x0052422000\x00\x00\x00\x00\x00\x00\x00\x00',
],
(Ecu.abs, 0x7b0, None): [
+ b'F152624150\x00\x00\x00\x00\x00\x00',
b'F152624221\x00\x00\x00\x00\x00\x00',
],
(Ecu.dsu, 0x791, None): [
+ b'881512407000\x00\x00\x00\x00',
b'881512409100\x00\x00\x00\x00',
],
(Ecu.eps, 0x7a1, None): [
b'8965B24081\x00\x00\x00\x00\x00\x00',
+ b'8965B24320\x00\x00\x00\x00\x00\x00',
],
(Ecu.fwdRadar, 0x750, 0xf): [
b'8821F4702300\x00\x00\x00\x00',
],
(Ecu.fwdCamera, 0x750, 0x6d): [
+ b'8646F2401200\x00\x00\x00\x00',
b'8646F2402200\x00\x00\x00\x00',
],
},
@@ -2016,7 +2090,9 @@ DBC = {
CAR.LEXUS_RX_TSS2: dbc_dict('toyota_nodsu_pt_generated', 'toyota_tss2_adas'),
CAR.LEXUS_RXH_TSS2: dbc_dict('toyota_nodsu_pt_generated', 'toyota_tss2_adas'),
CAR.CHR: dbc_dict('toyota_nodsu_pt_generated', 'toyota_adas'),
+ CAR.CHR_TSS2: dbc_dict('toyota_nodsu_pt_generated', None),
CAR.CHRH: dbc_dict('toyota_nodsu_pt_generated', 'toyota_adas'),
+ CAR.CHRH_TSS2: dbc_dict('toyota_nodsu_pt_generated', None),
CAR.CAMRY: dbc_dict('toyota_nodsu_pt_generated', 'toyota_adas'),
CAR.CAMRYH: dbc_dict('toyota_nodsu_pt_generated', 'toyota_adas'),
CAR.CAMRY_TSS2: dbc_dict('toyota_nodsu_pt_generated', 'toyota_tss2_adas'),
@@ -2058,7 +2134,7 @@ EPS_SCALE = defaultdict(lambda: 73, {CAR.PRIUS: 66, CAR.COROLLA: 88, CAR.LEXUS_I
# Toyota/Lexus Safety Sense 2.0 and 2.5
TSS2_CAR = {CAR.RAV4_TSS2, CAR.RAV4_TSS2_2022, CAR.COROLLA_TSS2, CAR.COROLLAH_TSS2, CAR.LEXUS_ES_TSS2, CAR.LEXUS_ESH_TSS2, CAR.RAV4H_TSS2, CAR.RAV4H_TSS2_2022,
CAR.LEXUS_RX_TSS2, CAR.LEXUS_RXH_TSS2, CAR.HIGHLANDER_TSS2, CAR.HIGHLANDERH_TSS2, CAR.PRIUS_TSS2, CAR.CAMRY_TSS2, CAR.CAMRYH_TSS2,
- CAR.MIRAI, CAR.LEXUS_NX_TSS2, CAR.LEXUS_NXH_TSS2, CAR.ALPHARD_TSS2, CAR.AVALON_TSS2, CAR.AVALONH_TSS2, CAR.ALPHARDH_TSS2}
+ CAR.MIRAI, CAR.LEXUS_NX_TSS2, CAR.LEXUS_NXH_TSS2, CAR.ALPHARD_TSS2, CAR.AVALON_TSS2, CAR.AVALONH_TSS2, CAR.ALPHARDH_TSS2, CAR.CHR_TSS2, CAR.CHRH_TSS2}
NO_DSU_CAR = TSS2_CAR | {CAR.CHR, CAR.CHRH, CAR.CAMRY, CAR.CAMRYH}
@@ -2066,9 +2142,9 @@ NO_DSU_CAR = TSS2_CAR | {CAR.CHR, CAR.CHRH, CAR.CAMRY, CAR.CAMRYH}
UNSUPPORTED_DSU_CAR = {CAR.LEXUS_IS, CAR.LEXUS_RC}
# these cars have a radar which sends ACC messages instead of the camera
-RADAR_ACC_CAR = {CAR.RAV4H_TSS2_2022, CAR.RAV4_TSS2_2022}
+RADAR_ACC_CAR = {CAR.RAV4H_TSS2_2022, CAR.RAV4_TSS2_2022, CAR.CHR_TSS2, CAR.CHRH_TSS2}
-EV_HYBRID_CAR = {CAR.AVALONH_2019, CAR.AVALONH_TSS2, CAR.CAMRYH, CAR.CAMRYH_TSS2, CAR.CHRH, CAR.COROLLAH_TSS2, CAR.HIGHLANDERH, CAR.HIGHLANDERH_TSS2, CAR.PRIUS,
+EV_HYBRID_CAR = {CAR.AVALONH_2019, CAR.AVALONH_TSS2, CAR.CAMRYH, CAR.CAMRYH_TSS2, CAR.CHRH, CAR.CHRH_TSS2, CAR.COROLLAH_TSS2, CAR.HIGHLANDERH, CAR.HIGHLANDERH_TSS2, CAR.PRIUS,
CAR.PRIUS_V, CAR.RAV4H, CAR.RAV4H_TSS2, CAR.RAV4H_TSS2_2022, CAR.LEXUS_CTH, CAR.MIRAI, CAR.LEXUS_ESH, CAR.LEXUS_ESH_TSS2, CAR.LEXUS_NXH, CAR.LEXUS_RXH,
CAR.LEXUS_RXH_TSS2, CAR.LEXUS_NXH_TSS2, CAR.PRIUS_TSS2, CAR.ALPHARDH_TSS2}
diff --git a/selfdrive/car/volkswagen/carcontroller.py b/selfdrive/car/volkswagen/carcontroller.py
index 4b19f4d13c..c17b632450 100644
--- a/selfdrive/car/volkswagen/carcontroller.py
+++ b/selfdrive/car/volkswagen/carcontroller.py
@@ -3,7 +3,7 @@ from opendbc.can.packer import CANPacker
from common.numpy_fast import clip
from common.conversions import Conversions as CV
from common.realtime import DT_CTRL
-from selfdrive.car import apply_std_steer_torque_limits
+from selfdrive.car import apply_driver_steer_torque_limits
from selfdrive.car.volkswagen import mqbcan, pqcan
from selfdrive.car.volkswagen.values import CANBUS, PQ_CARS, CarControllerParams
@@ -24,7 +24,7 @@ class CarController:
self.hcaSameTorqueCount = 0
self.hcaEnabledFrameCount = 0
- def update(self, CC, CS, ext_bus):
+ def update(self, CC, CS, ext_bus, now_nanos):
actuators = CC.actuators
hud_control = CC.hudControl
can_sends = []
@@ -44,7 +44,7 @@ class CarController:
if CC.latActive:
new_steer = int(round(actuators.steer * self.CCP.STEER_MAX))
- apply_steer = apply_std_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.CCP)
+ apply_steer = apply_driver_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.CCP)
if apply_steer == 0:
hcaEnabled = False
self.hcaEnabledFrameCount = 0
diff --git a/selfdrive/car/volkswagen/carstate.py b/selfdrive/car/volkswagen/carstate.py
index 7ea9aa871b..64d1246880 100644
--- a/selfdrive/car/volkswagen/carstate.py
+++ b/selfdrive/car/volkswagen/carstate.py
@@ -44,7 +44,7 @@ class CarState(CarStateBase):
ret.vEgoRaw = float(np.mean([ret.wheelSpeeds.fl, ret.wheelSpeeds.fr, ret.wheelSpeeds.rl, ret.wheelSpeeds.rr]))
ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw)
- ret.standstill = ret.vEgo < 0.1
+ ret.standstill = ret.vEgoRaw == 0
# Update steering angle, rate, yaw rate, and driver input torque. VW send
# the sign/direction in a separate signal so they must be recombined.
@@ -160,7 +160,7 @@ class CarState(CarStateBase):
# vEgo obtained from Bremse_1 vehicle speed rather than Bremse_3 wheel speeds because Bremse_3 isn't present on NSF
ret.vEgoRaw = pt_cp.vl["Bremse_1"]["Geschwindigkeit_neu__Bremse_1_"] * CV.KPH_TO_MS
ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw)
- ret.standstill = ret.vEgo < 0.1
+ ret.standstill = ret.vEgoRaw == 0
# Update steering angle, rate, yaw rate, and driver input torque. VW send
# the sign/direction in a separate signal so they must be recombined.
diff --git a/selfdrive/car/volkswagen/interface.py b/selfdrive/car/volkswagen/interface.py
index da0ce25afa..521c68184d 100644
--- a/selfdrive/car/volkswagen/interface.py
+++ b/selfdrive/car/volkswagen/interface.py
@@ -23,7 +23,7 @@ class CarInterface(CarInterfaceBase):
@staticmethod
def _get_params(ret, candidate, fingerprint, car_fw, experimental_long):
ret.carName = "volkswagen"
- ret.radarOffCan = True
+ ret.radarUnavailable = True
use_off_car_defaults = len(fingerprint[0]) == 0 # Pick sensible carParams during offline doc generation/CI jobs
@@ -107,6 +107,11 @@ class CarInterface(CarInterfaceBase):
ret.mass = 2011 + STD_CARGO_KG
ret.wheelbase = 2.98
+ elif candidate == CAR.CRAFTER_MK2:
+ ret.mass = 2100 + STD_CARGO_KG
+ ret.wheelbase = 3.64 # SWB, LWB is 4.49, TBD how to detect difference
+ ret.minSteerSpeed = 50 * CV.KPH_TO_MS
+
elif candidate == CAR.GOLF_MK7:
ret.mass = 1397 + STD_CARGO_KG
ret.wheelbase = 2.62
@@ -239,5 +244,5 @@ class CarInterface(CarInterfaceBase):
return ret
- def apply(self, c):
- return self.CC.update(c, self.CS, self.ext_bus)
+ def apply(self, c, now_nanos):
+ return self.CC.update(c, self.CS, self.ext_bus, now_nanos)
diff --git a/selfdrive/car/volkswagen/values.py b/selfdrive/car/volkswagen/values.py
index d1f6bfb02c..158a178b03 100755
--- a/selfdrive/car/volkswagen/values.py
+++ b/selfdrive/car/volkswagen/values.py
@@ -111,6 +111,7 @@ class CANBUS:
class CAR:
ARTEON_MK1 = "VOLKSWAGEN ARTEON 1ST GEN" # Chassis AN, Mk1 VW Arteon and variants
ATLAS_MK1 = "VOLKSWAGEN ATLAS 1ST GEN" # Chassis CA, Mk1 VW Atlas and Atlas Cross Sport
+ CRAFTER_MK2 = "VOLKSWAGEN CRAFTER 2ND GEN" # Chassis SY/SZ, Mk2 VW Crafter, VW Grand California, MAN TGE
GOLF_MK7 = "VOLKSWAGEN GOLF 7TH GEN" # Chassis 5G/AU/BA/BE, Mk7 VW Golf and variants
JETTA_MK7 = "VOLKSWAGEN JETTA 7TH GEN" # Chassis BU, Mk7 VW Jetta
PASSAT_MK8 = "VOLKSWAGEN PASSAT 8TH GEN" # Chassis 3G, Mk8 VW Passat and variants
@@ -122,7 +123,7 @@ class CAR:
TIGUAN_MK2 = "VOLKSWAGEN TIGUAN 2ND GEN" # Chassis AD/BW, Mk2 VW Tiguan and variants
TOURAN_MK2 = "VOLKSWAGEN TOURAN 2ND GEN" # Chassis 1T, Mk2 VW Touran and variants
TRANSPORTER_T61 = "VOLKSWAGEN TRANSPORTER T6.1" # Chassis 7H/7L, T6-facelift Transporter/Multivan/Caravelle/California
- TROC_MK1 = "VOLKSWAGEN T-ROC 1ST GEN" # Chassis A1, Mk1 VW VW T-Roc and variants
+ TROC_MK1 = "VOLKSWAGEN T-ROC 1ST GEN" # Chassis A1, Mk1 VW T-Roc and variants
AUDI_A3_MK3 = "AUDI A3 3RD GEN" # Chassis 8V/FF, Mk3 Audi A3 and variants
AUDI_Q2_MK1 = "AUDI Q2 1ST GEN" # Chassis GA, Mk1 Audi Q2 (RoW) and Q2L (China only)
AUDI_Q3_MK2 = "AUDI Q3 2ND GEN" # Chassis 8U/F3/FS, Mk2 Audi Q3 and variants
@@ -184,6 +185,13 @@ CAR_INFO: Dict[str, Union[VWCarInfo, List[VWCarInfo]]] = {
VWCarInfo("Volkswagen Teramont Cross Sport 2021-22"),
VWCarInfo("Volkswagen Teramont X 2021-22"),
],
+ CAR.CRAFTER_MK2: [
+ VWCarInfo("Volkswagen Crafter 2017-23", video_link="https://youtu.be/4100gLeabmo"),
+ VWCarInfo("Volkswagen e-Crafter 2018-23", video_link="https://youtu.be/4100gLeabmo"),
+ VWCarInfo("Volkswagen Grand California 2019-23", video_link="https://youtu.be/4100gLeabmo"),
+ VWCarInfo("MAN TGE 2017-23", video_link="https://youtu.be/4100gLeabmo"),
+ VWCarInfo("MAN eTGE 2020-23", video_link="https://youtu.be/4100gLeabmo"),
+ ],
CAR.GOLF_MK7: [
VWCarInfo("Volkswagen e-Golf 2014-20"),
VWCarInfo("Volkswagen Golf 2015-20"),
@@ -214,7 +222,7 @@ CAR_INFO: Dict[str, Union[VWCarInfo, List[VWCarInfo]]] = {
],
CAR.TAOS_MK1: VWCarInfo("Volkswagen Taos 2022"),
CAR.TCROSS_MK1: VWCarInfo("Volkswagen T-Cross 2021", footnotes=[Footnote.VW_MQB_A0]),
- CAR.TIGUAN_MK2: VWCarInfo("Volkswagen Tiguan 2019-22"),
+ CAR.TIGUAN_MK2: VWCarInfo("Volkswagen Tiguan 2018-23"),
CAR.TOURAN_MK2: VWCarInfo("Volkswagen Touran 2017"),
CAR.TRANSPORTER_T61: [
VWCarInfo("Volkswagen Caravelle 2020"),
@@ -352,6 +360,23 @@ FW_VERSIONS = {
b'\xf1\x875Q0907572P \xf1\x890682',
],
},
+ CAR.CRAFTER_MK2: {
+ (Ecu.engine, 0x7e0, None): [
+ b'\xf1\x8704L906056EK\xf1\x896391',
+ ],
+ # Only current upstreamed vehicle has a manual transmission
+ #(Ecu.transmission, 0x7e1, None): [
+ #],
+ (Ecu.srs, 0x715, None): [
+ b'\xf1\x873Q0959655BG\xf1\x890703\xf1\x82\x0e16120016130012051G1313052900',
+ ],
+ (Ecu.eps, 0x712, None): [
+ b'\xf1\x872N0909143E \xf1\x897021\xf1\x82\x05163AZ306A2',
+ ],
+ (Ecu.fwdRadar, 0x757, None): [
+ b'\xf1\x872Q0907572M \xf1\x890233',
+ ],
+ },
CAR.GOLF_MK7: {
(Ecu.engine, 0x7e0, None): [
b'\xf1\x8704E906016A \xf1\x897697',
@@ -373,6 +398,7 @@ FW_VERSIONS = {
b'\xf1\x8704L906056CR\xf1\x895813',
b'\xf1\x8704L906056HE\xf1\x893758',
b'\xf1\x8704L906056HN\xf1\x896590',
+ b'\xf1\x8704L906056HT\xf1\x896591',
b'\xf1\x870EA906016A \xf1\x898343',
b'\xf1\x870EA906016E \xf1\x894219',
b'\xf1\x870EA906016F \xf1\x894238',
@@ -405,6 +431,7 @@ FW_VERSIONS = {
b'\xf1\x870CW300041H \xf1\x891010',
b'\xf1\x870CW300042F \xf1\x891604',
b'\xf1\x870CW300043B \xf1\x891601',
+ b'\xf1\x870CW300043E \xf1\x891603',
b'\xf1\x870CW300044S \xf1\x894530',
b'\xf1\x870CW300044T \xf1\x895245',
b'\xf1\x870CW300045 \xf1\x894531',
@@ -442,6 +469,7 @@ FW_VERSIONS = {
b'\xf1\x875Q0959655AA\xf1\x890388\xf1\x82\x111413001113120053114317121C111C9113',
b'\xf1\x875Q0959655BH\xf1\x890336\xf1\x82\x1314160011123300314211012230229333463100',
b'\xf1\x875Q0959655BS\xf1\x890403\xf1\x82\x1314160011123300314240012250229333463100',
+ b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x13141600111233003142404A2251229333463100',
b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x13141600111233003142404A2252229333463100',
b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x13141600111233003142405A2252229333463100',
b'\xf1\x875Q0959655C \xf1\x890361\xf1\x82\x111413001112120004110415121610169112',
@@ -565,6 +593,7 @@ FW_VERSIONS = {
(Ecu.engine, 0x7e0, None): [
b'\xf1\x8703N906026E \xf1\x892114',
b'\xf1\x8704E906023AH\xf1\x893379',
+ b'\xf1\x8704L906026DP\xf1\x891538',
b'\xf1\x8704L906026ET\xf1\x891990',
b'\xf1\x8704L906026FP\xf1\x892012',
b'\xf1\x8704L906026GA\xf1\x892013',
@@ -583,6 +612,7 @@ FW_VERSIONS = {
],
(Ecu.srs, 0x715, None): [
b'\xf1\x873Q0959655AE\xf1\x890195\xf1\x82\r56140056130012416612124111',
+ b'\xf1\x873Q0959655AF\xf1\x890195\xf1\x82\r56140056130012026612120211',
b'\xf1\x873Q0959655AN\xf1\x890306\xf1\x82\r58160058140013036914110311',
b'\xf1\x873Q0959655BA\xf1\x890195\xf1\x82\r56140056130012516612125111',
b'\xf1\x873Q0959655BB\xf1\x890195\xf1\x82\r56140056130012026612120211',
@@ -593,6 +623,7 @@ FW_VERSIONS = {
(Ecu.eps, 0x712, None): [
b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566B00611A1',
b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566B00711A1',
+ b'\xf1\x875Q0909143K \xf1\x892033\xf1\x820514B0060703',
b'\xf1\x875Q0909143M \xf1\x892041\xf1\x820522B0060803',
b'\xf1\x875Q0909143M \xf1\x892041\xf1\x820522B0080803',
b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\00521B00606A1',
@@ -601,6 +632,7 @@ FW_VERSIONS = {
b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567B0020600',
],
(Ecu.fwdRadar, 0x757, None): [
+ b'\xf1\x873Q0907572A \xf1\x890126',
b'\xf1\x873Q0907572A \xf1\x890130',
b'\xf1\x873Q0907572B \xf1\x890192',
b'\xf1\x873Q0907572C \xf1\x890195',
@@ -697,39 +729,49 @@ FW_VERSIONS = {
},
CAR.TIGUAN_MK2: {
(Ecu.engine, 0x7e0, None): [
+ b'\xf1\x8703N906026D \xf1\x893680',
b'\xf1\x8704E906027NB\xf1\x899504',
b'\xf1\x8704L906026EJ\xf1\x893661',
b'\xf1\x8704L906027G \xf1\x899893',
b'\xf1\x875N0906259 \xf1\x890002',
+ b'\xf1\x875NA906259H \xf1\x890002',
b'\xf1\x875NA907115E \xf1\x890005',
b'\xf1\x8783A907115B \xf1\x890005',
+ b'\xf1\x8783A907115F \xf1\x890002',
b'\xf1\x8783A907115G \xf1\x890001',
],
(Ecu.transmission, 0x7e1, None): [
b'\xf1\x8709G927158DT\xf1\x893698',
+ b'\xf1\x8709G927158FM\xf1\x893757',
b'\xf1\x8709G927158GC\xf1\x893821',
b'\xf1\x8709G927158GD\xf1\x893820',
b'\xf1\x870D9300043 \xf1\x895202',
b'\xf1\x870DL300011N \xf1\x892001',
b'\xf1\x870DL300011N \xf1\x892012',
+ b'\xf1\x870DL300012P \xf1\x892103',
b'\xf1\x870DL300013A \xf1\x893005',
b'\xf1\x870DL300013G \xf1\x892119',
b'\xf1\x870DL300013G \xf1\x892120',
+ b'\xf1\x870DL300014C \xf1\x893703',
],
(Ecu.srs, 0x715, None): [
b'\xf1\x875Q0959655AR\xf1\x890317\xf1\x82\02331310031333334313132573732379333313100',
+ b'\xf1\x875Q0959655BJ\xf1\x890336\xf1\x82\x1312110031333300314232583732379333423100',
b'\xf1\x875Q0959655BM\xf1\x890403\xf1\x82\02316143231313500314641011750179333423100',
b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\02312110031333300314240583752379333423100',
b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\02331310031333336313140013950399333423100',
b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x1331310031333334313140013750379333423100',
b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x1331310031333334313140573752379333423100',
b'\xf1\x875Q0959655CB\xf1\x890421\xf1\x82\x1316143231313500314647021750179333613100',
+ b'\xf1\x875Q0959655CG\xf1\x890421\xf1\x82\x1331310031333300314240024050409333613100',
],
(Ecu.eps, 0x712, None): [
b'\xf1\x875Q0909143M \xf1\x892041\xf1\x820529A6060603',
b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521A60604A1',
b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567A6000600',
+ b'\xf1\x875QF909144A \xf1\x895581\xf1\x82\x0571A60834A1',
b'\xf1\x875QF909144B \xf1\x895582\xf1\x82\00571A60634A1',
+ b'\xf1\x875QF909144B \xf1\x895582\xf1\x82\x0571A62A32A1',
b'\xf1\x875QM909144B \xf1\x891081\xf1\x82\x0521A60604A1',
b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\x0521A60604A1',
b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\00521A60804A1',
@@ -737,6 +779,7 @@ FW_VERSIONS = {
(Ecu.fwdRadar, 0x757, None): [
b'\xf1\x872Q0907572AA\xf1\x890396',
b'\xf1\x872Q0907572J \xf1\x890156',
+ b'\xf1\x872Q0907572M \xf1\x890233',
b'\xf1\x872Q0907572Q \xf1\x890342',
b'\xf1\x872Q0907572R \xf1\x890372',
b'\xf1\x872Q0907572T \xf1\x890383',
@@ -933,25 +976,33 @@ FW_VERSIONS = {
b'\xf1\x8704L906021EL\xf1\x897542',
b'\xf1\x8704L906026BP\xf1\x891198',
b'\xf1\x8704L906026BP\xf1\x897608',
+ b'\xf1\x8704L906056CR\xf1\x892797',
b'\xf1\x8705E906018AS\xf1\x899596',
+ b'\xf1\x878V0906264H \xf1\x890005',
],
(Ecu.transmission, 0x7e1, None): [
+ b'\xf1\x870CW300041D \xf1\x891004',
+ b'\xf1\x870CW300041G \xf1\x891003',
b'\xf1\x870CW300050J \xf1\x891908',
b'\xf1\x870D9300042M \xf1\x895016',
],
(Ecu.srs, 0x715, None): [
b'\xf1\x873Q0959655AC\xf1\x890189\xf1\x82\r11110011110011021511110200',
+ b'\xf1\x873Q0959655AS\xf1\x890200\xf1\x82\r11110011110011021511110200',
b'\xf1\x873Q0959655AS\xf1\x890200\xf1\x82\r12110012120012021612110200',
+ b'\xf1\x873Q0959655BH\xf1\x890703\xf1\x82\x0e1312001313001305171311052900',
b'\xf1\x873Q0959655CM\xf1\x890720\xf1\x82\0161312001313001305171311052900',
],
(Ecu.eps, 0x712, None): [
b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\00521N01342A1',
b'\xf1\x875Q0909144P \xf1\x891043\xf1\x82\00511N01805A0',
+ b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521N01309A1',
b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\00521N05808A1',
],
(Ecu.fwdRadar, 0x757, None): [
b'\xf1\x875Q0907572B \xf1\x890200\xf1\x82\00101',
b'\xf1\x875Q0907572H \xf1\x890620',
+ b'\xf1\x875Q0907572K \xf1\x890402\xf1\x82\x0101',
b'\xf1\x875Q0907572P \xf1\x890682',
],
},
@@ -999,6 +1050,7 @@ FW_VERSIONS = {
b'\xf1\x8704E906027DD\xf1\x893123',
b'\xf1\x8704L906026DE\xf1\x895418',
b'\xf1\x875NA907115E \xf1\x890003',
+ b'\xf1\x875NA907115E \xf1\x890005',
],
(Ecu.transmission, 0x7e1, None): [
b'\xf1\x870D9300043 \xf1\x895202',
@@ -1007,8 +1059,8 @@ FW_VERSIONS = {
b'\xf1\x870DL300013G \xf1\x892119',
],
(Ecu.srs, 0x715, None): [
- b'\xf1\x873Q0959655BJ\xf1\x890703\xf1\x82\0161213001211001205212111052100',
- b'\xf1\x873Q0959655CN\xf1\x890720\xf1\x82\0161213001211001205212112052100',
+ b'\xf1\x873Q0959655BJ\xf1\x890703\xf1\x82\x0e1213001211001205212111052100',
+ b'\xf1\x873Q0959655CN\xf1\x890720\xf1\x82\x0e1213001211001205212112052100',
b'\xf1\x873Q0959655CQ\xf1\x890720\xf1\x82\x0e1213111211001205212112052111',
],
(Ecu.eps, 0x712, None): [
@@ -1023,6 +1075,7 @@ FW_VERSIONS = {
},
CAR.SKODA_OCTAVIA_MK3: {
(Ecu.engine, 0x7e0, None): [
+ b'\xf1\x8704C906025L \xf1\x896198',
b'\xf1\x8704E906016ER\xf1\x895823',
b'\xf1\x8704E906027HD\xf1\x893742',
b'\xf1\x8704E906027MH\xf1\x894786',
@@ -1034,6 +1087,7 @@ FW_VERSIONS = {
b'\xf1\x870CW300041L \xf1\x891601',
b'\xf1\x870CW300041N \xf1\x891605',
b'\xf1\x870CW300043B \xf1\x891601',
+ b'\xf1\x870CW300043P \xf1\x891605',
b'\xf1\x870D9300041C \xf1\x894936',
b'\xf1\x870D9300041J \xf1\x894902',
b'\xf1\x870D9300041P \xf1\x894507',
@@ -1043,6 +1097,7 @@ FW_VERSIONS = {
b'\xf1\x873Q0959655AQ\xf1\x890200\xf1\x82\r11120011100010312212113100',
b'\xf1\x873Q0959655AS\xf1\x890200\xf1\x82\r11120011100010022212110200',
b'\xf1\x873Q0959655BH\xf1\x890703\xf1\x82\0163221003221002105755331052100',
+ b'\xf1\x873Q0959655CM\xf1\x890720\xf1\x82\x0e3221003221002105755331052100',
b'\xf1\x873Q0959655CN\xf1\x890720\xf1\x82\x0e3221003221002105755331052100',
b'\xf1\x875QD959655 \xf1\x890388\xf1\x82\x111101000011110006110411111111119111',
],
@@ -1069,6 +1124,7 @@ FW_VERSIONS = {
b'\xf1\x870CW300050 \xf1\x891709',
],
(Ecu.srs, 0x715, None): [
+ b'\xf1\x872Q0959655AJ\xf1\x890250\xf1\x82\x1211110411110411--04040404131111112H14',
b'\xf1\x872Q0959655AM\xf1\x890351\xf1\x82\022111104111104112104040404111111112H14',
],
(Ecu.eps, 0x712, None): [
diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py
index 01c203be60..a951d5b1af 100755
--- a/selfdrive/controls/controlsd.py
+++ b/selfdrive/controls/controlsd.py
@@ -17,7 +17,7 @@ from selfdrive.boardd.boardd import can_list_to_can_capnp
from selfdrive.car.car_helpers import get_car, get_startup_event, get_one_can
from selfdrive.controls.lib.lateral_planner import CAMERA_OFFSET
from selfdrive.controls.lib.drive_helpers import VCruiseHelper, get_lag_adjusted_curvature
-from selfdrive.controls.lib.latcontrol import LatControl
+from selfdrive.controls.lib.latcontrol import LatControl, MIN_LATERAL_CONTROL_SPEED
from selfdrive.controls.lib.longcontrol import LongControl
from selfdrive.controls.lib.latcontrol_pid import LatControlPID
from selfdrive.controls.lib.latcontrol_indi import LatControlINDI
@@ -38,7 +38,7 @@ REPLAY = "REPLAY" in os.environ
SIMULATION = "SIMULATION" in os.environ
NOSENSOR = "NOSENSOR" in os.environ
IGNORE_PROCESSES = {"uploader", "deleter", "loggerd", "logmessaged", "tombstoned", "statsd",
- "logcatd", "proclogd", "clocksd", "updated", "timezoned", "manage_athenad", "laikad"} | \
+ "logcatd", "proclogd", "clocksd", "updated", "timezoned", "manage_athenad"} | \
{k for k, v in managed_processes.items() if not v.enabled}
ThermalStatus = log.DeviceState.ThermalStatus
@@ -100,11 +100,12 @@ class Controls:
get_one_can(self.can_sock)
num_pandas = len(messaging.recv_one_retry(self.sm.sock['pandaStates']).pandaStates)
- self.CI, self.CP = get_car(self.can_sock, self.pm.sock['sendcan'], num_pandas)
+ experimental_long_allowed = self.params.get_bool("ExperimentalLongitudinalEnabled") and not is_release_branch()
+ self.CI, self.CP = get_car(self.can_sock, self.pm.sock['sendcan'], experimental_long_allowed, num_pandas)
else:
self.CI, self.CP = CI, CI.CP
- self.joystick_mode = self.params.get_bool("JoystickDebugMode") or (self.CP.notCar and sm is None)
+ self.joystick_mode = self.params.get_bool("JoystickDebugMode") or self.CP.notCar
# set alternative experiences from parameters
self.disengage_on_accelerator = self.params.get_bool("DisengageOnAccelerator")
@@ -133,9 +134,6 @@ class Controls:
safety_config.safetyModel = car.CarParams.SafetyModel.noOutput
self.CP.safetyConfigs = [safety_config]
- if is_release_branch():
- self.CP.experimentalLongitudinalAvailable = False
-
# Write CarParams for radard
cp_bytes = self.CP.to_bytes()
self.params.put("CarParams", cp_bytes)
@@ -143,7 +141,7 @@ class Controls:
put_nonblocking("CarParamsPersistent", cp_bytes)
# cleanup old params
- if not self.CP.experimentalLongitudinalAvailable:
+ if not self.CP.experimentalLongitudinalAvailable or is_release_branch():
self.params.remove("ExperimentalLongitudinalEnabled")
if not self.CP.openpilotLongitudinalControl:
self.params.remove("ExperimentalMode")
@@ -170,12 +168,13 @@ class Controls:
self.state = State.disabled
self.enabled = False
self.active = False
- self.can_rcv_timeout = False
self.soft_disable_timer = 0
self.mismatch_counter = 0
self.cruise_mismatch_counter = 0
- self.can_rcv_timeout_counter = 0
+ self.can_rcv_timeout_counter = 0 # conseuctive timeout count
+ self.can_rcv_cum_timeout_counter = 0 # cumulative timeout count
self.last_blinker_frame = 0
+ self.last_steering_pressed_frame = 0
self.distance_traveled = 0
self.last_functional_fan_frame = 0
self.events_prev = []
@@ -185,10 +184,12 @@ class Controls:
self.steer_limited = False
self.desired_curvature = 0.0
self.desired_curvature_rate = 0.0
+ self.experimental_mode = False
self.v_cruise_helper = VCruiseHelper(self.CP)
# TODO: no longer necessary, aside from process replay
self.sm['liveParameters'].valid = True
+ self.can_log_mono_time = 0
self.startup_event = get_startup_event(car_recognized, controller_available, len(self.CP.carFw) > 0)
@@ -280,8 +281,9 @@ class Controls:
# Alert if fan isn't spinning for 5 seconds
if self.sm['peripheralState'].pandaType != log.PandaState.PandaType.unknown:
- if self.sm['peripheralState'].fanSpeedRpm == 0 and self.sm['deviceState'].fanSpeedPercentDesired > 50:
- if (self.sm.frame - self.last_functional_fan_frame) * DT_CTRL > 5.0:
+ if self.sm['peripheralState'].fanSpeedRpm < 500 and self.sm['deviceState'].fanSpeedPercentDesired > 50:
+ # allow enough time for the fan controller in the panda to recover from stalls
+ if (self.sm.frame - self.last_functional_fan_frame) * DT_CTRL > 15.0:
self.events.add(EventName.fanMalfunction)
else:
self.last_functional_fan_frame = self.sm.frame
@@ -350,9 +352,10 @@ class Controls:
self.events.add(EventName.canError)
# generic catch-all. ideally, a more specific event should be added above instead
+ can_rcv_timeout = self.can_rcv_timeout_counter >= 5
has_disable_events = self.events.any(ET.NO_ENTRY) and (self.events.any(ET.SOFT_DISABLE) or self.events.any(ET.IMMEDIATE_DISABLE))
no_system_errors = (not has_disable_events) or (len(self.events) == num_events)
- if (not self.sm.all_checks() or self.can_rcv_timeout) and no_system_errors:
+ if (not self.sm.all_checks() or can_rcv_timeout) and no_system_errors:
if not self.sm.all_alive():
self.events.add(EventName.commIssue)
elif not self.sm.all_freq_ok():
@@ -364,7 +367,7 @@ class Controls:
'invalid': [s for s, valid in self.sm.valid.items() if not valid],
'not_alive': [s for s, alive in self.sm.alive.items() if not alive],
'not_freq_ok': [s for s, freq_ok in self.sm.freq_ok.items() if not freq_ok],
- 'can_rcv_timeout': self.can_rcv_timeout,
+ 'can_rcv_timeout': can_rcv_timeout,
}
if logs != self.logged_comm_issue:
cloudlog.event("commIssue", error=True, **logs)
@@ -427,6 +430,8 @@ class Controls:
# Update carState from CAN
can_strs = messaging.drain_sock_raw(self.can_sock, wait_for_one=True)
CS = self.CI.update(self.CC, can_strs)
+ if len(can_strs) and REPLAY:
+ self.can_log_mono_time = messaging.log_from_bytes(can_strs[0]).logMonoTime
self.sm.update(0)
@@ -444,9 +449,9 @@ class Controls:
# Check for CAN timeout
if not can_strs:
self.can_rcv_timeout_counter += 1
- self.can_rcv_timeout = True
+ self.can_rcv_cum_timeout_counter += 1
else:
- self.can_rcv_timeout = False
+ self.can_rcv_timeout_counter = 0
# When the panda and controlsd do not agree on controls_allowed
# we want to disengage openpilot. However the status from the panda goes through
@@ -542,7 +547,7 @@ class Controls:
else:
self.state = State.enabled
self.current_alert_types.append(ET.ENABLE)
- self.v_cruise_helper.initialize_v_cruise(CS)
+ self.v_cruise_helper.initialize_v_cruise(CS, self.experimental_mode)
# Check if openpilot is engaged and actuators are enabled
self.enabled = self.state in ENABLED_STATES
@@ -570,9 +575,11 @@ class Controls:
CC = car.CarControl.new_message()
CC.enabled = self.enabled
+
# Check which actuators can be enabled
- CC.latActive = self.active and not CS.steerFaultTemporary and not CS.steerFaultPermanent # and \
- # CS.vEgo > self.CP.minSteerSpeed and not CS.standstill
+ standstill = CS.vEgo <= max(self.CP.minSteerSpeed, MIN_LATERAL_CONTROL_SPEED) or CS.standstill
+ CC.latActive = self.active and not CS.steerFaultTemporary and not CS.steerFaultPermanent and \
+ (not standstill or self.joystick_mode)
CC.longActive = self.enabled and not self.events.any(ET.OVERRIDE_LONGITUDINAL) and self.CP.openpilotLongitudinalControl
actuators = CC.actuators
@@ -607,6 +614,7 @@ class Controls:
actuators.steer, actuators.steeringAngleDeg, lac_log = self.LaC.update(CC.latActive, CS, self.VM, lp,
self.last_actuators, self.steer_limited, self.desired_curvature,
self.desired_curvature_rate, self.sm['liveLocationKalman'])
+ actuators.curvature = self.desired_curvature
else:
lac_log = log.ControlsState.LateralDebugState.new_message()
if self.sm.rcv_frame['testJoystick'] > 0:
@@ -623,29 +631,34 @@ class Controls:
lac_log.output = actuators.steer
lac_log.saturated = abs(actuators.steer) >= 0.9
+ if CS.steeringPressed:
+ self.last_steering_pressed_frame = self.sm.frame
+ recent_steer_pressed = (self.sm.frame - self.last_steering_pressed_frame)*DT_CTRL < 2.0
+
# Send a "steering required alert" if saturation count has reached the limit
- if (lac_log.active and not CS.steeringPressed and self.CP.lateralTuning.which() == 'torque' and not self.joystick_mode):
- undershooting = abs(lac_log.desiredLateralAccel) / abs(1e-3 + lac_log.actualLateralAccel) > 1.2
- turning = abs(lac_log.desiredLateralAccel) > 1.0
- good_speed = CS.vEgo > 5
- max_torque = abs(self.last_actuators.steer) > 0.99
- if undershooting and turning and good_speed and max_torque:
- self.events.add(EventName.steerSaturated)
- elif lac_log.active and lac_log.saturated:
- dpath_points = lat_plan.dPathPoints
- if len(dpath_points):
- # Check if we deviated from the path
- # TODO use desired vs actual curvature
- if self.CP.steerControlType == SteerControlType.angle:
- steering_value = actuators.steeringAngleDeg
- else:
- steering_value = actuators.steer
+ if lac_log.active and not recent_steer_pressed:
+ if self.CP.lateralTuning.which() == 'torque' and not self.joystick_mode:
+ undershooting = abs(lac_log.desiredLateralAccel) / abs(1e-3 + lac_log.actualLateralAccel) > 1.2
+ turning = abs(lac_log.desiredLateralAccel) > 1.0
+ good_speed = CS.vEgo > 5
+ max_torque = abs(self.last_actuators.steer) > 0.99
+ if undershooting and turning and good_speed and max_torque:
+ lac_log.active and self.events.add(EventName.steerSaturated)
+ elif lac_log.saturated:
+ dpath_points = lat_plan.dPathPoints
+ if len(dpath_points):
+ # Check if we deviated from the path
+ # TODO use desired vs actual curvature
+ if self.CP.steerControlType == SteerControlType.angle:
+ steering_value = actuators.steeringAngleDeg
+ else:
+ steering_value = actuators.steer
- left_deviation = steering_value > 0 and dpath_points[0] < -0.20
- right_deviation = steering_value < 0 and dpath_points[0] > 0.20
+ left_deviation = steering_value > 0 and dpath_points[0] < -0.20
+ right_deviation = steering_value < 0 and dpath_points[0] > 0.20
- if left_deviation or right_deviation:
- self.events.add(EventName.steerSaturated)
+ if left_deviation or right_deviation:
+ self.events.add(EventName.steerSaturated)
# Ensure no NaNs/Infs
for p in ACTUATOR_FIELDS:
@@ -725,7 +738,8 @@ class Controls:
if not self.read_only and self.initialized:
# send car controls over can
- self.last_actuators, can_sends = self.CI.apply(CC)
+ now_nanos = self.can_log_mono_time if REPLAY else int(sec_since_boot() * 1e9)
+ self.last_actuators, can_sends = self.CI.apply(CC, now_nanos)
self.pm.send('sendcan', can_list_to_can_capnp(can_sends, msgtype='sendcan', valid=CS.canValid))
CC.actuatorsOutput = self.last_actuators
if self.CP.steerControlType == car.CarParams.SteerControlType.angle:
@@ -756,7 +770,6 @@ class Controls:
controlsState.alertType = current_alert.alert_type
controlsState.alertSound = current_alert.audible_alert
- controlsState.canMonoTimes = list(CS.canMonoTimes)
controlsState.longitudinalPlanMonoTime = self.sm.logMonoTime['longitudinalPlan']
controlsState.lateralPlanMonoTime = self.sm.logMonoTime['lateralPlan']
controlsState.enabled = self.enabled
@@ -776,8 +789,8 @@ class Controls:
controlsState.cumLagMs = -self.rk.remaining * 1000.
controlsState.startMonoTime = int(start_time * 1e9)
controlsState.forceDecel = bool(force_decel)
- controlsState.canErrorCounter = self.can_rcv_timeout_counter
- controlsState.experimentalMode = self.params.get_bool("ExperimentalMode") and self.CP.openpilotLongitudinalControl
+ controlsState.canErrorCounter = self.can_rcv_cum_timeout_counter
+ controlsState.experimentalMode = self.experimental_mode
lat_tuning = self.CP.lateralTuning.which()
if self.joystick_mode:
@@ -828,6 +841,7 @@ class Controls:
self.prof.checkpoint("Ratekeeper", ignore=True)
self.is_metric = self.params.get_bool("IsMetric")
+ self.experimental_mode = self.params.get_bool("ExperimentalMode") and self.CP.openpilotLongitudinalControl
# Sample data from sockets and get a carState
CS = self.data_sample()
diff --git a/selfdrive/controls/lib/drive_helpers.py b/selfdrive/controls/lib/drive_helpers.py
index 3d5ec8ac1d..05c3897335 100644
--- a/selfdrive/controls/lib/drive_helpers.py
+++ b/selfdrive/controls/lib/drive_helpers.py
@@ -8,15 +8,15 @@ from selfdrive.modeld.constants import T_IDXS
# WARNING: this value was determined based on the model's training distribution,
# model predictions above this speed can be unpredictable
-V_CRUISE_MAX = 145 # kph
-V_CRUISE_MIN = 8 # kph
-V_CRUISE_ENABLE_MIN = 40 # kph
-V_CRUISE_INITIAL = 255 # kph
+# V_CRUISE's are in kph
+V_CRUISE_MIN = 8
+V_CRUISE_MAX = 145
+V_CRUISE_UNSET = 255
+V_CRUISE_INITIAL = 40
+V_CRUISE_INITIAL_EXPERIMENTAL_MODE = 105
IMPERIAL_INCREMENT = 1.6 # should be CV.MPH_TO_KPH, but this causes rounding errors
MIN_SPEED = 1.0
-LAT_MPC_N = 16
-LON_MPC_N = 32
CONTROL_N = 17
CAR_ROTATION_RADIUS = 0.0
@@ -39,15 +39,15 @@ CRUISE_INTERVAL_SIGN = {
class VCruiseHelper:
def __init__(self, CP):
self.CP = CP
- self.v_cruise_kph = V_CRUISE_INITIAL
- self.v_cruise_cluster_kph = V_CRUISE_INITIAL
+ self.v_cruise_kph = V_CRUISE_UNSET
+ self.v_cruise_cluster_kph = V_CRUISE_UNSET
self.v_cruise_kph_last = 0
self.button_timers = {ButtonType.decelCruise: 0, ButtonType.accelCruise: 0}
self.button_change_states = {btn: {"standstill": False, "enabled": False} for btn in self.button_timers}
@property
def v_cruise_initialized(self):
- return self.v_cruise_kph != V_CRUISE_INITIAL
+ return self.v_cruise_kph != V_CRUISE_UNSET
def update_v_cruise(self, CS, enabled, is_metric):
self.v_cruise_kph_last = self.v_cruise_kph
@@ -62,8 +62,8 @@ class VCruiseHelper:
self.v_cruise_kph = CS.cruiseState.speed * CV.MS_TO_KPH
self.v_cruise_cluster_kph = CS.cruiseState.speedCluster * CV.MS_TO_KPH
else:
- self.v_cruise_kph = V_CRUISE_INITIAL
- self.v_cruise_cluster_kph = V_CRUISE_INITIAL
+ self.v_cruise_kph = V_CRUISE_UNSET
+ self.v_cruise_cluster_kph = V_CRUISE_UNSET
def _update_v_cruise_non_pcm(self, CS, enabled, is_metric):
# handle button presses. TODO: this should be in state_control, but a decelCruise press
@@ -125,16 +125,18 @@ class VCruiseHelper:
self.button_timers[b.type.raw] = 1 if b.pressed else 0
self.button_change_states[b.type.raw] = {"standstill": CS.cruiseState.standstill, "enabled": enabled}
- def initialize_v_cruise(self, CS):
+ def initialize_v_cruise(self, CS, experimental_mode: bool) -> None:
# initializing is handled by the PCM
if self.CP.pcmCruise:
return
+ initial = V_CRUISE_INITIAL_EXPERIMENTAL_MODE if experimental_mode else V_CRUISE_INITIAL
+
# 250kph or above probably means we never had a set speed
if any(b.type in (ButtonType.accelCruise, ButtonType.resumeCruise) for b in CS.buttonEvents) and self.v_cruise_kph_last < 250:
self.v_cruise_kph = self.v_cruise_kph_last
else:
- self.v_cruise_kph = int(round(clip(CS.vEgo * CV.MS_TO_KPH, V_CRUISE_ENABLE_MIN, V_CRUISE_MAX)))
+ self.v_cruise_kph = int(round(clip(CS.vEgo * CV.MS_TO_KPH, initial, V_CRUISE_MAX)))
self.v_cruise_cluster_kph = self.v_cruise_kph
diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py
index 3036828662..e4ddfb5326 100644
--- a/selfdrive/controls/lib/events.py
+++ b/selfdrive/controls/lib/events.py
@@ -230,7 +230,7 @@ def startup_master_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubM
return StartupAlert("WARNING: This branch is not tested", branch, alert_status=AlertStatus.userPrompt)
def below_engage_speed_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int) -> Alert:
- return NoEntryAlert(f"Speed Below {get_display_speed(CP.minEnableSpeed, metric)}")
+ return NoEntryAlert(f"Drive above {get_display_speed(CP.minEnableSpeed, metric)} to engage")
def below_steer_speed_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int) -> Alert:
@@ -292,7 +292,7 @@ def calibration_invalid_alert(CP: car.CarParams, CS: car.CarState, sm: messaging
rpy = sm['liveCalibration'].rpyCalib
yaw = math.degrees(rpy[2] if len(rpy) == 3 else math.nan)
pitch = math.degrees(rpy[1] if len(rpy) == 3 else math.nan)
- angles = f"Pitch: {pitch:.1f}°, Yaw: {yaw:.1f}°"
+ angles = f"Remount Device (Pitch: {pitch:.1f}°, Yaw: {yaw:.1f}°)"
return NormalPermanentAlert("Calibration Invalid", angles)
@@ -317,9 +317,9 @@ def modeld_lagging_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubM
def wrong_car_mode_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int) -> Alert:
- text = "Cruise Mode Disabled"
+ text = "Enable Adaptive Cruise to Engage"
if CP.carName == "honda":
- text = "Main Switch Off"
+ text = "Enable Main Switch to Engage"
return NoEntryAlert(text)
@@ -729,8 +729,8 @@ EVENTS: Dict[int, Dict[str, Union[Alert, AlertCallbackType]]] = {
},
EventName.espDisabled: {
- ET.SOFT_DISABLE: soft_disable_alert("ESP Off"),
- ET.NO_ENTRY: NoEntryAlert("ESP Off"),
+ ET.SOFT_DISABLE: soft_disable_alert("Electronic Stability Control Disabled"),
+ ET.NO_ENTRY: NoEntryAlert("Electronic Stability Control Disabled"),
},
EventName.lowBattery: {
diff --git a/selfdrive/controls/lib/latcontrol.py b/selfdrive/controls/lib/latcontrol.py
index edf8f9232a..c3d2974f02 100644
--- a/selfdrive/controls/lib/latcontrol.py
+++ b/selfdrive/controls/lib/latcontrol.py
@@ -3,7 +3,7 @@ from abc import abstractmethod, ABC
from common.numpy_fast import clip
from common.realtime import DT_CTRL
-MIN_STEER_SPEED = 0.0
+MIN_LATERAL_CONTROL_SPEED = 0.3 # m/s
class LatControl(ABC):
diff --git a/selfdrive/controls/lib/latcontrol_angle.py b/selfdrive/controls/lib/latcontrol_angle.py
index d692f80b4b..9ed140d38e 100644
--- a/selfdrive/controls/lib/latcontrol_angle.py
+++ b/selfdrive/controls/lib/latcontrol_angle.py
@@ -1,7 +1,7 @@
import math
from cereal import log
-from selfdrive.controls.lib.latcontrol import LatControl, MIN_STEER_SPEED
+from selfdrive.controls.lib.latcontrol import LatControl
STEER_ANGLE_SATURATION_THRESHOLD = 2.5 # Degrees
@@ -14,7 +14,7 @@ class LatControlAngle(LatControl):
def update(self, active, CS, VM, params, last_actuators, steer_limited, desired_curvature, desired_curvature_rate, llk):
angle_log = log.ControlsState.LateralAngleState.new_message()
- if CS.vEgo < MIN_STEER_SPEED or not active:
+ if not active:
angle_log.active = False
angle_steers_des = float(CS.steeringAngleDeg)
else:
diff --git a/selfdrive/controls/lib/latcontrol_indi.py b/selfdrive/controls/lib/latcontrol_indi.py
index 2bc3cef76b..dca82c6729 100644
--- a/selfdrive/controls/lib/latcontrol_indi.py
+++ b/selfdrive/controls/lib/latcontrol_indi.py
@@ -5,7 +5,7 @@ from cereal import log
from common.filter_simple import FirstOrderFilter
from common.numpy_fast import clip, interp
from common.realtime import DT_CTRL
-from selfdrive.controls.lib.latcontrol import LatControl, MIN_STEER_SPEED
+from selfdrive.controls.lib.latcontrol import LatControl
class LatControlINDI(LatControl):
@@ -82,7 +82,7 @@ class LatControlINDI(LatControl):
rate_des = VM.get_steer_from_curvature(-desired_curvature_rate, CS.vEgo, 0)
indi_log.steeringRateDesiredDeg = math.degrees(rate_des)
- if CS.vEgo < MIN_STEER_SPEED or not active:
+ if not active:
indi_log.active = False
self.steer_filter.x = 0.0
output_steer = 0
diff --git a/selfdrive/controls/lib/latcontrol_pid.py b/selfdrive/controls/lib/latcontrol_pid.py
index c42735d84c..b4de86cfbc 100644
--- a/selfdrive/controls/lib/latcontrol_pid.py
+++ b/selfdrive/controls/lib/latcontrol_pid.py
@@ -1,7 +1,7 @@
import math
from cereal import car, log
-from selfdrive.controls.lib.latcontrol import LatControl, MIN_STEER_SPEED
+from selfdrive.controls.lib.latcontrol import LatControl
from selfdrive.controls.lib.pid import PIDController
SteerControlType = car.CarParams.SteerControlType
@@ -35,7 +35,7 @@ class LatControlPID(LatControl):
pid_log.steeringAngleDesiredDeg = angle_steers_des
pid_log.angleError = error
- if CS.vEgo < MIN_STEER_SPEED or not active:
+ if not active:
output_steer = 0.0
pid_log.active = False
self.pid.reset()
diff --git a/selfdrive/controls/lib/latcontrol_torque.py b/selfdrive/controls/lib/latcontrol_torque.py
index d10d39d945..2f56094379 100644
--- a/selfdrive/controls/lib/latcontrol_torque.py
+++ b/selfdrive/controls/lib/latcontrol_torque.py
@@ -2,7 +2,7 @@ import math
from cereal import log
from common.numpy_fast import interp
-from selfdrive.controls.lib.latcontrol import LatControl, MIN_STEER_SPEED
+from selfdrive.controls.lib.latcontrol import LatControl
from selfdrive.controls.lib.pid import PIDController
from selfdrive.controls.lib.vehicle_model import ACCELERATION_DUE_TO_GRAVITY
@@ -39,7 +39,7 @@ class LatControlTorque(LatControl):
def update(self, active, CS, VM, params, last_actuators, steer_limited, desired_curvature, desired_curvature_rate, llk):
pid_log = log.ControlsState.LateralTorqueState.new_message()
- if CS.vEgo < MIN_STEER_SPEED or not active:
+ if not active:
output_torque = 0.0
pid_log.active = False
else:
diff --git a/selfdrive/controls/lib/lateral_mpc_lib/SConscript b/selfdrive/controls/lib/lateral_mpc_lib/SConscript
index df1e2a2a1a..745ed99d10 100644
--- a/selfdrive/controls/lib/lateral_mpc_lib/SConscript
+++ b/selfdrive/controls/lib/lateral_mpc_lib/SConscript
@@ -44,9 +44,10 @@ generated_files = [
] + build_files
acados_dir = '#third_party/acados'
-acados_templates_dir = '#pyextra/acados_template/c_templates_tera'
+acados_templates_dir = '#third_party/acados/acados_template/c_templates_tera'
source_list = ['lat_mpc.py',
+ '#/selfdrive/modeld/constants.py',
f'{acados_dir}/include/acados_c/ocp_nlp_interface.h',
f'{acados_dir}/x86_64/lib/libacados.so',
f'{acados_dir}/larch64/lib/libacados.so',
@@ -70,8 +71,8 @@ lib_solver = lenv.SharedLibrary(f"{gen}/acados_ocp_solver_lat",
LIBS=['m', 'acados', 'hpipm', 'blasfeo', 'qpOASES_e'])
# generate cython stuff
-acados_ocp_solver_pyx = File("#pyextra/acados_template/acados_ocp_solver_pyx.pyx")
-acados_ocp_solver_common = File("#pyextra/acados_template/acados_solver_common.pxd")
+acados_ocp_solver_pyx = File("#third_party/acados/acados_template/acados_ocp_solver_pyx.pyx")
+acados_ocp_solver_common = File("#third_party/acados/acados_template/acados_solver_common.pxd")
libacados_ocp_solver_pxd = File(f'{gen}/acados_solver.pxd')
libacados_ocp_solver_c = File(f'{gen}/acados_ocp_solver_pyx.c')
diff --git a/selfdrive/controls/lib/lateral_mpc_lib/lat_mpc.py b/selfdrive/controls/lib/lateral_mpc_lib/lat_mpc.py
index 9607532ace..ca7b991e69 100755
--- a/selfdrive/controls/lib/lateral_mpc_lib/lat_mpc.py
+++ b/selfdrive/controls/lib/lateral_mpc_lib/lat_mpc.py
@@ -3,12 +3,12 @@ import os
import numpy as np
from casadi import SX, vertcat, sin, cos
-
from common.realtime import sec_since_boot
+# WARNING: imports outside of constants will not trigger a rebuild
from selfdrive.modeld.constants import T_IDXS
if __name__ == '__main__': # generating code
- from pyextra.acados_template import AcadosModel, AcadosOcp, AcadosOcpSolver
+ from third_party.acados.acados_template import AcadosModel, AcadosOcp, AcadosOcpSolver
else:
from selfdrive.controls.lib.lateral_mpc_lib.c_generated_code.acados_ocp_solver_pyx import AcadosOcpSolverCython # pylint: disable=no-name-in-module, import-error
@@ -17,12 +17,12 @@ EXPORT_DIR = os.path.join(LAT_MPC_DIR, "c_generated_code")
JSON_FILE = os.path.join(LAT_MPC_DIR, "acados_ocp_lat.json")
X_DIM = 4
P_DIM = 2
-N = 16
COST_E_DIM = 3
COST_DIM = COST_E_DIM + 2
SPEED_OFFSET = 10.0
MODEL_NAME = 'lat'
ACADOS_SOLVER_TYPE = 'SQP_RTI'
+N = 32
def gen_lat_model():
model = AcadosModel()
@@ -168,14 +168,14 @@ class LateralMpc():
self.solver.constraints_set(0, "lbx", x0_cp)
self.solver.constraints_set(0, "ubx", x0_cp)
self.yref[:,0] = y_pts
- v_ego = p_cp[0]
+ v_ego = p_cp[0, 0]
# rotation_radius = p_cp[1]
self.yref[:,1] = heading_pts * (v_ego + SPEED_OFFSET)
self.yref[:,2] = yaw_rate_pts * (v_ego + SPEED_OFFSET)
for i in range(N):
self.solver.cost_set(i, "yref", self.yref[i])
- self.solver.set(i, "p", p_cp)
- self.solver.set(N, "p", p_cp)
+ self.solver.set(i, "p", p_cp[i])
+ self.solver.set(N, "p", p_cp[N])
self.solver.cost_set(N, "yref", self.yref[N][:COST_E_DIM])
t = sec_since_boot()
diff --git a/selfdrive/controls/lib/lateral_planner.py b/selfdrive/controls/lib/lateral_planner.py
index 932ad49535..7230b5ad14 100644
--- a/selfdrive/controls/lib/lateral_planner.py
+++ b/selfdrive/controls/lib/lateral_planner.py
@@ -16,12 +16,12 @@ CAMERA_OFFSET = 0.04
PATH_COST = 1.0
LATERAL_MOTION_COST = 0.11
LATERAL_ACCEL_COST = 0.0
-LATERAL_JERK_COST = 0.05
+LATERAL_JERK_COST = 0.04
# Extreme steering rate is unpleasant, even
# when it does not cause bad jerk.
# TODO this cost should be lowered when low
# speed lateral control is stable on all cars
-STEERING_RATE_COST = 800.0
+STEERING_RATE_COST = 700.0
class LateralPlanner:
@@ -35,6 +35,7 @@ class LateralPlanner:
self.solution_invalid_cnt = 0
self.path_xyz = np.zeros((TRAJECTORY_SIZE, 3))
+ self.velocity_xyz = np.zeros((TRAJECTORY_SIZE, 3))
self.plan_yaw = np.zeros((TRAJECTORY_SIZE,))
self.plan_yaw_rate = np.zeros((TRAJECTORY_SIZE,))
self.t_idxs = np.arange(TRAJECTORY_SIZE)
@@ -49,7 +50,6 @@ class LateralPlanner:
def update(self, sm):
# clip speed , lateral planning is not possible at 0 speed
- self.v_ego = max(MIN_SPEED, sm['carState'].vEgo)
measured_curvature = sm['controlsState'].curvature
# Parse model predictions
@@ -59,6 +59,10 @@ class LateralPlanner:
self.t_idxs = np.array(md.position.t)
self.plan_yaw = np.array(md.orientation.z)
self.plan_yaw_rate = np.array(md.orientationRate.z)
+ self.velocity_xyz = np.column_stack([md.velocity.x, md.velocity.y, md.velocity.z])
+ car_speed = np.linalg.norm(self.velocity_xyz, axis=1)
+ self.v_plan = np.clip(car_speed, MIN_SPEED, np.inf)
+ self.v_ego = self.v_plan[0]
# Lane change logic
desire_state = md.meta.desireState
@@ -68,21 +72,20 @@ class LateralPlanner:
lane_change_prob = self.l_lane_change_prob + self.r_lane_change_prob
self.DH.update(sm['carState'], sm['carControl'].latActive, lane_change_prob)
- d_path_xyz = self.path_xyz
self.lat_mpc.set_weights(PATH_COST, LATERAL_MOTION_COST,
LATERAL_ACCEL_COST, LATERAL_JERK_COST,
STEERING_RATE_COST)
- y_pts = np.interp(self.v_ego * self.t_idxs[:LAT_MPC_N + 1], np.linalg.norm(d_path_xyz, axis=1), d_path_xyz[:, 1])
- heading_pts = np.interp(self.v_ego * self.t_idxs[:LAT_MPC_N + 1], np.linalg.norm(self.path_xyz, axis=1), self.plan_yaw)
- yaw_rate_pts = np.interp(self.v_ego * self.t_idxs[:LAT_MPC_N + 1], np.linalg.norm(self.path_xyz, axis=1), self.plan_yaw_rate)
+ y_pts = self.path_xyz[:LAT_MPC_N+1, 1]
+ heading_pts = self.plan_yaw[:LAT_MPC_N+1]
+ yaw_rate_pts = self.plan_yaw_rate[:LAT_MPC_N+1]
self.y_pts = y_pts
assert len(y_pts) == LAT_MPC_N + 1
assert len(heading_pts) == LAT_MPC_N + 1
assert len(yaw_rate_pts) == LAT_MPC_N + 1
- lateral_factor = max(0, self.factor1 - (self.factor2 * self.v_ego**2))
- p = np.array([self.v_ego, lateral_factor])
+ lateral_factor = np.clip(self.factor1 - (self.factor2 * self.v_plan**2), 0.0, np.inf)
+ p = np.column_stack([self.v_plan, lateral_factor])
self.lat_mpc.run(self.x0,
p,
y_pts,
diff --git a/selfdrive/controls/lib/longcontrol.py b/selfdrive/controls/lib/longcontrol.py
index 545a4c43ff..e8095813f2 100644
--- a/selfdrive/controls/lib/longcontrol.py
+++ b/selfdrive/controls/lib/longcontrol.py
@@ -30,10 +30,8 @@ def long_control_state_trans(CP, active, long_control_state, v_ego, v_target,
long_control_state = LongCtrlState.off
else:
- if long_control_state == LongCtrlState.off:
+ if long_control_state in (LongCtrlState.off, LongCtrlState.pid):
long_control_state = LongCtrlState.pid
-
- elif long_control_state == LongCtrlState.pid:
if stopping_condition:
long_control_state = LongCtrlState.stopping
diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/SConscript b/selfdrive/controls/lib/longitudinal_mpc_lib/SConscript
index 5a9e69c297..7f5daf157c 100644
--- a/selfdrive/controls/lib/longitudinal_mpc_lib/SConscript
+++ b/selfdrive/controls/lib/longitudinal_mpc_lib/SConscript
@@ -51,9 +51,10 @@ generated_files = [
] + build_files
acados_dir = '#third_party/acados'
-acados_templates_dir = '#pyextra/acados_template/c_templates_tera'
+acados_templates_dir = '#third_party/acados/acados_template/c_templates_tera'
source_list = ['long_mpc.py',
+ '#/selfdrive/modeld/constants.py',
f'{acados_dir}/include/acados_c/ocp_nlp_interface.h',
f'{acados_dir}/x86_64/lib/libacados.so',
f'{acados_dir}/larch64/lib/libacados.so',
@@ -77,8 +78,8 @@ lib_solver = lenv.SharedLibrary(f"{gen}/acados_ocp_solver_long",
LIBS=['m', 'acados', 'hpipm', 'blasfeo', 'qpOASES_e'])
# generate cython stuff
-acados_ocp_solver_pyx = File("#pyextra/acados_template/acados_ocp_solver_pyx.pyx")
-acados_ocp_solver_common = File("#pyextra/acados_template/acados_solver_common.pxd")
+acados_ocp_solver_pyx = File("#third_party/acados/acados_template/acados_ocp_solver_pyx.pyx")
+acados_ocp_solver_common = File("#third_party/acados/acados_template/acados_solver_common.pxd")
libacados_ocp_solver_pxd = File(f'{gen}/acados_solver.pxd')
libacados_ocp_solver_c = File(f'{gen}/acados_ocp_solver_pyx.c')
diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py b/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py
index 79a9ec4f0c..660002691a 100644
--- a/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py
+++ b/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py
@@ -5,11 +5,12 @@ import numpy as np
from common.realtime import sec_since_boot
from common.numpy_fast import clip
from system.swaglog import cloudlog
+# WARNING: imports outside of constants will not trigger a rebuild
from selfdrive.modeld.constants import index_function
from selfdrive.controls.lib.radar_helpers import _LEAD_ACCEL_TAU
if __name__ == '__main__': # generating code
- from pyextra.acados_template import AcadosModel, AcadosOcp, AcadosOcpSolver
+ from third_party.acados.acados_template import AcadosModel, AcadosOcp, AcadosOcpSolver
else:
from selfdrive.controls.lib.longitudinal_mpc_lib.c_generated_code.acados_ocp_solver_pyx import AcadosOcpSolverCython # pylint: disable=no-name-in-module, import-error
@@ -306,7 +307,7 @@ class LongitudinalMpc:
self.cruise_min_a = min_a
self.max_a = max_a
- def update(self, carstate, radarstate, v_cruise, x, v, a, j):
+ def update(self, radarstate, v_cruise, x, v, a, j):
v_ego = self.x0[1]
self.status = radarstate.leadOne.status or radarstate.leadTwo.status
diff --git a/selfdrive/controls/lib/longitudinal_planner.py b/selfdrive/controls/lib/longitudinal_planner.py
index a0f6318323..2ef9051122 100755
--- a/selfdrive/controls/lib/longitudinal_planner.py
+++ b/selfdrive/controls/lib/longitudinal_planner.py
@@ -15,7 +15,6 @@ from selfdrive.controls.lib.drive_helpers import V_CRUISE_MAX, CONTROL_N
from system.swaglog import cloudlog
LON_MPC_STEP = 0.2 # first step is 0.2s
-AWARENESS_DECEL = -0.2 # car smoothly decel at .2m/s^2 when user is distracted
A_CRUISE_MIN = -1.2
A_CRUISE_MAX_VALS = [1.6, 1.2, 0.8, 0.6]
A_CRUISE_MAX_BP = [0., 10.0, 25., 40.]
@@ -111,9 +110,7 @@ class LongitudinalPlanner:
self.v_model_error = sm['modelV2'].temporalPose.trans[0] - v_ego
if force_slow_decel:
- # if required so, force a smooth deceleration
- accel_limits_turns[1] = min(accel_limits_turns[1], AWARENESS_DECEL)
- accel_limits_turns[0] = min(accel_limits_turns[0], accel_limits_turns[1])
+ v_cruise = 0.0
# clip limits, cannot init MPC outside of bounds
accel_limits_turns[0] = min(accel_limits_turns[0], self.a_desired + 0.05)
accel_limits_turns[1] = max(accel_limits_turns[1], self.a_desired - 0.05)
@@ -122,9 +119,10 @@ class LongitudinalPlanner:
self.mpc.set_accel_limits(accel_limits_turns[0], accel_limits_turns[1])
self.mpc.set_cur_state(self.v_desired_filter.x, self.a_desired)
x, v, a, j = self.parse_model(sm['modelV2'], self.v_model_error)
- self.mpc.update(sm['carState'], sm['radarState'], v_cruise, x, v, a, j)
+ self.mpc.update(sm['radarState'], v_cruise, x, v, a, j)
- self.v_desired_trajectory = np.interp(T_IDXS[:CONTROL_N], T_IDXS_MPC, self.mpc.v_solution)
+ self.v_desired_trajectory_full = np.interp(T_IDXS, T_IDXS_MPC, self.mpc.v_solution)
+ self.v_desired_trajectory = self.v_desired_trajectory_full[:CONTROL_N]
self.a_desired_trajectory = np.interp(T_IDXS[:CONTROL_N], T_IDXS_MPC, self.mpc.a_solution)
self.j_desired_trajectory = np.interp(T_IDXS[:CONTROL_N], T_IDXS_MPC[:-1], self.mpc.j_solution)
diff --git a/selfdrive/controls/lib/tests/test_latcontrol.py b/selfdrive/controls/lib/tests/test_latcontrol.py
index f15ab2fa56..993774f719 100755
--- a/selfdrive/controls/lib/tests/test_latcontrol.py
+++ b/selfdrive/controls/lib/tests/test_latcontrol.py
@@ -20,7 +20,7 @@ class TestLatControl(unittest.TestCase):
@parameterized.expand([(HONDA.CIVIC, LatControlPID), (TOYOTA.RAV4, LatControlTorque), (TOYOTA.PRIUS, LatControlINDI), (NISSAN.LEAF, LatControlAngle)])
def test_saturation(self, car_name, controller):
CarInterface, CarController, CarState = interfaces[car_name]
- CP = CarInterface.get_params(car_name)
+ CP = CarInterface.get_non_essential_params(car_name)
CI = CarInterface(CP, CarController, CarState)
VM = VehicleModel(CP)
diff --git a/selfdrive/controls/lib/tests/test_vehicle_model.py b/selfdrive/controls/lib/tests/test_vehicle_model.py
index 3e08cb0aa0..03d97a7e3f 100755
--- a/selfdrive/controls/lib/tests/test_vehicle_model.py
+++ b/selfdrive/controls/lib/tests/test_vehicle_model.py
@@ -12,7 +12,7 @@ from selfdrive.controls.lib.vehicle_model import VehicleModel, dyn_ss_sol, creat
class TestVehicleModel(unittest.TestCase):
def setUp(self):
- CP = CarInterface.get_params(CAR.CIVIC)
+ CP = CarInterface.get_non_essential_params(CAR.CIVIC)
self.VM = VehicleModel(CP)
def test_round_trip_yaw_rate(self):
diff --git a/selfdrive/controls/plannerd.py b/selfdrive/controls/plannerd.py
index 93d0c80dac..543274d841 100755
--- a/selfdrive/controls/plannerd.py
+++ b/selfdrive/controls/plannerd.py
@@ -1,12 +1,28 @@
#!/usr/bin/env python3
+import numpy as np
from cereal import car
from common.params import Params
from common.realtime import Priority, config_realtime_process
from system.swaglog import cloudlog
+from selfdrive.modeld.constants import T_IDXS
from selfdrive.controls.lib.longitudinal_planner import LongitudinalPlanner
from selfdrive.controls.lib.lateral_planner import LateralPlanner
import cereal.messaging as messaging
+def cumtrapz(x, t):
+ return np.concatenate([[0], np.cumsum(((x[0:-1] + x[1:])/2) * np.diff(t))])
+
+def publish_ui_plan(sm, pm, lateral_planner, longitudinal_planner):
+ plan_odo = cumtrapz(longitudinal_planner.v_desired_trajectory_full, T_IDXS)
+ model_odo = cumtrapz(lateral_planner.v_plan, T_IDXS)
+
+ ui_send = messaging.new_message('uiPlan')
+ ui_send.valid = sm.all_checks(service_list=['carState', 'controlsState', 'modelV2'])
+ uiPlan = ui_send.uiPlan
+ uiPlan.position.x = np.interp(plan_odo, model_odo, lateral_planner.lat_mpc.x_sol[:,0]).tolist()
+ uiPlan.position.y = np.interp(plan_odo, model_odo, lateral_planner.lat_mpc.x_sol[:,1]).tolist()
+ uiPlan.position.z = np.interp(plan_odo, model_odo, lateral_planner.path_xyz[:,2]).tolist()
+ pm.send('uiPlan', ui_send)
def plannerd_thread(sm=None, pm=None):
config_realtime_process(5, Priority.CTRL_LOW)
@@ -24,7 +40,7 @@ def plannerd_thread(sm=None, pm=None):
poll=['radarState', 'modelV2'], ignore_avg_freq=['radarState'])
if pm is None:
- pm = messaging.PubMaster(['longitudinalPlan', 'lateralPlan'])
+ pm = messaging.PubMaster(['longitudinalPlan', 'lateralPlan', 'uiPlan'])
while True:
sm.update()
@@ -34,7 +50,7 @@ def plannerd_thread(sm=None, pm=None):
lateral_planner.publish(sm, pm)
longitudinal_planner.update(sm)
longitudinal_planner.publish(sm, pm)
-
+ publish_ui_plan(sm, pm, lateral_planner, longitudinal_planner)
def main(sm=None, pm=None):
plannerd_thread(sm, pm)
diff --git a/selfdrive/controls/radard.py b/selfdrive/controls/radard.py
index 3d958139d6..34f0f274fe 100755
--- a/selfdrive/controls/radard.py
+++ b/selfdrive/controls/radard.py
@@ -8,9 +8,9 @@ from cereal import car
from common.numpy_fast import interp
from common.params import Params
from common.realtime import Ratekeeper, Priority, config_realtime_process
-from selfdrive.controls.lib.cluster.fastcluster_py import cluster_points_centroid
from selfdrive.controls.lib.radar_helpers import Cluster, Track, RADAR_TO_CAMERA
from system.swaglog import cloudlog
+from third_party.cluster.fastcluster_py import cluster_points_centroid
class KalmanParams():
@@ -35,7 +35,7 @@ class KalmanParams():
self.K = [[interp(dt, dts, K0)], [interp(dt, dts, K1)]]
-def laplacian_cdf(x, mu, b):
+def laplacian_pdf(x, mu, b):
b = max(b, 1e-4)
return math.exp(-abs(x-mu)/b)
@@ -45,9 +45,9 @@ def match_vision_to_cluster(v_ego, lead, clusters):
offset_vision_dist = lead.x[0] - RADAR_TO_CAMERA
def prob(c):
- prob_d = laplacian_cdf(c.dRel, offset_vision_dist, lead.xStd[0])
- prob_y = laplacian_cdf(c.yRel, -lead.y[0], lead.yStd[0])
- prob_v = laplacian_cdf(c.vRel + v_ego, lead.v[0], lead.vStd[0])
+ prob_d = laplacian_pdf(c.dRel, offset_vision_dist, lead.xStd[0])
+ prob_y = laplacian_pdf(c.yRel, -lead.y[0], lead.yStd[0])
+ prob_v = laplacian_pdf(c.vRel + v_ego, lead.v[0], lead.vStd[0])
# This is isn't exactly right, but good heuristic
return prob_d * prob_y * prob_v
@@ -165,7 +165,6 @@ class RadarD():
dat.valid = sm.all_checks() and len(rr.errors) == 0
radarState = dat.radarState
radarState.mdMonoTime = sm.logMonoTime['modelV2']
- radarState.canMonoTimes = list(rr.canMonoTimes)
radarState.radarErrors = list(rr.errors)
radarState.carStateMonoTime = sm.logMonoTime['carState']
diff --git a/selfdrive/controls/tests/test_clustering.py b/selfdrive/controls/tests/test_clustering.py
index 290b267029..99c24d5938 100644
--- a/selfdrive/controls/tests/test_clustering.py
+++ b/selfdrive/controls/tests/test_clustering.py
@@ -7,8 +7,8 @@ from fastcluster import linkage_vector
from scipy.cluster import _hierarchy
from scipy.spatial.distance import pdist
-from selfdrive.controls.lib.cluster.fastcluster_py import hclust, ffi
-from selfdrive.controls.lib.cluster.fastcluster_py import cluster_points_centroid
+from third_party.cluster.fastcluster_py import hclust, ffi
+from third_party.cluster.fastcluster_py import cluster_points_centroid
def fcluster(Z, t, criterion='inconsistent', depth=2, R=None, monocrit=None):
diff --git a/selfdrive/controls/tests/test_cruise_speed.py b/selfdrive/controls/tests/test_cruise_speed.py
index cd1d31cf07..b83116af45 100755
--- a/selfdrive/controls/tests/test_cruise_speed.py
+++ b/selfdrive/controls/tests/test_cruise_speed.py
@@ -3,7 +3,7 @@ import numpy as np
from parameterized import parameterized_class
import unittest
-from selfdrive.controls.lib.drive_helpers import VCruiseHelper, V_CRUISE_MIN, V_CRUISE_MAX, V_CRUISE_ENABLE_MIN, IMPERIAL_INCREMENT
+from selfdrive.controls.lib.drive_helpers import VCruiseHelper, V_CRUISE_MIN, V_CRUISE_MAX, V_CRUISE_INITIAL, IMPERIAL_INCREMENT
from cereal import car
from common.conversions import Conversions as CV
from selfdrive.test.longitudinal_maneuvers.maneuver import Maneuver
@@ -53,16 +53,16 @@ class TestVCruiseHelper(unittest.TestCase):
for _ in range(2):
self.v_cruise_helper.update_v_cruise(car.CarState(cruiseState={"available": False}), enabled=False, is_metric=False)
- def enable(self, v_ego):
+ def enable(self, v_ego, experimental_mode):
# Simulates user pressing set with a current speed
- self.v_cruise_helper.initialize_v_cruise(car.CarState(vEgo=v_ego))
+ self.v_cruise_helper.initialize_v_cruise(car.CarState(vEgo=v_ego), experimental_mode)
def test_adjust_speed(self):
"""
Asserts speed changes on falling edges of buttons.
"""
- self.enable(V_CRUISE_ENABLE_MIN * CV.KPH_TO_MS)
+ self.enable(V_CRUISE_INITIAL * CV.KPH_TO_MS, False)
for btn in (ButtonType.accelCruise, ButtonType.decelCruise):
for pressed in (True, False):
@@ -86,7 +86,7 @@ class TestVCruiseHelper(unittest.TestCase):
CS.buttonEvents = [ButtonEvent(type=ButtonType.decelCruise, pressed=pressed)]
self.v_cruise_helper.update_v_cruise(CS, enabled=enabled, is_metric=False)
if pressed:
- self.enable(V_CRUISE_ENABLE_MIN * CV.KPH_TO_MS)
+ self.enable(V_CRUISE_INITIAL * CV.KPH_TO_MS, False)
# Expected diff on enabling. Speed should not change on falling edge of pressed
self.assertEqual(not pressed, self.v_cruise_helper.v_cruise_kph == self.v_cruise_helper.v_cruise_kph_last)
@@ -96,7 +96,7 @@ class TestVCruiseHelper(unittest.TestCase):
Asserts we don't increment set speed if user presses resume/accel to exit cruise standstill.
"""
- self.enable(0)
+ self.enable(0, False)
for standstill in (True, False):
for pressed in (True, False):
@@ -116,7 +116,7 @@ class TestVCruiseHelper(unittest.TestCase):
for v_ego in np.linspace(0, 100, 101):
self.reset_cruise_speed_state()
- self.enable(V_CRUISE_ENABLE_MIN * CV.KPH_TO_MS)
+ self.enable(V_CRUISE_INITIAL * CV.KPH_TO_MS, False)
# first decrement speed, then perform gas pressed logic
expected_v_cruise_kph = self.v_cruise_helper.v_cruise_kph - IMPERIAL_INCREMENT
@@ -137,13 +137,14 @@ class TestVCruiseHelper(unittest.TestCase):
Asserts allowed cruise speeds on enabling with SET.
"""
- for v_ego in np.linspace(0, 100, 101):
- self.reset_cruise_speed_state()
- self.assertFalse(self.v_cruise_helper.v_cruise_initialized)
+ for experimental_mode in (True, False):
+ for v_ego in np.linspace(0, 100, 101):
+ self.reset_cruise_speed_state()
+ self.assertFalse(self.v_cruise_helper.v_cruise_initialized)
- self.enable(float(v_ego))
- self.assertTrue(V_CRUISE_ENABLE_MIN <= self.v_cruise_helper.v_cruise_kph <= V_CRUISE_MAX)
- self.assertTrue(self.v_cruise_helper.v_cruise_initialized)
+ self.enable(float(v_ego), experimental_mode)
+ self.assertTrue(V_CRUISE_INITIAL <= self.v_cruise_helper.v_cruise_kph <= V_CRUISE_MAX)
+ self.assertTrue(self.v_cruise_helper.v_cruise_initialized)
if __name__ == "__main__":
diff --git a/selfdrive/controls/tests/test_lateral_mpc.py b/selfdrive/controls/tests/test_lateral_mpc.py
index df5154b2b4..b569da09b4 100644
--- a/selfdrive/controls/tests/test_lateral_mpc.py
+++ b/selfdrive/controls/tests/test_lateral_mpc.py
@@ -17,7 +17,8 @@ def run_mpc(lat_mpc=None, v_ref=30., x_init=0., y_init=0., psi_init=0., curvatur
curv_rate_pts = np.zeros(LAT_MPC_N + 1)
x0 = np.array([x_init, y_init, psi_init, curvature_init])
- p = np.array([v_ref, CAR_ROTATION_RADIUS])
+ p = np.column_stack([v_ref * np.ones(LAT_MPC_N + 1),
+ CAR_ROTATION_RADIUS * np.ones(LAT_MPC_N + 1)])
# converge in no more than 10 iterations
for _ in range(10):
diff --git a/selfdrive/controls/tests/test_startup.py b/selfdrive/controls/tests/test_startup.py
index ba2d2f5c02..92fc2468bb 100755
--- a/selfdrive/controls/tests/test_startup.py
+++ b/selfdrive/controls/tests/test_startup.py
@@ -72,6 +72,7 @@ class TestStartup(unittest.TestCase):
params.clear_all()
params.put_bool("Passive", False)
params.put_bool("OpenpilotEnabledToggle", True)
+ params.put_bool("ObdMultiplexingDisabled", True)
# Build capnn version of FW array
if fw_versions is not None:
diff --git a/selfdrive/controls/tests/test_state_machine.py b/selfdrive/controls/tests/test_state_machine.py
index 8f263a98e7..d5f468f214 100755
--- a/selfdrive/controls/tests/test_state_machine.py
+++ b/selfdrive/controls/tests/test_state_machine.py
@@ -31,7 +31,7 @@ class TestStateMachine(unittest.TestCase):
def setUp(self):
CarInterface, CarController, CarState = interfaces["mock"]
- CP = CarInterface.get_params("mock")
+ CP = CarInterface.get_non_essential_params("mock")
CI = CarInterface(CP, CarController, CarState)
self.controlsd = Controls(CI=CI)
diff --git a/selfdrive/debug/cycle_alerts.py b/selfdrive/debug/cycle_alerts.py
index b40c8e304c..71c7b34be5 100755
--- a/selfdrive/debug/cycle_alerts.py
+++ b/selfdrive/debug/cycle_alerts.py
@@ -51,7 +51,7 @@ def cycle_alerts(duration=200, is_metric=False):
cameras = ['roadCameraState', 'wideRoadCameraState', 'driverCameraState']
CS = car.CarState.new_message()
- CP = CarInterface.get_params("HONDA CIVIC 2016")
+ CP = CarInterface.get_non_essential_params("HONDA CIVIC 2016")
sm = messaging.SubMaster(['deviceState', 'pandaStates', 'roadCameraState', 'modelV2', 'liveCalibration',
'driverMonitoringState', 'longitudinalPlan', 'lateralPlan', 'liveLocationKalman',
'managerState'] + cameras)
diff --git a/selfdrive/debug/fingerprint_from_route.py b/selfdrive/debug/fingerprint_from_route.py
index 326e68f8e7..b3598b105c 100755
--- a/selfdrive/debug/fingerprint_from_route.py
+++ b/selfdrive/debug/fingerprint_from_route.py
@@ -17,7 +17,7 @@ def get_fingerprint(lr):
for c in msg.can:
# read also msgs sent by EON on CAN bus 0x80 and filter out the
# addr with more than 11 bits
- if c.src % 0x80 == 0 and c.address < 0x800:
+ if c.src % 0x80 == 0 and c.address < 0x800 and c.address not in (0x7df, 0x7e0, 0x7e8):
msgs[c.address] = len(c.dat)
# show CAN fingerprint
diff --git a/selfdrive/debug/get_fingerprint.py b/selfdrive/debug/get_fingerprint.py
index e678db4f17..f7f7a1604f 100755
--- a/selfdrive/debug/get_fingerprint.py
+++ b/selfdrive/debug/get_fingerprint.py
@@ -22,7 +22,7 @@ while True:
for c in lc.can:
# read also msgs sent by EON on CAN bus 0x80 and filter out the
# addr with more than 11 bits
- if c.src in [0, 2] and c.address < 0x800:
+ if c.src % 0x80 == 0 and c.address < 0x800 and c.address not in (0x7df, 0x7e0, 0x7e8):
msgs[c.address] = len(c.dat)
fingerprint = ', '.join("%d: %d" % v for v in sorted(msgs.items()))
diff --git a/selfdrive/debug/hyundai_enable_radar_points.py b/selfdrive/debug/hyundai_enable_radar_points.py
index ac7e7102d0..07ce5ebddb 100755
--- a/selfdrive/debug/hyundai_enable_radar_points.py
+++ b/selfdrive/debug/hyundai_enable_radar_points.py
@@ -52,6 +52,10 @@ SUPPORTED_FW_VERSIONS = {
b'IK__ SCC F-CUP 1.00 1.02 96400-G9100\x18\x07\x06\x17\x12 ': ConfigValues(
default_config=b"\x00\x00\x00\x01\x00\x00",
tracks_enabled=b"\x00\x00\x00\x01\x00\x01"),
+ # 2019 SANTA FE
+ b"TM__ SCC F-CUP 1.00 1.00 99110-S1210\x19\x01%\x168 ": ConfigValues(
+ default_config=b"\x00\x00\x00\x01\x00\x00",
+ tracks_enabled=b"\x00\x00\x00\x01\x00\x01"),
}
if __name__ == "__main__":
diff --git a/selfdrive/debug/internal/fuzz_fw_fingerprint.py b/selfdrive/debug/internal/fuzz_fw_fingerprint.py
index 1ea133cc19..a18390fef3 100755
--- a/selfdrive/debug/internal/fuzz_fw_fingerprint.py
+++ b/selfdrive/debug/internal/fuzz_fw_fingerprint.py
@@ -28,7 +28,7 @@ if __name__ == "__main__":
for candidate, fws in FWS.items():
fw_dict = {}
for (tp, addr, subaddr), fw_list in fws.items():
- fw_dict[(addr, subaddr)] = random.choice(fw_list)
+ fw_dict[(addr, subaddr)] = [random.choice(fw_list)]
matches = match_fw_to_car_fuzzy(fw_dict, log=False, exclude=candidate)
diff --git a/selfdrive/debug/internal/test_paramsd.py b/selfdrive/debug/internal/test_paramsd.py
index 3d8e422c35..81524496f7 100755
--- a/selfdrive/debug/internal/test_paramsd.py
+++ b/selfdrive/debug/internal/test_paramsd.py
@@ -20,7 +20,7 @@ T_SIM = 5 * 60 # s
DT = 0.01
-CP = CarInterface.get_params(CAR.CIVIC)
+CP = CarInterface.get_non_essential_params(CAR.CIVIC)
VM = VehicleModel(CP)
x, y = 0, 0 # m, m
diff --git a/selfdrive/debug/print_docs_diff.py b/selfdrive/debug/print_docs_diff.py
index b804286458..103dd52dd8 100755
--- a/selfdrive/debug/print_docs_diff.py
+++ b/selfdrive/debug/print_docs_diff.py
@@ -9,6 +9,7 @@ from selfdrive.car.docs_definitions import Column
FOOTNOTE_TAG = "{}"
STAR_ICON = ''
+VIDEO_ICON = ''
COLUMNS = "|" + "|".join([column.value for column in Column]) + "|"
COLUMN_HEADER = "|---|---|---|{}|".format("|".join([":---:"] * (len(Column) - 3)))
ARROW_SYMBOL = "➡️"
@@ -39,8 +40,8 @@ def match_cars(base_cars, new_cars):
def build_column_diff(base_car, new_car):
row_builder = []
for column in Column:
- base_column = base_car.get_column(column, STAR_ICON, FOOTNOTE_TAG)
- new_column = new_car.get_column(column, STAR_ICON, FOOTNOTE_TAG)
+ base_column = base_car.get_column(column, STAR_ICON, VIDEO_ICON, FOOTNOTE_TAG)
+ new_column = new_car.get_column(column, STAR_ICON, VIDEO_ICON, FOOTNOTE_TAG)
if base_column != new_column:
row_builder.append(f"{base_column} {ARROW_SYMBOL} {new_column}")
@@ -74,11 +75,11 @@ def print_car_info_diff(path):
# Removals
for car_info in car_removals:
- changes["removals"].append(format_row([car_info.get_column(column, STAR_ICON, FOOTNOTE_TAG) for column in Column]))
+ changes["removals"].append(format_row([car_info.get_column(column, STAR_ICON, VIDEO_ICON, FOOTNOTE_TAG) for column in Column]))
# Additions
for car_info in car_additions:
- changes["additions"].append(format_row([car_info.get_column(column, STAR_ICON, FOOTNOTE_TAG) for column in Column]))
+ changes["additions"].append(format_row([car_info.get_column(column, STAR_ICON, VIDEO_ICON, FOOTNOTE_TAG) for column in Column]))
for new_car, base_car in car_changes:
# Column changes
diff --git a/selfdrive/debug/vw_mqb_config.py b/selfdrive/debug/vw_mqb_config.py
index 8c4dbc55ee..8952405b8e 100755
--- a/selfdrive/debug/vw_mqb_config.py
+++ b/selfdrive/debug/vw_mqb_config.py
@@ -126,6 +126,7 @@ if __name__ == "__main__":
uds_client.security_access(ACCESS_TYPE_LEVEL_1.SEND_KEY, struct.pack("!I", key)) # type: ignore
except (NegativeResponseError, MessageTimeoutError):
print("Security access failed!")
+ print("Open the hood and retry (disables the \"diagnostic firewall\" on newer vehicles)")
quit()
try:
diff --git a/selfdrive/locationd/.gitignore b/selfdrive/locationd/.gitignore
index 5268902785..86a228a6ff 100644
--- a/selfdrive/locationd/.gitignore
+++ b/selfdrive/locationd/.gitignore
@@ -3,3 +3,4 @@ ubloxd_test
params_learner
paramsd
locationd
+test/test_glonass_runner
diff --git a/selfdrive/locationd/SConscript b/selfdrive/locationd/SConscript
index 4b7fba19b6..61a0ed7f42 100644
--- a/selfdrive/locationd/SConscript
+++ b/selfdrive/locationd/SConscript
@@ -7,8 +7,14 @@ if GetOption('kaitai'):
cmd = f"kaitai-struct-compiler --target cpp_stl --outdir {generated} $SOURCES"
env.Command(['generated/ubx.cpp', 'generated/ubx.h'], 'ubx.ksy', cmd)
env.Command(['generated/gps.cpp', 'generated/gps.h'], 'gps.ksy', cmd)
+ glonass = env.Command(['generated/glonass.cpp', 'generated/glonass.h'], 'glonass.ksy', cmd)
-env.Program("ubloxd", ["ubloxd.cc", "ublox_msg.cc", "generated/ubx.cpp", "generated/gps.cpp"], LIBS=loc_libs)
+ # kaitai issue: https://github.com/kaitai-io/kaitai_struct/issues/910
+ patch = env.Command(None, 'glonass_fix.patch', 'git apply $SOURCES')
+ env.Depends(patch, glonass)
+
+glonass_obj = env.Object('generated/glonass.cpp')
+env.Program("ubloxd", ["ubloxd.cc", "ublox_msg.cc", "generated/ubx.cpp", "generated/gps.cpp", glonass_obj], LIBS=loc_libs)
ekf_sym_cc = env.SharedObject("#rednose/helpers/ekf_sym.cc")
locationd_sources = ["locationd.cc", "models/live_kf.cc", ekf_sym_cc]
@@ -20,3 +26,6 @@ lenv.Depends(locationd, libkf)
if File("liblocationd.cc").exists():
liblocationd = lenv.SharedLibrary("liblocationd", ["liblocationd.cc"] + locationd_sources, LIBS=loc_libs + transformations)
lenv.Depends(liblocationd, libkf)
+
+if GetOption('test'):
+ env.Program("test/test_glonass_runner", ['test/test_glonass_runner.cc', 'test/test_glonass_kaitai.cc', glonass_obj], LIBS=[loc_libs])
\ No newline at end of file
diff --git a/selfdrive/locationd/generated/glonass.cpp b/selfdrive/locationd/generated/glonass.cpp
new file mode 100644
index 0000000000..cd0f96ab68
--- /dev/null
+++ b/selfdrive/locationd/generated/glonass.cpp
@@ -0,0 +1,353 @@
+// This is a generated file! Please edit source .ksy file and use kaitai-struct-compiler to rebuild
+
+#include "glonass.h"
+
+glonass_t::glonass_t(kaitai::kstream* p__io, kaitai::kstruct* p__parent, glonass_t* p__root) : kaitai::kstruct(p__io) {
+ m__parent = p__parent;
+ m__root = this;
+
+ try {
+ _read();
+ } catch(...) {
+ _clean_up();
+ throw;
+ }
+}
+
+void glonass_t::_read() {
+ m_idle_chip = m__io->read_bits_int_be(1);
+ m_string_number = m__io->read_bits_int_be(4);
+ //m__io->align_to_byte();
+ switch (string_number()) {
+ case 4: {
+ m_data = new string_4_t(m__io, this, m__root);
+ break;
+ }
+ case 1: {
+ m_data = new string_1_t(m__io, this, m__root);
+ break;
+ }
+ case 3: {
+ m_data = new string_3_t(m__io, this, m__root);
+ break;
+ }
+ case 5: {
+ m_data = new string_5_t(m__io, this, m__root);
+ break;
+ }
+ case 2: {
+ m_data = new string_2_t(m__io, this, m__root);
+ break;
+ }
+ default: {
+ m_data = new string_non_immediate_t(m__io, this, m__root);
+ break;
+ }
+ }
+ m_hamming_code = m__io->read_bits_int_be(8);
+ m_pad_1 = m__io->read_bits_int_be(11);
+ m_superframe_number = m__io->read_bits_int_be(16);
+ m_pad_2 = m__io->read_bits_int_be(8);
+ m_frame_number = m__io->read_bits_int_be(8);
+}
+
+glonass_t::~glonass_t() {
+ _clean_up();
+}
+
+void glonass_t::_clean_up() {
+ if (m_data) {
+ delete m_data; m_data = 0;
+ }
+}
+
+glonass_t::string_4_t::string_4_t(kaitai::kstream* p__io, glonass_t* p__parent, glonass_t* p__root) : kaitai::kstruct(p__io) {
+ m__parent = p__parent;
+ m__root = p__root;
+ f_tau_n = false;
+ f_delta_tau_n = false;
+
+ try {
+ _read();
+ } catch(...) {
+ _clean_up();
+ throw;
+ }
+}
+
+void glonass_t::string_4_t::_read() {
+ m_tau_n_sign = m__io->read_bits_int_be(1);
+ m_tau_n_value = m__io->read_bits_int_be(21);
+ m_delta_tau_n_sign = m__io->read_bits_int_be(1);
+ m_delta_tau_n_value = m__io->read_bits_int_be(4);
+ m_e_n = m__io->read_bits_int_be(5);
+ m_not_used_1 = m__io->read_bits_int_be(14);
+ m_p4 = m__io->read_bits_int_be(1);
+ m_f_t = m__io->read_bits_int_be(4);
+ m_not_used_2 = m__io->read_bits_int_be(3);
+ m_n_t = m__io->read_bits_int_be(11);
+ m_n = m__io->read_bits_int_be(5);
+ m_m = m__io->read_bits_int_be(2);
+}
+
+glonass_t::string_4_t::~string_4_t() {
+ _clean_up();
+}
+
+void glonass_t::string_4_t::_clean_up() {
+}
+
+int32_t glonass_t::string_4_t::tau_n() {
+ if (f_tau_n)
+ return m_tau_n;
+ m_tau_n = ((tau_n_sign()) ? ((tau_n_value() * -1)) : (tau_n_value()));
+ f_tau_n = true;
+ return m_tau_n;
+}
+
+int32_t glonass_t::string_4_t::delta_tau_n() {
+ if (f_delta_tau_n)
+ return m_delta_tau_n;
+ m_delta_tau_n = ((delta_tau_n_sign()) ? ((delta_tau_n_value() * -1)) : (delta_tau_n_value()));
+ f_delta_tau_n = true;
+ return m_delta_tau_n;
+}
+
+glonass_t::string_non_immediate_t::string_non_immediate_t(kaitai::kstream* p__io, glonass_t* p__parent, glonass_t* p__root) : kaitai::kstruct(p__io) {
+ m__parent = p__parent;
+ m__root = p__root;
+
+ try {
+ _read();
+ } catch(...) {
+ _clean_up();
+ throw;
+ }
+}
+
+void glonass_t::string_non_immediate_t::_read() {
+ m_data_1 = m__io->read_bits_int_be(64);
+ m_data_2 = m__io->read_bits_int_be(8);
+}
+
+glonass_t::string_non_immediate_t::~string_non_immediate_t() {
+ _clean_up();
+}
+
+void glonass_t::string_non_immediate_t::_clean_up() {
+}
+
+glonass_t::string_5_t::string_5_t(kaitai::kstream* p__io, glonass_t* p__parent, glonass_t* p__root) : kaitai::kstruct(p__io) {
+ m__parent = p__parent;
+ m__root = p__root;
+
+ try {
+ _read();
+ } catch(...) {
+ _clean_up();
+ throw;
+ }
+}
+
+void glonass_t::string_5_t::_read() {
+ m_n_a = m__io->read_bits_int_be(11);
+ m_tau_c = m__io->read_bits_int_be(32);
+ m_not_used = m__io->read_bits_int_be(1);
+ m_n_4 = m__io->read_bits_int_be(5);
+ m_tau_gps = m__io->read_bits_int_be(22);
+ m_l_n = m__io->read_bits_int_be(1);
+}
+
+glonass_t::string_5_t::~string_5_t() {
+ _clean_up();
+}
+
+void glonass_t::string_5_t::_clean_up() {
+}
+
+glonass_t::string_1_t::string_1_t(kaitai::kstream* p__io, glonass_t* p__parent, glonass_t* p__root) : kaitai::kstruct(p__io) {
+ m__parent = p__parent;
+ m__root = p__root;
+ f_x_vel = false;
+ f_x_accel = false;
+ f_x = false;
+
+ try {
+ _read();
+ } catch(...) {
+ _clean_up();
+ throw;
+ }
+}
+
+void glonass_t::string_1_t::_read() {
+ m_not_used = m__io->read_bits_int_be(2);
+ m_p1 = m__io->read_bits_int_be(2);
+ m_t_k = m__io->read_bits_int_be(12);
+ m_x_vel_sign = m__io->read_bits_int_be(1);
+ m_x_vel_value = m__io->read_bits_int_be(23);
+ m_x_accel_sign = m__io->read_bits_int_be(1);
+ m_x_accel_value = m__io->read_bits_int_be(4);
+ m_x_sign = m__io->read_bits_int_be(1);
+ m_x_value = m__io->read_bits_int_be(26);
+}
+
+glonass_t::string_1_t::~string_1_t() {
+ _clean_up();
+}
+
+void glonass_t::string_1_t::_clean_up() {
+}
+
+int32_t glonass_t::string_1_t::x_vel() {
+ if (f_x_vel)
+ return m_x_vel;
+ m_x_vel = ((x_vel_sign()) ? ((x_vel_value() * -1)) : (x_vel_value()));
+ f_x_vel = true;
+ return m_x_vel;
+}
+
+int32_t glonass_t::string_1_t::x_accel() {
+ if (f_x_accel)
+ return m_x_accel;
+ m_x_accel = ((x_accel_sign()) ? ((x_accel_value() * -1)) : (x_accel_value()));
+ f_x_accel = true;
+ return m_x_accel;
+}
+
+int32_t glonass_t::string_1_t::x() {
+ if (f_x)
+ return m_x;
+ m_x = ((x_sign()) ? ((x_value() * -1)) : (x_value()));
+ f_x = true;
+ return m_x;
+}
+
+glonass_t::string_2_t::string_2_t(kaitai::kstream* p__io, glonass_t* p__parent, glonass_t* p__root) : kaitai::kstruct(p__io) {
+ m__parent = p__parent;
+ m__root = p__root;
+ f_y_vel = false;
+ f_y_accel = false;
+ f_y = false;
+
+ try {
+ _read();
+ } catch(...) {
+ _clean_up();
+ throw;
+ }
+}
+
+void glonass_t::string_2_t::_read() {
+ m_b_n = m__io->read_bits_int_be(3);
+ m_p2 = m__io->read_bits_int_be(1);
+ m_t_b = m__io->read_bits_int_be(7);
+ m_not_used = m__io->read_bits_int_be(5);
+ m_y_vel_sign = m__io->read_bits_int_be(1);
+ m_y_vel_value = m__io->read_bits_int_be(23);
+ m_y_accel_sign = m__io->read_bits_int_be(1);
+ m_y_accel_value = m__io->read_bits_int_be(4);
+ m_y_sign = m__io->read_bits_int_be(1);
+ m_y_value = m__io->read_bits_int_be(26);
+}
+
+glonass_t::string_2_t::~string_2_t() {
+ _clean_up();
+}
+
+void glonass_t::string_2_t::_clean_up() {
+}
+
+int32_t glonass_t::string_2_t::y_vel() {
+ if (f_y_vel)
+ return m_y_vel;
+ m_y_vel = ((y_vel_sign()) ? ((y_vel_value() * -1)) : (y_vel_value()));
+ f_y_vel = true;
+ return m_y_vel;
+}
+
+int32_t glonass_t::string_2_t::y_accel() {
+ if (f_y_accel)
+ return m_y_accel;
+ m_y_accel = ((y_accel_sign()) ? ((y_accel_value() * -1)) : (y_accel_value()));
+ f_y_accel = true;
+ return m_y_accel;
+}
+
+int32_t glonass_t::string_2_t::y() {
+ if (f_y)
+ return m_y;
+ m_y = ((y_sign()) ? ((y_value() * -1)) : (y_value()));
+ f_y = true;
+ return m_y;
+}
+
+glonass_t::string_3_t::string_3_t(kaitai::kstream* p__io, glonass_t* p__parent, glonass_t* p__root) : kaitai::kstruct(p__io) {
+ m__parent = p__parent;
+ m__root = p__root;
+ f_gamma_n = false;
+ f_z_vel = false;
+ f_z_accel = false;
+ f_z = false;
+
+ try {
+ _read();
+ } catch(...) {
+ _clean_up();
+ throw;
+ }
+}
+
+void glonass_t::string_3_t::_read() {
+ m_p3 = m__io->read_bits_int_be(1);
+ m_gamma_n_sign = m__io->read_bits_int_be(1);
+ m_gamma_n_value = m__io->read_bits_int_be(10);
+ m_not_used = m__io->read_bits_int_be(1);
+ m_p = m__io->read_bits_int_be(2);
+ m_l_n = m__io->read_bits_int_be(1);
+ m_z_vel_sign = m__io->read_bits_int_be(1);
+ m_z_vel_value = m__io->read_bits_int_be(23);
+ m_z_accel_sign = m__io->read_bits_int_be(1);
+ m_z_accel_value = m__io->read_bits_int_be(4);
+ m_z_sign = m__io->read_bits_int_be(1);
+ m_z_value = m__io->read_bits_int_be(26);
+}
+
+glonass_t::string_3_t::~string_3_t() {
+ _clean_up();
+}
+
+void glonass_t::string_3_t::_clean_up() {
+}
+
+int32_t glonass_t::string_3_t::gamma_n() {
+ if (f_gamma_n)
+ return m_gamma_n;
+ m_gamma_n = ((gamma_n_sign()) ? ((gamma_n_value() * -1)) : (gamma_n_value()));
+ f_gamma_n = true;
+ return m_gamma_n;
+}
+
+int32_t glonass_t::string_3_t::z_vel() {
+ if (f_z_vel)
+ return m_z_vel;
+ m_z_vel = ((z_vel_sign()) ? ((z_vel_value() * -1)) : (z_vel_value()));
+ f_z_vel = true;
+ return m_z_vel;
+}
+
+int32_t glonass_t::string_3_t::z_accel() {
+ if (f_z_accel)
+ return m_z_accel;
+ m_z_accel = ((z_accel_sign()) ? ((z_accel_value() * -1)) : (z_accel_value()));
+ f_z_accel = true;
+ return m_z_accel;
+}
+
+int32_t glonass_t::string_3_t::z() {
+ if (f_z)
+ return m_z;
+ m_z = ((z_sign()) ? ((z_value() * -1)) : (z_value()));
+ f_z = true;
+ return m_z;
+}
diff --git a/selfdrive/locationd/generated/glonass.h b/selfdrive/locationd/generated/glonass.h
new file mode 100644
index 0000000000..19867ba22b
--- /dev/null
+++ b/selfdrive/locationd/generated/glonass.h
@@ -0,0 +1,375 @@
+#ifndef GLONASS_H_
+#define GLONASS_H_
+
+// This is a generated file! Please edit source .ksy file and use kaitai-struct-compiler to rebuild
+
+#include "kaitai/kaitaistruct.h"
+#include
+
+#if KAITAI_STRUCT_VERSION < 9000L
+#error "Incompatible Kaitai Struct C++/STL API: version 0.9 or later is required"
+#endif
+
+class glonass_t : public kaitai::kstruct {
+
+public:
+ class string_4_t;
+ class string_non_immediate_t;
+ class string_5_t;
+ class string_1_t;
+ class string_2_t;
+ class string_3_t;
+
+ glonass_t(kaitai::kstream* p__io, kaitai::kstruct* p__parent = 0, glonass_t* p__root = 0);
+
+private:
+ void _read();
+ void _clean_up();
+
+public:
+ ~glonass_t();
+
+ class string_4_t : public kaitai::kstruct {
+
+ public:
+
+ string_4_t(kaitai::kstream* p__io, glonass_t* p__parent = 0, glonass_t* p__root = 0);
+
+ private:
+ void _read();
+ void _clean_up();
+
+ public:
+ ~string_4_t();
+
+ private:
+ bool f_tau_n;
+ int32_t m_tau_n;
+
+ public:
+ int32_t tau_n();
+
+ private:
+ bool f_delta_tau_n;
+ int32_t m_delta_tau_n;
+
+ public:
+ int32_t delta_tau_n();
+
+ private:
+ bool m_tau_n_sign;
+ uint64_t m_tau_n_value;
+ bool m_delta_tau_n_sign;
+ uint64_t m_delta_tau_n_value;
+ uint64_t m_e_n;
+ uint64_t m_not_used_1;
+ bool m_p4;
+ uint64_t m_f_t;
+ uint64_t m_not_used_2;
+ uint64_t m_n_t;
+ uint64_t m_n;
+ uint64_t m_m;
+ glonass_t* m__root;
+ glonass_t* m__parent;
+
+ public:
+ bool tau_n_sign() const { return m_tau_n_sign; }
+ uint64_t tau_n_value() const { return m_tau_n_value; }
+ bool delta_tau_n_sign() const { return m_delta_tau_n_sign; }
+ uint64_t delta_tau_n_value() const { return m_delta_tau_n_value; }
+ uint64_t e_n() const { return m_e_n; }
+ uint64_t not_used_1() const { return m_not_used_1; }
+ bool p4() const { return m_p4; }
+ uint64_t f_t() const { return m_f_t; }
+ uint64_t not_used_2() const { return m_not_used_2; }
+ uint64_t n_t() const { return m_n_t; }
+ uint64_t n() const { return m_n; }
+ uint64_t m() const { return m_m; }
+ glonass_t* _root() const { return m__root; }
+ glonass_t* _parent() const { return m__parent; }
+ };
+
+ class string_non_immediate_t : public kaitai::kstruct {
+
+ public:
+
+ string_non_immediate_t(kaitai::kstream* p__io, glonass_t* p__parent = 0, glonass_t* p__root = 0);
+
+ private:
+ void _read();
+ void _clean_up();
+
+ public:
+ ~string_non_immediate_t();
+
+ private:
+ uint64_t m_data_1;
+ uint64_t m_data_2;
+ glonass_t* m__root;
+ glonass_t* m__parent;
+
+ public:
+ uint64_t data_1() const { return m_data_1; }
+ uint64_t data_2() const { return m_data_2; }
+ glonass_t* _root() const { return m__root; }
+ glonass_t* _parent() const { return m__parent; }
+ };
+
+ class string_5_t : public kaitai::kstruct {
+
+ public:
+
+ string_5_t(kaitai::kstream* p__io, glonass_t* p__parent = 0, glonass_t* p__root = 0);
+
+ private:
+ void _read();
+ void _clean_up();
+
+ public:
+ ~string_5_t();
+
+ private:
+ uint64_t m_n_a;
+ uint64_t m_tau_c;
+ bool m_not_used;
+ uint64_t m_n_4;
+ uint64_t m_tau_gps;
+ bool m_l_n;
+ glonass_t* m__root;
+ glonass_t* m__parent;
+
+ public:
+ uint64_t n_a() const { return m_n_a; }
+ uint64_t tau_c() const { return m_tau_c; }
+ bool not_used() const { return m_not_used; }
+ uint64_t n_4() const { return m_n_4; }
+ uint64_t tau_gps() const { return m_tau_gps; }
+ bool l_n() const { return m_l_n; }
+ glonass_t* _root() const { return m__root; }
+ glonass_t* _parent() const { return m__parent; }
+ };
+
+ class string_1_t : public kaitai::kstruct {
+
+ public:
+
+ string_1_t(kaitai::kstream* p__io, glonass_t* p__parent = 0, glonass_t* p__root = 0);
+
+ private:
+ void _read();
+ void _clean_up();
+
+ public:
+ ~string_1_t();
+
+ private:
+ bool f_x_vel;
+ int32_t m_x_vel;
+
+ public:
+ int32_t x_vel();
+
+ private:
+ bool f_x_accel;
+ int32_t m_x_accel;
+
+ public:
+ int32_t x_accel();
+
+ private:
+ bool f_x;
+ int32_t m_x;
+
+ public:
+ int32_t x();
+
+ private:
+ uint64_t m_not_used;
+ uint64_t m_p1;
+ uint64_t m_t_k;
+ bool m_x_vel_sign;
+ uint64_t m_x_vel_value;
+ bool m_x_accel_sign;
+ uint64_t m_x_accel_value;
+ bool m_x_sign;
+ uint64_t m_x_value;
+ glonass_t* m__root;
+ glonass_t* m__parent;
+
+ public:
+ uint64_t not_used() const { return m_not_used; }
+ uint64_t p1() const { return m_p1; }
+ uint64_t t_k() const { return m_t_k; }
+ bool x_vel_sign() const { return m_x_vel_sign; }
+ uint64_t x_vel_value() const { return m_x_vel_value; }
+ bool x_accel_sign() const { return m_x_accel_sign; }
+ uint64_t x_accel_value() const { return m_x_accel_value; }
+ bool x_sign() const { return m_x_sign; }
+ uint64_t x_value() const { return m_x_value; }
+ glonass_t* _root() const { return m__root; }
+ glonass_t* _parent() const { return m__parent; }
+ };
+
+ class string_2_t : public kaitai::kstruct {
+
+ public:
+
+ string_2_t(kaitai::kstream* p__io, glonass_t* p__parent = 0, glonass_t* p__root = 0);
+
+ private:
+ void _read();
+ void _clean_up();
+
+ public:
+ ~string_2_t();
+
+ private:
+ bool f_y_vel;
+ int32_t m_y_vel;
+
+ public:
+ int32_t y_vel();
+
+ private:
+ bool f_y_accel;
+ int32_t m_y_accel;
+
+ public:
+ int32_t y_accel();
+
+ private:
+ bool f_y;
+ int32_t m_y;
+
+ public:
+ int32_t y();
+
+ private:
+ uint64_t m_b_n;
+ bool m_p2;
+ uint64_t m_t_b;
+ uint64_t m_not_used;
+ bool m_y_vel_sign;
+ uint64_t m_y_vel_value;
+ bool m_y_accel_sign;
+ uint64_t m_y_accel_value;
+ bool m_y_sign;
+ uint64_t m_y_value;
+ glonass_t* m__root;
+ glonass_t* m__parent;
+
+ public:
+ uint64_t b_n() const { return m_b_n; }
+ bool p2() const { return m_p2; }
+ uint64_t t_b() const { return m_t_b; }
+ uint64_t not_used() const { return m_not_used; }
+ bool y_vel_sign() const { return m_y_vel_sign; }
+ uint64_t y_vel_value() const { return m_y_vel_value; }
+ bool y_accel_sign() const { return m_y_accel_sign; }
+ uint64_t y_accel_value() const { return m_y_accel_value; }
+ bool y_sign() const { return m_y_sign; }
+ uint64_t y_value() const { return m_y_value; }
+ glonass_t* _root() const { return m__root; }
+ glonass_t* _parent() const { return m__parent; }
+ };
+
+ class string_3_t : public kaitai::kstruct {
+
+ public:
+
+ string_3_t(kaitai::kstream* p__io, glonass_t* p__parent = 0, glonass_t* p__root = 0);
+
+ private:
+ void _read();
+ void _clean_up();
+
+ public:
+ ~string_3_t();
+
+ private:
+ bool f_gamma_n;
+ int32_t m_gamma_n;
+
+ public:
+ int32_t gamma_n();
+
+ private:
+ bool f_z_vel;
+ int32_t m_z_vel;
+
+ public:
+ int32_t z_vel();
+
+ private:
+ bool f_z_accel;
+ int32_t m_z_accel;
+
+ public:
+ int32_t z_accel();
+
+ private:
+ bool f_z;
+ int32_t m_z;
+
+ public:
+ int32_t z();
+
+ private:
+ bool m_p3;
+ bool m_gamma_n_sign;
+ uint64_t m_gamma_n_value;
+ bool m_not_used;
+ uint64_t m_p;
+ bool m_l_n;
+ bool m_z_vel_sign;
+ uint64_t m_z_vel_value;
+ bool m_z_accel_sign;
+ uint64_t m_z_accel_value;
+ bool m_z_sign;
+ uint64_t m_z_value;
+ glonass_t* m__root;
+ glonass_t* m__parent;
+
+ public:
+ bool p3() const { return m_p3; }
+ bool gamma_n_sign() const { return m_gamma_n_sign; }
+ uint64_t gamma_n_value() const { return m_gamma_n_value; }
+ bool not_used() const { return m_not_used; }
+ uint64_t p() const { return m_p; }
+ bool l_n() const { return m_l_n; }
+ bool z_vel_sign() const { return m_z_vel_sign; }
+ uint64_t z_vel_value() const { return m_z_vel_value; }
+ bool z_accel_sign() const { return m_z_accel_sign; }
+ uint64_t z_accel_value() const { return m_z_accel_value; }
+ bool z_sign() const { return m_z_sign; }
+ uint64_t z_value() const { return m_z_value; }
+ glonass_t* _root() const { return m__root; }
+ glonass_t* _parent() const { return m__parent; }
+ };
+
+private:
+ bool m_idle_chip;
+ uint64_t m_string_number;
+ kaitai::kstruct* m_data;
+ uint64_t m_hamming_code;
+ uint64_t m_pad_1;
+ uint64_t m_superframe_number;
+ uint64_t m_pad_2;
+ uint64_t m_frame_number;
+ glonass_t* m__root;
+ kaitai::kstruct* m__parent;
+
+public:
+ bool idle_chip() const { return m_idle_chip; }
+ uint64_t string_number() const { return m_string_number; }
+ kaitai::kstruct* data() const { return m_data; }
+ uint64_t hamming_code() const { return m_hamming_code; }
+ uint64_t pad_1() const { return m_pad_1; }
+ uint64_t superframe_number() const { return m_superframe_number; }
+ uint64_t pad_2() const { return m_pad_2; }
+ uint64_t frame_number() const { return m_frame_number; }
+ glonass_t* _root() const { return m__root; }
+ kaitai::kstruct* _parent() const { return m__parent; }
+};
+
+#endif // GLONASS_H_
diff --git a/selfdrive/locationd/generated/gps.cpp b/selfdrive/locationd/generated/gps.cpp
index 9b020735bb..8e1cb85b95 100644
--- a/selfdrive/locationd/generated/gps.cpp
+++ b/selfdrive/locationd/generated/gps.cpp
@@ -274,9 +274,9 @@ gps_t::tlm_t::tlm_t(kaitai::kstream* p__io, gps_t* p__parent, gps_t* p__root) :
}
void gps_t::tlm_t::_read() {
- m_magic = m__io->read_bytes(1);
- if (!(magic() == std::string("\x8B", 1))) {
- throw kaitai::validation_not_equal_error(std::string("\x8B", 1), magic(), _io(), std::string("/types/tlm/seq/0"));
+ m_preamble = m__io->read_bytes(1);
+ if (!(preamble() == std::string("\x8B", 1))) {
+ throw kaitai::validation_not_equal_error(std::string("\x8B", 1), preamble(), _io(), std::string("/types/tlm/seq/0"));
}
m_tlm = m__io->read_bits_int_be(14);
m_integrity_status = m__io->read_bits_int_be(1);
diff --git a/selfdrive/locationd/generated/gps.h b/selfdrive/locationd/generated/gps.h
index 293e2e4a05..9dfc5031f5 100644
--- a/selfdrive/locationd/generated/gps.h
+++ b/selfdrive/locationd/generated/gps.h
@@ -273,7 +273,7 @@ public:
~tlm_t();
private:
- std::string m_magic;
+ std::string m_preamble;
uint64_t m_tlm;
bool m_integrity_status;
bool m_reserved;
@@ -281,7 +281,7 @@ public:
gps_t* m__parent;
public:
- std::string magic() const { return m_magic; }
+ std::string preamble() const { return m_preamble; }
uint64_t tlm() const { return m_tlm; }
bool integrity_status() const { return m_integrity_status; }
bool reserved() const { return m_reserved; }
diff --git a/selfdrive/locationd/generated/ubx.cpp b/selfdrive/locationd/generated/ubx.cpp
index 5e743e1ee7..34fe1e52ca 100644
--- a/selfdrive/locationd/generated/ubx.cpp
+++ b/selfdrive/locationd/generated/ubx.cpp
@@ -89,13 +89,10 @@ void ubx_t::rxm_rawx_t::_read() {
m_num_meas = m__io->read_u1();
m_rec_stat = m__io->read_u1();
m_reserved1 = m__io->read_bytes(3);
- int l_measurements = num_meas();
m__raw_measurements = new std::vector();
- m__raw_measurements->reserve(l_measurements);
m__io__raw_measurements = new std::vector();
- m__io__raw_measurements->reserve(l_measurements);
m_measurements = new std::vector();
- m_measurements->reserve(l_measurements);
+ const int l_measurements = num_meas();
for (int i = 0; i < l_measurements; i++) {
m__raw_measurements->push_back(m__io->read_bytes(32));
kaitai::kstream* io__raw_measurements = new kaitai::kstream(m__raw_measurements->at(m__raw_measurements->size() - 1));
@@ -184,9 +181,8 @@ void ubx_t::rxm_sfrbx_t::_read() {
m_reserved2 = m__io->read_bytes(1);
m_version = m__io->read_u1();
m_reserved3 = m__io->read_bytes(1);
- int l_body = num_words();
m_body = new std::vector();
- m_body->reserve(l_body);
+ const int l_body = num_words();
for (int i = 0; i < l_body; i++) {
m_body->push_back(m__io->read_u4le());
}
diff --git a/selfdrive/locationd/glonass.ksy b/selfdrive/locationd/glonass.ksy
new file mode 100644
index 0000000000..be99f6e497
--- /dev/null
+++ b/selfdrive/locationd/glonass.ksy
@@ -0,0 +1,176 @@
+# http://gauss.gge.unb.ca/GLONASS.ICD.pdf
+# some variables are misprinted but good in the old doc
+# https://www.unavco.org/help/glossary/docs/ICD_GLONASS_4.0_(1998)_en.pdf
+meta:
+ id: glonass
+ endian: be
+ bit-endian: be
+seq:
+ - id: idle_chip
+ type: b1
+ - id: string_number
+ type: b4
+ - id: data
+ type:
+ switch-on: string_number
+ cases:
+ 1: string_1
+ 2: string_2
+ 3: string_3
+ 4: string_4
+ 5: string_5
+ _: string_non_immediate
+ - id: hamming_code
+ type: b8
+ - id: pad_1
+ type: b11
+ - id: superframe_number
+ type: b16
+ - id: pad_2
+ type: b8
+ - id: frame_number
+ type: b8
+
+types:
+ string_1:
+ seq:
+ - id: not_used
+ type: b2
+ - id: p1
+ type: b2
+ - id: t_k
+ type: b12
+ - id: x_vel_sign
+ type: b1
+ - id: x_vel_value
+ type: b23
+ - id: x_accel_sign
+ type: b1
+ - id: x_accel_value
+ type: b4
+ - id: x_sign
+ type: b1
+ - id: x_value
+ type: b26
+ instances:
+ x_vel:
+ value: 'x_vel_sign ? (x_vel_value * (-1)) : x_vel_value'
+ x_accel:
+ value: 'x_accel_sign ? (x_accel_value * (-1)) : x_accel_value'
+ x:
+ value: 'x_sign ? (x_value * (-1)) : x_value'
+ string_2:
+ seq:
+ - id: b_n
+ type: b3
+ - id: p2
+ type: b1
+ - id: t_b
+ type: b7
+ - id: not_used
+ type: b5
+ - id: y_vel_sign
+ type: b1
+ - id: y_vel_value
+ type: b23
+ - id: y_accel_sign
+ type: b1
+ - id: y_accel_value
+ type: b4
+ - id: y_sign
+ type: b1
+ - id: y_value
+ type: b26
+ instances:
+ y_vel:
+ value: 'y_vel_sign ? (y_vel_value * (-1)) : y_vel_value'
+ y_accel:
+ value: 'y_accel_sign ? (y_accel_value * (-1)) : y_accel_value'
+ y:
+ value: 'y_sign ? (y_value * (-1)) : y_value'
+ string_3:
+ seq:
+ - id: p3
+ type: b1
+ - id: gamma_n_sign
+ type: b1
+ - id: gamma_n_value
+ type: b10
+ - id: not_used
+ type: b1
+ - id: p
+ type: b2
+ - id: l_n
+ type: b1
+ - id: z_vel_sign
+ type: b1
+ - id: z_vel_value
+ type: b23
+ - id: z_accel_sign
+ type: b1
+ - id: z_accel_value
+ type: b4
+ - id: z_sign
+ type: b1
+ - id: z_value
+ type: b26
+ instances:
+ gamma_n:
+ value: 'gamma_n_sign ? (gamma_n_value * (-1)) : gamma_n_value'
+ z_vel:
+ value: 'z_vel_sign ? (z_vel_value * (-1)) : z_vel_value'
+ z_accel:
+ value: 'z_accel_sign ? (z_accel_value * (-1)) : z_accel_value'
+ z:
+ value: 'z_sign ? (z_value * (-1)) : z_value'
+ string_4:
+ seq:
+ - id: tau_n_sign
+ type: b1
+ - id: tau_n_value
+ type: b21
+ - id: delta_tau_n_sign
+ type: b1
+ - id: delta_tau_n_value
+ type: b4
+ - id: e_n
+ type: b5
+ - id: not_used_1
+ type: b14
+ - id: p4
+ type: b1
+ - id: f_t
+ type: b4
+ - id: not_used_2
+ type: b3
+ - id: n_t
+ type: b11
+ - id: n
+ type: b5
+ - id: m
+ type: b2
+ instances:
+ tau_n:
+ value: 'tau_n_sign ? (tau_n_value * (-1)) : tau_n_value'
+ delta_tau_n:
+ value: 'delta_tau_n_sign ? (delta_tau_n_value * (-1)) : delta_tau_n_value'
+ string_5:
+ seq:
+ - id: n_a
+ type: b11
+ - id: tau_c
+ type: b32
+ - id: not_used
+ type: b1
+ - id: n_4
+ type: b5
+ - id: tau_gps
+ type: b22
+ - id: l_n
+ type: b1
+ string_non_immediate:
+ seq:
+ - id: data_1
+ type: b64
+ - id: data_2
+ type: b8
diff --git a/selfdrive/locationd/glonass_fix.patch b/selfdrive/locationd/glonass_fix.patch
new file mode 100644
index 0000000000..fa34a8ef15
--- /dev/null
+++ b/selfdrive/locationd/glonass_fix.patch
@@ -0,0 +1,13 @@
+diff --git a/selfdrive/locationd/generated/glonass.cpp b/selfdrive/locationd/generated/glonass.cpp
+index 5b17bc327..b5c6aa610 100644
+--- a/selfdrive/locationd/generated/glonass.cpp
++++ b/selfdrive/locationd/generated/glonass.cpp
+@@ -17,7 +17,7 @@ glonass_t::glonass_t(kaitai::kstream* p__io, kaitai::kstruct* p__parent, glonass
+ void glonass_t::_read() {
+ m_idle_chip = m__io->read_bits_int_be(1);
+ m_string_number = m__io->read_bits_int_be(4);
+- m__io->align_to_byte();
++ //m__io->align_to_byte();
+ switch (string_number()) {
+ case 4: {
+ m_data = new string_4_t(m__io, this, m__root);
diff --git a/selfdrive/locationd/gps.ksy b/selfdrive/locationd/gps.ksy
index 6f5cde316b..893ad1b25b 100644
--- a/selfdrive/locationd/gps.ksy
+++ b/selfdrive/locationd/gps.ksy
@@ -19,7 +19,7 @@ seq:
types:
tlm:
seq:
- - id: magic
+ - id: preamble
contents: [0x8b]
- id: tlm
type: b14
diff --git a/selfdrive/locationd/laikad.py b/selfdrive/locationd/laikad.py
index 6936d88acc..10c5e1b7e5 100755
--- a/selfdrive/locationd/laikad.py
+++ b/selfdrive/locationd/laikad.py
@@ -3,6 +3,7 @@ import json
import math
import os
import time
+import shutil
from collections import defaultdict
from concurrent.futures import Future, ProcessPoolExecutor
from datetime import datetime
@@ -16,30 +17,30 @@ from common.params import Params, put_nonblocking
from laika import AstroDog
from laika.constants import SECS_IN_HR, SECS_IN_MIN
from laika.downloader import DownloadFailed
-from laika.ephemeris import Ephemeris, EphemerisType, convert_ublox_ephem, parse_qcom_ephem
+from laika.ephemeris import Ephemeris, EphemerisType, convert_ublox_gps_ephem, convert_ublox_glonass_ephem, parse_qcom_ephem
from laika.gps_time import GPSTime
from laika.helpers import ConstellationId
from laika.raw_gnss import GNSSMeasurement, correct_measurements, process_measurements, read_raw_ublox, read_raw_qcom
-from selfdrive.locationd.laikad_helpers import calc_pos_fix_gauss_newton, get_posfix_sympy_fun
+from laika.opt import calc_pos_fix, get_posfix_sympy_fun, calc_vel_fix, get_velfix_sympy_func
from selfdrive.locationd.models.constants import GENERATED_DIR, ObservationKind
from selfdrive.locationd.models.gnss_kf import GNSSKalman
from selfdrive.locationd.models.gnss_kf import States as GStates
from system.swaglog import cloudlog
MAX_TIME_GAP = 10
-EPHEMERIS_CACHE = 'LaikadEphemeris'
+EPHEMERIS_CACHE = 'LaikadEphemerisV2'
DOWNLOADS_CACHE_FOLDER = "/tmp/comma_download_cache/"
-CACHE_VERSION = 0.1
+CACHE_VERSION = 0.2
POS_FIX_RESIDUAL_THRESHOLD = 100.0
class Laikad:
- def __init__(self, valid_const=("GPS", "GLONASS"), auto_fetch_orbits=True, auto_update=False,
- valid_ephem_types=(EphemerisType.ULTRA_RAPID_ORBIT, EphemerisType.NAV),
+ def __init__(self, valid_const=("GPS", "GLONASS"), auto_fetch_navs=True, auto_update=False,
+ valid_ephem_types=(EphemerisType.NAV,),
save_ephemeris=False, use_qcom=False):
"""
valid_const: GNSS constellation which can be used
- auto_fetch_orbits: If true fetch orbits from internet when needed
+ auto_fetch_navs: If true fetch navs from internet when needed
auto_update: If true download AstroDog will download all files needed. This can be ephemeris or correction data like ionosphere.
valid_ephem_types: Valid ephemeris types to be used by AstroDog
save_ephemeris: If true saves and loads nav and orbit ephemeris to cache.
@@ -47,20 +48,20 @@ class Laikad:
self.astro_dog = AstroDog(valid_const=valid_const, auto_update=auto_update, valid_ephem_types=valid_ephem_types, clear_old_ephemeris=True, cache_dir=DOWNLOADS_CACHE_FOLDER)
self.gnss_kf = GNSSKalman(GENERATED_DIR, cython=True, erratic_clock=use_qcom)
- self.auto_fetch_orbits = auto_fetch_orbits
+ self.auto_fetch_navs = auto_fetch_navs
self.orbit_fetch_executor: Optional[ProcessPoolExecutor] = None
self.orbit_fetch_future: Optional[Future] = None
- self.last_fetch_orbits_t = None
+ self.last_fetch_navs_t = None
self.got_first_gnss_msg = False
self.last_cached_t = None
self.save_ephemeris = save_ephemeris
self.load_cache()
self.posfix_functions = {constellation: get_posfix_sympy_fun(constellation) for constellation in (ConstellationId.GPS, ConstellationId.GLONASS)}
- self.last_pos_fix = []
- self.last_pos_residual = []
- self.last_pos_fix_t = None
+ self.velfix_function = get_velfix_sympy_func()
+ self.last_fix_pos = None
+ self.last_fix_t = None
self.gps_week = None
self.use_qcom = use_qcom
@@ -74,38 +75,48 @@ class Laikad:
try:
cache = json.loads(cache, object_hook=deserialize_hook)
- self.astro_dog.add_orbits(cache['orbits'])
- self.astro_dog.add_navs(cache['nav'])
- self.last_fetch_orbits_t = cache['last_fetch_orbits_t']
+ if cache['version'] == CACHE_VERSION:
+ self.astro_dog.add_navs(cache['navs'])
+ self.last_fetch_navs_t = cache['last_fetch_navs_t']
+ else:
+ cache['navs'] = {}
except json.decoder.JSONDecodeError:
cloudlog.exception("Error parsing cache")
- timestamp = self.last_fetch_orbits_t.as_datetime() if self.last_fetch_orbits_t is not None else 'Nan'
+ timestamp = self.last_fetch_navs_t.as_datetime() if self.last_fetch_navs_t is not None else 'Nan'
cloudlog.debug(
- f"Loaded nav ({sum([len(v) for v in cache['nav']])}) and orbits ({sum([len(v) for v in cache['orbits']])}) cache with timestamp: {timestamp}. Unique orbit and nav sats: {list(cache['orbits'].keys())} {list(cache['nav'].keys())} " +
- f"With time range: {[f'{start.as_datetime()}, {end.as_datetime()}' for (start,end) in self.astro_dog.orbit_fetched_times._ranges]}")
+ f"Loaded navs ({sum([len(v) for v in cache['navs']])}) cache with timestamp: {timestamp}. Unique orbit and nav sats: {list(cache['navs'].keys())} " +
+ f"With time range: {[f'{start.as_datetime()}, {end.as_datetime()}' for (start,end) in self.astro_dog.navs_fetched_times._ranges]}")
def cache_ephemeris(self, t: GPSTime):
if self.save_ephemeris and (self.last_cached_t is None or t - self.last_cached_t > SECS_IN_MIN):
put_nonblocking(EPHEMERIS_CACHE, json.dumps(
- {'version': CACHE_VERSION, 'last_fetch_orbits_t': self.last_fetch_orbits_t, 'orbits': self.astro_dog.orbits, 'nav': self.astro_dog.nav},
+ {'version': CACHE_VERSION, 'last_fetch_navs_t': self.last_fetch_navs_t, 'navs': self.astro_dog.navs},
cls=CacheSerializer))
cloudlog.debug("Cache saved")
self.last_cached_t = t
- def get_est_pos(self, t, processed_measurements):
- if self.last_pos_fix_t is None or abs(self.last_pos_fix_t - t) >= 2:
- min_measurements = 6 if any(p.constellation_id == ConstellationId.GLONASS for p in processed_measurements) else 5
- pos_fix, pos_fix_residual = calc_pos_fix_gauss_newton(processed_measurements, self.posfix_functions, min_measurements=min_measurements)
- if len(pos_fix) > 0:
- self.last_pos_fix_t = t
- residual_median = np.median(np.abs(pos_fix_residual))
- if np.median(np.abs(pos_fix_residual)) < POS_FIX_RESIDUAL_THRESHOLD:
- cloudlog.debug(f"Pos fix is within threshold with median: {residual_median.round()}")
- self.last_pos_fix = pos_fix[:3]
- self.last_pos_residual = pos_fix_residual
- else:
- cloudlog.debug(f"Pos fix failed with median: {residual_median.round()}. All residuals: {np.round(pos_fix_residual)}")
- return self.last_pos_fix
+ def get_lsq_fix(self, t, measurements):
+ if self.last_fix_t is None or abs(self.last_fix_t - t) > 0:
+ min_measurements = 5 if any(p.constellation_id == ConstellationId.GLONASS for p in measurements) else 4
+ position_solution, pr_residuals, pos_std = calc_pos_fix(measurements, self.posfix_functions, min_measurements=min_measurements)
+ if len(position_solution) < 3:
+ return None
+ position_estimate = position_solution[:3]
+
+ position_std_residual = np.median(np.abs(pr_residuals))
+ position_std = np.median(np.abs(pos_std))/10
+ position_std = max(position_std_residual, position_std) * np.ones(3)
+
+ velocity_solution, prr_residuals, vel_std = calc_vel_fix(measurements, position_estimate, self.velfix_function, min_measurements=min_measurements)
+ if len(velocity_solution) < 3:
+ return None
+ velocity_estimate = velocity_solution[:3]
+
+ velocity_std_residual = np.median(np.abs(prr_residuals))
+ velocity_std = np.median(np.abs(vel_std))/10
+ velocity_std = max(velocity_std, velocity_std_residual) * np.ones(3)
+
+ return position_estimate, position_std, velocity_estimate, velocity_std
def is_good_report(self, gnss_msg):
if gnss_msg.which() == 'drMeasurementReport' and self.use_qcom:
@@ -134,70 +145,97 @@ class Laikad:
if self.use_qcom:
return gnss_msg.which() == 'drSvPoly'
else:
- return gnss_msg.which() == 'ephemeris'
+ return gnss_msg.which() in ('ephemeris', 'glonassEphemeris')
def read_ephemeris(self, gnss_msg):
- # TODO this only works on GLONASS
if self.use_qcom:
# TODO this is not robust to gps week rollover
if self.gps_week is None:
return
ephem = parse_qcom_ephem(gnss_msg.drSvPoly, self.gps_week)
else:
- ephem = convert_ublox_ephem(gnss_msg.ephemeris)
+ if gnss_msg.which() == 'ephemeris':
+ ephem = convert_ublox_gps_ephem(gnss_msg.ephemeris)
+ elif gnss_msg.which() == 'glonassEphemeris':
+ ephem = convert_ublox_glonass_ephem(gnss_msg.glonassEphemeris)
+ else:
+ cloudlog.error(f"Unsupported ephemeris type: {gnss_msg.which()}")
+ return
self.astro_dog.add_navs({ephem.prn: [ephem]})
self.cache_ephemeris(t=ephem.epoch)
+ def process_report(self, new_meas, t):
+ # Filter measurements with unexpected pseudoranges for GPS and GLONASS satellites
+ new_meas = [m for m in new_meas if 1e7 < m.observables['C1C'] < 3e7]
+ processed_measurements = process_measurements(new_meas, self.astro_dog)
+ if self.last_fix_pos is not None:
+ corrected_measurements = correct_measurements(processed_measurements, self.last_fix_pos, self.astro_dog)
+ instant_fix = self.get_lsq_fix(t, corrected_measurements)
+ #instant_fix = self.get_lsq_fix(t, processed_measurements)
+ else:
+ corrected_measurements = []
+ instant_fix = self.get_lsq_fix(t, processed_measurements)
+ if instant_fix is None:
+ return None
+ else:
+ position_estimate, position_std, velocity_estimate, velocity_std = instant_fix
+ self.last_fix_t = t
+ self.last_fix_pos = position_estimate
+ self.lat_fix_pos_std = position_std
+ if (t*1e9) % 10 == 0:
+ cloudlog.debug(f"Measurements Incoming/Processed/Corrected: {len(new_meas), len(processed_measurements), len(corrected_measurements)}")
+ return position_estimate, position_std, velocity_estimate, velocity_std, corrected_measurements, processed_measurements
+
def process_gnss_msg(self, gnss_msg, gnss_mono_time: int, block=False):
- if self.is_good_report(gnss_msg):
+ if self.is_ephemeris(gnss_msg):
+ self.read_ephemeris(gnss_msg)
+ return None
+ elif self.is_good_report(gnss_msg):
+
week, tow, new_meas = self.read_report(gnss_msg)
- self.gps_week = week
+ if len(new_meas) == 0:
+ return None
+ self.gps_week = week
t = gnss_mono_time * 1e-9
if week > 0:
self.got_first_gnss_msg = True
latest_msg_t = GPSTime(week, tow)
- if self.auto_fetch_orbits:
- self.fetch_orbits(latest_msg_t, block)
-
- # Filter measurements with unexpected pseudoranges for GPS and GLONASS satellites
- new_meas = [m for m in new_meas if 1e7 < m.observables['C1C'] < 3e7]
+ if self.auto_fetch_navs:
+ self.fetch_navs(latest_msg_t, block)
- processed_measurements = process_measurements(new_meas, self.astro_dog)
- est_pos = self.get_est_pos(t, processed_measurements)
-
- corrected_measurements = correct_measurements(processed_measurements, est_pos, self.astro_dog) if len(est_pos) > 0 else []
- if gnss_mono_time % 10 == 0:
- cloudlog.debug(f"Measurements Incoming/Processed/Corrected: {len(new_meas), len(processed_measurements), len(corrected_measurements)}")
-
- self.update_localizer(est_pos, t, corrected_measurements)
- kf_valid = all(self.kf_valid(t))
- ecef_pos = self.gnss_kf.x[GStates.ECEF_POS]
- ecef_vel = self.gnss_kf.x[GStates.ECEF_VELOCITY]
-
- p = self.gnss_kf.P.diagonal()
- pos_std = np.sqrt(p[GStates.ECEF_POS])
- vel_std = np.sqrt(p[GStates.ECEF_VELOCITY])
+ output = self.process_report(new_meas, t)
+ if output is None:
+ return None
+ position_estimate, position_std, velocity_estimate, velocity_std, corrected_measurements, _ = output
+ self.update_localizer(position_estimate, t, corrected_measurements)
meas_msgs = [create_measurement_msg(m) for m in corrected_measurements]
- dat = messaging.new_message("gnssMeasurements")
+ msg = messaging.new_message("gnssMeasurements")
measurement_msg = log.LiveLocationKalman.Measurement.new_message
- dat.gnssMeasurements = {
+
+ P_diag = self.gnss_kf.P.diagonal()
+ kf_valid = all(self.kf_valid(t))
+ msg.gnssMeasurements = {
"gpsWeek": week,
"gpsTimeOfWeek": tow,
- "positionECEF": measurement_msg(value=ecef_pos.tolist(), std=pos_std.tolist(), valid=kf_valid),
- "velocityECEF": measurement_msg(value=ecef_vel.tolist(), std=vel_std.tolist(), valid=kf_valid),
- # TODO std is incorrectly the dimension of the measurements and not 3D
- "positionFixECEF": measurement_msg(value=self.last_pos_fix, std=self.last_pos_residual, valid=self.last_pos_fix_t == t),
- "ubloxMonoTime": gnss_mono_time,
+ "kalmanPositionECEF": measurement_msg(value=self.gnss_kf.x[GStates.ECEF_POS].tolist(),
+ std=np.sqrt(P_diag[GStates.ECEF_POS]).tolist(),
+ valid=kf_valid),
+ "kalmanVelocityECEF": measurement_msg(value=self.gnss_kf.x[GStates.ECEF_VELOCITY].tolist(),
+ std=np.sqrt(P_diag[GStates.ECEF_VELOCITY]).tolist(),
+ valid=kf_valid),
+ "positionECEF": measurement_msg(value=position_estimate, std=position_std.tolist(), valid=bool(self.last_fix_t == t)),
+ "velocityECEF": measurement_msg(value=velocity_estimate, std=velocity_std.tolist(), valid=bool(self.last_fix_t == t)),
+
+ "measTime": gnss_mono_time,
"correctedMeasurements": meas_msgs
}
- return dat
- elif self.is_ephemeris(gnss_msg):
- self.read_ephemeris(gnss_msg)
+ return msg
#elif gnss_msg.which() == 'ionoData':
- # todo add this. Needed to better correct messages offline. First fix ublox_msg.cc to sent them.
+ # TODO: add this, Needed to better correct messages offline. First fix ublox_msg.cc to sent them.
+
def update_localizer(self, est_pos, t: float, measurements: List[GNSSMeasurement]):
# Check time and outputs are valid
@@ -232,9 +270,9 @@ class Laikad:
p_initial_diag[GStates.ECEF_POS] = 1000 ** 2
self.gnss_kf.init_state(x_initial, covs_diag=p_initial_diag)
- def fetch_orbits(self, t: GPSTime, block):
- # Download new orbits if 1 hour of orbits data left
- if t + SECS_IN_HR not in self.astro_dog.orbit_fetched_times and (self.last_fetch_orbits_t is None or abs(t - self.last_fetch_orbits_t) > SECS_IN_MIN):
+ def fetch_navs(self, t: GPSTime, block):
+ # Download new navs if 1 hour of navs data left
+ if t + SECS_IN_HR not in self.astro_dog.navs_fetched_times and (self.last_fetch_navs_t is None or abs(t - self.last_fetch_navs_t) > SECS_IN_MIN):
astro_dog_vars = self.astro_dog.valid_const, self.astro_dog.auto_update, self.astro_dog.valid_ephem_types, self.astro_dog.cache_dir
ret = None
@@ -249,22 +287,22 @@ class Laikad:
if ret is not None:
if ret[0] is None:
- self.last_fetch_orbits_t = ret[2]
+ self.last_fetch_navs_t = ret[2]
else:
- self.astro_dog.orbits, self.astro_dog.orbit_fetched_times, self.last_fetch_orbits_t = ret
+ self.astro_dog.navs, self.astro_dog.navs_fetched_times, self.last_fetch_navs_t = ret
self.cache_ephemeris(t=t)
def get_orbit_data(t: GPSTime, valid_const, auto_update, valid_ephem_types, cache_dir):
astro_dog = AstroDog(valid_const=valid_const, auto_update=auto_update, valid_ephem_types=valid_ephem_types, cache_dir=cache_dir)
- cloudlog.info(f"Start to download/parse orbits for time {t.as_datetime()}")
+ cloudlog.info(f"Start to download/parse navs for time {t.as_datetime()}")
start_time = time.monotonic()
try:
- astro_dog.get_orbit_data(t, only_predictions=True)
- cloudlog.info(f"Done parsing orbits. Took {time.monotonic() - start_time:.1f}s")
- cloudlog.debug(f"Downloaded orbits ({sum([len(v) for v in astro_dog.orbits])}): {list(astro_dog.orbits.keys())}" +
+ astro_dog.get_navs(t)
+ cloudlog.info(f"Done parsing navs. Took {time.monotonic() - start_time:.1f}s")
+ cloudlog.debug(f"Downloaded navs ({sum([len(v) for v in astro_dog.navs])}): {list(astro_dog.navs.keys())}" +
f"With time range: {[f'{start.as_datetime()}, {end.as_datetime()}' for (start,end) in astro_dog.orbit_fetched_times._ranges]}")
- return astro_dog.orbits, astro_dog.orbit_fetched_times, t
+ return astro_dog.navs, astro_dog.navs_fetched_times, t
except (DownloadFailed, RuntimeError, ValueError, IOError) as e:
cloudlog.warning(f"No orbit data found or parsing failure: {e}")
return None, None, t
@@ -349,9 +387,31 @@ class EphemerisSourceType(IntEnum):
qcom = 3
-def main(sm=None, pm=None):
+def process_msg(laikad, gnss_msg, mono_time, block=False):
+ # TODO: Understand and use remaining unknown constellations
+ if gnss_msg.which() == "drMeasurementReport":
+ if getattr(gnss_msg, gnss_msg.which()).source not in ['glonass', 'gps', 'beidou', 'sbas']:
+ return None
+
+ if getattr(gnss_msg, gnss_msg.which()).gpsWeek > np.iinfo(np.int16).max:
+ # gpsWeek 65535 is received rarely from quectel, this cannot be
+ # passed to GnssMeasurements's gpsWeek (Int16)
+ return None
+
+ return laikad.process_gnss_msg(gnss_msg, mono_time, block=block)
+
+
+def clear_tmp_cache():
+ if os.path.exists(DOWNLOADS_CACHE_FOLDER):
+ shutil.rmtree(DOWNLOADS_CACHE_FOLDER)
+ os.mkdir(DOWNLOADS_CACHE_FOLDER)
+
+
+def main(sm=None, pm=None, qc=None):
+ #clear_tmp_cache()
+
use_qcom = not Params().get_bool("UbloxAvailable", block=True)
- if use_qcom:
+ if use_qcom or (qc is not None and qc):
raw_gnss_socket = "qcomGnss"
else:
raw_gnss_socket = "ubloxGnss"
@@ -361,9 +421,14 @@ def main(sm=None, pm=None):
if pm is None:
pm = messaging.PubMaster(['gnssMeasurements'])
+ # disable until set as main gps source, to better analyze startup time
+ use_internet = False #"LAIKAD_NO_INTERNET" not in os.environ
+
replay = "REPLAY" in os.environ
- use_internet = "LAIKAD_NO_INTERNET" not in os.environ
- laikad = Laikad(save_ephemeris=not replay, auto_fetch_orbits=use_internet, use_qcom=use_qcom)
+ if replay or "CI" in os.environ:
+ use_internet = True
+
+ laikad = Laikad(save_ephemeris=not replay, auto_fetch_navs=use_internet, use_qcom=use_qcom)
while True:
sm.update()
@@ -371,25 +436,17 @@ def main(sm=None, pm=None):
if sm.updated[raw_gnss_socket]:
gnss_msg = sm[raw_gnss_socket]
- # TODO: Understand and use remaining unknown constellations
- if gnss_msg.which() == "drMeasurementReport":
- if getattr(gnss_msg, gnss_msg.which()).source not in ['glonass', 'gps', 'beidou', 'sbas']:
- continue
+ msg = process_msg(laikad, gnss_msg, sm.logMonoTime[raw_gnss_socket], replay)
+ if msg is None:
+ # TODO: beautify this, locationd needs a valid message
+ msg = messaging.new_message("gnssMeasurements")
+ pm.send('gnssMeasurements', msg)
- if getattr(gnss_msg, gnss_msg.which()).gpsWeek > np.iinfo(np.int16).max:
- # gpsWeek 65535 is received rarely from quectel, this cannot be
- # passed to GnssMeasurements's gpsWeek (Int16)
- continue
-
- msg = laikad.process_gnss_msg(gnss_msg, sm.logMonoTime[raw_gnss_socket], block=replay)
- if msg is not None:
- pm.send('gnssMeasurements', msg)
if not laikad.got_first_gnss_msg and sm.updated['clocks']:
clocks_msg = sm['clocks']
t = GPSTime.from_datetime(datetime.utcfromtimestamp(clocks_msg.wallTimeNanos * 1E-9))
- if laikad.auto_fetch_orbits:
- laikad.fetch_orbits(t, block=replay)
-
+ if laikad.auto_fetch_navs:
+ laikad.fetch_navs(t, block=replay)
if __name__ == "__main__":
main()
diff --git a/selfdrive/locationd/laikad_helpers.py b/selfdrive/locationd/laikad_helpers.py
deleted file mode 100644
index f13e8e73bb..0000000000
--- a/selfdrive/locationd/laikad_helpers.py
+++ /dev/null
@@ -1,89 +0,0 @@
-import numpy as np
-import sympy
-
-from laika.constants import EARTH_ROTATION_RATE, SPEED_OF_LIGHT
-from laika.helpers import ConstellationId
-
-
-def calc_pos_fix_gauss_newton(measurements, posfix_functions, x0=None, signal='C1C', min_measurements=6):
- '''
- Calculates gps fix using gauss newton method
- To solve the problem a minimal of 4 measurements are required.
- If Glonass is included 5 are required to solve for the additional free variable.
- returns:
- 0 -> list with positions
- '''
- if x0 is None:
- x0 = [0, 0, 0, 0, 0]
- n = len(measurements)
- if n < min_measurements:
- return [], []
-
- Fx_pos = pr_residual(measurements, posfix_functions, signal=signal)
- x = gauss_newton(Fx_pos, x0)
- residual, _ = Fx_pos(x, weight=1.0)
- return x.tolist(), residual.tolist()
-
-
-def pr_residual(measurements, posfix_functions, signal='C1C'):
- def Fx_pos(inp, weight=None):
- vals, gradients = [], []
-
- for meas in measurements:
- pr = meas.observables[signal]
- pr += meas.sat_clock_err * SPEED_OF_LIGHT
-
- w = (1 / meas.observables_std[signal]) if weight is None else weight
-
- val, *gradient = posfix_functions[meas.constellation_id](*inp, pr, *meas.sat_pos, w)
- vals.append(val)
- gradients.append(gradient)
- return np.asarray(vals), np.asarray(gradients)
-
- return Fx_pos
-
-
-def gauss_newton(fun, b, xtol=1e-8, max_n=25):
- for _ in range(max_n):
- # Compute function and jacobian on current estimate
- r, J = fun(b)
-
- # Update estimate
- delta = np.linalg.pinv(J) @ r
- b -= delta
-
- # Check step size for stopping condition
- if np.linalg.norm(delta) < xtol:
- break
- return b
-
-
-def get_posfix_sympy_fun(constellation):
- # Unknowns
- x, y, z = sympy.Symbol('x'), sympy.Symbol('y'), sympy.Symbol('z')
- bc = sympy.Symbol('bc')
- bg = sympy.Symbol('bg')
- var = [x, y, z, bc, bg]
-
- # Knowns
- pr = sympy.Symbol('pr')
- sat_x, sat_y, sat_z = sympy.Symbol('sat_x'), sympy.Symbol('sat_y'), sympy.Symbol('sat_z')
- weight = sympy.Symbol('weight')
-
- theta = EARTH_ROTATION_RATE * (pr - bc) / SPEED_OF_LIGHT
- val = sympy.sqrt(
- (sat_x * sympy.cos(theta) + sat_y * sympy.sin(theta) - x) ** 2 +
- (sat_y * sympy.cos(theta) - sat_x * sympy.sin(theta) - y) ** 2 +
- (sat_z - z) ** 2
- )
-
- if constellation == ConstellationId.GLONASS:
- res = weight * (val - (pr - bc - bg))
- elif constellation == ConstellationId.GPS:
- res = weight * (val - (pr - bc))
- else:
- raise NotImplementedError(f"Constellation {constellation} not supported")
-
- res = [res] + [sympy.diff(res, v) for v in var]
-
- return sympy.lambdify([x, y, z, bc, bg, pr, sat_x, sat_y, sat_z, weight], res, modules=["numpy"])
diff --git a/selfdrive/locationd/liblocationd.cc b/selfdrive/locationd/liblocationd.cc
index da57fb7ff4..32fec7724a 100755
--- a/selfdrive/locationd/liblocationd.cc
+++ b/selfdrive/locationd/liblocationd.cc
@@ -3,8 +3,8 @@
extern "C" {
typedef Localizer* Localizer_t;
- Localizer *localizer_init() {
- return new Localizer();
+ Localizer *localizer_init(bool has_ublox) {
+ return new Localizer(has_ublox);
}
void localizer_get_message_bytes(Localizer *localizer, bool inputsOK, bool sensorsOK, bool gpsOK, bool msgValid,
diff --git a/selfdrive/locationd/locationd.cc b/selfdrive/locationd/locationd.cc
index 4325900c0e..307626506a 100755
--- a/selfdrive/locationd/locationd.cc
+++ b/selfdrive/locationd/locationd.cc
@@ -25,8 +25,16 @@ const double MAX_FILTER_REWIND_TIME = 0.8; // s
// TODO: GPS sensor time offsets are empirically calculated
// They should be replaced with synced time from a real clock
-const double GPS_LOCATION_SENSOR_TIME_OFFSET = 0.630; // s
-const double GPS_LOCATION_EXTERNAL_SENSOR_TIME_OFFSET = 0.095; // s
+const double GPS_QUECTEL_SENSOR_TIME_OFFSET = 0.630; // s
+const double GPS_UBLOX_SENSOR_TIME_OFFSET = 0.095; // s
+const float GPS_MUL_FACTOR = 10.0;
+const float GPS_POS_STD_THRESHOLD = 50.0;
+const float GPS_VEL_STD_THRESHOLD = 5.0;
+const float GPS_POS_ERROR_RESET_THRESHOLD = 300.0;
+const float GPS_POS_STD_RESET_THRESHOLD = 2.0;
+const float GPS_VEL_STD_RESET_THRESHOLD = 0.5;
+const float GPS_ORIENTATION_ERROR_RESET_THRESHOLD = 1.0;
+const int GPS_ORIENTATION_ERROR_RESET_CNT = 3;
static VectorXd floatlist2vector(const capnp::List::Reader& floatlist) {
VectorXd res(floatlist.size());
@@ -77,6 +85,8 @@ Localizer::Localizer() {
this->converter = std::make_unique((ECEF) { .x = ecef_pos[0], .y = ecef_pos[1], .z = ecef_pos[2] });
}
+Localizer::Localizer(bool has_ublox) : Localizer() { ublox_available = has_ublox; }
+
void Localizer::build_live_location(cereal::LiveLocationKalman::Builder& fix) {
VectorXd predicted_state = this->kf->get_x();
MatrixXdr predicted_cov = this->kf->get_P();
@@ -220,7 +230,7 @@ void Localizer::handle_sensor(double current_time, const cereal::SensorEventData
}
double sensor_time = 1e-9 * log.getTimestamp();
-
+
// sensor time and log time should be close
if (std::abs(current_time - sensor_time) > 0.1) {
LOGE("Sensor reading ignored, sensor timestamp more than 100ms off from log time");
@@ -301,7 +311,7 @@ void Localizer::handle_gps(double current_time, const cereal::GpsLocationData::R
}
if (gps_invalid_flag || gps_unreasonable || gps_accuracy_insane || gps_lat_lng_alt_insane || gps_vel_insane || gps_accuracy_insane_quectel) {
- this->gps_valid = false;
+ //this->gps_valid = false;
this->determine_gps_mode(current_time);
return;
}
@@ -309,15 +319,15 @@ void Localizer::handle_gps(double current_time, const cereal::GpsLocationData::R
double sensor_time = current_time - sensor_time_offset;
// Process message
- this->gps_valid = true;
+ //this->gps_valid = true;
this->gps_mode = true;
Geodetic geodetic = { log.getLatitude(), log.getLongitude(), log.getAltitude() };
this->converter = std::make_unique(geodetic);
VectorXd ecef_pos = this->converter->ned2ecef({ 0.0, 0.0, 0.0 }).to_vector();
VectorXd ecef_vel = this->converter->ned2ecef({ log.getVNED()[0], log.getVNED()[1], log.getVNED()[2] }).to_vector() - ecef_pos;
- MatrixXdr ecef_pos_R = Vector3d::Constant(std::pow(10.0 * log.getAccuracy(),2) + std::pow(10.0 * log.getVerticalAccuracy(),2)).asDiagonal();
- MatrixXdr ecef_vel_R = Vector3d::Constant(std::pow(log.getSpeedAccuracy() * 10.0, 2)).asDiagonal();
+ MatrixXdr ecef_pos_R = Vector3d::Constant(std::pow(GPS_MUL_FACTOR * log.getAccuracy(),2) + std::pow(GPS_MUL_FACTOR * log.getVerticalAccuracy(),2)).asDiagonal();
+ MatrixXdr ecef_vel_R = Vector3d::Constant(std::pow(GPS_MUL_FACTOR * log.getSpeedAccuracy(), 2)).asDiagonal();
this->unix_timestamp_millis = log.getUnixTimestampMillis();
double gps_est_error = (this->kf->get_x().segment(STATE_ECEF_POS_START) - ecef_pos).norm();
@@ -344,13 +354,96 @@ void Localizer::handle_gps(double current_time, const cereal::GpsLocationData::R
this->reset_kalman(NAN, initial_pose_ecef_quat, ecef_pos, ecef_vel, ecef_pos_R, ecef_vel_R);
}
+ this->last_gps_msg = sensor_time;
+ this->kf->predict_and_observe(sensor_time, OBSERVATION_ECEF_POS, { ecef_pos }, { ecef_pos_R });
+ this->kf->predict_and_observe(sensor_time, OBSERVATION_ECEF_VEL, { ecef_vel }, { ecef_vel_R });
+}
+
+void Localizer::handle_gnss(double current_time, const cereal::GnssMeasurements::Reader& log) {
+
+ if(!log.getPositionECEF().getValid() || !log.getVelocityECEF().getValid()) {
+ this->determine_gps_mode(current_time);
+ return;
+ }
+
+ double sensor_time = log.getMeasTime() * 1e-9;
+ if (ublox_available)
+ sensor_time -= GPS_UBLOX_SENSOR_TIME_OFFSET;
+ else
+ sensor_time -= GPS_QUECTEL_SENSOR_TIME_OFFSET;
+
+ auto ecef_pos_v = log.getPositionECEF().getValue();
+ VectorXd ecef_pos = Vector3d(ecef_pos_v[0], ecef_pos_v[1], ecef_pos_v[2]);
+
+ // indexed at 0 cause all std values are the same MAE
+ auto ecef_pos_std = log.getPositionECEF().getStd()[0];
+ MatrixXdr ecef_pos_R = Vector3d::Constant(pow(GPS_MUL_FACTOR*ecef_pos_std, 2)).asDiagonal();
+
+ auto ecef_vel_v = log.getVelocityECEF().getValue();
+ VectorXd ecef_vel = Vector3d(ecef_vel_v[0], ecef_vel_v[1], ecef_vel_v[2]);
+
+ // indexed at 0 cause all std values are the same MAE
+ auto ecef_vel_std = log.getVelocityECEF().getStd()[0];
+ MatrixXdr ecef_vel_R = Vector3d::Constant(pow(GPS_MUL_FACTOR*ecef_vel_std, 2)).asDiagonal();
+
+ double gps_est_error = (this->kf->get_x().segment(STATE_ECEF_POS_START) - ecef_pos).norm();
+
+ VectorXd orientation_ecef = quat2euler(vector2quat(this->kf->get_x().segment(STATE_ECEF_ORIENTATION_START)));
+ VectorXd orientation_ned = ned_euler_from_ecef({ ecef_pos[0], ecef_pos[1], ecef_pos[2] }, orientation_ecef);
+
+ LocalCoord convs((ECEF){ .x = ecef_pos[0], .y = ecef_pos[1], .z = ecef_pos[2] });
+ ECEF next_ecef = {.x = ecef_pos[0] + ecef_vel[0], .y = ecef_pos[1] + ecef_vel[1], .z = ecef_pos[2] + ecef_vel[2]};
+ VectorXd ned_vel = convs.ecef2ned(next_ecef).to_vector();
+ double bearing_rad = atan2(ned_vel[1], ned_vel[0]);
+
+ VectorXd orientation_ned_gps = Vector3d(0.0, 0.0, bearing_rad);
+ VectorXd orientation_error = (orientation_ned - orientation_ned_gps).array() - M_PI;
+ for (int i = 0; i < orientation_error.size(); i++) {
+ orientation_error(i) = std::fmod(orientation_error(i), 2.0 * M_PI);
+ if (orientation_error(i) < 0.0) {
+ orientation_error(i) += 2.0 * M_PI;
+ }
+ orientation_error(i) -= M_PI;
+ }
+ VectorXd initial_pose_ecef_quat = quat2vector(euler2quat(ecef_euler_from_ned({ ecef_pos(0), ecef_pos(1), ecef_pos(2) }, orientation_ned_gps)));
+
+ if (ecef_pos_std > GPS_POS_STD_THRESHOLD || ecef_vel_std > GPS_VEL_STD_THRESHOLD) {
+ this->determine_gps_mode(current_time);
+ return;
+ }
+
+ // prevent jumping gnss measurements (covered lots, standstill...)
+ bool orientation_reset = ecef_vel_std < GPS_VEL_STD_RESET_THRESHOLD;
+ orientation_reset &= orientation_error.norm() > GPS_ORIENTATION_ERROR_RESET_THRESHOLD;
+ orientation_reset &= !this->standstill;
+ if (orientation_reset) {
+ this->orientation_reset_count++;
+ }
+ else {
+ this->orientation_reset_count = 0;
+ }
+
+ if ((gps_est_error > GPS_POS_ERROR_RESET_THRESHOLD && ecef_pos_std < GPS_POS_STD_RESET_THRESHOLD) || this->last_gps_msg == 0) {
+ // always reset on first gps message and if the location is off but the accuracy is high
+ LOGE("Locationd vs gnssMeasurement position difference too large, kalman reset");
+ this->reset_kalman(NAN, initial_pose_ecef_quat, ecef_pos, ecef_vel, ecef_pos_R, ecef_vel_R);
+ } else if (orientation_reset_count > GPS_ORIENTATION_ERROR_RESET_CNT) {
+ LOGE("Locationd vs gnssMeasurement orientation difference too large, kalman reset");
+ this->reset_kalman(NAN, initial_pose_ecef_quat, ecef_pos, ecef_vel, ecef_pos_R, ecef_vel_R);
+ this->kf->predict_and_observe(sensor_time, OBSERVATION_ECEF_ORIENTATION_FROM_GPS, { initial_pose_ecef_quat });
+ this->orientation_reset_count = 0;
+ }
+
+ this->gps_mode = true;
+ this->last_gps_msg = sensor_time;
this->kf->predict_and_observe(sensor_time, OBSERVATION_ECEF_POS, { ecef_pos }, { ecef_pos_R });
this->kf->predict_and_observe(sensor_time, OBSERVATION_ECEF_VEL, { ecef_vel }, { ecef_vel_R });
}
void Localizer::handle_car_state(double current_time, const cereal::CarState::Reader& log) {
this->car_speed = std::abs(log.getVEgo());
- if (log.getStandstill()) {
+ this->standstill = log.getStandstill();
+ if (this->standstill) {
this->kf->predict_and_observe(current_time, OBSERVATION_NO_ROT, { Vector3d(0.0, 0.0, 0.0) });
this->kf->predict_and_observe(current_time, OBSERVATION_NO_ACCEL, { Vector3d(0.0, 0.0, 0.0) });
}
@@ -359,7 +452,7 @@ void Localizer::handle_car_state(double current_time, const cereal::CarState::Re
void Localizer::handle_cam_odo(double current_time, const cereal::CameraOdometry::Reader& log) {
VectorXd rot_device = this->device_from_calib * floatlist2vector(log.getRot());
VectorXd trans_device = this->device_from_calib * floatlist2vector(log.getTrans());
-
+
if (!this->is_timestamp_valid(current_time)) {
this->observation_timings_invalid = true;
return;
@@ -497,9 +590,11 @@ void Localizer::handle_msg(const cereal::Event::Reader& log) {
} else if (log.isGyroscope()) {
this->handle_sensor(t, log.getGyroscope());
} else if (log.isGpsLocation()) {
- this->handle_gps(t, log.getGpsLocation(), GPS_LOCATION_SENSOR_TIME_OFFSET);
+ this->handle_gps(t, log.getGpsLocation(), GPS_QUECTEL_SENSOR_TIME_OFFSET);
} else if (log.isGpsLocationExternal()) {
- this->handle_gps(t, log.getGpsLocationExternal(), GPS_LOCATION_EXTERNAL_SENSOR_TIME_OFFSET);
+ this->handle_gps(t, log.getGpsLocationExternal(), GPS_UBLOX_SENSOR_TIME_OFFSET);
+ //} else if (log.isGnssMeasurements()) {
+ // this->handle_gnss(t, log.getGnssMeasurements());
} else if (log.isCarState()) {
this->handle_car_state(t, log.getCarState());
} else if (log.isCameraOdometry()) {
@@ -524,7 +619,7 @@ kj::ArrayPtr Localizer::get_message_bytes(MessageBuilder& msg_build
}
bool Localizer::is_gps_ok() {
- return this->gps_valid;
+ return (this->kf->get_filter_time() - this->last_gps_msg) < 2.0;
}
bool Localizer::critical_services_valid(std::map critical_services) {
@@ -536,7 +631,7 @@ bool Localizer::critical_services_valid(std::map critical_s
return true;
}
-bool Localizer::is_timestamp_valid(double current_time) {
+bool Localizer::is_timestamp_valid(double current_time) {
double filter_time = this->kf->get_filter_time();
if (!std::isnan(filter_time) && ((filter_time - current_time) > MAX_FILTER_REWIND_TIME)) {
LOGE("Observation timestamp is older than the max rewind threshold of the filter");
@@ -563,19 +658,18 @@ void Localizer::determine_gps_mode(double current_time) {
int Localizer::locationd_thread() {
ublox_available = Params().getBool("UbloxAvailable", true);
-
const char* gps_location_socket;
if (ublox_available) {
gps_location_socket = "gpsLocationExternal";
} else {
gps_location_socket = "gpsLocation";
}
- const std::initializer_list service_list = {gps_location_socket, "cameraOdometry", "liveCalibration",
+ const std::initializer_list service_list = {gps_location_socket, "cameraOdometry", "liveCalibration",
"carState", "carParams", "accelerometer", "gyroscope"};
- PubMaster pm({"liveLocationKalman"});
// TODO: remove carParams once we're always sending at 100Hz
SubMaster sm(service_list, {}, nullptr, {gps_location_socket, "carParams"});
+ PubMaster pm({"liveLocationKalman"});
uint64_t cnt = 0;
bool filterInitialized = false;
diff --git a/selfdrive/locationd/locationd.h b/selfdrive/locationd/locationd.h
index f0872d9f56..a292a3c936 100755
--- a/selfdrive/locationd/locationd.h
+++ b/selfdrive/locationd/locationd.h
@@ -24,6 +24,7 @@
class Localizer {
public:
Localizer();
+ Localizer(bool has_ublox);
int locationd_thread();
@@ -52,6 +53,7 @@ public:
void handle_msg(const cereal::Event::Reader& log);
void handle_sensor(double current_time, const cereal::SensorEventData::Reader& log);
void handle_gps(double current_time, const cereal::GpsLocationData::Reader& log, const double sensor_time_offset);
+ void handle_gnss(double current_time, const cereal::GnssMeasurements::Reader& log);
void handle_car_state(double current_time, const cereal::CarState::Reader& log);
void handle_cam_odo(double current_time, const cereal::CameraOdometry::Reader& log);
void handle_live_calib(double current_time, const cereal::LiveCalibrationData::Reader& log);
@@ -76,8 +78,10 @@ private:
double reset_tracker = 0.0;
bool device_fell = false;
bool gps_mode = false;
- bool gps_valid = false;
+ double last_gps_msg = 0;
bool ublox_available = true;
bool observation_timings_invalid = false;
- std::map observation_values_invalid;
+ std::map observation_values_invalid;
+ bool standstill = true;
+ int32_t orientation_reset_count = 0;
};
diff --git a/selfdrive/locationd/models/lane_kf.py b/selfdrive/locationd/models/lane_kf.py
new file mode 100755
index 0000000000..4d38fa8e09
--- /dev/null
+++ b/selfdrive/locationd/models/lane_kf.py
@@ -0,0 +1,105 @@
+#!/usr/bin/env python3
+import sys
+import numpy as np
+import sympy as sp
+
+from selfdrive.locationd.models.constants import ObservationKind
+from rednose.helpers.ekf_sym import gen_code, EKF_sym
+
+
+class LaneKalman():
+ name = 'lane'
+
+ @staticmethod
+ def generate_code(generated_dir):
+ # make functions and jacobians with sympy
+ # state variables
+ dim = 6
+ state = sp.MatrixSymbol('state', dim, 1)
+
+ dd = sp.Symbol('dd') # WARNING: NOT TIME
+
+ # Time derivative of the state as a function of state
+ state_dot = sp.Matrix(np.zeros((dim, 1)))
+ state_dot[:3,0] = sp.Matrix(state[3:6,0])
+
+ # Basic descretization, 1st order intergrator
+ # Can be pretty bad if dt is big
+ f_sym = sp.Matrix(state) + dd*state_dot
+
+ #
+ # Observation functions
+ #
+ h_lane_sym = sp.Matrix(state[:3,0])
+ obs_eqs = [[h_lane_sym, ObservationKind.LANE_PT, None]]
+ gen_code(generated_dir, LaneKalman.name, f_sym, dd, state, obs_eqs, dim, dim)
+
+ def __init__(self, generated_dir, pt_std=5):
+ # state
+ # left and right lane centers in ecef
+ # WARNING: this is not a temporal model
+ # the 'time' in this kalman filter is
+ # the distance traveled by the vehicle,
+ # which should approximately be the
+ # distance along the lane path
+ # a more logical parametrization
+ # states 0-2 are ecef coordinates distance d
+ # states 3-5 is the 3d "velocity" of the
+ # lane in ecef (m/m).
+ x_initial = np.array([0,0,0,
+ 0,0,0])
+
+ # state covariance
+ P_initial = np.diag([1e16, 1e16, 1e16,
+ 1**2, 1**2, 1**2])
+
+ # process noise
+ Q = np.diag([0.1**2, 0.1**2, 0.1**2,
+ 0.1**2, 0.1**2, 0.1*2])
+
+ self.dim_state = len(x_initial)
+
+ # init filter
+ self.filter = EKF_sym(generated_dir, self.name, Q, x_initial, P_initial, x_initial.shape[0], P_initial.shape[0])
+ self.obs_noise = {ObservationKind.LANE_PT: np.diag([pt_std**2]*3)}
+
+ @property
+ def x(self):
+ return self.filter.state()
+
+ @property
+ def P(self):
+ return self.filter.covs()
+
+ def predict(self, t):
+ return self.filter.predict(t)
+
+ def rts_smooth(self, estimates):
+ return self.filter.rts_smooth(estimates, norm_quats=False)
+
+
+ def init_state(self, state, covs_diag=None, covs=None, filter_time=None):
+ if covs_diag is not None:
+ P = np.diag(covs_diag)
+ elif covs is not None:
+ P = covs
+ else:
+ P = self.filter.covs()
+ self.filter.init_state(state, P, filter_time)
+
+ def predict_and_observe(self, t, kind, data):
+ data = np.atleast_2d(data)
+ return self.filter.predict_and_update_batch(t, kind, data, self.get_R(kind, len(data)))
+
+ def get_R(self, kind, n):
+ obs_noise = self.obs_noise[kind]
+ dim = obs_noise.shape[0]
+ R = np.zeros((n, dim, dim))
+ for i in range(n):
+ R[i,:,:] = obs_noise
+ return R
+
+
+if __name__ == "__main__":
+ generated_dir = sys.argv[2]
+ LaneKalman.generate_code(generated_dir)
diff --git a/selfdrive/locationd/paramsd.py b/selfdrive/locationd/paramsd.py
index 9bd4ed0837..7e30b1e3a7 100755
--- a/selfdrive/locationd/paramsd.py
+++ b/selfdrive/locationd/paramsd.py
@@ -14,8 +14,9 @@ from system.swaglog import cloudlog
MAX_ANGLE_OFFSET_DELTA = 20 * DT_MDL # Max 20 deg/s
-ROLL_MAX_DELTA = np.radians(20.0) * DT_MDL # 20deg in 1 second is well within curvature limits
+ROLL_MAX_DELTA = math.radians(20.0) * DT_MDL # 20deg in 1 second is well within curvature limits
ROLL_MIN, ROLL_MAX = math.radians(-10), math.radians(10)
+ROLL_STD_MAX = math.radians(1.5)
LATERAL_ACC_SENSOR_THRESHOLD = 4.0
@@ -36,10 +37,8 @@ class ParamsLearner:
self.yaw_rate = 0.0
self.yaw_rate_std = 0.0
self.roll = 0.0
- self.steering_pressed = False
self.steering_angle = 0.0
-
- self.valid = True
+ self.roll_valid = False
def handle_log(self, t, which, msg):
if which == 'liveLocationKalman':
@@ -48,8 +47,8 @@ class ParamsLearner:
localizer_roll = msg.orientationNED.value[0]
localizer_roll_std = np.radians(1) if np.isnan(msg.orientationNED.std[0]) else msg.orientationNED.std[0]
- roll_valid = msg.orientationNED.valid and ROLL_MIN < localizer_roll < ROLL_MAX
- if roll_valid:
+ self.roll_valid = (localizer_roll_std < ROLL_STD_MAX) and (ROLL_MIN < localizer_roll < ROLL_MAX) and msg.sensorsOK
+ if self.roll_valid:
roll = localizer_roll
# Experimentally found multiplier of 2 to be best trade-off between stability and accuracy or similar?
roll_std = 2 * localizer_roll_std
@@ -88,10 +87,9 @@ class ParamsLearner:
elif which == 'carState':
self.steering_angle = msg.steeringAngleDeg
- self.steering_pressed = msg.steeringPressed
self.speed = msg.vEgo
- in_linear_region = abs(self.steering_angle) < 45 or not self.steering_pressed
+ in_linear_region = abs(self.steering_angle) < 45
self.active = self.speed > 1 and in_linear_region
if self.active:
@@ -158,6 +156,7 @@ def main(sm=None, pm=None):
learner = ParamsLearner(CP, params['steerRatio'], params['stiffnessFactor'], math.radians(params['angleOffsetAverageDeg']))
angle_offset_average = params['angleOffsetAverageDeg']
angle_offset = angle_offset_average
+ roll = 0.0
while True:
sm.update()
@@ -177,6 +176,8 @@ def main(sm=None, pm=None):
angle_offset_average = clip(math.degrees(x[States.ANGLE_OFFSET]), angle_offset_average - MAX_ANGLE_OFFSET_DELTA, angle_offset_average + MAX_ANGLE_OFFSET_DELTA)
angle_offset = clip(math.degrees(x[States.ANGLE_OFFSET] + x[States.ANGLE_OFFSET_FAST]), angle_offset - MAX_ANGLE_OFFSET_DELTA, angle_offset + MAX_ANGLE_OFFSET_DELTA)
+ roll = clip(float(x[States.ROAD_ROLL]), roll - ROLL_MAX_DELTA, roll + ROLL_MAX_DELTA)
+ roll_std = float(P[States.ROAD_ROLL])
# Account for the opposite signs of the yaw rates
sensors_valid = bool(abs(learner.speed * (x[States.YAW_RATE] + learner.yaw_rate)) < LATERAL_ACC_SENSOR_THRESHOLD)
@@ -187,12 +188,14 @@ def main(sm=None, pm=None):
liveParameters.sensorValid = sensors_valid
liveParameters.steerRatio = float(x[States.STEER_RATIO])
liveParameters.stiffnessFactor = float(x[States.STIFFNESS])
- liveParameters.roll = float(x[States.ROAD_ROLL])
+ liveParameters.roll = roll
liveParameters.angleOffsetAverageDeg = angle_offset_average
liveParameters.angleOffsetDeg = angle_offset
liveParameters.valid = all((
abs(liveParameters.angleOffsetAverageDeg) < 10.0,
abs(liveParameters.angleOffsetDeg) < 10.0,
+ abs(liveParameters.roll) < ROLL_MAX,
+ roll_std < ROLL_STD_MAX,
0.2 <= liveParameters.stiffnessFactor <= 5.0,
min_sr <= liveParameters.steerRatio <= max_sr,
))
diff --git a/selfdrive/locationd/test/_test_locationd_lib.py b/selfdrive/locationd/test/_test_locationd_lib.py
index c4a053bbc6..819bb1570e 100755
--- a/selfdrive/locationd/test/_test_locationd_lib.py
+++ b/selfdrive/locationd/test/_test_locationd_lib.py
@@ -19,7 +19,7 @@ LIBLOCATIOND_PATH = os.path.abspath(os.path.join(os.path.dirname(__file__), '../
class TestLocationdLib(unittest.TestCase):
def setUp(self):
header = '''typedef ...* Localizer_t;
-Localizer_t localizer_init();
+Localizer_t localizer_init(bool has_ublox);
void localizer_get_message_bytes(Localizer_t localizer, bool inputsOK, bool sensorsOK, bool gpsOK, bool msgValid, char *buff, size_t buff_size);
void localizer_handle_msg_bytes(Localizer_t localizer, const char *data, size_t size);'''
@@ -27,7 +27,7 @@ void localizer_handle_msg_bytes(Localizer_t localizer, const char *data, size_t
self.ffi.cdef(header)
self.lib = self.ffi.dlopen(LIBLOCATIOND_PATH)
- self.localizer = self.lib.localizer_init()
+ self.localizer = self.lib.localizer_init(True) # default to ublox
self.buff_size = 2048
self.msg_buff = self.ffi.new(f'char[{self.buff_size}]')
diff --git a/selfdrive/locationd/test/test_glonass_kaitai.cc b/selfdrive/locationd/test/test_glonass_kaitai.cc
new file mode 100644
index 0000000000..22f5202a3d
--- /dev/null
+++ b/selfdrive/locationd/test/test_glonass_kaitai.cc
@@ -0,0 +1,360 @@
+#include
+#include
+#include
+#include
+#include
+#include
+
+#include "catch2/catch.hpp"
+#include "selfdrive/locationd/generated/glonass.h"
+
+typedef std::vector> string_data;
+
+#define IDLE_CHIP_IDX 0
+#define STRING_NUMBER_IDX 1
+// string data 1-5
+#define HC_IDX 0
+#define PAD1_IDX 1
+#define SUPERFRAME_IDX 2
+#define PAD2_IDX 3
+#define FRAME_IDX 4
+
+// Indexes for string number 1
+#define ST1_NU_IDX 2
+#define ST1_P1_IDX 3
+#define ST1_T_K_IDX 4
+#define ST1_X_VEL_S_IDX 5
+#define ST1_X_VEL_V_IDX 6
+#define ST1_X_ACCEL_S_IDX 7
+#define ST1_X_ACCEL_V_IDX 8
+#define ST1_X_S_IDX 9
+#define ST1_X_V_IDX 10
+#define ST1_HC_OFF 11
+
+// Indexes for string number 2
+#define ST2_BN_IDX 2
+#define ST2_P2_IDX 3
+#define ST2_TB_IDX 4
+#define ST2_NU_IDX 5
+#define ST2_Y_VEL_S_IDX 6
+#define ST2_Y_VEL_V_IDX 7
+#define ST2_Y_ACCEL_S_IDX 8
+#define ST2_Y_ACCEL_V_IDX 9
+#define ST2_Y_S_IDX 10
+#define ST2_Y_V_IDX 11
+#define ST2_HC_OFF 12
+
+// Indexes for string number 3
+#define ST3_P3_IDX 2
+#define ST3_GAMMA_N_S_IDX 3
+#define ST3_GAMMA_N_V_IDX 4
+#define ST3_NU_1_IDX 5
+#define ST3_P_IDX 6
+#define ST3_L_N_IDX 7
+#define ST3_Z_VEL_S_IDX 8
+#define ST3_Z_VEL_V_IDX 9
+#define ST3_Z_ACCEL_S_IDX 10
+#define ST3_Z_ACCEL_V_IDX 11
+#define ST3_Z_S_IDX 12
+#define ST3_Z_V_IDX 13
+#define ST3_HC_OFF 14
+
+// Indexes for string number 4
+#define ST4_TAU_N_S_IDX 2
+#define ST4_TAU_N_V_IDX 3
+#define ST4_DELTA_TAU_N_S_IDX 4
+#define ST4_DELTA_TAU_N_V_IDX 5
+#define ST4_E_N_IDX 6
+#define ST4_NU_1_IDX 7
+#define ST4_P4_IDX 8
+#define ST4_F_T_IDX 9
+#define ST4_NU_2_IDX 10
+#define ST4_N_T_IDX 11
+#define ST4_N_IDX 12
+#define ST4_M_IDX 13
+#define ST4_HC_OFF 14
+
+// Indexes for string number 5
+#define ST5_N_A_IDX 2
+#define ST5_TAU_C_IDX 3
+#define ST5_NU_IDX 4
+#define ST5_N_4_IDX 5
+#define ST5_TAU_GPS_IDX 6
+#define ST5_L_N_IDX 7
+#define ST5_HC_OFF 8
+
+// Indexes for non immediate
+#define ST6_DATA_1_IDX 2
+#define ST6_DATA_2_IDX 3
+#define ST6_HC_OFF 4
+
+
+std::string generate_inp_data(string_data& data) {
+ std::string inp_data = "";
+ for (auto& [b, v] : data) {
+ std::string tmp = std::bitset<64>(v).to_string();
+ inp_data += tmp.substr(64-b, b);
+ }
+ assert(inp_data.size() == 128);
+
+ std::string string_data;
+ string_data.reserve(16);
+ for (int i = 0; i < 128; i+=8) {
+ std::string substr = inp_data.substr(i, 8);
+ string_data.push_back( (uint8_t)std::stoi(substr.c_str(), 0, 2));
+ }
+
+ return string_data;
+}
+
+string_data generate_string_data(uint8_t string_number) {
+
+ srand((unsigned)time(0));
+ string_data data; //
+ data.push_back({1, 0}); // idle chip
+ data.push_back({4, string_number}); // string number
+
+ if (string_number == 1) {
+ data.push_back({2, 3}); // not_used
+ data.push_back({2, 1}); // p1
+ data.push_back({12, 113}); // t_k
+ data.push_back({1, rand() & 1}); // x_vel_sign
+ data.push_back({23, 7122}); // x_vel_value
+ data.push_back({1, rand() & 1}); // x_accel_sign
+ data.push_back({4, 3}); // x_accel_value
+ data.push_back({1, rand() & 1}); // x_sign
+ data.push_back({26, 33554431}); // x_value
+ } else if (string_number == 2) {
+ data.push_back({3, 3}); // b_n
+ data.push_back({1, 1}); // p2
+ data.push_back({7, 123}); // t_b
+ data.push_back({5, 31}); // not_used
+ data.push_back({1, rand() & 1}); // y_vel_sign
+ data.push_back({23, 7422}); // y_vel_value
+ data.push_back({1, rand() & 1}); // y_accel_sign
+ data.push_back({4, 3}); // y_accel_value
+ data.push_back({1, rand() & 1}); // y_sign
+ data.push_back({26, 67108863}); // y_value
+ } else if (string_number == 3) {
+ data.push_back({1, 0}); // p3
+ data.push_back({1, 1}); // gamma_n_sign
+ data.push_back({10, 123}); // gamma_n_value
+ data.push_back({1, 0}); // not_used
+ data.push_back({2, 2}); // p
+ data.push_back({1, 1}); // l_n
+ data.push_back({1, rand() & 1}); // z_vel_sign
+ data.push_back({23, 1337}); // z_vel_value
+ data.push_back({1, rand() & 1}); // z_accel_sign
+ data.push_back({4, 9}); // z_accel_value
+ data.push_back({1, rand() & 1}); // z_sign
+ data.push_back({26, 100023}); // z_value
+ } else if (string_number == 4) {
+ data.push_back({1, rand() & 1}); // tau_n_sign
+ data.push_back({21, 197152}); // tau_n_value
+ data.push_back({1, rand() & 1}); // delta_tau_n_sign
+ data.push_back({4, 4}); // delta_tau_n_value
+ data.push_back({5, 0}); // e_n
+ data.push_back({14, 2}); // not_used_1
+ data.push_back({1, 1}); // p4
+ data.push_back({4, 9}); // f_t
+ data.push_back({3, 3}); // not_used_2
+ data.push_back({11, 2047}); // n_t
+ data.push_back({5, 2}); // n
+ data.push_back({2, 1}); // m
+ } else if (string_number == 5) {
+ data.push_back({11, 2047}); // n_a
+ data.push_back({32, 4294767295}); // tau_c
+ data.push_back({1, 0}); // not_used_1
+ data.push_back({5, 2}); // n_4
+ data.push_back({22, 4114304}); // tau_gps
+ data.push_back({1, 0}); // l_n
+ } else { // non-immediate data is not parsed
+ data.push_back({64, rand()}); // data_1
+ data.push_back({8, 6}); // data_2
+ }
+
+ data.push_back({8, rand() & 0xFF}); // hamming code
+ data.push_back({11, rand() & 0x7FF}); // pad
+ data.push_back({16, rand() & 0xFFFF}); // superframe
+ data.push_back({8, rand() & 0xFF}); // pad
+ data.push_back({8, rand() & 0xFF}); // frame
+ return data;
+}
+
+TEST_CASE("parse_string_number_1"){
+ string_data data = generate_string_data(1);
+ std::string inp_data = generate_inp_data(data);
+
+ kaitai::kstream stream(inp_data);
+ glonass_t gl_string(&stream);
+
+ REQUIRE(gl_string.idle_chip() == data[IDLE_CHIP_IDX].second);
+ REQUIRE(gl_string.string_number() == data[STRING_NUMBER_IDX].second);
+ REQUIRE(gl_string.hamming_code() == data[ST1_HC_OFF + HC_IDX].second);
+ REQUIRE(gl_string.pad_1() == data[ST1_HC_OFF + PAD1_IDX].second);
+ REQUIRE(gl_string.superframe_number() == data[ST1_HC_OFF + SUPERFRAME_IDX].second);
+ REQUIRE(gl_string.pad_2() == data[ST1_HC_OFF + PAD2_IDX].second);
+ REQUIRE(gl_string.frame_number() == data[ST1_HC_OFF + FRAME_IDX].second);
+
+ kaitai::kstream str1(inp_data);
+ glonass_t str1_data(&str1);
+ glonass_t::string_1_t* s1 = static_cast(str1_data.data());
+
+ REQUIRE(s1->not_used() == data[ST1_NU_IDX].second);
+ REQUIRE(s1->p1() == data[ST1_P1_IDX].second);
+ REQUIRE(s1->t_k() == data[ST1_T_K_IDX].second);
+
+ int mul = s1->x_vel_sign() ? (-1) : 1;
+ REQUIRE(s1->x_vel() == (data[ST1_X_VEL_V_IDX].second * mul));
+ mul = s1->x_accel_sign() ? (-1) : 1;
+ REQUIRE(s1->x_accel() == (data[ST1_X_ACCEL_V_IDX].second * mul));
+ mul = s1->x_sign() ? (-1) : 1;
+ REQUIRE(s1->x() == (data[ST1_X_V_IDX].second * mul));
+}
+
+TEST_CASE("parse_string_number_2"){
+ string_data data = generate_string_data(2);
+ std::string inp_data = generate_inp_data(data);
+
+ kaitai::kstream stream(inp_data);
+ glonass_t gl_string(&stream);
+
+ REQUIRE(gl_string.idle_chip() == data[IDLE_CHIP_IDX].second);
+ REQUIRE(gl_string.string_number() == data[STRING_NUMBER_IDX].second);
+ REQUIRE(gl_string.hamming_code() == data[ST2_HC_OFF + HC_IDX].second);
+ REQUIRE(gl_string.pad_1() == data[ST2_HC_OFF + PAD1_IDX].second);
+ REQUIRE(gl_string.superframe_number() == data[ST2_HC_OFF + SUPERFRAME_IDX].second);
+ REQUIRE(gl_string.pad_2() == data[ST2_HC_OFF + PAD2_IDX].second);
+ REQUIRE(gl_string.frame_number() == data[ST2_HC_OFF + FRAME_IDX].second);
+
+ kaitai::kstream str2(inp_data);
+ glonass_t str2_data(&str2);
+ glonass_t::string_2_t* s2 = static_cast(str2_data.data());
+
+ REQUIRE(s2->b_n() == data[ST2_BN_IDX].second);
+ REQUIRE(s2->not_used() == data[ST2_NU_IDX].second);
+ REQUIRE(s2->p2() == data[ST2_P2_IDX].second);
+ REQUIRE(s2->t_b() == data[ST2_TB_IDX].second);
+ int mul = s2->y_vel_sign() ? (-1) : 1;
+ REQUIRE(s2->y_vel() == (data[ST2_Y_VEL_V_IDX].second * mul));
+ mul = s2->y_accel_sign() ? (-1) : 1;
+ REQUIRE(s2->y_accel() == (data[ST2_Y_ACCEL_V_IDX].second * mul));
+ mul = s2->y_sign() ? (-1) : 1;
+ REQUIRE(s2->y() == (data[ST2_Y_V_IDX].second * mul));
+}
+
+TEST_CASE("parse_string_number_3"){
+ string_data data = generate_string_data(3);
+ std::string inp_data = generate_inp_data(data);
+
+ kaitai::kstream stream(inp_data);
+ glonass_t gl_string(&stream);
+
+ REQUIRE(gl_string.idle_chip() == data[IDLE_CHIP_IDX].second);
+ REQUIRE(gl_string.string_number() == data[STRING_NUMBER_IDX].second);
+ REQUIRE(gl_string.hamming_code() == data[ST3_HC_OFF + HC_IDX].second);
+ REQUIRE(gl_string.pad_1() == data[ST3_HC_OFF + PAD1_IDX].second);
+ REQUIRE(gl_string.superframe_number() == data[ST3_HC_OFF + SUPERFRAME_IDX].second);
+ REQUIRE(gl_string.pad_2() == data[ST3_HC_OFF + PAD2_IDX].second);
+ REQUIRE(gl_string.frame_number() == data[ST3_HC_OFF + FRAME_IDX].second);
+
+ kaitai::kstream str3(inp_data);
+ glonass_t str3_data(&str3);
+ glonass_t::string_3_t* s3 = static_cast(str3_data.data());
+
+ REQUIRE(s3->p3() == data[ST3_P3_IDX].second);
+ int mul = s3->gamma_n_sign() ? (-1) : 1;
+ REQUIRE(s3->gamma_n() == (data[ST3_GAMMA_N_V_IDX].second * mul));
+ REQUIRE(s3->not_used() == data[ST3_NU_1_IDX].second);
+ REQUIRE(s3->p() == data[ST3_P_IDX].second);
+ REQUIRE(s3->l_n() == data[ST3_L_N_IDX].second);
+ mul = s3->z_vel_sign() ? (-1) : 1;
+ REQUIRE(s3->z_vel() == (data[ST3_Z_VEL_V_IDX].second * mul));
+ mul = s3->z_accel_sign() ? (-1) : 1;
+ REQUIRE(s3->z_accel() == (data[ST3_Z_ACCEL_V_IDX].second * mul));
+ mul = s3->z_sign() ? (-1) : 1;
+ REQUIRE(s3->z() == (data[ST3_Z_V_IDX].second * mul));
+}
+
+TEST_CASE("parse_string_number_4"){
+ string_data data = generate_string_data(4);
+ std::string inp_data = generate_inp_data(data);
+
+ kaitai::kstream stream(inp_data);
+ glonass_t gl_string(&stream);
+
+ REQUIRE(gl_string.idle_chip() == data[IDLE_CHIP_IDX].second);
+ REQUIRE(gl_string.string_number() == data[STRING_NUMBER_IDX].second);
+ REQUIRE(gl_string.hamming_code() == data[ST4_HC_OFF + HC_IDX].second);
+ REQUIRE(gl_string.pad_1() == data[ST4_HC_OFF + PAD1_IDX].second);
+ REQUIRE(gl_string.superframe_number() == data[ST4_HC_OFF + SUPERFRAME_IDX].second);
+ REQUIRE(gl_string.pad_2() == data[ST4_HC_OFF + PAD2_IDX].second);
+ REQUIRE(gl_string.frame_number() == data[ST4_HC_OFF + FRAME_IDX].second);
+
+ kaitai::kstream str4(inp_data);
+ glonass_t str4_data(&str4);
+ glonass_t::string_4_t* s4 = static_cast(str4_data.data());
+
+ int mul = s4->tau_n_sign() ? (-1) : 1;
+ REQUIRE(s4->tau_n() == (data[ST4_TAU_N_V_IDX].second * mul));
+ mul = s4->delta_tau_n_sign() ? (-1) : 1;
+ REQUIRE(s4->delta_tau_n() == (data[ST4_DELTA_TAU_N_V_IDX].second * mul));
+ REQUIRE(s4->e_n() == data[ST4_E_N_IDX].second);
+ REQUIRE(s4->not_used_1() == data[ST4_NU_1_IDX].second);
+ REQUIRE(s4->p4() == data[ST4_P4_IDX].second);
+ REQUIRE(s4->f_t() == data[ST4_F_T_IDX].second);
+ REQUIRE(s4->not_used_2() == data[ST4_NU_2_IDX].second);
+ REQUIRE(s4->n_t() == data[ST4_N_T_IDX].second);
+ REQUIRE(s4->n() == data[ST4_N_IDX].second);
+ REQUIRE(s4->m() == data[ST4_M_IDX].second);
+}
+
+TEST_CASE("parse_string_number_5"){
+ string_data data = generate_string_data(5);
+ std::string inp_data = generate_inp_data(data);
+
+ kaitai::kstream stream(inp_data);
+ glonass_t gl_string(&stream);
+
+ REQUIRE(gl_string.idle_chip() == data[IDLE_CHIP_IDX].second);
+ REQUIRE(gl_string.string_number() == data[STRING_NUMBER_IDX].second);
+ REQUIRE(gl_string.hamming_code() == data[ST5_HC_OFF + HC_IDX].second);
+ REQUIRE(gl_string.pad_1() == data[ST5_HC_OFF + PAD1_IDX].second);
+ REQUIRE(gl_string.superframe_number() == data[ST5_HC_OFF + SUPERFRAME_IDX].second);
+ REQUIRE(gl_string.pad_2() == data[ST5_HC_OFF + PAD2_IDX].second);
+ REQUIRE(gl_string.frame_number() == data[ST5_HC_OFF + FRAME_IDX].second);
+
+ kaitai::kstream str5(inp_data);
+ glonass_t str5_data(&str5);
+ glonass_t::string_5_t* s5 = static_cast(str5_data.data());
+
+ REQUIRE(s5->n_a() == data[ST5_N_A_IDX].second);
+ REQUIRE(s5->tau_c() == data[ST5_TAU_C_IDX].second);
+ REQUIRE(s5->not_used() == data[ST5_NU_IDX].second);
+ REQUIRE(s5->n_4() == data[ST5_N_4_IDX].second);
+ REQUIRE(s5->tau_gps() == data[ST5_TAU_GPS_IDX].second);
+ REQUIRE(s5->l_n() == data[ST5_L_N_IDX].second);
+}
+
+TEST_CASE("parse_string_number_NI"){
+ string_data data = generate_string_data((rand() % 10) + 6);
+ std::string inp_data = generate_inp_data(data);
+
+ kaitai::kstream stream(inp_data);
+ glonass_t gl_string(&stream);
+
+ REQUIRE(gl_string.idle_chip() == data[IDLE_CHIP_IDX].second);
+ REQUIRE(gl_string.string_number() == data[STRING_NUMBER_IDX].second);
+ REQUIRE(gl_string.hamming_code() == data[ST6_HC_OFF + HC_IDX].second);
+ REQUIRE(gl_string.pad_1() == data[ST6_HC_OFF + PAD1_IDX].second);
+ REQUIRE(gl_string.superframe_number() == data[ST6_HC_OFF + SUPERFRAME_IDX].second);
+ REQUIRE(gl_string.pad_2() == data[ST6_HC_OFF + PAD2_IDX].second);
+ REQUIRE(gl_string.frame_number() == data[ST6_HC_OFF + FRAME_IDX].second);
+
+ kaitai::kstream strni(inp_data);
+ glonass_t strni_data(&strni);
+ glonass_t::string_non_immediate_t* sni = static_cast(strni_data.data());
+
+ REQUIRE(sni->data_1() == data[ST6_DATA_1_IDX].second);
+ REQUIRE(sni->data_2() == data[ST6_DATA_2_IDX].second);
+}
diff --git a/selfdrive/locationd/test/test_glonass_runner.cc b/selfdrive/locationd/test/test_glonass_runner.cc
new file mode 100644
index 0000000000..62bf7476a1
--- /dev/null
+++ b/selfdrive/locationd/test/test_glonass_runner.cc
@@ -0,0 +1,2 @@
+#define CATCH_CONFIG_MAIN
+#include "catch2/catch.hpp"
diff --git a/selfdrive/locationd/test/test_laikad.py b/selfdrive/locationd/test/test_laikad.py
index 198ecfe935..10ac7790b6 100755
--- a/selfdrive/locationd/test/test_laikad.py
+++ b/selfdrive/locationd/test/test_laikad.py
@@ -4,7 +4,7 @@ import unittest
from collections import defaultdict
from datetime import datetime
from unittest import mock
-from unittest.mock import Mock, patch
+from unittest.mock import patch
from common.params import Params
from laika.constants import SECS_IN_DAY
@@ -22,7 +22,24 @@ def get_log(segs=range(0)):
logs = []
for i in segs:
logs.extend(LogReader(get_url("4cf7a6ad03080c90|2021-09-29--13-46-36", i)))
- return [m for m in logs if m.which() == 'ubloxGnss']
+
+ all_logs = [m for m in logs if m.which() == 'ubloxGnss']
+ low_gnss = []
+ for m in all_logs:
+ if m.ubloxGnss.which() != 'measurementReport':
+ continue
+
+ MAX_MEAS = 7
+ if m.ubloxGnss.measurementReport.numMeas > MAX_MEAS:
+ mb = m.as_builder()
+ mb.ubloxGnss.measurementReport.numMeas = MAX_MEAS
+ mb.ubloxGnss.measurementReport.measurements = list(m.ubloxGnss.measurementReport.measurements)[:MAX_MEAS]
+ mb.ubloxGnss.measurementReport.measurements[0].pseudorange += 1000
+ low_gnss.append(mb.as_reader())
+ else:
+ low_gnss.append(m)
+
+ return all_logs, low_gnss
def verify_messages(lr, laikad, return_one_success=False):
@@ -59,55 +76,56 @@ class TestLaikad(unittest.TestCase):
@classmethod
def setUpClass(cls):
- logs = get_log(range(1))
+ logs, low_gnss = get_log(range(1))
cls.logs = logs
+ cls.low_gnss = low_gnss
first_gps_time = get_first_gps_time(logs)
cls.first_gps_time = first_gps_time
def setUp(self):
Params().remove(EPHEMERIS_CACHE)
- def test_fetch_orbits_non_blocking(self):
+ def test_fetch_navs_non_blocking(self):
gpstime = GPSTime.from_datetime(datetime(2021, month=3, day=1))
laikad = Laikad()
- laikad.fetch_orbits(gpstime, block=False)
+ laikad.fetch_navs(gpstime, block=False)
laikad.orbit_fetch_future.result(30)
# Get results and save orbits to laikad:
- laikad.fetch_orbits(gpstime, block=False)
+ laikad.fetch_navs(gpstime, block=False)
- ephem = laikad.astro_dog.orbits['G01'][0]
+ ephem = laikad.astro_dog.navs['G01'][0]
self.assertIsNotNone(ephem)
- laikad.fetch_orbits(gpstime+2*SECS_IN_DAY, block=False)
+ laikad.fetch_navs(gpstime+2*SECS_IN_DAY, block=False)
laikad.orbit_fetch_future.result(30)
# Get results and save orbits to laikad:
- laikad.fetch_orbits(gpstime + 2 * SECS_IN_DAY, block=False)
+ laikad.fetch_navs(gpstime + 2 * SECS_IN_DAY, block=False)
- ephem2 = laikad.astro_dog.orbits['G01'][0]
+ ephem2 = laikad.astro_dog.navs['G01'][0]
self.assertIsNotNone(ephem)
self.assertNotEqual(ephem, ephem2)
- def test_fetch_orbits_with_wrong_clocks(self):
+ def test_fetch_navs_with_wrong_clocks(self):
laikad = Laikad()
- def check_has_orbits():
- self.assertGreater(len(laikad.astro_dog.orbits), 0)
- ephem = laikad.astro_dog.orbits['G01'][0]
+ def check_has_navs():
+ self.assertGreater(len(laikad.astro_dog.navs), 0)
+ ephem = laikad.astro_dog.navs['G01'][0]
self.assertIsNotNone(ephem)
real_current_time = GPSTime.from_datetime(datetime(2021, month=3, day=1))
wrong_future_clock_time = real_current_time + SECS_IN_DAY
- laikad.fetch_orbits(wrong_future_clock_time, block=True)
- check_has_orbits()
- self.assertEqual(laikad.last_fetch_orbits_t, wrong_future_clock_time)
+ laikad.fetch_navs(wrong_future_clock_time, block=True)
+ check_has_navs()
+ self.assertEqual(laikad.last_fetch_navs_t, wrong_future_clock_time)
# Test fetching orbits with earlier time
- assert real_current_time < laikad.last_fetch_orbits_t
+ assert real_current_time < laikad.last_fetch_navs_t
laikad.astro_dog.orbits = {}
- laikad.fetch_orbits(real_current_time, block=True)
- check_has_orbits()
- self.assertEqual(laikad.last_fetch_orbits_t, real_current_time)
+ laikad.fetch_navs(real_current_time, block=True)
+ check_has_navs()
+ self.assertEqual(laikad.last_fetch_navs_t, real_current_time)
def test_ephemeris_source_in_msg(self):
data_mock = defaultdict(str)
@@ -115,22 +133,22 @@ class TestLaikad(unittest.TestCase):
gpstime = GPS_TIME_PREDICTION_ORBITS_RUSSIAN_SRC
laikad = Laikad()
- laikad.fetch_orbits(gpstime, block=True)
- meas = get_measurement_mock(gpstime, laikad.astro_dog.orbits['R01'][0])
+ laikad.fetch_navs(gpstime, block=True)
+ meas = get_measurement_mock(gpstime, laikad.astro_dog.navs['R01'][0])
msg = create_measurement_msg(meas)
- self.assertEqual(msg.ephemerisSource.type.raw, EphemerisSourceType.glonassIacUltraRapid)
+ self.assertEqual(msg.ephemerisSource.type.raw, EphemerisSourceType.nav)
# Verify gps satellite returns same source
- meas = get_measurement_mock(gpstime, laikad.astro_dog.orbits['R01'][0])
+ meas = get_measurement_mock(gpstime, laikad.astro_dog.navs['R01'][0])
msg = create_measurement_msg(meas)
- self.assertEqual(msg.ephemerisSource.type.raw, EphemerisSourceType.glonassIacUltraRapid)
+ self.assertEqual(msg.ephemerisSource.type.raw, EphemerisSourceType.nav)
# Test nasa source by using older date
gpstime = GPSTime.from_datetime(datetime(2021, month=3, day=1))
laikad = Laikad()
- laikad.fetch_orbits(gpstime, block=True)
- meas = get_measurement_mock(gpstime, laikad.astro_dog.orbits['G01'][0])
+ laikad.fetch_navs(gpstime, block=True)
+ meas = get_measurement_mock(gpstime, laikad.astro_dog.navs['G01'][0])
msg = create_measurement_msg(meas)
- self.assertEqual(msg.ephemerisSource.type.raw, EphemerisSourceType.nasaUltraRapid)
+ self.assertEqual(msg.ephemerisSource.type.raw, EphemerisSourceType.nav)
# Test nav source type
ephem = GPSEphemeris(data_mock, gpstime)
@@ -142,7 +160,7 @@ class TestLaikad(unittest.TestCase):
laikad = Laikad(auto_update=True, valid_ephem_types=EphemerisType.ULTRA_RAPID_ORBIT)
correct_msgs = verify_messages(self.logs, laikad)
- correct_msgs_expected = 555
+ correct_msgs_expected = 559
self.assertEqual(correct_msgs_expected, len(correct_msgs))
self.assertEqual(correct_msgs_expected, len([m for m in correct_msgs if m.gnssMeasurements.positionECEF.valid]))
@@ -161,7 +179,6 @@ class TestLaikad(unittest.TestCase):
def test_laika_online_nav_only(self):
laikad = Laikad(auto_update=True, valid_ephem_types=EphemerisType.NAV)
# Disable fetch_orbits to test NAV only
- laikad.fetch_orbits = Mock()
correct_msgs = verify_messages(self.logs, laikad)
correct_msgs_expected = 559
self.assertEqual(correct_msgs_expected, len(correct_msgs))
@@ -171,45 +188,45 @@ class TestLaikad(unittest.TestCase):
def test_laika_offline(self, downloader_mock):
downloader_mock.side_effect = DownloadFailed("Mock download failed")
laikad = Laikad(auto_update=False)
- laikad.fetch_orbits(GPS_TIME_PREDICTION_ORBITS_RUSSIAN_SRC, block=True)
+ laikad.fetch_navs(GPS_TIME_PREDICTION_ORBITS_RUSSIAN_SRC, block=True)
@mock.patch('laika.downloader.download_and_cache_file')
def test_download_failed_russian_source(self, downloader_mock):
downloader_mock.side_effect = DownloadFailed
laikad = Laikad(auto_update=False)
correct_msgs = verify_messages(self.logs, laikad)
- self.assertEqual(16, len(correct_msgs))
- self.assertEqual(16, len([m for m in correct_msgs if m.gnssMeasurements.positionECEF.valid]))
+ self.assertEqual(255, len(correct_msgs))
+ self.assertEqual(255, len([m for m in correct_msgs if m.gnssMeasurements.positionECEF.valid]))
def test_laika_get_orbits(self):
laikad = Laikad(auto_update=False)
# Pretend process has loaded the orbits on startup by using the time of the first gps message.
- laikad.fetch_orbits(self.first_gps_time, block=True)
- self.dict_has_values(laikad.astro_dog.orbits)
+ laikad.fetch_navs(self.first_gps_time, block=True)
+ self.dict_has_values(laikad.astro_dog.navs)
@unittest.skip("Use to debug live data")
- def test_laika_get_orbits_now(self):
+ def test_laika_get_navs_now(self):
laikad = Laikad(auto_update=False)
- laikad.fetch_orbits(GPSTime.from_datetime(datetime.utcnow()), block=True)
+ laikad.fetch_navs(GPSTime.from_datetime(datetime.utcnow()), block=True)
prn = "G01"
- self.assertGreater(len(laikad.astro_dog.orbits[prn]), 0)
+ self.assertGreater(len(laikad.astro_dog.navs[prn]), 0)
prn = "R01"
- self.assertGreater(len(laikad.astro_dog.orbits[prn]), 0)
- print(min(laikad.astro_dog.orbits[prn], key=lambda e: e.epoch).epoch.as_datetime())
+ self.assertGreater(len(laikad.astro_dog.navs[prn]), 0)
+ print(min(laikad.astro_dog.navs[prn], key=lambda e: e.epoch).epoch.as_datetime())
- def test_get_orbits_in_process(self):
+ def test_get_navs_in_process(self):
laikad = Laikad(auto_update=False)
- has_orbits = False
+ has_navs = False
for m in self.logs:
laikad.process_gnss_msg(m.ubloxGnss, m.logMonoTime, block=False)
if laikad.orbit_fetch_future is not None:
laikad.orbit_fetch_future.result()
- vals = laikad.astro_dog.orbits.values()
- has_orbits = len(vals) > 0 and max([len(v) for v in vals]) > 0
- if has_orbits:
+ vals = laikad.astro_dog.navs.values()
+ has_navs = len(vals) > 0 and max([len(v) for v in vals]) > 0
+ if has_navs:
break
- self.assertTrue(has_orbits)
- self.assertGreater(len(laikad.astro_dog.orbit_fetched_times._ranges), 0)
+ self.assertTrue(has_navs)
+ self.assertGreater(len(laikad.astro_dog.navs_fetched_times._ranges), 0)
self.assertEqual(None, laikad.orbit_fetch_future)
def test_cache(self):
@@ -228,17 +245,16 @@ class TestLaikad(unittest.TestCase):
wait_for_cache()
Params().remove(EPHEMERIS_CACHE)
- laikad.astro_dog.get_navs(self.first_gps_time)
- laikad.fetch_orbits(self.first_gps_time, block=True)
+ #laikad.astro_dog.get_navs(self.first_gps_time)
+ laikad.fetch_navs(self.first_gps_time, block=True)
# Wait for cache to save
wait_for_cache()
# Check both nav and orbits separate
laikad = Laikad(auto_update=False, valid_ephem_types=EphemerisType.NAV, save_ephemeris=True)
- # Verify orbits and nav are loaded from cache
- self.dict_has_values(laikad.astro_dog.orbits)
- self.dict_has_values(laikad.astro_dog.nav)
+ # Verify navs are loaded from cache
+ self.dict_has_values(laikad.astro_dog.navs)
# Verify cache is working for only nav by running a segment
msg = verify_messages(self.logs, laikad, return_one_success=True)
self.assertIsNotNone(msg)
@@ -246,7 +262,7 @@ class TestLaikad(unittest.TestCase):
with patch('selfdrive.locationd.laikad.get_orbit_data', return_value=None) as mock_method:
# Verify no orbit downloads even if orbit fetch times is reset since the cache has recently been saved and we don't want to download high frequently
laikad.astro_dog.orbit_fetched_times = TimeRangeHolder()
- laikad.fetch_orbits(self.first_gps_time, block=False)
+ laikad.fetch_navs(self.first_gps_time, block=False)
mock_method.assert_not_called()
# Verify cache is working for only orbits by running a segment
@@ -256,6 +272,18 @@ class TestLaikad(unittest.TestCase):
# Verify orbit data is not downloaded
mock_method.assert_not_called()
+ def test_low_gnss_meas(self):
+ cnt = 0
+ laikad = Laikad()
+ for m in self.low_gnss:
+ msg = laikad.process_gnss_msg(m.ubloxGnss, m.logMonoTime, block=True)
+ if msg is None:
+ continue
+ gm = msg.gnssMeasurements
+ if len(gm.correctedMeasurements) != 0 and gm.positionECEF.valid:
+ cnt += 1
+ self.assertEqual(cnt, 559)
+
def dict_has_values(self, dct):
self.assertGreater(len(dct), 0)
self.assertGreater(min([len(v) for v in dct.values()]), 0)
diff --git a/selfdrive/locationd/test/test_locationd.py b/selfdrive/locationd/test/test_locationd.py
index 7569530211..9f643e2b8f 100755
--- a/selfdrive/locationd/test/test_locationd.py
+++ b/selfdrive/locationd/test/test_locationd.py
@@ -8,6 +8,7 @@ import capnp
import cereal.messaging as messaging
from cereal.services import service_list
from common.params import Params
+from common.transformations.coordinates import ecef2geodetic
from selfdrive.manager.process_config import managed_processes
@@ -45,16 +46,25 @@ class TestLocationdProc(unittest.TestCase):
except capnp.lib.capnp.KjException:
msg = messaging.new_message(name, 0)
+
if name == "gpsLocationExternal":
msg.gpsLocationExternal.flags = 1
msg.gpsLocationExternal.verticalAccuracy = 1.0
msg.gpsLocationExternal.speedAccuracy = 1.0
msg.gpsLocationExternal.bearingAccuracyDeg = 1.0
msg.gpsLocationExternal.vNED = [0.0, 0.0, 0.0]
- msg.gpsLocationExternal.latitude = self.lat
- msg.gpsLocationExternal.longitude = self.lon
+ msg.gpsLocationExternal.latitude = float(self.lat)
+ msg.gpsLocationExternal.longitude = float(self.lon)
msg.gpsLocationExternal.unixTimestampMillis = t * 1e6
- msg.gpsLocationExternal.altitude = self.alt
+ msg.gpsLocationExternal.altitude = float(self.alt)
+ #if name == "gnssMeasurements":
+ # msg.gnssMeasurements.measTime = t
+ # msg.gnssMeasurements.positionECEF.value = [self.x , self.y, self.z]
+ # msg.gnssMeasurements.positionECEF.std = [0,0,0]
+ # msg.gnssMeasurements.positionECEF.valid = True
+ # msg.gnssMeasurements.velocityECEF.value = []
+ # msg.gnssMeasurements.velocityECEF.std = [0,0,0]
+ # msg.gnssMeasurements.velocityECEF.valid = True
elif name == 'cameraOdometry':
msg.cameraOdometry.rot = [0.0, 0.0, 0.0]
msg.cameraOdometry.rotStd = [0.0, 0.0, 0.0]
@@ -67,9 +77,11 @@ class TestLocationdProc(unittest.TestCase):
# first reset params
Params().remove('LastGPSPosition')
- self.lat = 30 + (random.random() * 10.0)
- self.lon = -70 + (random.random() * 10.0)
- self.alt = 5 + (random.random() * 10.0)
+ self.x = -2710700 + (random.random() * 1e5)
+ self.y = -4280600 + (random.random() * 1e5)
+ self.z = 3850300 + (random.random() * 1e5)
+ self.lat, self.lon, self.alt = ecef2geodetic([self.x, self.y, self.z])
+
self.fake_duration = 90 # secs
# get fake messages at the correct frequency, listed in services.py
fake_msgs = []
@@ -83,7 +95,6 @@ class TestLocationdProc(unittest.TestCase):
time.sleep(1) # wait for async params write
lastGPS = json.loads(Params().get('LastGPSPosition'))
-
self.assertAlmostEqual(lastGPS['latitude'], self.lat, places=3)
self.assertAlmostEqual(lastGPS['longitude'], self.lon, places=3)
self.assertAlmostEqual(lastGPS['altitude'], self.alt, places=3)
diff --git a/selfdrive/locationd/test/test_ublox_processing.py b/selfdrive/locationd/test/test_ublox_processing.py
index 427003b24c..cd4ce0de04 100755
--- a/selfdrive/locationd/test/test_ublox_processing.py
+++ b/selfdrive/locationd/test/test_ublox_processing.py
@@ -1,13 +1,15 @@
import unittest
-
+import time
import numpy as np
from laika import AstroDog
from laika.helpers import ConstellationId
-from laika.raw_gnss import calc_pos_fix, correct_measurements, process_measurements, read_raw_ublox
+from laika.raw_gnss import correct_measurements, process_measurements, read_raw_ublox
+from laika.opt import calc_pos_fix
from selfdrive.test.openpilotci import get_url
from tools.lib.logreader import LogReader
-
+from selfdrive.test.helpers import with_processes
+import cereal.messaging as messaging
def get_gnss_measurements(log_reader):
gnss_measurements = []
@@ -20,6 +22,12 @@ def get_gnss_measurements(log_reader):
gnss_measurements.append(read_raw_ublox(report))
return gnss_measurements
+def get_ublox_raw(log_reader):
+ ublox_raw = []
+ for msg in log_reader:
+ if msg.which() == "ubloxRaw":
+ ublox_raw.append(msg)
+ return ublox_raw
class TestUbloxProcessing(unittest.TestCase):
NUM_TEST_PROCESS_MEAS = 10
@@ -29,6 +37,10 @@ class TestUbloxProcessing(unittest.TestCase):
lr = LogReader(get_url("4cf7a6ad03080c90|2021-09-29--13-46-36", 0))
cls.gnss_measurements = get_gnss_measurements(lr)
+ # test gps ephemeris continuity check (drive has ephemeris issues with cutover data)
+ lr = LogReader(get_url("37b6542f3211019a|2023-01-15--23-45-10", 14))
+ cls.ublox_raw = get_ublox_raw(lr)
+
def test_read_ublox_raw(self):
count_gps = 0
count_glonass = 0
@@ -54,14 +66,14 @@ class TestUbloxProcessing(unittest.TestCase):
processed_meas = process_measurements(measurements, dog)
count_processed_measurements += len(processed_meas)
pos_fix = calc_pos_fix(processed_meas)
- if len(pos_fix) > 0 and all(pos_fix[0] != 0):
+ if len(pos_fix) > 0 and all(p != 0 for p in pos_fix[0]):
position_fix_found += 1
corrected_meas = correct_measurements(processed_meas, pos_fix[0][:3], dog)
count_corrected_measurements += len(corrected_meas)
pos_fix = calc_pos_fix(corrected_meas)
- if len(pos_fix) > 0 and all(pos_fix[0] != 0):
+ if len(pos_fix) > 0 and all(p != 0 for p in pos_fix[0]):
pos_ests.append(pos_fix[0])
position_fix_found_after_correcting += 1
@@ -75,6 +87,29 @@ class TestUbloxProcessing(unittest.TestCase):
self.assertEqual(count_processed_measurements, 69)
self.assertEqual(count_corrected_measurements, 69)
+ @with_processes(['ubloxd'])
+ def test_ublox_gps_cutover(self):
+ time.sleep(2)
+ ugs = messaging.sub_sock("ubloxGnss", timeout=0.1)
+ ur_pm = messaging.PubMaster(['ubloxRaw'])
+
+ def replay_segment():
+ rcv_msgs = []
+ for msg in self.ublox_raw:
+ ur_pm.send(msg.which(), msg.as_builder())
+ time.sleep(0.01)
+ rcv_msgs += messaging.drain_sock(ugs)
+
+ time.sleep(0.1)
+ rcv_msgs += messaging.drain_sock(ugs)
+ return rcv_msgs
+
+ # replay twice to enforce cutover data on rewind
+ rcv_msgs = replay_segment()
+ rcv_msgs += replay_segment()
+
+ ephems_cnt = sum(m.ubloxGnss.which() == 'ephemeris' for m in rcv_msgs)
+ self.assertEqual(ephems_cnt, 15)
if __name__ == "__main__":
unittest.main()
diff --git a/selfdrive/locationd/torqued.py b/selfdrive/locationd/torqued.py
index 588bca1578..fcc068d34e 100755
--- a/selfdrive/locationd/torqued.py
+++ b/selfdrive/locationd/torqued.py
@@ -22,15 +22,15 @@ FIT_POINTS_TOTAL_QLOG = 600
MIN_VEL = 15 # m/s
FRICTION_FACTOR = 1.5 # ~85% of data coverage
FACTOR_SANITY = 0.3
+FACTOR_SANITY_QLOG = 0.5
FRICTION_SANITY = 0.5
+FRICTION_SANITY_QLOG = 0.8
STEER_MIN_THRESHOLD = 0.02
MIN_FILTER_DECAY = 50
MAX_FILTER_DECAY = 250
LAT_ACC_THRESHOLD = 1
STEER_BUCKET_BOUNDS = [(-0.5, -0.3), (-0.3, -0.2), (-0.2, -0.1), (-0.1, 0), (0, 0.1), (0.1, 0.2), (0.2, 0.3), (0.3, 0.5)]
MIN_BUCKET_POINTS = np.array([100, 300, 500, 500, 500, 500, 300, 100])
-MAX_RESETS = 5.0
-MAX_INVALID_THRESHOLD = 10
MIN_ENGAGE_BUFFER = 2 # secs
VERSION = 1 # bump this to invalidate old parameter caches
@@ -100,10 +100,15 @@ class TorqueEstimator:
self.min_bucket_points = MIN_BUCKET_POINTS / 10
self.min_points_total = MIN_POINTS_TOTAL_QLOG
self.fit_points = FIT_POINTS_TOTAL_QLOG
+ self.factor_sanity = FACTOR_SANITY_QLOG
+ self.friction_sanity = FRICTION_SANITY_QLOG
+
else:
self.min_bucket_points = MIN_BUCKET_POINTS
self.min_points_total = MIN_POINTS_TOTAL
self.fit_points = FIT_POINTS_TOTAL
+ self.factor_sanity = FACTOR_SANITY
+ self.friction_sanity = FRICTION_SANITY
self.offline_friction = 0.0
self.offline_latAccelFactor = 0.0
@@ -123,10 +128,10 @@ class TorqueEstimator:
'points': []
}
self.decay = MIN_FILTER_DECAY
- self.min_lataccel_factor = (1.0 - FACTOR_SANITY) * self.offline_latAccelFactor
- self.max_lataccel_factor = (1.0 + FACTOR_SANITY) * self.offline_latAccelFactor
- self.min_friction = (1.0 - FRICTION_SANITY) * self.offline_friction
- self.max_friction = (1.0 + FRICTION_SANITY) * self.offline_friction
+ self.min_lataccel_factor = (1.0 - self.factor_sanity) * self.offline_latAccelFactor
+ self.max_lataccel_factor = (1.0 + self.factor_sanity) * self.offline_latAccelFactor
+ self.min_friction = (1.0 - self.friction_sanity) * self.offline_friction
+ self.max_friction = (1.0 + self.friction_sanity) * self.offline_friction
# try to restore cached params
params = Params()
@@ -165,7 +170,6 @@ class TorqueEstimator:
def reset(self):
self.resets += 1.0
- self.invalid_values_tracker = 0.0
self.decay = MIN_FILTER_DECAY
self.raw_points = defaultdict(lambda: deque(maxlen=self.hist_len))
self.filtered_points = PointBuckets(x_bounds=STEER_BUCKET_BOUNDS, min_points=self.min_bucket_points, min_points_total=self.min_points_total)
@@ -190,12 +194,6 @@ class TorqueEstimator:
self.filtered_params[param].update(value)
self.filtered_params[param].update_alpha(self.decay)
- def is_sane(self, latAccelFactor, latAccelOffset, friction):
- if any([val is None or np.isnan(val) for val in [latAccelFactor, latAccelOffset, friction]]):
- return False
- return (self.max_friction >= friction >= self.min_friction) and\
- (self.max_lataccel_factor >= latAccelFactor >= self.min_lataccel_factor)
-
def handle_log(self, t, which, msg):
if which == "carControl":
self.raw_points["carControl_t"].append(t + self.lag)
@@ -225,23 +223,20 @@ class TorqueEstimator:
liveTorqueParameters.useParams = self.use_params
if self.filtered_points.is_valid():
- latAccelFactor, latAccelOffset, friction_coeff = self.estimate_params()
+ latAccelFactor, latAccelOffset, frictionCoeff = self.estimate_params()
liveTorqueParameters.latAccelFactorRaw = float(latAccelFactor)
liveTorqueParameters.latAccelOffsetRaw = float(latAccelOffset)
- liveTorqueParameters.frictionCoefficientRaw = float(friction_coeff)
+ liveTorqueParameters.frictionCoefficientRaw = float(frictionCoeff)
- if self.is_sane(latAccelFactor, latAccelOffset, friction_coeff):
- liveTorqueParameters.liveValid = True
- self.update_params({'latAccelFactor': latAccelFactor, 'latAccelOffset': latAccelOffset, 'frictionCoefficient': friction_coeff})
- self.invalid_values_tracker = max(0.0, self.invalid_values_tracker - 0.5)
- else:
- cloudlog.exception("Live torque parameters are outside acceptable bounds.")
+ if any([val is None or np.isnan(val) for val in [latAccelFactor, latAccelOffset, frictionCoeff]]):
+ cloudlog.exception("Live torque parameters are invalid.")
liveTorqueParameters.liveValid = False
- self.invalid_values_tracker += 1.0
- # Reset when ~10 invalid over 5 secs
- if self.invalid_values_tracker > MAX_INVALID_THRESHOLD:
- # Do not reset the filter as it may cause a drastic jump, just reset points
- self.reset()
+ self.reset()
+ else:
+ liveTorqueParameters.liveValid = True
+ latAccelFactor = np.clip(latAccelFactor, self.min_lataccel_factor, self.max_lataccel_factor)
+ frictionCoeff = np.clip(frictionCoeff, self.min_friction, self.max_friction)
+ self.update_params({'latAccelFactor': latAccelFactor, 'latAccelOffset': latAccelOffset, 'frictionCoefficient': frictionCoeff})
else:
liveTorqueParameters.liveValid = False
diff --git a/selfdrive/locationd/ublox_msg.cc b/selfdrive/locationd/ublox_msg.cc
index b45dffae33..b746989466 100644
--- a/selfdrive/locationd/ublox_msg.cc
+++ b/selfdrive/locationd/ublox_msg.cc
@@ -65,6 +65,21 @@ inline bool UbloxMsgParser::valid_so_far() {
return true;
}
+inline uint16_t UbloxMsgParser::get_glonass_year(uint8_t N4, uint16_t Nt) {
+ // convert time to year (conversion from A3.1.3)
+ int J = 0;
+ if (1 <= Nt && Nt <= 366) {
+ J = 1;
+ } else if (367 <= Nt && Nt <= 731) {
+ J = 2;
+ } else if (732 <= Nt && Nt <= 1096) {
+ J = 3;
+ } else if (1097 <= Nt && Nt <= 1461) {
+ J = 4;
+ }
+ uint16_t year = 1996 + 4*(N4 -1) + (J - 1);
+ return year;
+}
bool UbloxMsgParser::add_data(const uint8_t *incoming_data, uint32_t incoming_data_len, size_t &bytes_consumed) {
int needed = needed_bytes();
@@ -103,9 +118,9 @@ std::pair> UbloxMsgParser::gen_msg() {
switch (ubx_message.msg_type()) {
case 0x0107:
return {"gpsLocationExternal", gen_nav_pvt(static_cast(body))};
- case 0x0213:
+ case 0x0213: // UBX-RXM-SFRB (Broadcast Navigation Data Subframe)
return {"ubloxGnss", gen_rxm_sfrbx(static_cast(body))};
- case 0x0215:
+ case 0x0215: // UBX-RXM-RAW (Multi-GNSS Raw Measurement Data)
return {"ubloxGnss", gen_rxm_rawx(static_cast(body))};
case 0x0a09:
return {"ubloxGnss", gen_mon_hw(static_cast(body))};
@@ -147,115 +162,256 @@ kj::Array UbloxMsgParser::gen_nav_pvt(ubx_t::nav_pvt_t *msg) {
return capnp::messageToFlatArray(msg_builder);
}
-
-kj::Array UbloxMsgParser::gen_rxm_sfrbx(ubx_t::rxm_sfrbx_t *msg) {
+kj::Array UbloxMsgParser::parse_gps_ephemeris(ubx_t::rxm_sfrbx_t *msg) {
+ // GPS subframes are packed into 10x 4 bytes, each containing 3 actual bytes
+ // We will first need to separate the data from the padding and parity
auto body = *msg->body();
+ assert(body.size() == 10);
+
+ std::string subframe_data;
+ subframe_data.reserve(30);
+ for (uint32_t word : body) {
+ word = word >> 6; // TODO: Verify parity
+ subframe_data.push_back(word >> 16);
+ subframe_data.push_back(word >> 8);
+ subframe_data.push_back(word >> 0);
+ }
- if (msg->gnss_id() == ubx_t::gnss_type_t::GNSS_TYPE_GPS) {
- // GPS subframes are packed into 10x 4 bytes, each containing 3 actual bytes
- // We will first need to separate the data from the padding and parity
- assert(body.size() == 10);
+ // Collect subframes in map and parse when we have all the parts
+ {
+ kaitai::kstream stream(subframe_data);
+ gps_t subframe(&stream);
- std::string subframe_data;
- subframe_data.reserve(30);
- for (uint32_t word : body) {
- word = word >> 6; // TODO: Verify parity
- subframe_data.push_back(word >> 16);
- subframe_data.push_back(word >> 8);
- subframe_data.push_back(word >> 0);
+ int subframe_id = subframe.how()->subframe_id();
+ if (subframe_id > 3) {
+ // dont parse almanac subframes
+ return kj::Array();
+ }
+ gps_subframes[msg->sv_id()][subframe_id] = subframe_data;
+ }
+
+ // publish if subframes 1-3 have been collected
+ if (gps_subframes[msg->sv_id()].size() == 3) {
+ MessageBuilder msg_builder;
+ auto eph = msg_builder.initEvent().initUbloxGnss().initEphemeris();
+ eph.setSvId(msg->sv_id());
+
+ int iode_s2 = 0;
+ int iode_s3 = 0;
+ int iodc_lsb = 0;
+
+ // Subframe 1
+ {
+ kaitai::kstream stream(gps_subframes[msg->sv_id()][1]);
+ gps_t subframe(&stream);
+ gps_t::subframe_1_t* subframe_1 = static_cast(subframe.body());
+
+ eph.setGpsWeek(subframe_1->week_no());
+ eph.setTgd(subframe_1->t_gd() * pow(2, -31));
+ eph.setToc(subframe_1->t_oc() * pow(2, 4));
+ eph.setAf2(subframe_1->af_2() * pow(2, -55));
+ eph.setAf1(subframe_1->af_1() * pow(2, -43));
+ eph.setAf0(subframe_1->af_0() * pow(2, -31));
+ eph.setSvHealth(subframe_1->sv_health());
+ eph.setTowCount(subframe.how()->tow_count());
+ iodc_lsb = subframe_1->iodc_lsb();
}
- // Collect subframes in map and parse when we have all the parts
+ // Subframe 2
{
- kaitai::kstream stream(subframe_data);
+ kaitai::kstream stream(gps_subframes[msg->sv_id()][2]);
gps_t subframe(&stream);
- int subframe_id = subframe.how()->subframe_id();
+ gps_t::subframe_2_t* subframe_2 = static_cast(subframe.body());
+
+ eph.setCrs(subframe_2->c_rs() * pow(2, -5));
+ eph.setDeltaN(subframe_2->delta_n() * pow(2, -43) * gpsPi);
+ eph.setM0(subframe_2->m_0() * pow(2, -31) * gpsPi);
+ eph.setCuc(subframe_2->c_uc() * pow(2, -29));
+ eph.setEcc(subframe_2->e() * pow(2, -33));
+ eph.setCus(subframe_2->c_us() * pow(2, -29));
+ eph.setA(pow(subframe_2->sqrt_a() * pow(2, -19), 2.0));
+ eph.setToe(subframe_2->t_oe() * pow(2, 4));
+ iode_s2 = subframe_2->iode();
+ }
- if (subframe_id == 1) gps_subframes[msg->sv_id()].clear();
- gps_subframes[msg->sv_id()][subframe_id] = subframe_data;
+ // Subframe 3
+ {
+ kaitai::kstream stream(gps_subframes[msg->sv_id()][3]);
+ gps_t subframe(&stream);
+ gps_t::subframe_3_t* subframe_3 = static_cast(subframe.body());
+
+ eph.setCic(subframe_3->c_ic() * pow(2, -29));
+ eph.setOmega0(subframe_3->omega_0() * pow(2, -31) * gpsPi);
+ eph.setCis(subframe_3->c_is() * pow(2, -29));
+ eph.setI0(subframe_3->i_0() * pow(2, -31) * gpsPi);
+ eph.setCrc(subframe_3->c_rc() * pow(2, -5));
+ eph.setOmega(subframe_3->omega() * pow(2, -31) * gpsPi);
+ eph.setOmegaDot(subframe_3->omega_dot() * pow(2, -43) * gpsPi);
+ eph.setIode(subframe_3->iode());
+ eph.setIDot(subframe_3->idot() * pow(2, -43) * gpsPi);
+ iode_s3 = subframe_3->iode();
}
- if (gps_subframes[msg->sv_id()].size() == 5) {
- MessageBuilder msg_builder;
- auto eph = msg_builder.initEvent().initUbloxGnss().initEphemeris();
- eph.setSvId(msg->sv_id());
-
- // Subframe 1
- {
- kaitai::kstream stream(gps_subframes[msg->sv_id()][1]);
- gps_t subframe(&stream);
- gps_t::subframe_1_t* subframe_1 = static_cast(subframe.body());
-
- eph.setGpsWeek(subframe_1->week_no());
- eph.setTgd(subframe_1->t_gd() * pow(2, -31));
- eph.setToc(subframe_1->t_oc() * pow(2, 4));
- eph.setAf2(subframe_1->af_2() * pow(2, -55));
- eph.setAf1(subframe_1->af_1() * pow(2, -43));
- eph.setAf0(subframe_1->af_0() * pow(2, -31));
- }
-
- // Subframe 2
- {
- kaitai::kstream stream(gps_subframes[msg->sv_id()][2]);
- gps_t subframe(&stream);
- gps_t::subframe_2_t* subframe_2 = static_cast(subframe.body());
-
- eph.setCrs(subframe_2->c_rs() * pow(2, -5));
- eph.setDeltaN(subframe_2->delta_n() * pow(2, -43) * gpsPi);
- eph.setM0(subframe_2->m_0() * pow(2, -31) * gpsPi);
- eph.setCuc(subframe_2->c_uc() * pow(2, -29));
- eph.setEcc(subframe_2->e() * pow(2, -33));
- eph.setCus(subframe_2->c_us() * pow(2, -29));
- eph.setA(pow(subframe_2->sqrt_a() * pow(2, -19), 2.0));
- eph.setToe(subframe_2->t_oe() * pow(2, 4));
- }
-
- // Subframe 3
- {
- kaitai::kstream stream(gps_subframes[msg->sv_id()][3]);
- gps_t subframe(&stream);
- gps_t::subframe_3_t* subframe_3 = static_cast(subframe.body());
-
- eph.setCic(subframe_3->c_ic() * pow(2, -29));
- eph.setOmega0(subframe_3->omega_0() * pow(2, -31) * gpsPi);
- eph.setCis(subframe_3->c_is() * pow(2, -29));
- eph.setI0(subframe_3->i_0() * pow(2, -31) * gpsPi);
- eph.setCrc(subframe_3->c_rc() * pow(2, -5));
- eph.setOmega(subframe_3->omega() * pow(2, -31) * gpsPi);
- eph.setOmegaDot(subframe_3->omega_dot() * pow(2, -43) * gpsPi);
- eph.setIode(subframe_3->iode());
- eph.setIDot(subframe_3->idot() * pow(2, -43) * gpsPi);
- }
-
- // Subframe 4
- {
- kaitai::kstream stream(gps_subframes[msg->sv_id()][4]);
- gps_t subframe(&stream);
- gps_t::subframe_4_t* subframe_4 = static_cast(subframe.body());
-
- // This is page 18, why is the page id 56?
- if (subframe_4->data_id() == 1 && subframe_4->page_id() == 56) {
- auto iono = static_cast(subframe_4->body());
- double a0 = iono->a0() * pow(2, -30);
- double a1 = iono->a1() * pow(2, -27);
- double a2 = iono->a2() * pow(2, -24);
- double a3 = iono->a3() * pow(2, -24);
- eph.setIonoAlpha({a0, a1, a2, a3});
-
- double b0 = iono->b0() * pow(2, 11);
- double b1 = iono->b1() * pow(2, 14);
- double b2 = iono->b2() * pow(2, 16);
- double b3 = iono->b3() * pow(2, 16);
- eph.setIonoBeta({b0, b1, b2, b3});
- }
- }
-
- return capnp::messageToFlatArray(msg_builder);
+ gps_subframes[msg->sv_id()].clear();
+ if (iodc_lsb != iode_s2 || iodc_lsb != iode_s3) {
+ // data set cutover, reject ephemeris
+ return kj::Array();
}
+ return capnp::messageToFlatArray(msg_builder);
}
return kj::Array();
}
+kj::Array UbloxMsgParser::parse_glonass_ephemeris(ubx_t::rxm_sfrbx_t *msg) {
+ if (msg->sv_id() == 255) {
+ // data can be decoded before identifying the SV number, in this case 255
+ // is returned, which means "unknown" (ublox p32)
+ return kj::Array();
+ }
+
+ auto body = *msg->body();
+ assert(body.size() == 4);
+ {
+ std::string string_data;
+ string_data.reserve(16);
+ for (uint32_t word : body) {
+ for (int i = 3; i >= 0; i--)
+ string_data.push_back(word >> 8*i);
+ }
+
+ kaitai::kstream stream(string_data);
+ glonass_t gl_string(&stream);
+
+ int string_number = gl_string.string_number();
+ if (string_number > 5 || gl_string.idle_chip()) {
+ // dont parse non immediate data, idle_chip == 0
+ return kj::Array();
+ }
+
+ // immediate data is the same within one superframe
+ if (glonass_superframes[msg->sv_id()] != gl_string.superframe_number()) {
+ glonass_strings[msg->sv_id()].clear();
+ glonass_superframes[msg->sv_id()] = gl_string.superframe_number();
+ }
+ glonass_strings[msg->sv_id()][string_number] = string_data;
+ }
+
+ // publish if strings 1-5 have been collected
+ if (glonass_strings[msg->sv_id()].size() != 5) {
+ return kj::Array();
+ }
+
+ MessageBuilder msg_builder;
+ auto eph = msg_builder.initEvent().initUbloxGnss().initGlonassEphemeris();
+ eph.setSvId(msg->sv_id());
+ uint16_t current_day = 0;
+
+ // string number 1
+ {
+ kaitai::kstream stream(glonass_strings[msg->sv_id()][1]);
+ glonass_t gl_stream(&stream);
+ glonass_t::string_1_t* data = static_cast(gl_stream.data());
+
+ eph.setP1(data->p1());
+ eph.setTk(data->t_k());
+ eph.setXVel(data->x_vel() * pow(2, -20));
+ eph.setXAccel(data->x_accel() * pow(2, -30));
+ eph.setX(data->x() * pow(2, -11));
+ }
+
+ // string number 2
+ {
+ kaitai::kstream stream(glonass_strings[msg->sv_id()][2]);
+ glonass_t gl_stream(&stream);
+ glonass_t::string_2_t* data = static_cast(gl_stream.data());
+
+ eph.setSvHealth(data->b_n()>>2); // MSB indicates health
+ eph.setP2(data->p2());
+ eph.setTb(data->t_b());
+ eph.setYVel(data->y_vel() * pow(2, -20));
+ eph.setYAccel(data->y_accel() * pow(2, -30));
+ eph.setY(data->y() * pow(2, -11));
+ }
+
+ // string number 3
+ {
+ kaitai::kstream stream(glonass_strings[msg->sv_id()][3]);
+ glonass_t gl_stream(&stream);
+ glonass_t::string_3_t* data = static_cast(gl_stream.data());
+
+ eph.setP3(data->p3());
+ eph.setGammaN(data->gamma_n() * pow(2, -40));
+ eph.setSvHealth(eph.getSvHealth() | data->l_n());
+ eph.setZVel(data->z_vel() * pow(2, -20));
+ eph.setZAccel(data->z_accel() * pow(2, -30));
+ eph.setZ(data->z() * pow(2, -11));
+ }
+
+ // string number 4
+ {
+ kaitai::kstream stream(glonass_strings[msg->sv_id()][4]);
+ glonass_t gl_stream(&stream);
+ glonass_t::string_4_t* data = static_cast(gl_stream.data());
+
+ current_day = data->n_t();
+ eph.setTauN(data->tau_n() * pow(2, -30));
+ eph.setDeltaTauN(data->delta_tau_n() * pow(2, -30));
+ eph.setAge(data->e_n());
+ eph.setP4(data->p4());
+ eph.setSvURA(glonass_URA_lookup.at(data->f_t()));
+ if (msg->sv_id() != data->n()) {
+ LOGE("SV_ID != SLOT_NUMBER: %d %d", msg->sv_id(), data->n())
+ }
+ eph.setSvType(data->m());
+ }
+
+ // string number 5
+ {
+ kaitai::kstream stream(glonass_strings[msg->sv_id()][5]);
+ glonass_t gl_stream(&stream);
+ glonass_t::string_5_t* data = static_cast(gl_stream.data());
+
+ // string5 parsing is only needed to get the year, this can be removed and
+ // the year can be fetched later in laika (note rollovers and leap year)
+ uint8_t n_4 = data->n_4();
+ uint16_t year = get_glonass_year(n_4, current_day);
+ if (current_day > 1461) {
+ // impossible day within last 4 year, reject ephemeris
+ // TODO: check if this can be detected via hamming code
+ LOGE("INVALID DATA: current day out of range: %d, %d", current_day, n_4);
+ glonass_strings[msg->sv_id()].clear();
+ return kj::Array();
+ }
+
+ uint16_t last_leap_year = 1996 + 4*(n_4-1);
+ uint16_t days_till_this_year = (year - last_leap_year)*365;
+ if (days_till_this_year != 0) {
+ days_till_this_year++;
+ }
+
+ eph.setYear(year);
+ eph.setDayInYear(current_day - days_till_this_year);
+ eph.setHour((eph.getTk()>>7) & 0x1F);
+ eph.setMinute((eph.getTk()>>1) & 0x3F);
+ eph.setSecond((eph.getTk() & 0x1) * 30);
+ }
+
+ glonass_strings[msg->sv_id()].clear();
+ return capnp::messageToFlatArray(msg_builder);
+}
+
+
+kj::Array UbloxMsgParser::gen_rxm_sfrbx(ubx_t::rxm_sfrbx_t *msg) {
+ switch (msg->gnss_id()) {
+ case ubx_t::gnss_type_t::GNSS_TYPE_GPS:
+ return parse_gps_ephemeris(msg);
+ case ubx_t::gnss_type_t::GNSS_TYPE_GLONASS:
+ return parse_glonass_ephemeris(msg);
+ default:
+ return kj::Array();
+ }
+}
+
kj::Array UbloxMsgParser::gen_rxm_rawx(ubx_t::rxm_rawx_t *msg) {
MessageBuilder msg_builder;
auto mr = msg_builder.initEvent().initUbloxGnss().initMeasurementReport();
diff --git a/selfdrive/locationd/ublox_msg.h b/selfdrive/locationd/ublox_msg.h
index 542e72816b..6988f20b74 100644
--- a/selfdrive/locationd/ublox_msg.h
+++ b/selfdrive/locationd/ublox_msg.h
@@ -10,6 +10,7 @@
#include "cereal/messaging/messaging.h"
#include "common/util.h"
#include "selfdrive/locationd/generated/gps.h"
+#include "selfdrive/locationd/generated/glonass.h"
#include "selfdrive/locationd/generated/ubx.h"
using namespace std::string_literals;
@@ -101,11 +102,22 @@ class UbloxMsgParser {
inline bool valid_cheksum();
inline bool valid();
inline bool valid_so_far();
+ inline uint16_t get_glonass_year(uint8_t N4, uint16_t Nt);
+
+ kj::Array parse_gps_ephemeris(ubx_t::rxm_sfrbx_t *msg);
+ kj::Array parse_glonass_ephemeris(ubx_t::rxm_sfrbx_t *msg);
std::unordered_map> gps_subframes;
size_t bytes_in_parse_buf = 0;
uint8_t msg_parse_buf[ublox::UBLOX_HEADER_SIZE + ublox::UBLOX_MAX_MSG_SIZE];
-};
+ // user range accuracy in meters
+ const std::unordered_map glonass_URA_lookup =
+ {{ 0, 1}, { 1, 2}, { 2, 2.5}, { 3, 4}, { 4, 5}, {5, 7},
+ { 6, 10}, { 7, 12}, { 8, 14}, { 9, 16}, {10, 32},
+ {11, 64}, {12, 128}, {13, 256}, {14, 512}, {15, 1024}};
+ std::unordered_map> glonass_strings;
+ std::unordered_map glonass_superframes;
+};
diff --git a/selfdrive/loggerd/SConscript b/selfdrive/loggerd/SConscript
index 92706c53ec..3b961bce6e 100644
--- a/selfdrive/loggerd/SConscript
+++ b/selfdrive/loggerd/SConscript
@@ -13,6 +13,8 @@ if arch == "Darwin":
# fix OpenCL
del libs[libs.index('OpenCL')]
env['FRAMEWORKS'] = ['OpenCL']
+ # exclude v4l
+ del src[src.index('encoder/v4l_encoder.cc')]
logger_lib = env.Library('logger', src)
libs.insert(0, logger_lib)
diff --git a/selfdrive/loggerd/loggerd.cc b/selfdrive/loggerd/loggerd.cc
index 9beb3c3bf1..e09cdfaa9e 100644
--- a/selfdrive/loggerd/loggerd.cc
+++ b/selfdrive/loggerd/loggerd.cc
@@ -24,15 +24,25 @@ void logger_rotate(LoggerdState *s) {
}
void rotate_if_needed(LoggerdState *s) {
- if (s->ready_to_rotate == s->max_waiting) {
- logger_rotate(s);
- }
+ // all encoders ready, trigger rotation
+ bool all_ready = s->ready_to_rotate == s->max_waiting;
+ // fallback logic to prevent extremely long segments in the case of camera, encoder, etc. malfunctions
+ bool timed_out = false;
double tms = millis_since_boot();
- if ((tms - s->last_rotate_tms) > SEGMENT_LENGTH * 1000 &&
- (tms - s->last_camera_seen_tms) > NO_CAMERA_PATIENCE &&
- !LOGGERD_TEST) {
- LOGW("no camera packet seen. auto rotating");
+ double seg_length_secs = (tms - s->last_rotate_tms) / 1000.;
+ if ((seg_length_secs > SEGMENT_LENGTH) && !LOGGERD_TEST) {
+ // TODO: might be nice to put these reasons in the sentinel
+ if ((tms - s->last_camera_seen_tms) > NO_CAMERA_PATIENCE) {
+ timed_out = true;
+ LOGE("no camera packets seen. auto rotating");
+ } else if (seg_length_secs > SEGMENT_LENGTH*1.2) {
+ timed_out = true;
+ LOGE("segment too long. auto rotating");
+ }
+ }
+
+ if (all_ready || timed_out) {
logger_rotate(s);
}
}
diff --git a/selfdrive/loggerd/tests/test_loggerd.py b/selfdrive/loggerd/tests/test_loggerd.py
index 9c3565d130..857dc5c4e9 100755
--- a/selfdrive/loggerd/tests/test_loggerd.py
+++ b/selfdrive/loggerd/tests/test_loggerd.py
@@ -86,7 +86,7 @@ class TestLoggerd(unittest.TestCase):
params.clear_all()
for k, _, v in fake_params:
params.put(k, v)
- params.put("LaikadEphemeris", "abc")
+ params.put("LaikadEphemerisV2", "abc")
lr = list(LogReader(str(self._gen_bootlog())))
initData = lr[0].initData
@@ -103,14 +103,14 @@ class TestLoggerd(unittest.TestCase):
# check params
logged_params = {entry.key: entry.value for entry in initData.params.entries}
- expected_params = set(k for k, _, __ in fake_params) | {'LaikadEphemeris'}
+ expected_params = set(k for k, _, __ in fake_params) | {'LaikadEphemerisV2'}
assert set(logged_params.keys()) == expected_params, set(logged_params.keys()) ^ expected_params
- assert logged_params['LaikadEphemeris'] == b'', f"DONT_LOG param value was logged: {repr(logged_params['LaikadEphemeris'])}"
+ assert logged_params['LaikadEphemerisV2'] == b'', f"DONT_LOG param value was logged: {repr(logged_params['LaikadEphemerisV2'])}"
for param_key, initData_key, v in fake_params:
self.assertEqual(getattr(initData, initData_key), v)
self.assertEqual(logged_params[param_key].decode(), v)
- params.put("LaikadEphemeris", "")
+ params.put("LaikadEphemerisV2", "")
def test_rotation(self):
os.environ["LOGGERD_TEST"] = "1"
diff --git a/selfdrive/manager/build.py b/selfdrive/manager/build.py
index c8a7d41539..5b69e3dca7 100755
--- a/selfdrive/manager/build.py
+++ b/selfdrive/manager/build.py
@@ -15,7 +15,7 @@ from system.version import is_dirty
MAX_CACHE_SIZE = 4e9 if "CI" in os.environ else 2e9
CACHE_DIR = Path("/data/scons_cache" if AGNOS else "/tmp/scons_cache")
-TOTAL_SCONS_NODES = 2395
+TOTAL_SCONS_NODES = 2460
MAX_BUILD_PROGRESS = 100
PREBUILT = os.path.exists(os.path.join(BASEDIR, 'prebuilt'))
diff --git a/selfdrive/manager/manager.py b/selfdrive/manager/manager.py
index 928507f65b..963d94066b 100755
--- a/selfdrive/manager/manager.py
+++ b/selfdrive/manager/manager.py
@@ -20,11 +20,9 @@ from selfdrive.manager.process_config import managed_processes
from selfdrive.athena.registration import register, UNREGISTERED_DONGLE_ID
from system.swaglog import cloudlog, add_file_handler
from system.version import is_dirty, get_commit, get_version, get_origin, get_short_branch, \
- terms_version, training_version, is_tested_branch
+ terms_version, training_version, is_tested_branch, is_release_branch
-sys.path.append(os.path.join(BASEDIR, "pyextra"))
-
def manager_init() -> None:
# update system time from panda
@@ -38,7 +36,7 @@ def manager_init() -> None:
default_params: List[Tuple[str, Union[str, bytes]]] = [
("CompletedTrainingVersion", "0"),
- ("DisengageOnAccelerator", "1"),
+ ("DisengageOnAccelerator", "0"),
("GsmMetered", "1"),
("HasAcceptedTerms", "0"),
("LanguageSetting", "main_en"),
@@ -78,6 +76,7 @@ def manager_init() -> None:
params.put("GitBranch", get_short_branch(default=""))
params.put("GitRemote", get_origin(default=""))
params.put_bool("IsTestedBranch", is_tested_branch())
+ params.put_bool("IsReleaseBranch", is_release_branch())
# set dongle id
reg_res = register(show_spinner=True)
diff --git a/selfdrive/manager/process.py b/selfdrive/manager/process.py
index dabfbe4ee0..ce18073d9b 100644
--- a/selfdrive/manager/process.py
+++ b/selfdrive/manager/process.py
@@ -290,10 +290,11 @@ class DaemonProcess(ManagerProcess):
def ensure_running(procs: ValuesView[ManagerProcess], started: bool, params=None, CP: car.CarParams=None,
- not_run: Optional[List[str]]=None) -> None:
+ not_run: Optional[List[str]]=None) -> List[ManagerProcess]:
if not_run is None:
not_run = []
+ running = []
for p in procs:
# Conditions that make a process run
run = any((
@@ -311,7 +312,10 @@ def ensure_running(procs: ValuesView[ManagerProcess], started: bool, params=None
if run:
p.start()
+ running.append(p)
else:
p.stop(block=False)
p.check_watchdog(started)
+
+ return running
diff --git a/selfdrive/manager/process_config.py b/selfdrive/manager/process_config.py
index c03e995497..8fc4d94e55 100644
--- a/selfdrive/manager/process_config.py
+++ b/selfdrive/manager/process_config.py
@@ -17,6 +17,11 @@ def logging(started, params, CP: car.CarParams) -> bool:
run = (not CP.notCar) or not params.get_bool("DisableLogging")
return started and run
+def ublox(started, params, CP: car.CarParams) -> bool:
+ use_ublox = os.path.exists('/dev/ttyHS0') and not os.path.exists('/persist/comma/use-quectel-gps')
+ params.put_bool("UbloxAvailable", use_ublox)
+ return started and use_ublox
+
procs = [
# due to qualcomm kernel bugs SIGKILLing camerad sometimes causes page table corruption
NativeProcess("camerad", "system/camerad", ["./camerad"], unkillable=True, callback=driverview),
@@ -35,7 +40,6 @@ procs = [
NativeProcess("mapsd", "selfdrive/navd", ["./map_renderer"], enabled=False),
NativeProcess("navmodeld", "selfdrive/modeld", ["./navmodeld"], enabled=False),
NativeProcess("sensord", "selfdrive/sensord", ["./sensord"], enabled=not PC),
- NativeProcess("ubloxd", "selfdrive/locationd", ["./ubloxd"], enabled=(not PC or WEBCAM)),
NativeProcess("ui", "selfdrive/ui", ["./ui"], offroad=True, watchdog_max_dt=(5 if not PC else None)),
NativeProcess("soundd", "selfdrive/ui/soundd", ["./soundd"], offroad=True),
NativeProcess("locationd", "selfdrive/locationd", ["./locationd"]),
@@ -50,7 +54,8 @@ procs = [
PythonProcess("navd", "selfdrive.navd.navd"),
PythonProcess("pandad", "selfdrive.boardd.pandad", offroad=True),
PythonProcess("paramsd", "selfdrive.locationd.paramsd"),
- PythonProcess("pigeond", "selfdrive.sensord.pigeond", enabled=TICI),
+ NativeProcess("ubloxd", "selfdrive/locationd", ["./ubloxd"], enabled=TICI, onroad=False, callback=ublox),
+ PythonProcess("pigeond", "selfdrive.sensord.pigeond", enabled=TICI, onroad=False, callback=ublox),
PythonProcess("plannerd", "selfdrive.controls.plannerd"),
PythonProcess("radard", "selfdrive.controls.radard"),
PythonProcess("thermald", "selfdrive.thermald.thermald", offroad=True),
diff --git a/selfdrive/manager/test/test_manager.py b/selfdrive/manager/test/test_manager.py
index 6d4df0423a..889ab3d279 100755
--- a/selfdrive/manager/test/test_manager.py
+++ b/selfdrive/manager/test/test_manager.py
@@ -4,17 +4,17 @@ import signal
import time
import unittest
+from cereal import car
from common.params import Params
import selfdrive.manager.manager as manager
-from selfdrive.manager.process import DaemonProcess
+from selfdrive.manager.process import ensure_running
from selfdrive.manager.process_config import managed_processes
from system.hardware import HARDWARE
os.environ['FAKEUPLOAD'] = "1"
MAX_STARTUP_TIME = 3
-ALL_PROCESSES = [p.name for p in managed_processes.values() if (type(p) is not DaemonProcess) and p.enabled and (p.name not in ['pandad', ])]
-
+BLACKLIST_PROCS = ['manage_athenad', 'pandad', 'pigeond']
class TestManager(unittest.TestCase):
def setUp(self):
@@ -47,24 +47,25 @@ class TestManager(unittest.TestCase):
HARDWARE.set_power_save(False)
manager.manager_init()
manager.manager_prepare()
- for p in ALL_PROCESSES:
- managed_processes[p].start()
+
+ CP = car.CarParams.new_message()
+ procs = ensure_running(managed_processes.values(), True, Params(), CP, not_run=BLACKLIST_PROCS)
time.sleep(10)
- for p in reversed(ALL_PROCESSES):
- with self.subTest(proc=p):
- state = managed_processes[p].get_process_state_msg()
- self.assertTrue(state.running, f"{p} not running")
- exit_code = managed_processes[p].stop(retry=False)
+ for p in procs:
+ with self.subTest(proc=p.name):
+ state = p.get_process_state_msg()
+ self.assertTrue(state.running, f"{p.name} not running")
+ exit_code = p.stop(retry=False)
- self.assertTrue(exit_code is not None, f"{p} failed to exit")
+ self.assertTrue(exit_code is not None, f"{p.name} failed to exit")
# TODO: interrupted blocking read exits with 1 in cereal. use a more unique return code
exit_codes = [0, 1]
- if managed_processes[p].sigkill:
+ if p.sigkill:
exit_codes = [-signal.SIGKILL]
- self.assertIn(exit_code, exit_codes, f"{p} died with {exit_code}")
+ self.assertIn(exit_code, exit_codes, f"{p.name} died with {exit_code}")
if __name__ == "__main__":
diff --git a/selfdrive/modeld/SConscript b/selfdrive/modeld/SConscript
index 82338e456b..7bbc1b3477 100644
--- a/selfdrive/modeld/SConscript
+++ b/selfdrive/modeld/SConscript
@@ -70,30 +70,14 @@ lenv.Program('_dmonitoringmodeld', [
if use_thneed and arch == "larch64" or GetOption('pc_thneed'):
fn = File("models/supercombo").abspath
- if GetOption('pc_thneed'):
- cmd = f"cd {Dir('#').abspath}/tinygrad_repo && GPU=1 NATIVE_EXPLOG=1 OPTWG=1 UNSAFE_FLOAT4=1 DEBUGCL=1 python3 openpilot/compile.py {fn}.onnx {fn}.thneed"
- else:
- cmd = f"cd {Dir('#').abspath}/tinygrad_repo && FLOAT16=1 MATMUL=1 PYOPENCL_NO_CACHE=1 NATIVE_EXPLOG=1 OPTWG=1 UNSAFE_FLOAT4=1 DEBUGCL=1 python3 openpilot/compile.py {fn}.onnx {fn}.thneed"
-
- # is there a better way then listing all of tinygrad?
- lenv.Command(fn + ".thneed", [fn + ".onnx",
- "#tinygrad_repo/openpilot/compile.py",
- "#tinygrad_repo/accel/opencl/conv.cl",
- "#tinygrad_repo/accel/opencl/matmul.cl",
- "#tinygrad_repo/accel/opencl/ops_opencl.py",
- "#tinygrad_repo/accel/opencl/preprocessing.py",
- "#tinygrad_repo/extra/onnx.py",
- "#tinygrad_repo/extra/thneed.py",
- "#tinygrad_repo/extra/utils.py",
- "#tinygrad_repo/tinygrad/llops/ops_gpu.py",
- "#tinygrad_repo/tinygrad/llops/ops_opencl.py",
- "#tinygrad_repo/tinygrad/helpers.py",
- "#tinygrad_repo/tinygrad/mlops.py",
- "#tinygrad_repo/tinygrad/ops.py",
- "#tinygrad_repo/tinygrad/shapetracker.py",
- "#tinygrad_repo/tinygrad/tensor.py",
- "#tinygrad_repo/tinygrad/nn/__init__.py"
- ], cmd)
+ tinygrad_opts = ["NATIVE_EXPLOG=1", "VALIDHACKS=1", "OPTWG=1", "IMAGE=2", "GPU=1", "CLCACHE=0"]
+ if not GetOption('pc_thneed'):
+ # use FLOAT16 on device for speed + don't cache the CL kernels for space
+ tinygrad_opts += ["FLOAT16=1", "PYOPENCL_NO_CACHE=1"]
+ cmd = f"cd {Dir('#').abspath}/tinygrad_repo && " + ' '.join(tinygrad_opts) + f" python3 openpilot/compile.py {fn}.onnx {fn}.thneed"
+
+ tinygrad_files = sum([lenv.Glob("#"+x) for x in open(File("#release/files_common").abspath).read().split("\n") if x.startswith("tinygrad_repo/")], [])
+ lenv.Command(fn + ".thneed", [fn + ".onnx"] + tinygrad_files, cmd)
llenv = lenv.Clone()
if GetOption('pc_thneed'):
@@ -116,4 +100,4 @@ llenv.Program('_modeld', [
lenv.Program('_navmodeld', [
"navmodeld.cc",
"models/nav.cc",
- ]+common_model, LIBS=libs + transformations)
\ No newline at end of file
+ ]+common_model, LIBS=libs + transformations)
diff --git a/selfdrive/modeld/models/driving.cc b/selfdrive/modeld/models/driving.cc
index ac101bfee7..5538d6ff9b 100644
--- a/selfdrive/modeld/models/driving.cc
+++ b/selfdrive/modeld/models/driving.cc
@@ -200,7 +200,7 @@ void fill_meta(cereal::ModelDataV2::MetaData::Builder meta, const ModelOutputMet
}
template
-void fill_xyzt(cereal::ModelDataV2::XYZTData::Builder xyzt, const std::array &t,
+void fill_xyzt(cereal::XYZTData::Builder xyzt, const std::array &t,
const std::array &x, const std::array &y, const std::array &z) {
xyzt.setT(to_kj_array_ptr(t));
xyzt.setX(to_kj_array_ptr(x));
@@ -209,7 +209,7 @@ void fill_xyzt(cereal::ModelDataV2::XYZTData::Builder xyzt, const std::array
-void fill_xyzt(cereal::ModelDataV2::XYZTData::Builder xyzt, const std::array &t,
+void fill_xyzt(cereal::XYZTData::Builder xyzt, const std::array &t,
const std::array &x, const std::array &y, const std::array &z,
const std::array &x_std, const std::array &y_std, const std::array &z_std) {
fill_xyzt(xyzt, t, x, y, z);
diff --git a/selfdrive/modeld/models/supercombo.onnx b/selfdrive/modeld/models/supercombo.onnx
index 8805b3dce8..a483fa4db4 100644
--- a/selfdrive/modeld/models/supercombo.onnx
+++ b/selfdrive/modeld/models/supercombo.onnx
@@ -1,3 +1,3 @@
version https://git-lfs.github.com/spec/v1
-oid sha256:db746e3753de84367595fedd089c2bd41b06bd401ea28e085663533d0e63d74b
-size 45962473
+oid sha256:736ddc08497d7596bae4d9515a8efb996676be80e67a6d34d632bb8af2ed3fa9
+size 45962515
diff --git a/selfdrive/modeld/thneed/thneed.h b/selfdrive/modeld/thneed/thneed.h
index 65475ccf7f..6475577734 100644
--- a/selfdrive/modeld/thneed/thneed.h
+++ b/selfdrive/modeld/thneed/thneed.h
@@ -12,7 +12,7 @@
#include
-#include "selfdrive/modeld/thneed/include/msm_kgsl.h"
+#include "msm_kgsl.h"
using namespace std;
diff --git a/selfdrive/navd/map_renderer.cc b/selfdrive/navd/map_renderer.cc
index 91f31d06dc..51676bb3a3 100644
--- a/selfdrive/navd/map_renderer.cc
+++ b/selfdrive/navd/map_renderer.cc
@@ -169,7 +169,7 @@ void MapRenderer::publish(const double render_time) {
VisionBuf* buf = vipc_server->get_buffer(VisionStreamType::VISION_STREAM_MAP);
VisionIpcBufExtra extra = {
.frame_id = frame_id,
- .timestamp_sof = sm->rcv_time("liveLocationKalman"),
+ .timestamp_sof = (*sm)["liveLocationKalman"].getLogMonoTime(),
.timestamp_eof = ts,
};
@@ -206,7 +206,7 @@ void MapRenderer::publish(const double render_time) {
// Send state msg
MessageBuilder msg;
auto state = msg.initEvent().initMapRenderState();
- state.setLocationMonoTime(sm->rcv_time("liveLocationKalman"));
+ state.setLocationMonoTime((*sm)["liveLocationKalman"].getLogMonoTime());
state.setRenderTime(render_time);
state.setFrameId(frame_id);
pm->send("mapRenderState", msg);
diff --git a/selfdrive/navd/navd.py b/selfdrive/navd/navd.py
index 81e3bdb3df..7af911ab2a 100755
--- a/selfdrive/navd/navd.py
+++ b/selfdrive/navd/navd.py
@@ -226,7 +226,11 @@ class RouteEngine:
remaining = 1.0 - along_geometry / max(step['distance'], 1)
total_distance = step['distance'] * remaining
total_time = step['duration'] * remaining
- total_time_typical = step['duration_typical'] * remaining
+
+ if step['duration_typical'] is None:
+ total_time_typical = total_time
+ else:
+ total_time_typical = step['duration_typical'] * remaining
# Add up totals for future steps
for i in range(self.step_idx + 1, len(self.route)):
diff --git a/selfdrive/sensord/libdiag.h b/selfdrive/sensord/libdiag.h
deleted file mode 100644
index 03a59464ed..0000000000
--- a/selfdrive/sensord/libdiag.h
+++ /dev/null
@@ -1,37 +0,0 @@
-#pragma once
-
-#include
-#include
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-#define DIAG_MAX_RX_PKT_SIZ 4096
-
-bool Diag_LSM_Init(uint8_t* pIEnv);
-bool Diag_LSM_DeInit(void);
-
-// DCI
-
-#define DIAG_CON_APSS 0x001
-#define DIAG_CON_MPSS 0x002
-#define DIAG_CON_LPASS 0x004
-#define DIAG_CON_WCNSS 0x008
-
-enum {
- DIAG_DCI_NO_ERROR = 1001,
-} diag_dci_error_type;
-
-int diag_register_dci_client(int*, uint16_t*, int, void*);
-int diag_log_stream_config(int client_id, int set_mask, uint16_t log_codes_array[], int num_codes);
-int diag_register_dci_stream(void (*func_ptr_logs)(unsigned char *ptr, int len), void (*func_ptr_events)(unsigned char *ptr, int len));
-int diag_release_dci_client(int*);
-
-int diag_send_dci_async_req(int client_id, unsigned char buf[], int bytes, unsigned char *rsp_ptr, int rsp_len,
- void (*func_ptr)(unsigned char *ptr, int len, void *data_ptr), void *data_ptr);
-
-
-#ifdef __cplusplus
-}
-#endif
diff --git a/selfdrive/sensord/pigeond.py b/selfdrive/sensord/pigeond.py
index f56af1c705..9d0a62bd3b 100755
--- a/selfdrive/sensord/pigeond.py
+++ b/selfdrive/sensord/pigeond.py
@@ -123,7 +123,7 @@ class TTYPigeon():
init_baudrate(self)
# clear configuration
- self.send_with_ack(b"\xb5\x62\x06\x09\x0d\x00\x00\x00\x1f\x1f\x00\x00\x00\x00\x00\x00\x00\x00\x17\x71\x5b")
+ self.send_with_ack(b"\xb5\x62\x06\x09\x0d\x00\x1f\x1f\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x17\x71\xd7")
# clear flash memory (almanac backup)
self.send_with_ack(b"\xB5\x62\x09\x14\x04\x00\x01\x00\x00\x00\x22\xf0")
@@ -303,8 +303,7 @@ def main():
pigeon, pm = create_pigeon()
init_baudrate(pigeon)
- r = initialize_pigeon(pigeon)
- Params().put_bool("UbloxAvailable", r)
+ initialize_pigeon(pigeon)
# start receiving data
run_receiving(pigeon, pm)
diff --git a/selfdrive/sensord/rawgps/rawgpsd.py b/selfdrive/sensord/rawgps/rawgpsd.py
index 1c65051665..3fa5e927a2 100755
--- a/selfdrive/sensord/rawgps/rawgpsd.py
+++ b/selfdrive/sensord/rawgps/rawgpsd.py
@@ -11,7 +11,9 @@ from struct import unpack_from, calcsize, pack
from cereal import log
import cereal.messaging as messaging
+from common.gpio import gpio_init, gpio_set
from laika.gps_time import GPSTime
+from system.hardware.tici.pins import GPIO
from system.swaglog import cloudlog
from selfdrive.sensord.rawgps.modemdiag import ModemDiag, DIAG_LOG_F, setup_logs, send_recv
from selfdrive.sensord.rawgps.structs import (dict_unpacker, position_report, relist,
@@ -182,6 +184,7 @@ def main() -> NoReturn:
def cleanup(sig, frame):
cloudlog.warning(f"caught sig {sig}, disabling quectel gps")
+ gpio_set(GPIO.UBLOX_PWR_EN, False)
teardown_quectel(diag)
cloudlog.warning("quectel cleanup done")
sys.exit(0)
@@ -190,6 +193,8 @@ def main() -> NoReturn:
setup_quectel(diag)
cloudlog.warning("quectel setup done")
+ gpio_init(GPIO.UBLOX_PWR_EN, True)
+ gpio_set(GPIO.UBLOX_PWR_EN, True)
pm = messaging.PubMaster(['qcomGnss', 'gpsLocation'])
diff --git a/selfdrive/test/longitudinal_maneuvers/maneuver.py b/selfdrive/test/longitudinal_maneuvers/maneuver.py
index 65935f8979..00ddfe627e 100644
--- a/selfdrive/test/longitudinal_maneuvers/maneuver.py
+++ b/selfdrive/test/longitudinal_maneuvers/maneuver.py
@@ -19,6 +19,7 @@ class Maneuver:
self.ensure_start = kwargs.get("ensure_start", False)
self.enabled = kwargs.get("enabled", True)
self.e2e = kwargs.get("e2e", False)
+ self.force_decel = kwargs.get("force_decel", False)
self.duration = duration
self.title = title
@@ -32,6 +33,7 @@ class Maneuver:
only_lead2=self.only_lead2,
only_radar=self.only_radar,
e2e=self.e2e,
+ force_decel=self.force_decel,
)
valid = True
@@ -60,6 +62,10 @@ class Maneuver:
if self.ensure_start and log['v_rel'] > 0 and log['speeds'][-1] <= 0.1:
print('LongitudinalPlanner not starting!')
valid = False
+ if self.force_decel and log['speed'] > 1e-1 and log['acceleration'] > -0.04:
+ print('Not stopping with force decel')
+ valid = False
+
print("maneuver end", valid)
return valid, np.array(logs)
diff --git a/selfdrive/test/longitudinal_maneuvers/plant.py b/selfdrive/test/longitudinal_maneuvers/plant.py
index 8e150d800c..8febbf4022 100755
--- a/selfdrive/test/longitudinal_maneuvers/plant.py
+++ b/selfdrive/test/longitudinal_maneuvers/plant.py
@@ -15,7 +15,7 @@ class Plant:
messaging_initialized = False
def __init__(self, lead_relevancy=False, speed=0.0, distance_lead=2.0,
- enabled=True, only_lead2=False, only_radar=False, e2e=False):
+ enabled=True, only_lead2=False, only_radar=False, e2e=False, force_decel=False):
self.rate = 1. / DT_MDL
if not Plant.messaging_initialized:
@@ -39,6 +39,7 @@ class Plant:
self.only_lead2 = only_lead2
self.only_radar = only_radar
self.e2e = e2e
+ self.force_decel = force_decel
self.rk = Ratekeeper(self.rate, print_delay_threshold=100.0)
self.ts = 1. / self.rate
@@ -48,7 +49,7 @@ class Plant:
from selfdrive.car.honda.values import CAR
from selfdrive.car.honda.interface import CarInterface
- self.planner = LongitudinalPlanner(CarInterface.get_params(CAR.CIVIC), init_v=self.speed)
+ self.planner = LongitudinalPlanner(CarInterface.get_non_essential_params(CAR.CIVIC), init_v=self.speed)
@property
def current_time(self):
@@ -98,19 +99,20 @@ class Plant:
# Simulate model predicting slightly faster speed
# this is to ensure lead policy is effective when model
# does not predict slowdown in e2e mode
- position = log.ModelDataV2.XYZTData.new_message()
+ position = log.XYZTData.new_message()
position.x = [float(x) for x in (self.speed + 0.5) * np.array(T_IDXS)]
model.modelV2.position = position
- velocity = log.ModelDataV2.XYZTData.new_message()
+ velocity = log.XYZTData.new_message()
velocity.x = [float(x) for x in (self.speed + 0.5) * np.ones_like(T_IDXS)]
model.modelV2.velocity = velocity
- acceleration = log.ModelDataV2.XYZTData.new_message()
+ acceleration = log.XYZTData.new_message()
acceleration.x = [float(x) for x in np.zeros_like(T_IDXS)]
model.modelV2.acceleration = acceleration
control.controlsState.longControlState = LongCtrlState.pid if self.enabled else LongCtrlState.off
control.controlsState.vCruise = float(v_cruise * 3.6)
control.controlsState.experimentalMode = self.e2e
+ control.controlsState.forceDecel = self.force_decel
car_state.carState.vEgo = float(self.speed)
car_state.carState.standstill = self.speed < 0.01
diff --git a/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py b/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py
index 686b35e456..bc477ca9fe 100755
--- a/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py
+++ b/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py
@@ -1,6 +1,7 @@
#!/usr/bin/env python3
+import itertools
import os
-from parameterized import parameterized
+from parameterized import parameterized_class
import unittest
from common.params import Params
@@ -9,8 +10,8 @@ from selfdrive.test.longitudinal_maneuvers.maneuver import Maneuver
# TODO: make new FCW tests
-def create_maneuvers(e2e):
- return [
+def create_maneuvers(kwargs):
+ maneuvers = [
Maneuver(
'approach stopped car at 25m/s, initial distance: 120m',
duration=20.,
@@ -19,7 +20,7 @@ def create_maneuvers(e2e):
initial_distance_lead=120.,
speed_lead_values=[30., 0.],
breakpoints=[0., 1.],
- e2e=e2e,
+ **kwargs,
),
Maneuver(
'approach stopped car at 20m/s, initial distance 90m',
@@ -29,7 +30,7 @@ def create_maneuvers(e2e):
initial_distance_lead=90.,
speed_lead_values=[20., 0.],
breakpoints=[0., 1.],
- e2e=e2e,
+ **kwargs,
),
Maneuver(
'steady state following a car at 20m/s, then lead decel to 0mph at 1m/s^2',
@@ -39,7 +40,7 @@ def create_maneuvers(e2e):
initial_distance_lead=35.,
speed_lead_values=[20., 20., 0.],
breakpoints=[0., 15., 35.0],
- e2e=e2e,
+ **kwargs,
),
Maneuver(
'steady state following a car at 20m/s, then lead decel to 0mph at 2m/s^2',
@@ -49,7 +50,7 @@ def create_maneuvers(e2e):
initial_distance_lead=35.,
speed_lead_values=[20., 20., 0.],
breakpoints=[0., 15., 25.0],
- e2e=e2e,
+ **kwargs,
),
Maneuver(
'steady state following a car at 20m/s, then lead decel to 0mph at 3m/s^2',
@@ -59,7 +60,7 @@ def create_maneuvers(e2e):
initial_distance_lead=35.,
speed_lead_values=[20., 20., 0.],
breakpoints=[0., 15., 21.66],
- e2e=e2e,
+ **kwargs,
),
Maneuver(
'steady state following a car at 20m/s, then lead decel to 0mph at 3+m/s^2',
@@ -71,7 +72,7 @@ def create_maneuvers(e2e):
prob_lead_values=[0., 1., 1.],
cruise_values=[20., 20., 20.],
breakpoints=[2., 2.01, 8.8],
- e2e=e2e,
+ **kwargs,
),
Maneuver(
"approach stopped car at 20m/s, with prob_lead_values",
@@ -83,7 +84,7 @@ def create_maneuvers(e2e):
prob_lead_values=[0.0, 0., 1.],
cruise_values=[20., 20., 20.],
breakpoints=[0.0, 2., 2.01],
- e2e=e2e,
+ **kwargs,
),
Maneuver(
"approach slower cut-in car at 20m/s",
@@ -94,7 +95,7 @@ def create_maneuvers(e2e):
speed_lead_values=[15., 15.],
breakpoints=[1., 11.],
only_lead2=True,
- e2e=e2e,
+ **kwargs,
),
Maneuver(
"stay stopped behind radar override lead",
@@ -106,7 +107,7 @@ def create_maneuvers(e2e):
prob_lead_values=[0., 0.],
breakpoints=[1., 11.],
only_radar=True,
- e2e=e2e,
+ **kwargs,
),
Maneuver(
"NaN recovery",
@@ -117,10 +118,20 @@ def create_maneuvers(e2e):
speed_lead_values=[0., 0., 0.0],
breakpoints=[1., 1.01, 11.],
cruise_values=[float("nan"), 15., 15.],
- e2e=e2e,
+ **kwargs,
),
- # controls relies on planner commanding to move for stock-ACC resume spamming
Maneuver(
+ 'cruising at 25 m/s while disabled',
+ duration=20.,
+ initial_speed=25.,
+ lead_relevancy=False,
+ enabled=False,
+ **kwargs,
+ ),
+ ]
+ if not kwargs['force_decel']:
+ # controls relies on planner commanding to move for stock-ACC resume spamming
+ maneuvers.append(Maneuver(
"resume from a stop",
duration=20.,
initial_speed=0.,
@@ -129,20 +140,16 @@ def create_maneuvers(e2e):
speed_lead_values=[0., 0., 2.],
breakpoints=[1., 10., 15.],
ensure_start=True,
- e2e=e2e,
- ),
- Maneuver(
- 'cruising at 25 m/s while disabled',
- duration=20.,
- initial_speed=25.,
- lead_relevancy=False,
- enabled=False,
- e2e=e2e,
- ),
- ]
+ **kwargs,
+ ))
+ return maneuvers
+@parameterized_class(("e2e", "force_decel"), itertools.product([True, False], repeat=2))
class LongitudinalControl(unittest.TestCase):
+ e2e: bool
+ force_decel: bool
+
@classmethod
def setUpClass(cls):
os.environ['SIMULATION'] = "1"
@@ -154,11 +161,12 @@ class LongitudinalControl(unittest.TestCase):
params.put_bool("Passive", bool(os.getenv("PASSIVE")))
params.put_bool("OpenpilotEnabledToggle", True)
- @parameterized.expand([(man,) for e2e in [True, False] for man in create_maneuvers(e2e)])
- def test_maneuver(self, maneuver):
- print(maneuver.title, f'in {"e2e" if maneuver.e2e else "acc"} mode')
- valid, _ = maneuver.evaluate()
- self.assertTrue(valid, msg=maneuver.title)
+ def test_maneuver(self):
+ for maneuver in create_maneuvers({"e2e": self.e2e, "force_decel": self.force_decel}):
+ with self.subTest(title=maneuver.title, e2e=maneuver.e2e, force_decel=maneuver.force_decel):
+ print(maneuver.title, f'in {"e2e" if maneuver.e2e else "acc"} mode')
+ valid, _ = maneuver.evaluate()
+ self.assertTrue(valid)
if __name__ == "__main__":
diff --git a/selfdrive/test/process_replay/model_replay.py b/selfdrive/test/process_replay/model_replay.py
index ce861b37e6..68cbb28aaf 100755
--- a/selfdrive/test/process_replay/model_replay.py
+++ b/selfdrive/test/process_replay/model_replay.py
@@ -43,12 +43,12 @@ def replace_calib(msg, calib):
def nav_model_replay(lr):
- sm = messaging.SubMaster(['navModel', 'navThumbnail'])
+ sm = messaging.SubMaster(['navModel', 'navThumbnail', 'mapRenderState'])
pm = messaging.PubMaster(['liveLocationKalman', 'navRoute'])
nav = [m for m in lr if m.which() == 'navRoute']
llk = [m for m in lr if m.which() == 'liveLocationKalman']
- assert len(nav) > 0 and len(llk) >= NAV_FRAMES
+ assert len(nav) > 0 and len(llk) >= NAV_FRAMES and nav[0].logMonoTime < llk[-NAV_FRAMES].logMonoTime
log_msgs = []
try:
@@ -59,8 +59,8 @@ def nav_model_replay(lr):
# setup position and route
for _ in range(10):
- for s in (llk, nav):
- pm.send(s[0].which(), s[0].as_builder().to_bytes())
+ for s in (llk[-NAV_FRAMES], nav[0]):
+ pm.send(s.which(), s.as_builder().to_bytes())
sm.update(1000)
if sm.updated['navModel']:
break
@@ -74,12 +74,16 @@ def nav_model_replay(lr):
sm.update(0)
# run replay
- for n in range(NAV_FRAMES):
+ for n in range(len(llk) - NAV_FRAMES, len(llk)):
pm.send(llk[n].which(), llk[n].as_builder().to_bytes())
m = messaging.recv_one(sm.sock['navThumbnail'])
assert m is not None, f"no navThumbnail, frame={n}"
log_msgs.append(m)
+ m = messaging.recv_one(sm.sock['mapRenderState'])
+ assert m is not None, f"no mapRenderState, frame={n}"
+ log_msgs.append(m)
+
m = messaging.recv_one(sm.sock['navModel'])
assert m is not None, f"no navModel response, frame={n}"
log_msgs.append(m)
@@ -219,7 +223,7 @@ if __name__ == "__main__":
try:
expected_msgs = 2*MAX_FRAMES
if not NO_NAV:
- expected_msgs += NAV_FRAMES*2
+ expected_msgs += NAV_FRAMES*3
cmp_log = list(LogReader(BASE_URL + log_fn))[:expected_msgs]
ignore = [
@@ -231,6 +235,8 @@ if __name__ == "__main__":
'navModel.dspExecutionTime',
'navModel.modelExecutionTime',
'navThumbnail.timestampEof',
+ 'mapRenderState.locationMonoTime',
+ 'mapRenderState.renderTime',
]
if PC:
ignore += [
diff --git a/selfdrive/test/process_replay/model_replay_ref_commit b/selfdrive/test/process_replay/model_replay_ref_commit
index aa204e0f8a..c64f522352 100644
--- a/selfdrive/test/process_replay/model_replay_ref_commit
+++ b/selfdrive/test/process_replay/model_replay_ref_commit
@@ -1 +1 @@
-4ff972367fdb9546be68ee0ba0d45cf4f839dae7
+ba947edbb131a2a36ced7c490dfcf3280ad5b167
diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py
index bc55e33cbf..7dc0b139a3 100755
--- a/selfdrive/test/process_replay/process_replay.py
+++ b/selfdrive/test/process_replay/process_replay.py
@@ -180,7 +180,7 @@ def fingerprint(msgs, fsm, can_sock, fingerprint):
def get_car_params(msgs, fsm, can_sock, fingerprint):
if fingerprint:
CarInterface, _, _ = interfaces[fingerprint]
- CP = CarInterface.get_params(fingerprint)
+ CP = CarInterface.get_non_essential_params(fingerprint)
else:
can = FakeSocket(wait=False)
sendcan = FakeSocket(wait=False)
@@ -188,7 +188,7 @@ def get_car_params(msgs, fsm, can_sock, fingerprint):
canmsgs = [msg for msg in msgs if msg.which() == 'can']
for m in canmsgs[:300]:
can.send(m.as_builder().to_bytes())
- _, CP = get_car(can, sendcan)
+ _, CP = get_car(can, sendcan, Params().get_bool("ExperimentalLongitudinalEnabled"))
Params().put("CarParams", CP.to_bytes())
@@ -204,7 +204,7 @@ def controlsd_rcv_callback(msg, CP, cfg, fsm):
def radar_rcv_callback(msg, CP, cfg, fsm):
if msg.which() != "can":
return [], False
- elif CP.radarOffCan:
+ elif CP.radarUnavailable:
return ["radarState", "liveTracks"], True
radar_msgs = {"honda": [0x445], "toyota": [0x19f, 0x22f], "gm": [0x474],
@@ -251,8 +251,10 @@ def ublox_rcv_callback(msg):
def laika_rcv_callback(msg, CP, cfg, fsm):
if msg.which() == 'ubloxGnss' and msg.ubloxGnss.which() == "measurementReport":
return ["gnssMeasurements"], True
+ elif msg.which() == 'qcomGnss' and msg.qcomGnss.which() == "drMeasurementReport":
+ return ["gnssMeasurements"], True
else:
- return [], True
+ return [], False
CONFIGS = [
@@ -290,7 +292,7 @@ CONFIGS = [
ProcessConfig(
proc_name="plannerd",
pub_sub={
- "modelV2": ["lateralPlan", "longitudinalPlan"],
+ "modelV2": ["lateralPlan", "longitudinalPlan", "uiPlan"],
"carControl": [], "carState": [], "controlsState": [], "radarState": [],
},
ignore=["logMonoTime", "valid", "longitudinalPlan.processingDelay", "longitudinalPlan.solverExecutionTime", "lateralPlan.solverExecutionTime"],
@@ -360,24 +362,11 @@ CONFIGS = [
tolerance=None,
fake_pubsubmaster=False,
),
- ProcessConfig(
- proc_name="laikad",
- subtest_name="Offline",
- pub_sub={
- "ubloxGnss": ["gnssMeasurements"],
- "clocks": []
- },
- ignore=["logMonoTime"],
- init_callback=get_car_params,
- should_recv_callback=laika_rcv_callback,
- tolerance=NUMPY_TOLERANCE,
- fake_pubsubmaster=True,
- environ={"LAIKAD_NO_INTERNET": "1"},
- ),
ProcessConfig(
proc_name="laikad",
pub_sub={
"ubloxGnss": ["gnssMeasurements"],
+ "qcomGnss": ["gnssMeasurements"],
"clocks": []
},
ignore=["logMonoTime"],
@@ -418,6 +407,7 @@ def setup_env(simulation=False, CP=None, cfg=None, controlsState=None):
params.put_bool("WideCameraOnly", False)
params.put_bool("DisableLogging", False)
params.put_bool("UbloxAvailable", True)
+ params.put_bool("ObdMultiplexingDisabled", True)
os.environ["NO_RADAR_SLEEP"] = "1"
os.environ["REPLAY"] = "1"
@@ -459,6 +449,9 @@ def setup_env(simulation=False, CP=None, cfg=None, controlsState=None):
if CP.openpilotLongitudinalControl:
params.put_bool("ExperimentalLongitudinalEnabled", True)
+ # controlsd process configuration assume all routes are out of dashcam
+ params.put_bool("DashcamOverride", True)
+
def python_replay_process(cfg, lr, fingerprint=None):
sub_sockets = [s for _, sub in cfg.pub_sub.items() for s in sub]
@@ -474,6 +467,12 @@ def python_replay_process(cfg, lr, fingerprint=None):
all_msgs = sorted(lr, key=lambda msg: msg.logMonoTime)
pub_msgs = [msg for msg in all_msgs if msg.which() in list(cfg.pub_sub.keys())]
+ # laikad needs decision between submaster ubloxGnss and qcomGnss, prio given to ubloxGnss
+ if cfg.proc_name == "laikad":
+ args = (*args, not any(m.which() == "ubloxGnss" for m in pub_msgs))
+ service = "qcomGnss" if args[2] else "ubloxGnss"
+ pub_msgs = [m for m in pub_msgs if m.which() == service or m.which() == 'clocks']
+
controlsState = None
initialized = False
for msg in lr:
@@ -559,7 +558,7 @@ def cpp_replay_process(cfg, lr, fingerprint=None):
managed_processes[cfg.proc_name].start()
try:
- with Timeout(TIMEOUT):
+ with Timeout(TIMEOUT, error_msg=f"timed out testing process {repr(cfg.proc_name)}"):
while not all(pm.all_readers_updated(s) for s in cfg.pub_sub.keys()):
time.sleep(0)
@@ -573,7 +572,7 @@ def cpp_replay_process(cfg, lr, fingerprint=None):
resp_sockets = cfg.pub_sub[msg.which()] if cfg.should_recv_callback is None else cfg.should_recv_callback(msg)
for s in resp_sockets:
- response = messaging.recv_one(sockets[s])
+ response = messaging.recv_one_retry(sockets[s])
if response is None:
print(f"Warning, no response received {i}")
diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit
index 1d586b0334..b44c9c2f46 100644
--- a/selfdrive/test/process_replay/ref_commit
+++ b/selfdrive/test/process_replay/ref_commit
@@ -1 +1 @@
-05ba201bcf97b6c1067dbcde2a60f71f43469c56
+dfa8e947c4ef76a9d89974a434e94a078e1ccc6a
\ No newline at end of file
diff --git a/selfdrive/test/process_replay/test_processes.py b/selfdrive/test/process_replay/test_processes.py
index c58909bf7f..569090f606 100755
--- a/selfdrive/test/process_replay/test_processes.py
+++ b/selfdrive/test/process_replay/test_processes.py
@@ -29,6 +29,7 @@ source_segments = [
("SUBARU", "341dccd5359e3c97|2022-09-12--10-35-33--3"), # SUBARU.OUTBACK
("GM", "0c58b6a25109da2b|2021-02-23--16-35-50--11"), # GM.VOLT
("GM2", "376bf99325883932|2022-10-27--13-41-22--1"), # GM.BOLT_EUV
+ ("FORD", "54827bf84c38b14f|2023-01-26--21-59-07--4"), # FORD.BRONCO_SPORT_MK1
("NISSAN", "35336926920f3571|2021-02-12--18-38-48--46"), # NISSAN.XTRAIL
("VOLKSWAGEN", "de9592456ad7d144|2021-06-29--11-00-15--6"), # VOLKSWAGEN.GOLF
("MAZDA", "bd6a637565e91581|2021-10-30--15-14-53--4"), # MAZDA.CX9_2021
@@ -52,6 +53,7 @@ segments = [
("SUBARU", "regen1E72BBDCED5|2022-09-27--15-55-31--0"),
("GM", "regen45B05A80EF6|2022-09-27--15-57-22--0"),
("GM2", "376bf99325883932|2022-10-27--13-41-22--1"),
+ ("FORD", "54827bf84c38b14f|2023-01-26--21-59-07--4"),
("NISSAN", "regenC19D899B46D|2022-09-27--15-59-13--0"),
("VOLKSWAGEN", "regenD8F7AC4BD0D|2022-09-27--16-41-45--0"),
("MAZDA", "regenFC3F9ECBB64|2022-09-27--16-03-09--0"),
diff --git a/selfdrive/test/setup_device_ci.sh b/selfdrive/test/setup_device_ci.sh
index 9e06b98662..b7d586a83b 100755
--- a/selfdrive/test/setup_device_ci.sh
+++ b/selfdrive/test/setup_device_ci.sh
@@ -56,7 +56,7 @@ cd $SOURCE_DIR
rm -f .git/index.lock
git reset --hard
-git fetch --verbose origin $GIT_COMMIT
+git fetch --no-tags --no-recurse-submodules -j4 --verbose --depth 1 origin $GIT_COMMIT
find . -maxdepth 1 -not -path './.git' -not -name '.' -not -name '..' -exec rm -rf '{}' \;
git reset --hard $GIT_COMMIT
git checkout $GIT_COMMIT
@@ -69,6 +69,7 @@ git lfs pull
(ulimit -n 65535 && git lfs prune)
echo "git checkout done, t=$SECONDS"
+du -hs $SOURCE_DIR $SOURCE_DIR/.git
rsync -a --delete $SOURCE_DIR $TEST_DIR
diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py
index 4021e27de3..84511771f7 100755
--- a/selfdrive/test/test_onroad.py
+++ b/selfdrive/test/test_onroad.py
@@ -26,7 +26,7 @@ PROCS = {
"./encoderd": 17.0,
"./camerad": 14.5,
"./locationd": 9.1,
- "selfdrive.controls.plannerd": 11.7,
+ "selfdrive.controls.plannerd": 16.5,
"./_ui": 19.2,
"selfdrive.locationd.paramsd": 9.0,
"./_sensord": 12.0,
diff --git a/selfdrive/ui/SConscript b/selfdrive/ui/SConscript
index 669c214746..a8c8463bd7 100644
--- a/selfdrive/ui/SConscript
+++ b/selfdrive/ui/SConscript
@@ -1,4 +1,5 @@
import os
+import json
Import('qt_env', 'arch', 'common', 'messaging', 'visionipc',
'cereal', 'transformations')
@@ -66,11 +67,18 @@ if GetOption('test'):
# build translation files
-translation_sources = Glob("#selfdrive/ui/translations/*.ts", strings=True)
+with open(File("translations/languages.json").abspath) as f:
+ languages = json.loads(f.read())
+translation_sources = [f"#selfdrive/ui/translations/{l}.ts" for l in languages.values()]
translation_targets = [src.replace(".ts", ".qm") for src in translation_sources]
-lrelease = 'third_party/qt5/larch64/bin/lrelease' if arch == 'larch64' else 'lrelease'
-qt_env.Command(translation_targets, translation_sources, f"{lrelease} $SOURCES")
-
+lrelease_bin = 'third_party/qt5/larch64/bin/lrelease' if arch == 'larch64' else 'lrelease'
+
+lupdate = qt_env.Command(translation_sources, qt_src, "selfdrive/ui/update_translations.py")
+lrelease = qt_env.Command(translation_targets, translation_sources, f"{lrelease_bin} $SOURCES")
+qt_env.Depends(lrelease, lupdate)
+qt_env.NoClean(translation_sources)
+qt_env.Precious(translation_sources)
+qt_env.NoCache(lupdate)
# setup and factory resetter
if GetOption('extras'):
diff --git a/selfdrive/ui/installer/installer.cc b/selfdrive/ui/installer/installer.cc
index 7d8bbf74e0..1af72c04df 100644
--- a/selfdrive/ui/installer/installer.cc
+++ b/selfdrive/ui/installer/installer.cc
@@ -141,9 +141,9 @@ void Installer::cachedFetch(const QString &cache) {
void Installer::readProgress() {
const QVector> stages = {
// prefix, weight in percentage
- {tr("Receiving objects: "), 91},
- {tr("Resolving deltas: "), 2},
- {tr("Updating files: "), 7},
+ {"Receiving objects: ", 91},
+ {"Resolving deltas: ", 2},
+ {"Updating files: ", 7},
};
auto line = QString(proc.readAllStandardError());
diff --git a/selfdrive/ui/qt/maps/map.cc b/selfdrive/ui/qt/maps/map.cc
index b5519daccf..dd30b5feff 100644
--- a/selfdrive/ui/qt/maps/map.cc
+++ b/selfdrive/ui/qt/maps/map.cc
@@ -47,7 +47,7 @@ MapWindow::MapWindow(const QMapboxGLSettings &settings) : m_settings(settings),
map_eta->setVisible(false);
auto last_gps_position = coordinate_from_param("LastGPSPosition");
- if (last_gps_position) {
+ if (last_gps_position.has_value()) {
last_position = *last_gps_position;
}
@@ -82,6 +82,7 @@ void MapWindow::initLayers() {
m_map->setPaintProperty("navLayer", "line-color", QColor("#31a1ee"));
m_map->setPaintProperty("navLayer", "line-width", 7.5);
m_map->setLayoutProperty("navLayer", "line-cap", "round");
+ m_map->addAnnotationIcon("default_marker", QImage("../assets/navigation/default_marker.svg"));
}
if (!m_map->layerExists("carPosLayer")) {
qDebug() << "Initializing carPosLayer";
@@ -124,7 +125,8 @@ void MapWindow::updateState(const UIState &s) {
}
}
- if (sm.updated("gnssMeasurements")) {
+ // TODO should check a valid/status flag
+ if (sm.updated("gnssMeasurements") && sm["gnssMeasurements"].getGnssMeasurements().getGpsWeek() > 0){
auto laikad_location = sm["gnssMeasurements"].getGnssMeasurements();
auto laikad_pos = laikad_location.getPositionECEF();
auto laikad_pos_ecef = laikad_pos.getValue();
@@ -220,7 +222,6 @@ void MapWindow::updateState(const UIState &s) {
emit instructionsChanged(i);
}
} else {
- m_map->setPitch(MIN_PITCH);
clearRoute();
}
}
@@ -237,6 +238,7 @@ void MapWindow::updateState(const UIState &s) {
m_map->setLayoutProperty("navLayer", "visibility", "visible");
route_rcv_frame = sm.rcv_frame("navRoute");
+ updateDestinationMarker();
}
}
@@ -274,6 +276,7 @@ void MapWindow::clearRoute() {
if (!m_map.isNull()) {
m_map->setLayoutProperty("navLayer", "visibility", "none");
m_map->setPitch(MIN_PITCH);
+ updateDestinationMarker();
}
map_instructions->hideIfNoError();
@@ -361,6 +364,19 @@ void MapWindow::offroadTransition(bool offroad) {
last_bearing = {};
}
+void MapWindow::updateDestinationMarker() {
+ if (marker_id != -1) {
+ m_map->removeAnnotation(marker_id);
+ marker_id = -1;
+ }
+
+ auto nav_dest = coordinate_from_param("NavDestination");
+ if (nav_dest.has_value()) {
+ auto ano = QMapbox::SymbolAnnotation {*nav_dest, "default_marker"};
+ marker_id = m_map->addAnnotation(QVariant::fromValue(ano));
+ }
+}
+
MapInstructions::MapInstructions(QWidget * parent) : QWidget(parent) {
is_rhd = Params().getBool("IsRhdDetected");
QHBoxLayout *main_layout = new QHBoxLayout(this);
diff --git a/selfdrive/ui/qt/maps/map.h b/selfdrive/ui/qt/maps/map.h
index c3d5e92530..0d8b93a5f4 100644
--- a/selfdrive/ui/qt/maps/map.h
+++ b/selfdrive/ui/qt/maps/map.h
@@ -79,6 +79,7 @@ private:
QMapboxGLSettings m_settings;
QScopedPointer m_map;
+ QMapbox::AnnotationID marker_id = -1;
void initLayers();
@@ -111,6 +112,7 @@ private:
MapETA* map_eta;
void clearRoute();
+ void updateDestinationMarker();
uint64_t route_rcv_frame = 0;
private slots:
diff --git a/selfdrive/ui/qt/maps/map_helpers.cc b/selfdrive/ui/qt/maps/map_helpers.cc
index 8d5d4e1715..95db4f2bbd 100644
--- a/selfdrive/ui/qt/maps/map_helpers.cc
+++ b/selfdrive/ui/qt/maps/map_helpers.cc
@@ -31,7 +31,7 @@ QGeoCoordinate to_QGeoCoordinate(const QMapbox::Coordinate &in) {
QMapbox::CoordinatesCollections model_to_collection(
const cereal::LiveLocationKalman::Measurement::Reader &calibratedOrientationECEF,
const cereal::LiveLocationKalman::Measurement::Reader &positionECEF,
- const cereal::ModelDataV2::XYZTData::Reader &line){
+ const cereal::XYZTData::Reader &line){
Eigen::Vector3d ecef(positionECEF.getValue()[0], positionECEF.getValue()[1], positionECEF.getValue()[2]);
Eigen::Vector3d orient(calibratedOrientationECEF.getValue()[0], calibratedOrientationECEF.getValue()[1], calibratedOrientationECEF.getValue()[2]);
diff --git a/selfdrive/ui/qt/maps/map_helpers.h b/selfdrive/ui/qt/maps/map_helpers.h
index 6bd5b0f067..f9c56107e3 100644
--- a/selfdrive/ui/qt/maps/map_helpers.h
+++ b/selfdrive/ui/qt/maps/map_helpers.h
@@ -20,7 +20,7 @@ QGeoCoordinate to_QGeoCoordinate(const QMapbox::Coordinate &in);
QMapbox::CoordinatesCollections model_to_collection(
const cereal::LiveLocationKalman::Measurement::Reader &calibratedOrientationECEF,
const cereal::LiveLocationKalman::Measurement::Reader &positionECEF,
- const cereal::ModelDataV2::XYZTData::Reader &line);
+ const cereal::XYZTData::Reader &line);
QMapbox::CoordinatesCollections coordinate_to_collection(const QMapbox::Coordinate &c);
QMapbox::CoordinatesCollections capnp_coordinate_list_to_collection(const capnp::List::Reader &coordinate_list);
QMapbox::CoordinatesCollections coordinate_list_to_collection(const QList &coordinate_list);
diff --git a/selfdrive/ui/qt/offroad/driverview.cc b/selfdrive/ui/qt/offroad/driverview.cc
index 2f366a9b38..327c7537a2 100644
--- a/selfdrive/ui/qt/offroad/driverview.cc
+++ b/selfdrive/ui/qt/offroad/driverview.cc
@@ -27,7 +27,7 @@ void DriverViewWindow::mouseReleaseEvent(QMouseEvent* e) {
}
DriverViewScene::DriverViewScene(QWidget* parent) : sm({"driverStateV2"}), QWidget(parent) {
- face_img = loadPixmap("../assets/img_driver_face.png", {FACE_IMG_SIZE, FACE_IMG_SIZE});
+ face_img = loadPixmap("../assets/img_driver_face_static.png", {FACE_IMG_SIZE, FACE_IMG_SIZE});
}
void DriverViewScene::showEvent(QShowEvent* event) {
diff --git a/selfdrive/ui/qt/offroad/settings.cc b/selfdrive/ui/qt/offroad/settings.cc
index bde8628dc4..63b87149d4 100644
--- a/selfdrive/ui/qt/offroad/settings.cc
+++ b/selfdrive/ui/qt/offroad/settings.cc
@@ -132,16 +132,17 @@ void TogglesPanel::updateToggles() {
.arg(tr("New Driving Visualization"))
.arg(tr("The driving visualization will transition to the road-facing wide-angle camera at low speeds to better show some turns. The Experimental mode logo will also be shown in the top right corner."));
+ const bool is_release = params.getBool("IsReleaseBranch");
auto cp_bytes = params.get("CarParamsPersistent");
if (!cp_bytes.empty()) {
AlignedBuffer aligned_buf;
capnp::FlatArrayMessageReader cmsg(aligned_buf.align(cp_bytes.data(), cp_bytes.size()));
cereal::CarParams::Reader CP = cmsg.getRoot();
- if (!CP.getExperimentalLongitudinalAvailable()) {
+ if (!CP.getExperimentalLongitudinalAvailable() || is_release) {
params.remove("ExperimentalLongitudinalEnabled");
}
- op_long_toggle->setVisible(CP.getExperimentalLongitudinalAvailable());
+ op_long_toggle->setVisible(CP.getExperimentalLongitudinalAvailable() && !is_release);
const bool op_long = CP.getOpenpilotLongitudinalControl() && !CP.getExperimentalLongitudinalAvailable();
const bool exp_long_enabled = CP.getExperimentalLongitudinalAvailable() && params.getBool("ExperimentalLongitudinalEnabled");
@@ -154,9 +155,18 @@ void TogglesPanel::updateToggles() {
e2e_toggle->setEnabled(false);
params.remove("ExperimentalMode");
- const QString no_long = tr("Experimental mode is currently unavailable on this car, since the car's stock ACC is used for longitudinal control.");
- const QString exp_long = tr("Enable experimental longitudinal control to allow experimental mode.");
- e2e_toggle->setDescription("" + (CP.getExperimentalLongitudinalAvailable() ? exp_long : no_long) + "
" + e2e_description);
+ const QString unavailable = tr("Experimental mode is currently unavailable on this car since the car's stock ACC is used for longitudinal control.");
+
+ QString long_desc = unavailable + " " + \
+ tr("openpilot longitudinal control may come in a future update.");
+ if (CP.getExperimentalLongitudinalAvailable()) {
+ if (is_release) {
+ long_desc = unavailable + " " + tr("An experimental version of openpilot longitudinal control can be tested, along with Experimental mode, on non-release branches.");
+ } else {
+ long_desc = tr("Enable experimental longitudinal control to allow Experimental mode.");
+ }
+ }
+ e2e_toggle->setDescription("" + long_desc + "
" + e2e_description);
}
e2e_toggle->refresh();
diff --git a/selfdrive/ui/qt/offroad/software_settings.cc b/selfdrive/ui/qt/offroad/software_settings.cc
index 12d62e63fb..6db6a6cdfe 100644
--- a/selfdrive/ui/qt/offroad/software_settings.cc
+++ b/selfdrive/ui/qt/offroad/software_settings.cc
@@ -54,7 +54,7 @@ SoftwarePanel::SoftwarePanel(QWidget* parent) : ListWidget(parent) {
connect(targetBranchBtn, &ButtonControl::clicked, [=]() {
auto current = params.get("GitBranch");
QStringList branches = QString::fromStdString(params.get("UpdaterAvailableBranches")).split(",");
- for (QString b : {current.c_str(), "devel-staging", "devel", "master-ci", "master"}) {
+ for (QString b : {current.c_str(), "devel-staging", "devel", "nightly", "master-ci", "master"}) {
auto i = branches.indexOf(b);
if (i >= 0) {
branches.removeAt(i);
diff --git a/selfdrive/ui/qt/onroad.cc b/selfdrive/ui/qt/onroad.cc
index 95ad813dff..98c636b0a4 100644
--- a/selfdrive/ui/qt/onroad.cc
+++ b/selfdrive/ui/qt/onroad.cc
@@ -175,12 +175,63 @@ void OnroadAlerts::paintEvent(QPaintEvent *event) {
}
+ExperimentalButton::ExperimentalButton(QWidget *parent) : QPushButton(parent) {
+ setVisible(false);
+ setFixedSize(btn_size, btn_size);
+ setCheckable(true);
+
+ 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::toggled, [=](bool checked) {
+ params.putBool("ExperimentalMode", checked);
+ });
+}
+
+void ExperimentalButton::updateState(const UIState &s) {
+ const SubMaster &sm = *(s.sm);
+
+ // button is "visible" if engageable or enabled
+ const auto cs = sm["controlsState"].getControlsState();
+ setVisible(cs.getEngageable() || cs.getEnabled());
+
+ // button is "checked" if experimental mode is enabled
+ setChecked(sm["controlsState"].getControlsState().getExperimentalMode());
+
+ // disable button when experimental mode is not available, or has not been confirmed for the first time
+ const auto cp = sm["carParams"].getCarParams();
+ const bool experimental_mode_available = cp.getExperimentalLongitudinalAvailable() ? params.getBool("ExperimentalLongitudinalEnabled") : cp.getOpenpilotLongitudinalControl();
+ setEnabled(params.getBool("ExperimentalModeConfirmed") && experimental_mode_available);
+}
+
+void ExperimentalButton::paintEvent(QPaintEvent *event) {
+ QPainter p(this);
+ p.setRenderHint(QPainter::Antialiasing);
+
+ QPoint center(btn_size / 2, btn_size / 2);
+ QPixmap img = isChecked() ? experimental_img : engage_img;
+
+ p.setOpacity(1.0);
+ p.setPen(Qt::NoPen);
+ p.setBrush(QColor(0, 0, 0, 166));
+ p.drawEllipse(center, btn_size / 2, btn_size / 2);
+ p.setOpacity(isDown() ? 0.8 : 1.0);
+ p.drawPixmap((btn_size - img_size) / 2, (btn_size - img_size) / 2, img);
+}
+
+
AnnotatedCameraWidget::AnnotatedCameraWidget(VisionStreamType type, QWidget* parent) : fps_filter(UI_FREQ, 3, 1. / UI_FREQ), CameraWidget("camerad", type, true, parent) {
pm = std::make_unique>({"uiDebug"});
- engage_img = loadPixmap("../assets/img_chffr_wheel.png", {img_size, img_size});
- experimental_img = loadPixmap("../assets/img_experimental.svg", {img_size - 5, img_size - 5});
- dm_img = loadPixmap("../assets/img_driver_face.png", {img_size, img_size});
+ QVBoxLayout *main_layout = new QVBoxLayout(this);
+ main_layout->setMargin(bdr_s);
+ main_layout->setSpacing(0);
+
+ experimental_btn = new ExperimentalButton(this);
+ main_layout->addWidget(experimental_btn, 0, Qt::AlignTop | Qt::AlignRight);
+
+ dm_img = loadPixmap("../assets/img_driver_face.png", {img_size + 5, img_size + 5});
}
void AnnotatedCameraWidget::updateState(const UIState &s) {
@@ -224,15 +275,20 @@ void AnnotatedCameraWidget::updateState(const UIState &s) {
setProperty("speed", cur_speed);
setProperty("setSpeed", set_speed);
setProperty("speedUnit", s.scene.is_metric ? tr("km/h") : tr("mph"));
- setProperty("hideDM", cs.getAlertSize() != cereal::ControlsState::AlertSize::NONE);
+ setProperty("hideDM", (cs.getAlertSize() != cereal::ControlsState::AlertSize::NONE));
setProperty("status", s.status);
- // update engageability and DM icons at 2Hz
+ // update engageability/experimental mode button
+ experimental_btn->updateState(s);
+
+ // update DM icons at 2Hz
if (sm.frame % (UI_FREQ / 2) == 0) {
- setProperty("engageable", cs.getEngageable() || cs.getEnabled());
setProperty("dmActive", sm["driverMonitoringState"].getDriverMonitoringState().getIsActiveMode());
setProperty("rightHandDM", sm["driverMonitoringState"].getDriverMonitoringState().getIsRHD());
}
+
+ // DM icon transition
+ dm_fade_state = fmax(0.0, fmin(1.0, dm_fade_state+0.2*(0.5-(float)(dmActive))));
}
void AnnotatedCameraWidget::drawHud(QPainter &p) {
@@ -382,19 +438,6 @@ void AnnotatedCameraWidget::drawHud(QPainter &p) {
configFont(p, "Inter", 66, "Regular");
drawText(p, rect().center().x(), 290, speedUnit, 200);
- // engage-ability icon
- if (engageable) {
- SubMaster &sm = *(uiState()->sm);
- drawIcon(p, rect().right() - radius / 2 - bdr_s * 2, radius / 2 + int(bdr_s * 1.5),
- sm["controlsState"].getControlsState().getExperimentalMode() ? experimental_img : engage_img, blackColor(166), 1.0);
- }
-
- // dm icon
- if (!hideDM) {
- int dm_icon_x = rightHandDM ? rect().right() - radius / 2 - (bdr_s * 2) : radius / 2 + (bdr_s * 2);
- drawIcon(p, dm_icon_x, rect().bottom() - footer_h / 2,
- dm_img, blackColor(70), dmActive ? 1.0 : 0.2);
- }
p.restore();
}
@@ -414,7 +457,7 @@ void AnnotatedCameraWidget::drawIcon(QPainter &p, int x, int y, QPixmap &img, QB
p.setOpacity(1.0); // bg dictates opacity of ellipse
p.setPen(Qt::NoPen);
p.setBrush(bg);
- p.drawEllipse(x - radius / 2, y - radius / 2, radius, radius);
+ p.drawEllipse(x - btn_size / 2, y - btn_size / 2, btn_size, btn_size);
p.setOpacity(opacity);
p.drawPixmap(x - img.size().width() / 2, y - img.size().height() / 2, img);
}
@@ -498,13 +541,56 @@ void AnnotatedCameraWidget::drawLaneLines(QPainter &painter, const UIState *s) {
painter.restore();
}
-void AnnotatedCameraWidget::drawLead(QPainter &painter, const cereal::ModelDataV2::LeadDataV3::Reader &lead_data, const QPointF &vd) {
+void AnnotatedCameraWidget::drawDriverState(QPainter &painter, const UIState *s) {
+ const UIScene &scene = s->scene;
+
+ painter.save();
+
+ // base icon
+ int x = rightHandDM ? rect().right() - (btn_size - 24) / 2 - (bdr_s * 2) : (btn_size - 24) / 2 + (bdr_s * 2);
+ int y = rect().bottom() - footer_h / 2;
+ float opacity = dmActive ? 0.65 : 0.2;
+ drawIcon(painter, x, y, dm_img, blackColor(0), opacity);
+
+ // circle background
+ painter.setOpacity(1.0);
+ painter.setPen(Qt::NoPen);
+ painter.setBrush(blackColor(70));
+ painter.drawEllipse(x - btn_size / 2, y - btn_size / 2, btn_size, btn_size);
+
+ // face
+ QPointF face_kpts_draw[std::size(default_face_kpts_3d)];
+ float kp;
+ for (int i = 0; i < std::size(default_face_kpts_3d); ++i) {
+ kp = (scene.face_kpts_draw[i].v[2] - 8) / 120 + 1.0;
+ face_kpts_draw[i] = QPointF(scene.face_kpts_draw[i].v[0] * kp + x, scene.face_kpts_draw[i].v[1] * kp + y);
+ }
+
+ painter.setPen(QPen(QColor::fromRgbF(1.0, 1.0, 1.0, opacity), 5.2, Qt::SolidLine, Qt::RoundCap));
+ painter.drawPolyline(face_kpts_draw, std::size(default_face_kpts_3d));
+
+ // tracking arcs
+ const int arc_l = 133;
+ const float arc_t_default = 6.7;
+ const float arc_t_extend = 12.0;
+ QColor arc_color = QColor::fromRgbF(0.09, 0.945, 0.26, 0.4*(1.0-dm_fade_state)*(s->engaged()));
+ float delta_x = -scene.driver_pose_sins[1] * arc_l / 2;
+ float delta_y = -scene.driver_pose_sins[0] * arc_l / 2;
+ painter.setPen(QPen(arc_color, arc_t_default+arc_t_extend*fmin(1.0, scene.driver_pose_diff[1] * 5.0), Qt::SolidLine, Qt::RoundCap));
+ painter.drawArc(QRectF(std::fmin(x + delta_x, x), y - arc_l / 2, fabs(delta_x), arc_l), (scene.driver_pose_sins[1]>0 ? 90 : -90) * 16, 180 * 16);
+ painter.setPen(QPen(arc_color, arc_t_default+arc_t_extend*fmin(1.0, scene.driver_pose_diff[0] * 5.0), Qt::SolidLine, Qt::RoundCap));
+ painter.drawArc(QRectF(x - arc_l / 2, std::fmin(y + delta_y, y), arc_l, fabs(delta_y)), (scene.driver_pose_sins[0]>0 ? 0 : 180) * 16, 180 * 16);
+
+ painter.restore();
+}
+
+void AnnotatedCameraWidget::drawLead(QPainter &painter, const cereal::RadarState::LeadData::Reader &lead_data, const QPointF &vd) {
painter.save();
const float speedBuff = 10.;
const float leadBuff = 40.;
- const float d_rel = lead_data.getX()[0];
- const float v_rel = lead_data.getV()[0];
+ const float d_rel = lead_data.getDRel();
+ const float v_rel = lead_data.getVRel();
float fillAlpha = 0;
if (d_rel < leadBuff) {
@@ -539,6 +625,7 @@ void AnnotatedCameraWidget::paintGL() {
SubMaster &sm = *(s->sm);
const double start_draw_t = millis_since_boot();
const cereal::ModelDataV2::Reader &model = sm["modelV2"].getModelV2();
+ const cereal::RadarState::Reader &radar_state = sm["radarState"].getRadarState();
// draw camera frame
{
@@ -587,25 +674,32 @@ void AnnotatedCameraWidget::paintGL() {
if (s->worldObjectsVisible()) {
if (sm.rcv_frame("modelV2") > s->scene.started_frame) {
- update_model(s, sm["modelV2"].getModelV2());
+ update_model(s, sm["modelV2"].getModelV2(), sm["uiPlan"].getUiPlan());
if (sm.rcv_frame("radarState") > s->scene.started_frame) {
- update_leads(s, sm["radarState"].getRadarState(), sm["modelV2"].getModelV2().getPosition());
+ update_leads(s, radar_state, sm["modelV2"].getModelV2().getPosition());
}
}
drawLaneLines(painter, s);
if (s->scene.longitudinal_control) {
- const auto leads = model.getLeadsV3();
- if (leads[0].getProb() > .5) {
- drawLead(painter, leads[0], s->scene.lead_vertices[0]);
+ auto lead_one = radar_state.getLeadOne();
+ auto lead_two = radar_state.getLeadTwo();
+ if (lead_one.getStatus()) {
+ drawLead(painter, lead_one, s->scene.lead_vertices[0]);
}
- if (leads[1].getProb() > .5 && (std::abs(leads[1].getX()[0] - leads[0].getX()[0]) > 3.0)) {
- drawLead(painter, leads[1], s->scene.lead_vertices[1]);
+ if (lead_two.getStatus() && (std::abs(lead_one.getDRel() - lead_two.getDRel()) > 3.0)) {
+ drawLead(painter, lead_two, s->scene.lead_vertices[1]);
}
}
}
+ // DMoji
+ if (!hideDM && (sm.rcv_frame("driverStateV2") > s->scene.started_frame)) {
+ update_dmonitoring(s, sm["driverStateV2"].getDriverStateV2(), dm_fade_state, rightHandDM);
+ drawDriverState(painter, s);
+ }
+
drawHud(painter);
double cur_draw_t = millis_since_boot();
diff --git a/selfdrive/ui/qt/onroad.h b/selfdrive/ui/qt/onroad.h
index 9e18355970..73c2a37892 100644
--- a/selfdrive/ui/qt/onroad.h
+++ b/selfdrive/ui/qt/onroad.h
@@ -1,11 +1,16 @@
#pragma once
+#include
#include
#include
#include "common/util.h"
-#include "selfdrive/ui/qt/widgets/cameraview.h"
#include "selfdrive/ui/ui.h"
+#include "selfdrive/ui/qt/widgets/cameraview.h"
+
+
+const int btn_size = 192;
+const int img_size = (btn_size / 4) * 3;
// ***** onroad widgets *****
@@ -24,6 +29,21 @@ private:
Alert alert = {};
};
+class ExperimentalButton : public QPushButton {
+ Q_OBJECT
+
+public:
+ explicit ExperimentalButton(QWidget *parent = 0);
+ void updateState(const UIState &s);
+
+private:
+ void paintEvent(QPaintEvent *event) override;
+
+ Params params;
+ QPixmap engage_img;
+ QPixmap experimental_img;
+};
+
// container window for the NVG UI
class AnnotatedCameraWidget : public CameraWidget {
Q_OBJECT
@@ -36,7 +56,6 @@ class AnnotatedCameraWidget : public CameraWidget {
Q_PROPERTY(bool has_us_speed_limit MEMBER has_us_speed_limit);
Q_PROPERTY(bool is_metric MEMBER is_metric);
- Q_PROPERTY(bool engageable MEMBER engageable);
Q_PROPERTY(bool dmActive MEMBER dmActive);
Q_PROPERTY(bool hideDM MEMBER hideDM);
Q_PROPERTY(bool rightHandDM MEMBER rightHandDM);
@@ -50,21 +69,18 @@ private:
void drawIcon(QPainter &p, int x, int y, QPixmap &img, QBrush bg, float opacity);
void drawText(QPainter &p, int x, int y, const QString &text, int alpha = 255);
- QPixmap engage_img;
- QPixmap experimental_img;
+ ExperimentalButton *experimental_btn;
QPixmap dm_img;
- const int radius = 192;
- const int img_size = (radius / 2) * 1.5;
float speed;
QString speedUnit;
float setSpeed;
float speedLimit;
bool is_cruise_set = false;
bool is_metric = false;
- bool engageable = false;
bool dmActive = false;
bool hideDM = false;
bool rightHandDM = false;
+ float dm_fade_state = 1.0;
bool has_us_speed_limit = false;
bool has_eu_speed_limit = false;
bool v_ego_cluster_seen = false;
@@ -80,8 +96,9 @@ protected:
void showEvent(QShowEvent *event) override;
void updateFrameMat() override;
void drawLaneLines(QPainter &painter, const UIState *s);
- void drawLead(QPainter &painter, const cereal::ModelDataV2::LeadDataV3::Reader &lead_data, const QPointF &vd);
+ void drawLead(QPainter &painter, const cereal::RadarState::LeadData::Reader &lead_data, const QPointF &vd);
void drawHud(QPainter &p);
+ void drawDriverState(QPainter &painter, const UIState *s);
inline QColor redColor(int alpha = 255) { return QColor(201, 34, 49, alpha); }
inline QColor whiteColor(int alpha = 255) { return QColor(255, 255, 255, alpha); }
inline QColor blackColor(int alpha = 255) { return QColor(0, 0, 0, alpha); }
diff --git a/selfdrive/ui/qt/setup/reset.cc b/selfdrive/ui/qt/setup/reset.cc
index 582217c1d7..ccf9bf8053 100644
--- a/selfdrive/ui/qt/setup/reset.cc
+++ b/selfdrive/ui/qt/setup/reset.cc
@@ -11,14 +11,11 @@
#define NVME "/dev/nvme0n1"
#define USERDATA "/dev/disk/by-partlabel/userdata"
-void Reset::doReset() {
- // best effort to wipe nvme and sd card
+void Reset::doErase() {
+ // best effort to wipe nvme
std::system("sudo umount " NVME);
std::system("yes | sudo mkfs.ext4 " NVME);
- // we handle two cases here
- // * user-prompted factory reset
- // * recovering from a corrupt userdata by formatting
int rm = std::system("sudo rm -rf /data/*");
std::system("sudo umount " USERDATA);
int fmt = std::system("yes | sudo mkfs.ext4 " USERDATA);
@@ -30,22 +27,26 @@ void Reset::doReset() {
rebootBtn->show();
}
+void Reset::startReset() {
+ body->setText(tr("Resetting device...\nThis may take up to a minute."));
+ rejectBtn->hide();
+ rebootBtn->hide();
+ confirmBtn->hide();
+#ifdef __aarch64__
+ QTimer::singleShot(100, this, &Reset::doErase);
+#endif
+}
+
void Reset::confirm() {
const QString confirm_txt = tr("Are you sure you want to reset your device?");
if (body->text() != confirm_txt) {
body->setText(confirm_txt);
} else {
- body->setText(tr("Resetting device..."));
- rejectBtn->hide();
- rebootBtn->hide();
- confirmBtn->hide();
-#ifdef __aarch64__
- QTimer::singleShot(100, this, &Reset::doReset);
-#endif
+ startReset();
}
}
-Reset::Reset(bool recover, QWidget *parent) : QWidget(parent) {
+Reset::Reset(ResetMode mode, QWidget *parent) : QWidget(parent) {
QVBoxLayout *main_layout = new QVBoxLayout(this);
main_layout->setContentsMargins(45, 220, 45, 45);
main_layout->setSpacing(0);
@@ -56,7 +57,7 @@ Reset::Reset(bool recover, QWidget *parent) : QWidget(parent) {
main_layout->addSpacing(60);
- body = new QLabel(tr("System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot."));
+ body = new QLabel(tr("Press confirm to erase all content and settings. Press cancel to resume boot."));
body->setWordWrap(true);
body->setStyleSheet("font-size: 80px; font-weight: light;");
main_layout->addWidget(body, 1, Qt::AlignTop | Qt::AlignLeft);
@@ -82,10 +83,16 @@ Reset::Reset(bool recover, QWidget *parent) : QWidget(parent) {
blayout->addWidget(confirmBtn);
QObject::connect(confirmBtn, &QPushButton::clicked, this, &Reset::confirm);
+ bool recover = mode == ResetMode::RECOVER;
rejectBtn->setVisible(!recover);
rebootBtn->setVisible(recover);
if (recover) {
- body->setText(tr("Unable to mount data partition. Press confirm to reset your device."));
+ body->setText(tr("Unable to mount data partition. Partition may be corrupted. Press confirm to erase and reset your device."));
+ }
+
+ // automatically start if we're just finishing up an ABL reset
+ if (mode == ResetMode::FORMAT) {
+ startReset();
}
setStyleSheet(R"(
@@ -108,9 +115,17 @@ Reset::Reset(bool recover, QWidget *parent) : QWidget(parent) {
}
int main(int argc, char *argv[]) {
- bool recover = argc > 1 && strcmp(argv[1], "--recover") == 0;
+ ResetMode mode = ResetMode::USER_RESET;
+ if (argc > 1) {
+ if (strcmp(argv[1], "--recover") == 0) {
+ mode = ResetMode::RECOVER;
+ } else if (strcmp(argv[1], "--format") == 0) {
+ mode = ResetMode::FORMAT;
+ }
+ }
+
QApplication a(argc, argv);
- Reset reset(recover);
+ Reset reset(mode);
setMainWindow(&reset);
return a.exec();
}
diff --git a/selfdrive/ui/qt/setup/reset.h b/selfdrive/ui/qt/setup/reset.h
index 3a4994077c..04a191d829 100644
--- a/selfdrive/ui/qt/setup/reset.h
+++ b/selfdrive/ui/qt/setup/reset.h
@@ -2,18 +2,25 @@
#include
#include
+enum ResetMode {
+ USER_RESET, // user initiated a factory reset from openpilot
+ RECOVER, // userdata is corrupt for some reason, give a chance to recover
+ FORMAT, // finish up an ABL factory reset
+};
+
class Reset : public QWidget {
Q_OBJECT
public:
- explicit Reset(bool recover = false, QWidget *parent = 0);
+ explicit Reset(ResetMode mode, QWidget *parent = 0);
private:
QLabel *body;
QPushButton *rejectBtn;
QPushButton *rebootBtn;
QPushButton *confirmBtn;
- void doReset();
+ void doErase();
+ void startReset();
private slots:
void confirm();
diff --git a/selfdrive/ui/qt/setup/setup.cc b/selfdrive/ui/qt/setup/setup.cc
index 69dafcf741..de5021c8bc 100644
--- a/selfdrive/ui/qt/setup/setup.cc
+++ b/selfdrive/ui/qt/setup/setup.cc
@@ -20,15 +20,29 @@
const std::string USER_AGENT = "AGNOSSetup-";
const QString DASHCAM_URL = "https://dashcam.comma.ai";
+bool is_elf(char *fname) {
+ FILE *fp = fopen(fname, "rb");
+ if (fp == NULL) {
+ return false;
+ }
+ char buf[4];
+ size_t n = fread(buf, 1, 4, fp);
+ fclose(fp);
+ return n == 4 && buf[0] == 0x7f && buf[1] == 'E' && buf[2] == 'L' && buf[3] == 'F';
+}
+
void Setup::download(QString url) {
CURL *curl = curl_easy_init();
if (!curl) {
- emit finished(false);
+ emit finished(url, tr("Something went wrong. Reboot the device."));
return;
}
auto version = util::read_file("/VERSION");
+ struct curl_slist *list = NULL;
+ list = curl_slist_append(list, ("X-openpilot-serial: " + Hardware::get_serial()).c_str());
+
char tmpfile[] = "/tmp/installer_XXXXXX";
FILE *fp = fdopen(mkstemp(tmpfile), "w");
@@ -38,18 +52,28 @@ void Setup::download(QString url) {
curl_easy_setopt(curl, CURLOPT_VERBOSE, 1L);
curl_easy_setopt(curl, CURLOPT_FOLLOWLOCATION, 1L);
curl_easy_setopt(curl, CURLOPT_USERAGENT, (USER_AGENT + version).c_str());
+ curl_easy_setopt(curl, CURLOPT_HTTPHEADER, list);
+ curl_easy_setopt(curl, CURLOPT_TIMEOUT, 30L);
int ret = curl_easy_perform(curl);
-
long res_status = 0;
curl_easy_getinfo(curl, CURLINFO_RESPONSE_CODE, &res_status);
- if (ret == CURLE_OK && res_status == 200) {
- rename(tmpfile, "/tmp/installer");
- emit finished(true);
+
+ if (ret != CURLE_OK || res_status != 200) {
+ emit finished(url, tr("Ensure the entered URL is valid, and the device’s internet connection is good."));
+ } else if (!is_elf(tmpfile)) {
+ emit finished(url, tr("No custom software found at this URL."));
} else {
- emit finished(false);
+ rename(tmpfile, "/tmp/installer");
+
+ FILE *fp_url = fopen("/tmp/installer_url", "w");
+ fprintf(fp_url, "%s", url.toStdString().c_str());
+ fclose(fp_url);
+
+ emit finished(url);
}
+ curl_slist_free_all(list);
curl_easy_cleanup(curl);
fclose(fp);
}
@@ -170,7 +194,20 @@ QWidget * Setup::network_setup() {
QPushButton *cont = new QPushButton();
cont->setObjectName("navBtn");
cont->setProperty("primary", true);
- QObject::connect(cont, &QPushButton::clicked, this, &Setup::nextPage);
+ QObject::connect(cont, &QPushButton::clicked, [=]() {
+ auto w = currentWidget();
+ QTimer::singleShot(0, [=]() {
+ setCurrentWidget(downloading_widget);
+ });
+ QString url = InputDialog::getText(tr("Enter URL"), this, tr("for Custom Software"));
+ if (!url.isEmpty()) {
+ QTimer::singleShot(1000, this, [=]() {
+ download(url);
+ });
+ } else {
+ setCurrentWidget(w);
+ }
+ });
blayout->addWidget(cont);
// setup timer for testing internet connection
@@ -178,8 +215,8 @@ QWidget * Setup::network_setup() {
QObject::connect(request, &HttpRequest::requestDone, [=](const QString &, bool success) {
cont->setEnabled(success);
if (success) {
- const bool cell = networking->wifi->currentNetworkType() == NetworkType::CELL;
- cont->setText(cell ? tr("Continue without Wi-Fi") : tr("Continue"));
+ const bool wifi = networking->wifi->currentNetworkType() == NetworkType::WIFI;
+ cont->setText(wifi ? tr("Continue") : tr("Continue without Wi-Fi"));
} else {
cont->setText(tr("Waiting for internet"));
}
@@ -197,106 +234,6 @@ QWidget * Setup::network_setup() {
return widget;
}
-QWidget * radio_button(QString title, QButtonGroup *group) {
- QPushButton *btn = new QPushButton(title);
- btn->setCheckable(true);
- group->addButton(btn);
- btn->setStyleSheet(R"(
- QPushButton {
- height: 230;
- padding-left: 100px;
- padding-right: 100px;
- text-align: left;
- font-size: 80px;
- font-weight: 400;
- border-radius: 10px;
- background-color: #4F4F4F;
- }
- QPushButton:checked {
- background-color: #465BEA;
- }
- )");
-
- // checkmark icon
- QPixmap pix(":/img_circled_check.svg");
- btn->setIcon(pix);
- btn->setIconSize(QSize(0, 0));
- btn->setLayoutDirection(Qt::RightToLeft);
- QObject::connect(btn, &QPushButton::toggled, [=](bool checked) {
- btn->setIconSize(checked ? QSize(104, 104) : QSize(0, 0));
- });
- return btn;
-}
-
-QWidget * Setup::software_selection() {
- QWidget *widget = new QWidget();
- QVBoxLayout *main_layout = new QVBoxLayout(widget);
- main_layout->setContentsMargins(55, 50, 55, 50);
- main_layout->setSpacing(0);
-
- // title
- QLabel *title = new QLabel(tr("Choose Software to Install"));
- title->setStyleSheet("font-size: 90px; font-weight: 500;");
- main_layout->addWidget(title, 0, Qt::AlignLeft | Qt::AlignTop);
-
- main_layout->addSpacing(50);
-
- // dashcam + custom radio buttons
- QButtonGroup *group = new QButtonGroup(widget);
- group->setExclusive(true);
-
- QWidget *dashcam = radio_button(tr("Dashcam"), group);
- main_layout->addWidget(dashcam);
-
- main_layout->addSpacing(30);
-
- QWidget *custom = radio_button(tr("Custom Software"), group);
- main_layout->addWidget(custom);
-
- main_layout->addStretch();
-
- // back + continue buttons
- QHBoxLayout *blayout = new QHBoxLayout;
- main_layout->addLayout(blayout);
- blayout->setSpacing(50);
-
- QPushButton *back = new QPushButton(tr("Back"));
- back->setObjectName("navBtn");
- QObject::connect(back, &QPushButton::clicked, this, &Setup::prevPage);
- blayout->addWidget(back);
-
- QPushButton *cont = new QPushButton(tr("Continue"));
- cont->setObjectName("navBtn");
- cont->setEnabled(false);
- cont->setProperty("primary", true);
- blayout->addWidget(cont);
-
- QObject::connect(cont, &QPushButton::clicked, [=]() {
- auto w = currentWidget();
- QTimer::singleShot(0, [=]() {
- setCurrentWidget(downloading_widget);
- });
- QString url = DASHCAM_URL;
- if (group->checkedButton() != dashcam) {
- url = InputDialog::getText(tr("Enter URL"), this, tr("for Custom Software"));
- }
- if (!url.isEmpty()) {
- QTimer::singleShot(1000, this, [=]() {
- download(url);
- });
- } else {
- setCurrentWidget(w);
- }
- });
-
- connect(group, QOverload::of(&QButtonGroup::buttonClicked), [=](QAbstractButton *btn) {
- btn->setChecked(true);
- cont->setEnabled(true);
- });
-
- return widget;
-}
-
QWidget * Setup::downloading() {
QWidget *widget = new QWidget();
QVBoxLayout *main_layout = new QVBoxLayout(widget);
@@ -306,10 +243,10 @@ QWidget * Setup::downloading() {
return widget;
}
-QWidget * Setup::download_failed() {
+QWidget * Setup::download_failed(QLabel *url, QLabel *body) {
QWidget *widget = new QWidget();
QVBoxLayout *main_layout = new QVBoxLayout(widget);
- main_layout->setContentsMargins(55, 225, 55, 55);
+ main_layout->setContentsMargins(55, 185, 55, 55);
main_layout->setSpacing(0);
QLabel *title = new QLabel(tr("Download Failed"));
@@ -318,7 +255,13 @@ QWidget * Setup::download_failed() {
main_layout->addSpacing(67);
- QLabel *body = new QLabel(tr("Ensure the entered URL is valid, and the device’s internet connection is good."));
+ url->setWordWrap(true);
+ url->setAlignment(Qt::AlignTop | Qt::AlignLeft);
+ url->setStyleSheet("font-family: \"JetBrains Mono\"; font-size: 64px; font-weight: 400; margin-right: 100px;");
+ main_layout->addWidget(url);
+
+ main_layout->addSpacing(48);
+
body->setWordWrap(true);
body->setAlignment(Qt::AlignTop | Qt::AlignLeft);
body->setStyleSheet("font-size: 80px; font-weight: 300; margin-right: 100px;");
@@ -343,7 +286,7 @@ QWidget * Setup::download_failed() {
restart->setProperty("primary", true);
blayout->addWidget(restart);
QObject::connect(restart, &QPushButton::clicked, this, [=]() {
- setCurrentIndex(2);
+ setCurrentIndex(1);
});
widget->setStyleSheet(R"(
@@ -372,20 +315,23 @@ Setup::Setup(QWidget *parent) : QStackedWidget(parent) {
addWidget(getting_started());
addWidget(network_setup());
- addWidget(software_selection());
downloading_widget = downloading();
addWidget(downloading_widget);
- failed_widget = download_failed();
+ QLabel *url_label = new QLabel();
+ QLabel *body_label = new QLabel();
+ failed_widget = download_failed(url_label, body_label);
addWidget(failed_widget);
- QObject::connect(this, &Setup::finished, [=](bool success) {
- // hide setup on success
- qDebug() << "finished" << success;
- if (success) {
+ QObject::connect(this, &Setup::finished, [=](const QString &url, const QString &error) {
+ qDebug() << "finished" << url << error;
+ if (error.isEmpty()) {
+ // hide setup on success
QTimer::singleShot(3000, this, &QWidget::hide);
} else {
+ url_label->setText(url);
+ body_label->setText(error);
setCurrentWidget(failed_widget);
}
});
diff --git a/selfdrive/ui/qt/setup/setup.h b/selfdrive/ui/qt/setup/setup.h
index 8027e8bd4f..bf5d97070d 100644
--- a/selfdrive/ui/qt/setup/setup.h
+++ b/selfdrive/ui/qt/setup/setup.h
@@ -1,5 +1,6 @@
#pragma once
+#include
#include
#include
#include
@@ -14,15 +15,14 @@ private:
QWidget *low_voltage();
QWidget *getting_started();
QWidget *network_setup();
- QWidget *software_selection();
QWidget *downloading();
- QWidget *download_failed();
+ QWidget *download_failed(QLabel *url, QLabel *body);
QWidget *failed_widget;
QWidget *downloading_widget;
signals:
- void finished(bool success);
+ void finished(const QString &url, const QString &error = "");
public slots:
void nextPage();
diff --git a/selfdrive/ui/qt/util.cc b/selfdrive/ui/qt/util.cc
index 59903e3376..4f52310649 100644
--- a/selfdrive/ui/qt/util.cc
+++ b/selfdrive/ui/qt/util.cc
@@ -2,11 +2,14 @@
#include
#include
+#include
#include
#include
#include
#include
#include
+#include
+#include
#include "common/params.h"
#include "common/swaglog.h"
@@ -218,3 +221,37 @@ QColor interpColor(float xv, std::vector xp, std::vector fp) {
);
}
}
+
+static QHash load_bootstrap_icons() {
+ QHash icons;
+
+ QFile f(":/bootstrap-icons.svg");
+ if (f.open(QIODevice::ReadOnly | QIODevice::Text)) {
+ QDomDocument xml;
+ xml.setContent(&f);
+ QDomNode n = xml.documentElement().firstChild();
+ while (!n.isNull()) {
+ QDomElement e = n.toElement();
+ if (!e.isNull() && e.hasAttribute("id")) {
+ QString svg_str;
+ QTextStream stream(&svg_str);
+ n.save(stream, 0);
+ svg_str.replace("", "");
+ icons[e.attribute("id")] = svg_str.toUtf8();
+ }
+ n = n.nextSibling();
+ }
+ }
+ return icons;
+}
+
+QPixmap bootstrapPixmap(const QString &id) {
+ static QHash icons = load_bootstrap_icons();
+
+ QPixmap pixmap;
+ if (auto it = icons.find(id); it != icons.end()) {
+ pixmap.loadFromData(it.value(), "svg");
+ }
+ return pixmap;
+}
diff --git a/selfdrive/ui/qt/util.h b/selfdrive/ui/qt/util.h
index 61a27a8669..3188f3f9b9 100644
--- a/selfdrive/ui/qt/util.h
+++ b/selfdrive/ui/qt/util.h
@@ -22,6 +22,7 @@ void swagLogMessageHandler(QtMsgType type, const QMessageLogContext &context, co
void initApp(int argc, char *argv[]);
QWidget* topWidget (QWidget* widget);
QPixmap loadPixmap(const QString &fileName, const QSize &size = {}, Qt::AspectRatioMode aspectRatioMode = Qt::KeepAspectRatio);
+QPixmap bootstrapPixmap(const QString &id);
QRect getTextRect(QPainter &p, int flags, const QString &text);
void drawRoundedRect(QPainter &painter, const QRectF &rect, qreal xRadiusTop, qreal yRadiusTop, qreal xRadiusBottom, qreal yRadiusBottom);
diff --git a/selfdrive/ui/qt/widgets/cameraview.cc b/selfdrive/ui/qt/widgets/cameraview.cc
index 16aad13437..8c7a7072e2 100644
--- a/selfdrive/ui/qt/widgets/cameraview.cc
+++ b/selfdrive/ui/qt/widgets/cameraview.cc
@@ -358,7 +358,7 @@ void CameraWidget::vipcThread() {
while (!QThread::currentThread()->isInterruptionRequested()) {
if (!vipc_client || cur_stream != requested_stream_type) {
clearFrames();
- qDebug() << "connecting to stream " << requested_stream_type << ", was connected to " << cur_stream;
+ qDebug().nospace() << "connecting to stream " << requested_stream_type << ", was connected to " << cur_stream;
cur_stream = requested_stream_type;
vipc_client.reset(new VisionIpcClient(stream_name, cur_stream, false));
}
@@ -382,6 +382,10 @@ void CameraWidget::vipcThread() {
}
}
emit vipcThreadFrameReceived();
+ } else {
+ if (!isVisible()) {
+ vipc_client->connected = false;
+ }
}
}
diff --git a/selfdrive/ui/translations/main_de.ts b/selfdrive/ui/translations/main_de.ts
index ecb44557c9..5f3511d3cc 100644
--- a/selfdrive/ui/translations/main_de.ts
+++ b/selfdrive/ui/translations/main_de.ts
@@ -312,18 +312,6 @@
Installing...Installiere...
-
- Receiving objects:
- Empfange Objekte:
-
-
- Resolving deltas:
- Unterschiede verarbeiten:
-
-
- Updating files:
- Dateien aktualisieren:
- MapETA
@@ -588,18 +576,10 @@ location set
Are you sure you want to reset your device?Bist du sicher, dass du das Gerät auf Werkseinstellungen zurücksetzen möchtest?
-
- Resetting device...
- Gerät wird zurückgesetzt...
- System ResetSystem auf Werkseinstellungen zurücksetzen
-
- System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot.
- Zurücksetzen auf Werkseinstellungen wurde ausgewählt. Drücke Annehmen, um alle Inhalte und Einstellungen zu löschen. Drücke Abbrechen, um mit dem Starten des Gerätes fortzufahren.
- CancelAbbrechen
@@ -613,8 +593,17 @@ location set
Bestätigen
- Unable to mount data partition. Press confirm to reset your device.
- Datenpartition kann nicht geöffnet werden. Drücke Annehmen, um dein Gerät auf Werkseinstellungen zurückzusetzen.
+ Unable to mount data partition. Partition may be corrupted. Press confirm to erase and reset your device.
+
+
+
+ Press confirm to erase all content and settings. Press cancel to resume boot.
+
+
+
+ Resetting device...
+This may take up to a minute.
+
@@ -686,18 +675,6 @@ location set
Waiting for internetAuf Internet warten
-
- Choose Software to Install
- Software zum installieren auswählen
-
-
- Dashcam
- Dashcam
-
-
- Custom Software
- Spezifische Software
- Enter URLURL eingeben
@@ -726,6 +703,14 @@ location set
Start overVon neuem beginnen
+
+ No custom software found at this URL.
+
+
+
+ Something went wrong. Reboot the device.
+
+ SetupWidget
@@ -1044,11 +1029,19 @@ location set
Die Fahrvisualisierung wechselt bei niedrigen Geschwindigkeiten zur Straßengewandten Weitwinkelkamera, um manche Kurven besser zu zeigen. Außerdem wird das Experimenteller Modus logo oben rechts angezeigt.
- Experimental mode is currently unavailable on this car, since the car's stock ACC is used for longitudinal control.
- Der experimentelle Modus ist momentan für dieses Auto nicht verfügbar, da es den eingebauten adaptiven Tempomaten des Autos benutzt.
+ Experimental mode is currently unavailable on this car since the car's stock ACC is used for longitudinal control.
+ Der experimentelle Modus ist momentan für dieses Auto nicht verfügbar da es den eingebauten adaptiven Tempomaten des Autos benutzt.
+
+
+ openpilot longitudinal control may come in a future update.
+
+
+
+ An experimental version of openpilot longitudinal control can be tested, along with Experimental mode, on non-release branches.
+
- Enable experimental longitudinal control to allow experimental mode.
+ Enable experimental longitudinal control to allow Experimental mode.Aktiviere den experimentellen Openpilot Tempomaten für experimentelle Funktionen.
diff --git a/selfdrive/ui/translations/main_ja.ts b/selfdrive/ui/translations/main_ja.ts
index 8226dd59f9..1e0223606b 100644
--- a/selfdrive/ui/translations/main_ja.ts
+++ b/selfdrive/ui/translations/main_ja.ts
@@ -311,18 +311,6 @@
Installing...インストールしています...
-
- Receiving objects:
- オブジェクトをダウンロードしています:
-
-
- Resolving deltas:
- デルタを解決しています:
-
-
- Updating files:
- ファイルを更新しています:
- MapETA
@@ -586,18 +574,10 @@ location set
Are you sure you want to reset your device?初期化してもよろしいですか?
-
- Resetting device...
- デバイスが初期化されます...
- System Resetシステムを初期化
-
- System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot.
- システムの初期化をリクエストしました。「確認」ボタンを押すとデバイスが初期化されます。「キャンセル」ボタンを押すと起動を続行します。
- Cancelキャンセル
@@ -611,8 +591,17 @@ location set
確認
- Unable to mount data partition. Press confirm to reset your device.
- 「data」パーティションをマウントできません。「確認」ボタンを押すとデバイスが初期化されます。
+ Unable to mount data partition. Partition may be corrupted. Press confirm to erase and reset your device.
+
+
+
+ Press confirm to erase all content and settings. Press cancel to resume boot.
+
+
+
+ Resetting device...
+This may take up to a minute.
+
@@ -684,18 +673,6 @@ location set
Waiting for internetインターネット接続を待機中
-
- Choose Software to Install
- インストールするソフトウェアを選択してください
-
-
- Dashcam
- ドライブレコーダー
-
-
- Custom Software
- カスタムソフトウェア
- Enter URLURL を入力
@@ -724,6 +701,14 @@ location set
Start over最初からやり直す
+
+ No custom software found at this URL.
+
+
+
+ Something went wrong. Reboot the device.
+
+ SetupWidget
@@ -1017,14 +1002,6 @@ location set
On this car, openpilot defaults to the car's built-in ACC instead of openpilot's longitudinal control. Enable this to switch to openpilot longitudinal control. Enabling Experimental mode is recommended when using experimental openpilot longitudinal control.openpilotはこの車の場合、車に内蔵されているACCを標準で利用します。この機能を有効にすることで実験段階のopenpilotによるアクセル制御を利用できます。実験モードと合わせて利用することをお勧めします。
-
- Experimental mode is currently unavailable on this car, since the car's stock ACC is used for longitudinal control.
- この車のACCがアクセル制御を行うため、実験モードを利用することができません。
-
-
- Enable experimental longitudinal control to allow experimental mode.
- 実験段階のopenpilotによるアクセル制御を有効にしてください。
- openpilot defaults to driving in <b>chill mode</b>. Experimental mode enables <b>alpha-level features</b> that aren't ready for chill mode. Experimental features are listed below:openpilotは標準ではゆっくりとくつろげる運転を提供します。この実験モードを有効にすると、以下のくつろげる段階ではない開発中の機能を利用する事ができます。
@@ -1045,6 +1022,22 @@ location set
The driving visualization will transition to the road-facing wide-angle camera at low speeds to better show some turns. The Experimental mode logo will also be shown in the top right corner.新しい運転画面では、低速時に広角カメラの映像を表示することで、曲がる際の道路の視覚を向上します。実験段階を表すマークが右上に表示されます。
+
+ Experimental mode is currently unavailable on this car since the car's stock ACC is used for longitudinal control.
+ この車のACCがアクセル制御を行うため実験モードを利用することができません。
+
+
+ openpilot longitudinal control may come in a future update.
+
+
+
+ An experimental version of openpilot longitudinal control can be tested, along with Experimental mode, on non-release branches.
+
+
+
+ Enable experimental longitudinal control to allow Experimental mode.
+ 実験段階のopenpilotによるアクセル制御を有効にしてください。
+ Updater
diff --git a/selfdrive/ui/translations/main_ko.ts b/selfdrive/ui/translations/main_ko.ts
index bda64c53ab..be11f2efde 100644
--- a/selfdrive/ui/translations/main_ko.ts
+++ b/selfdrive/ui/translations/main_ko.ts
@@ -311,18 +311,6 @@
Installing...설치중...
-
- Receiving objects:
- 수신중:
-
-
- Resolving deltas:
- 델타병합:
-
-
- Updating files:
- 파일갱신:
- MapETA
@@ -415,7 +403,7 @@ location set
Waiting for GPS
- GPS를 기다리는 중
+ GPS 수신중 입니다
@@ -501,7 +489,7 @@ location set
Become a comma prime member at connect.comma.ai
- connect.comma.ai에서 comma prime에 가입합니다
+ connect.comma.ai 접속 comma prime 가입PRIME FEATURES:
@@ -586,18 +574,10 @@ location set
Are you sure you want to reset your device?장치를 초기화 하시겠습니까?
-
- Resetting device...
- 장치 초기화중...
- System Reset장치 초기화
-
- System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot.
- 장치를 초기화 합니다. 확인버튼을 누르면 모든 내용과 설정이 초기화됩니다. 부팅을 재개하려면 취소를 누르세요.
- Cancel취소
@@ -611,8 +591,18 @@ location set
확인
- Unable to mount data partition. Press confirm to reset your device.
- 데이터 파티션을 마운트할 수 없습니다. 확인 버튼을 눌러 장치를 리셋합니다.
+ Unable to mount data partition. Partition may be corrupted. Press confirm to erase and reset your device.
+ 데이터 파티션을 마운트할 수 없습니다. 파티션이 손상되었을 수 있습니다. 장치를 초기화하려면 확인을 누르세요.
+
+
+ Press confirm to erase all content and settings. Press cancel to resume boot.
+ 모든 콘텐츠와 설정을 지우려면 확인을 누르세요. 부팅을 재개하려면 취소를 누르세요.
+
+
+ Resetting device...
+This may take up to a minute.
+ 장치 초기화 중...
+최대 1분이 소요될 수 있습니다.
@@ -684,18 +674,6 @@ location set
Waiting for internet네트워크 접속을 기다립니다
-
- Choose Software to Install
- 설치할 소프트웨어를 선택하세요
-
-
- Dashcam
- Dashcam
-
-
- Custom Software
- Custom Software
- Enter URLURL 입력
@@ -724,6 +702,14 @@ location set
Start over다시 시작
+
+ Something went wrong. Reboot the device.
+ 문제가 발생했습니다. 장치를 재부팅하세요.
+
+
+ No custom software found at this URL.
+ 이 URL에서 커스텀 소프트웨어를 찾을 수 없습니다.
+ SetupWidget
@@ -1017,17 +1003,9 @@ location set
On this car, openpilot defaults to the car's built-in ACC instead of openpilot's longitudinal control. Enable this to switch to openpilot longitudinal control. Enabling Experimental mode is recommended when using experimental openpilot longitudinal control.이 차량은 openpilot 롱컨트롤 대신 차량의 내장 ACC로 기본 설정됩니다. openpilot 롱컨트롤을 사용하려면 이 옵션을 활성화하세요. 실험적 openpilot 롱컨트롤을 사용하는 경우 실험적 모드를 활성화 하세요.
-
- Experimental mode is currently unavailable on this car, since the car's stock ACC is used for longitudinal control.
- 차량의 기본 ACC가 롱컨트롤에 사용되기 때문에 현재 이 차량에서는 실험적 모드를 사용할수 없습니다.
-
-
- Enable experimental longitudinal control to allow experimental mode.
- 실험적 롱컨트롤을 사용하려면 실험적 모드를 활성화 하세요.
- openpilot defaults to driving in <b>chill mode</b>. Experimental mode enables <b>alpha-level features</b> that aren't ready for chill mode. Experimental features are listed below:
- openpilot은 기본적으로 <b>안정적 모드</b>로 주행합니다. 실험적 모드는 안정적 모드에 준비되지 않은 <b>알파 수준 기능</b>을 활성화 합니다. 실험 모드의 특징은 아래에 나열되어 있습니다
+ openpilot은 기본적으로 <b>안정적 모드</b>로 주행합니다. 실험적 모드는 안정적 모드에 준비되지 않은 <b>알파 수준 기능</b>을 활성화 합니다. 실험적 모드의 특징은 아래에 나열되어 있습니다🌮 End-to-End Longitudinal Control 🌮
@@ -1043,7 +1021,23 @@ location set
The driving visualization will transition to the road-facing wide-angle camera at low speeds to better show some turns. The Experimental mode logo will also be shown in the top right corner.
- 주행 시각화는 저속에서 도로를 향하는 광각 카메라로 전환되어 일부 회전을 더 잘 보여줍니다. 실험적 모드 로고도 우측상단에 표시됩니다.
+ 주행 시각화는 저속에서 도로를 향하는 광각 카메라로 전환되어 일부 회전을 더 잘 보여줍니다. 실험적 모드의 로고도 우측상단에 표시됩니다.
+
+
+ Experimental mode is currently unavailable on this car since the car's stock ACC is used for longitudinal control.
+ 차량에 장착된 ACC가 롱컨트롤에 사용되기 때문에 현재 이 차량은 실험적 모드를 사용할 수 없습니다.
+
+
+ openpilot longitudinal control may come in a future update.
+ 오픈파일럿 롱컨트롤은 향후 업데이트에서 제공될 수 있습니다.
+
+
+ An experimental version of openpilot longitudinal control can be tested, along with Experimental mode, on non-release branches.
+ 오픈파일럿 롱컨트롤의 실험 버전은 실험적 모드와 함께 릴리즈 되지 않은 브랜치에서 테스트할 수 있습니다.
+
+
+ Enable experimental longitudinal control to allow Experimental mode.
+ 실험적 롱컨트롤을 사용하려면 실험적 모드를 활성화 하세요.
diff --git a/selfdrive/ui/translations/main_pt-BR.ts b/selfdrive/ui/translations/main_pt-BR.ts
index 105d6f77f0..5c4eab3327 100644
--- a/selfdrive/ui/translations/main_pt-BR.ts
+++ b/selfdrive/ui/translations/main_pt-BR.ts
@@ -132,19 +132,19 @@
Driver Camera
- Câmera voltada para o Motorista
+ Câmera do MotoristaPREVIEW
- PREVISUAL
+ VERPreview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off)
- Pré-visualizar a câmera voltada para o motorista para garantir que monitor tem uma boa visibilidade (veículo precisa estar desligado)
+ Pré-visualizar a câmera voltada para o motorista para garantir que o monitoramento do sistema tenha uma boa visibilidade (veículo precisa estar desligado)Reset Calibration
- Resetar Calibragem
+ Reinicializar CalibragemRESET
@@ -200,7 +200,7 @@
openpilot requires the device to be mounted within 4° left or right and within 5° up or 8° down. openpilot is continuously calibrating, resetting is rarely required.
- o openpilot requer que o dispositivo seja montado dentro de 4° esquerda ou direita e dentro de 5° para cima ou 8° para baixo. o openpilot está continuamente calibrando, resetar raramente é necessário.
+ O openpilot requer que o dispositivo seja montado dentro de 4° esquerda ou direita e dentro de 5° para cima ou 8° para baixo. O openpilot está continuamente calibrando, resetar raramente é necessário. Your device is pointed %1° %2 and %3° %4.
@@ -312,18 +312,6 @@
Installing...Instalando...
-
- Receiving objects:
- Recebendo objetos:
-
-
- Resolving deltas:
- Resolvendo deltas:
-
-
- Updating files:
- Atualizando arquivos:
- MapETA
@@ -388,8 +376,8 @@
Get turn-by-turn directions displayed and more with a comma
prime subscription. Sign up now: https://connect.comma.ai
- Obtenha instruções passo a passo exibidas e muito mais com
-uma assinatura prime Inscreva-se agora: https://connect.comma.ai
+ Obtenha instruções passo a passo exibidas e muito mais com
+uma assinatura prime. Inscreva-se agora: https://connect.comma.aiNo home
@@ -502,7 +490,7 @@ trabalho definido
Become a comma prime member at connect.comma.ai
- Torne-se um membro comma prime em connect.comma.ai
+ Seja um membro comma prime em connect.comma.aiPRIME FEATURES:
@@ -514,11 +502,11 @@ trabalho definido
1 year of storage
- 1 ano de armazenamento
+ 1 ano na nuvemDeveloper perks
- Benefícios para desenvolvedor
+ Benefícios para devs
@@ -590,18 +578,10 @@ trabalho definido
Are you sure you want to reset your device?Tem certeza que quer resetar seu dispositivo?
-
- Resetting device...
- Resetando dispositivo...
- System ResetResetar Sistema
-
- System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot.
- Solicitado reset do sistema. Confirme para apagar todo conteúdo e configurações. Aperte cancelar para continuar boot.
- CancelCancelar
@@ -615,8 +595,17 @@ trabalho definido
Confirmar
- Unable to mount data partition. Press confirm to reset your device.
- Não foi possível montar a partição de dados. Pressione confirmar para resetar seu dispositivo.
+ Unable to mount data partition. Partition may be corrupted. Press confirm to erase and reset your device.
+
+
+
+ Press confirm to erase all content and settings. Press cancel to resume boot.
+
+
+
+ Resetting device...
+This may take up to a minute.
+
@@ -688,18 +677,6 @@ trabalho definido
Waiting for internetEsperando pela internet
-
- Choose Software to Install
- Escolher Software para Instalar
-
-
- Dashcam
- Dashcam
-
-
- Custom Software
- Sofware Customizado
- Enter URLPreencher URL
@@ -728,6 +705,14 @@ trabalho definido
Start overInicializar
+
+ No custom software found at this URL.
+
+
+
+ Something went wrong. Reboot the device.
+
+ SetupWidget
@@ -835,7 +820,7 @@ trabalho definido
Current Version
- Versao Atual
+ Versão AtualDownload
@@ -863,11 +848,11 @@ trabalho definido
UNINSTALL
- DESINSTAL
+ REMOVERUninstall %1
- Desintalar o %1
+ Desinstalar o %1Are you sure you want to uninstall?
@@ -987,7 +972,7 @@ trabalho definido
Disengage on Accelerator Pedal
- Desacionar Com Pedal Do Acelerador
+ Desacionar com Pedal do AceleradorWhen enabled, pressing the accelerator pedal will disengage openpilot.
@@ -995,7 +980,7 @@ trabalho definido
Show ETA in 24h Format
- Mostrar ETA em formato 24h
+ Mostrar ETA em Formato 24hUse 24h format instead of am/pm
@@ -1021,14 +1006,6 @@ trabalho definido
On this car, openpilot defaults to the car's built-in ACC instead of openpilot's longitudinal control. Enable this to switch to openpilot longitudinal control. Enabling Experimental mode is recommended when using experimental openpilot longitudinal control.Neste carro o penpilot por padrão utiliza o ACC nativo do veículo ao invés de controlar longitudinalmente. Ative isto para mudar para o controle longitudinal do openpilot. Ativar o Modo Experimental é recomendado quando em uso do controle longitudinal experimental do openpilot.
-
- Experimental mode is currently unavailable on this car, since the car's stock ACC is used for longitudinal control.
- O Modo Experimental está atualmente indisponível para este carro, já que o ACC original do carro é usado para controle longitudinal.
-
-
- Enable experimental longitudinal control to allow experimental mode.
- Ative o controle longitudinal experimental para permitir o modo experimental.
- openpilot defaults to driving in <b>chill mode</b>. Experimental mode enables <b>alpha-level features</b> that aren't ready for chill mode. Experimental features are listed below:openpilot por padrão funciona em <b>modo chill</b>. modo Experimental ativa <b>recursos de nível-alfa</b> que não estão prontos para o modo chill. Recursos experimentais estão listados abaixo:
@@ -1049,6 +1026,22 @@ trabalho definido
The driving visualization will transition to the road-facing wide-angle camera at low speeds to better show some turns. The Experimental mode logo will also be shown in the top right corner.A visualização da direção fará a transição para a câmera grande angular voltada para a estrada em baixas velocidades para mostrar melhor algumas curvas. O logotipo do modo Experimental também será exibido no canto superior direito.
+
+ Experimental mode is currently unavailable on this car since the car's stock ACC is used for longitudinal control.
+ O modo Experimental está atualmente indisponível para este carro já que o ACC original do carro é usado para controle longitudinal.
+
+
+ openpilot longitudinal control may come in a future update.
+ O controle longitudinal openpilot pode vir em uma atualização futura.
+
+
+ An experimental version of openpilot longitudinal control can be tested, along with Experimental mode, on non-release branches.
+ Uma versão experimental do controle longitudinal openpilot pode ser testada, juntamente com o modo Experimental, em branches de desenvolvimento.
+
+
+ Enable experimental longitudinal control to allow Experimental mode.
+ Ative o controle longitudinal experimental para permitir o modo Experimental.
+ Updater
diff --git a/selfdrive/ui/translations/main_th.ts b/selfdrive/ui/translations/main_th.ts
index 0de0ba5f9a..ce394ecb97 100644
--- a/selfdrive/ui/translations/main_th.ts
+++ b/selfdrive/ui/translations/main_th.ts
@@ -238,6 +238,14 @@
Disengage to Power Offยกเลิกระบบช่วยขับเพื่อปิดเครื่อง
+
+ Reset
+ รีเซ็ต
+
+
+ Review
+ ทบทวน
+ DriveStats
@@ -273,6 +281,17 @@
กำลังเปิดกล้อง
+
+ ExperimentalModeButton
+
+ EXPERIMENTAL MODE ON
+ คุณกำลังใช้โหมดทดลอง
+
+
+ CHILL MODE ON
+ คุณกำลังใช้โหมดชิล
+
+InputDialog
@@ -463,6 +482,17 @@ location set
จดจำ connect.comma.ai โดยการเพิ่มไปยังหน้าจอโฮม เพื่อใช้งานเหมือนเป็นแอปพลิเคชัน
+
+ ParamControl
+
+ Enable
+ เปิดใช้งาน
+
+
+ Cancel
+ ยกเลิก
+
+PrimeAdWidget
@@ -585,13 +615,6 @@ location set
ไม่สามารถเมานต์พาร์ติชั่นข้อมูล กดยืนยันเพื่อรีเซ็ตอุปกรณ์ของคุณ
-
- RichTextDialog
-
- Ok
- ตกลง
-
-SettingsWindow
@@ -850,6 +873,10 @@ location set
Select a branchเลือก Branch
+
+ Uninstall
+ ถอนการติดตั้ง
+ SshControl
@@ -974,29 +1001,57 @@ location set
Show map on left side when in split screen view.แสดงแผนที่ด้านซ้ายของหน้าจอเมื่ออยู่ในโหมดแบ่งหน้าจอ
-
- 🌮 End-to-end longitudinal (extremely alpha) 🌮
- 🌮 ควบคุมเร่ง/เบรคแบบ End-to-end (อยู่ขั้นพัฒนา) 🌮
- Experimental openpilot Longitudinal Controlทดลองใช้ระบบควบคุมการเร่ง/เบรคโดย openpilot
- <b>WARNING: openpilot longitudinal control is experimental for this car and will disable AEB.</b>
- <b>คำเตือน: การควบคุมการเร่ง/เบรคโดย openpilot สำหรับรถคันนี้ยังอยู่ในขั้นทดลอง และระบบเบรคฉุกเฉินอัตโนมัติ (AEB) จะถูกปิด</b>
+ Experimental Mode
+ โหมดทดลอง
- Let the driving model control the gas and brakes. openpilot will drive as it thinks a human would. Super experimental.
- ให้ openpilot ควบคุมการเร่ง/เบรคแบบ end-to-end โดย openpilot จะขับอย่างที่มนุษย์คิด ระบบยังอยู่ในขั้นทดลอง
+ WARNING: openpilot longitudinal control is experimental for this car and will disable Automatic Emergency Braking (AEB).
+ คำเตือน: การควบคุมการเร่ง/เบรคโดย openpilot สำหรับรถคันนี้ยังอยู่ในขั้นพัฒนา และระบบเบรคฉุกเฉินอัตโนมัติ (AEB) จะถูกปิด
- openpilot longitudinal control is not currently available for this car.
- ขณะนี้ยังไม่มีระบบควบคุมการเร่ง/เบรคโดย openpilot สำหรับรถคันนี้
+ On this car, openpilot defaults to the car's built-in ACC instead of openpilot's longitudinal control. Enable this to switch to openpilot longitudinal control. Enabling Experimental mode is recommended when using experimental openpilot longitudinal control.
+ โดยปกติสำหรับรถคันนี้ openpilot จะควบคุมการเร่ง/เบรคด้วยระบบ ACC จากโรงงาน แทนการควยคุมโดย openpilot เปิดสวิตซ์นี้เพื่อให้ openpilot ควบคุมการเร่ง/เบรค แนะนำให้เปิดโหมดทดลองเมื่อต้องการให้ openpilot ควบคุมการเร่ง/เบรค ซึ่งอยู่ในขั้นพัฒนา
- Enable experimental longitudinal control to enable this.
- เปิดใช้งานระบบควบคุมการเร่ง/เบรคขั้นทดลอง เพื่อเปิดใช้งานสิ่งนี้
+ openpilot defaults to driving in <b>chill mode</b>. Experimental mode enables <b>alpha-level features</b> that aren't ready for chill mode. Experimental features are listed below:
+ โดยปกติ openpilot จะขับใน<b>โหมดชิล</b> เปิดโหมดทดลองเพื่อใช้<b>ความสามารถในขั้นพัฒนา</b> ซึ่งยังไม่พร้อมสำหรับโหมดชิล ความสามารถในขั้นพัฒนามีดังนี้:
+
+
+ 🌮 End-to-End Longitudinal Control 🌮
+ 🌮 ควบคุมเร่ง/เบรคแบบ End-to-End 🌮
+
+
+ Let the driving model control the gas and brakes. openpilot will drive as it thinks a human would, including stopping for red lights and stop signs. Since the driving model decides the speed to drive, the set speed will only act as an upper bound. This is an alpha quality feature; mistakes should be expected.
+ ให้ openpilot ควบคุมการเร่ง/เบรค โดย openpilot จะขับอย่างที่มนุษย์คิด รวมถึงการหยุดที่ไฟแดง และป้ายหยุดรถ เนื่องจาก openpilot จะกำหนดความเร็วในการขับด้วยตัวเอง การตั้งความเร็วจะเป็นเพียงการกำหนดความเร็วสูงสูดเท่านั้น ความสามารถนี้ยังอยู่ในขั้นพัฒนา อาจเกิดข้อผิดพลาดขึ้นได้
+
+
+ New Driving Visualization
+ การแสดงภาพการขับขี่แบบใหม่
+
+
+ The driving visualization will transition to the road-facing wide-angle camera at low speeds to better show some turns. The Experimental mode logo will also be shown in the top right corner.
+ การแสดงภาพการขับขี่จะเปลี่ยนไปใช้กล้องมุมกว้างที่หันหน้าไปทางถนนเมื่ออยู่ในความเร็วต่ำ เพื่อแสดงภาพการเลี้ยวที่ดีขึ้น โลโก้โหมดการทดลองจะแสดงที่มุมบนขวาด้วย
+
+
+ Experimental mode is currently unavailable on this car since the car's stock ACC is used for longitudinal control.
+ ขณะนี้โหมดทดลองไม่สามารถใช้งานได้ในรถคันนี้ เนื่องจากเปิดใช้ระบบควบคุมการเร่ง/เบรคของรถที่ติดตั้งจากโรงงานอยู่
+
+
+ openpilot longitudinal control may come in a future update.
+ ระบบควบคุมการเร่ง/เบรคโดย openpilot อาจมาในการอัปเดตในอนาคต
+
+
+ An experimental version of openpilot longitudinal control can be tested, along with Experimental mode, on non-release branches.
+ เวอร์ชันทดลองของระบบควบคุมการเร่ง/เบรคโดย openpilot สามารถทดสอบได้พร้อมกับโหมดการทดลอง บน branch ที่กำลังพัฒนา
+
+
+ Enable experimental longitudinal control to allow Experimental mode.
+ เปิดระบบควบคุมการเร่ง/เบรคขั้นพัฒนาโดย openpilot เพื่อเปิดใช้งานโหมดทดลอง
@@ -1052,5 +1107,9 @@ location set
Forget Wi-Fi Network "%1"?เลิกใช้เครือข่าย Wi-Fi "%1"?
+
+ Forget
+ เลิกใช้
+
diff --git a/selfdrive/ui/translations/main_zh-CHS.ts b/selfdrive/ui/translations/main_zh-CHS.ts
index 31202e45f2..cfc055ac98 100644
--- a/selfdrive/ui/translations/main_zh-CHS.ts
+++ b/selfdrive/ui/translations/main_zh-CHS.ts
@@ -311,18 +311,6 @@
Installing...正在安装……
-
- Receiving objects:
- 正在接收:
-
-
- Resolving deltas:
- 正在处理:
-
-
- Updating files:
- 正在更新文件:
- MapETA
@@ -584,18 +572,10 @@ location set
Are you sure you want to reset your device?您确定要重置您的设备吗?
-
- Resetting device...
- 正在重置设备……
- System Reset恢复出厂设置
-
- System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot.
- 已触发系统重置:确认以删除所有内容和设置。取消以正常启动设备。
- Cancel取消
@@ -609,8 +589,17 @@ location set
确认
- Unable to mount data partition. Press confirm to reset your device.
- 无法挂载数据分区。 确认以重置您的设备。
+ Unable to mount data partition. Partition may be corrupted. Press confirm to erase and reset your device.
+
+
+
+ Press confirm to erase all content and settings. Press cancel to resume boot.
+
+
+
+ Resetting device...
+This may take up to a minute.
+
@@ -682,18 +671,6 @@ location set
Waiting for internet等待网络连接
-
- Choose Software to Install
- 选择要安装的软件
-
-
- Dashcam
- Dashcam(行车记录仪)
-
-
- Custom Software
- 自定义软件
- Enter URL输入网址
@@ -722,6 +699,14 @@ location set
Start over重来
+
+ No custom software found at this URL.
+
+
+
+ Something went wrong. Reboot the device.
+
+ SetupWidget
@@ -1015,14 +1000,6 @@ location set
On this car, openpilot defaults to the car's built-in ACC instead of openpilot's longitudinal control. Enable this to switch to openpilot longitudinal control. Enabling Experimental mode is recommended when using experimental openpilot longitudinal control.针对此车辆,openpilot默认使用车辆自带的ACC,而非openpilot的纵向控制。启用此选项将切换到openpilot纵向控制。当使用试验性的openpilot纵向控制时,建议同时启用试验模式。
-
- Experimental mode is currently unavailable on this car, since the car's stock ACC is used for longitudinal control.
- 由于此车辆使用自带的ACC纵向控制,当前无法使用试验模式。
-
-
- Enable experimental longitudinal control to allow experimental mode.
- 启用试验性的纵向控制,以便允许使用试验模式。
- openpilot defaults to driving in <b>chill mode</b>. Experimental mode enables <b>alpha-level features</b> that aren't ready for chill mode. Experimental features are listed below:openpilot 默认 <b>轻松模式</b>驾驶车辆。试验模式启用一些轻松模式之外的 <b>试验性功能</b>。试验性功能包括:
@@ -1043,6 +1020,22 @@ location set
The driving visualization will transition to the road-facing wide-angle camera at low speeds to better show some turns. The Experimental mode logo will also be shown in the top right corner.当低速行驶时,驾驶视角将切换到前向广角摄像头,便于更完整地显示转向路径。右上角将显示试验模式图标。
+
+ Experimental mode is currently unavailable on this car since the car's stock ACC is used for longitudinal control.
+ 由于此车辆使用自带的ACC纵向控制,当前无法使用试验模式。
+
+
+ openpilot longitudinal control may come in a future update.
+
+
+
+ An experimental version of openpilot longitudinal control can be tested, along with Experimental mode, on non-release branches.
+
+
+
+ Enable experimental longitudinal control to allow Experimental mode.
+ 启用试验性的纵向控制,以便允许使用试验模式。
+ Updater
diff --git a/selfdrive/ui/translations/main_zh-CHT.ts b/selfdrive/ui/translations/main_zh-CHT.ts
index 0379e926c4..e4058ee0db 100644
--- a/selfdrive/ui/translations/main_zh-CHT.ts
+++ b/selfdrive/ui/translations/main_zh-CHT.ts
@@ -311,18 +311,6 @@
Installing...安裝中…
-
- Receiving objects:
- 接收對象:
-
-
- Resolving deltas:
- 分析差異:
-
-
- Updating files:
- 更新檔案:
- MapETA
@@ -586,18 +574,10 @@ location set
Are you sure you want to reset your device?您確定要重置你的設備嗎?
-
- Resetting device...
- 重置設備中…
- System Reset系統重置
-
- System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot.
- 系統重置已觸發。請按確認刪除所有內容和設置。按取消恢復啟動。
- Cancel取消
@@ -611,8 +591,17 @@ location set
確認
- Unable to mount data partition. Press confirm to reset your device.
- 無法掛載數據分區。請按確認重置您的設備。
+ Unable to mount data partition. Partition may be corrupted. Press confirm to erase and reset your device.
+
+
+
+ Press confirm to erase all content and settings. Press cancel to resume boot.
+
+
+
+ Resetting device...
+This may take up to a minute.
+
@@ -684,18 +673,6 @@ location set
Waiting for internet連接至網路中
-
- Choose Software to Install
- 選擇要安裝的軟體
-
-
- Dashcam
- 行車記錄器
-
-
- Custom Software
- 定制的軟體
- Enter URL輸入網址
@@ -724,6 +701,14 @@ location set
Start over重新開始
+
+ No custom software found at this URL.
+
+
+
+ Something went wrong. Reboot the device.
+
+ SetupWidget
@@ -1017,14 +1002,6 @@ location set
On this car, openpilot defaults to the car's built-in ACC instead of openpilot's longitudinal control. Enable this to switch to openpilot longitudinal control. Enabling Experimental mode is recommended when using experimental openpilot longitudinal control.在本車輛中,openpilot預設將使用原車內建的ACC系統,而非openpilot縱向控制。開啟此開關來啟用openpilot縱向控制,使用此選項時建議一併啟用實驗模式。
-
- Experimental mode is currently unavailable on this car, since the car's stock ACC is used for longitudinal control.
- 因車輛使用內建ACC系統,無法在本車輛上啟動實驗模式。
-
-
- Enable experimental longitudinal control to allow experimental mode.
- 啟用實驗性縱向控制以使用實驗模式。
- openpilot defaults to driving in <b>chill mode</b>. Experimental mode enables <b>alpha-level features</b> that aren't ready for chill mode. Experimental features are listed below:openpilot 預設以 <b>輕鬆模式</b> 駕駛。 實驗模式啟用了尚未準備好進入輕鬆模式的 <b>alpha 級功能</b>。實驗功能如下:
@@ -1045,6 +1022,22 @@ location set
The driving visualization will transition to the road-facing wide-angle camera at low speeds to better show some turns. The Experimental mode logo will also be shown in the top right corner.低速行駛時,將會切換成路側廣角鏡頭,以完整顯示轉彎路徑,右上角將出現實驗模式圖案。
+
+ Experimental mode is currently unavailable on this car since the car's stock ACC is used for longitudinal control.
+ 因車輛使用內建ACC系統,無法在本車輛上啟動實驗模式。
+
+
+ openpilot longitudinal control may come in a future update.
+
+
+
+ An experimental version of openpilot longitudinal control can be tested, along with Experimental mode, on non-release branches.
+
+
+
+ Enable experimental longitudinal control to allow Experimental mode.
+ 啟用實驗性縱向控制以使用實驗模式。
+ Updater
diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc
index c62d737481..50843de68e 100644
--- a/selfdrive/ui/ui.cc
+++ b/selfdrive/ui/ui.cc
@@ -35,7 +35,7 @@ static bool calib_frame_to_full_frame(const UIState *s, float in_x, float in_y,
return false;
}
-int get_path_length_idx(const cereal::ModelDataV2::XYZTData::Reader &line, const float path_height) {
+int get_path_length_idx(const cereal::XYZTData::Reader &line, const float path_height) {
const auto line_x = line.getX();
int max_idx = 0;
for (int i = 1; i < TRAJECTORY_SIZE && line_x[i] <= path_height; ++i) {
@@ -44,7 +44,7 @@ int get_path_length_idx(const cereal::ModelDataV2::XYZTData::Reader &line, const
return max_idx;
}
-void update_leads(UIState *s, const cereal::RadarState::Reader &radar_state, const cereal::ModelDataV2::XYZTData::Reader &line) {
+void update_leads(UIState *s, const cereal::RadarState::Reader &radar_state, const cereal::XYZTData::Reader &line) {
for (int i = 0; i < 2; ++i) {
auto lead_data = (i == 0) ? radar_state.getLeadOne() : radar_state.getLeadTwo();
if (lead_data.getStatus()) {
@@ -54,7 +54,7 @@ void update_leads(UIState *s, const cereal::RadarState::Reader &radar_state, con
}
}
-void update_line_data(const UIState *s, const cereal::ModelDataV2::XYZTData::Reader &line,
+void update_line_data(const UIState *s, const cereal::XYZTData::Reader &line,
float y_off, float z_off, QPolygonF *pvd, int max_idx, bool allow_invert=true) {
const auto line_x = line.getX(), line_y = line.getY(), line_z = line.getZ();
QPolygonF left_points, right_points;
@@ -79,10 +79,15 @@ void update_line_data(const UIState *s, const cereal::ModelDataV2::XYZTData::Rea
*pvd = left_points + right_points;
}
-void update_model(UIState *s, const cereal::ModelDataV2::Reader &model) {
+void update_model(UIState *s,
+ const cereal::ModelDataV2::Reader &model,
+ const cereal::UiPlan::Reader &plan) {
UIScene &scene = s->scene;
- auto model_position = model.getPosition();
- float max_distance = std::clamp(model_position.getX()[TRAJECTORY_SIZE - 1],
+ auto plan_position = plan.getPosition();
+ if (plan_position.getX().size() < TRAJECTORY_SIZE){
+ plan_position = model.getPosition();
+ }
+ float max_distance = std::clamp(plan_position.getX()[TRAJECTORY_SIZE - 1],
MIN_DRAW_DISTANCE, MAX_DRAW_DISTANCE);
// update lane lines
@@ -108,8 +113,41 @@ void update_model(UIState *s, const cereal::ModelDataV2::Reader &model) {
const float lead_d = lead_one.getDRel() * 2.;
max_distance = std::clamp((float)(lead_d - fmin(lead_d * 0.35, 10.)), 0.0f, max_distance);
}
- max_idx = get_path_length_idx(model_position, max_distance);
- update_line_data(s, model_position, 0.9, 1.22, &scene.track_vertices, max_idx, false);
+ max_idx = get_path_length_idx(plan_position, max_distance);
+ update_line_data(s, plan_position, 0.9, 1.22, &scene.track_vertices, max_idx, false);
+}
+
+void update_dmonitoring(UIState *s, const cereal::DriverStateV2::Reader &driverstate, float dm_fade_state, bool is_rhd) {
+ UIScene &scene = s->scene;
+ const auto driver_orient = is_rhd ? driverstate.getRightDriverData().getFaceOrientation() : driverstate.getLeftDriverData().getFaceOrientation();
+ for (int i = 0; i < std::size(scene.driver_pose_vals); i++) {
+ float v_this = (i == 0 ? (driver_orient[i] < 0 ? 0.7 : 0.9) : 0.4) * driver_orient[i];
+ scene.driver_pose_diff[i] = fabs(scene.driver_pose_vals[i] - v_this);
+ scene.driver_pose_vals[i] = 0.8 * v_this + (1 - 0.8) * scene.driver_pose_vals[i];
+ scene.driver_pose_sins[i] = sinf(scene.driver_pose_vals[i]*(1.0-dm_fade_state));
+ scene.driver_pose_coss[i] = cosf(scene.driver_pose_vals[i]*(1.0-dm_fade_state));
+ }
+
+ const mat3 r_xyz = (mat3){{
+ scene.driver_pose_coss[1]*scene.driver_pose_coss[2],
+ scene.driver_pose_coss[1]*scene.driver_pose_sins[2],
+ -scene.driver_pose_sins[1],
+
+ -scene.driver_pose_sins[0]*scene.driver_pose_sins[1]*scene.driver_pose_coss[2] - scene.driver_pose_coss[0]*scene.driver_pose_sins[2],
+ -scene.driver_pose_sins[0]*scene.driver_pose_sins[1]*scene.driver_pose_sins[2] + scene.driver_pose_coss[0]*scene.driver_pose_coss[2],
+ -scene.driver_pose_sins[0]*scene.driver_pose_coss[1],
+
+ scene.driver_pose_coss[0]*scene.driver_pose_sins[1]*scene.driver_pose_coss[2] - scene.driver_pose_sins[0]*scene.driver_pose_sins[2],
+ scene.driver_pose_coss[0]*scene.driver_pose_sins[1]*scene.driver_pose_sins[2] + scene.driver_pose_sins[0]*scene.driver_pose_coss[2],
+ scene.driver_pose_coss[0]*scene.driver_pose_coss[1],
+ }};
+
+ // transform vertices
+ for (int kpi = 0; kpi < std::size(default_face_kpts_3d); kpi++) {
+ vec3 kpt_this = default_face_kpts_3d[kpi];
+ kpt_this = matvecmul3(r_xyz, kpt_this);
+ scene.face_kpts_draw[kpi] = (vec3){{(float)kpt_this.v[0], (float)kpt_this.v[1], (float)(kpt_this.v[2] * (1.0-dm_fade_state) + 8 * dm_fade_state)}};
+ }
}
static void update_sockets(UIState *s) {
@@ -163,7 +201,7 @@ static void update_state(UIState *s) {
scene.longitudinal_control = sm["carParams"].getCarParams().getOpenpilotLongitudinalControl();
}
if (sm.updated("wideRoadCameraState")) {
- float scale = (sm["wideRoadCameraState"].getWideRoadCameraState().getSensor() == cereal::FrameData::ImageSensor::AR0321) ? 6.0f : 1.0f;
+ float scale = (sm["wideRoadCameraState"].getWideRoadCameraState().getSensor() == cereal::FrameData::ImageSensor::AR0231) ? 6.0f : 1.0f;
scene.light_sensor = std::max(100.0f - scale * sm["wideRoadCameraState"].getWideRoadCameraState().getExposureValPercent(), 0.0f);
}
scene.started = sm["deviceState"].getDeviceState().getStarted() && scene.ignition;
@@ -213,8 +251,9 @@ void UIState::updateStatus() {
UIState::UIState(QObject *parent) : QObject(parent) {
sm = std::make_unique>({
"modelV2", "controlsState", "liveCalibration", "radarState", "deviceState", "roadCameraState",
- "pandaStates", "carParams", "driverMonitoringState", "carState", "liveLocationKalman",
+ "pandaStates", "carParams", "driverMonitoringState", "carState", "liveLocationKalman", "driverStateV2",
"wideRoadCameraState", "managerState", "navInstruction", "navRoute", "gnssMeasurements",
+ "uiPlan",
});
Params params;
diff --git a/selfdrive/ui/ui.h b/selfdrive/ui/ui.h
index 9e1c54948b..ad2a1fe1f4 100644
--- a/selfdrive/ui/ui.h
+++ b/selfdrive/ui/ui.h
@@ -25,6 +25,16 @@ typedef cereal::CarControl::HUDControl::AudibleAlert AudibleAlert;
const mat3 DEFAULT_CALIBRATION = {{ 0.0, 1.0, 0.0, 0.0, 0.0, 1.0, 1.0, 0.0, 0.0 }};
+const vec3 default_face_kpts_3d[] = {
+ {-5.98, -51.20, 8.00}, {-17.64, -49.14, 8.00}, {-23.81, -46.40, 8.00}, {-29.98, -40.91, 8.00}, {-32.04, -37.49, 8.00},
+ {-34.10, -32.00, 8.00}, {-36.16, -21.03, 8.00}, {-36.16, 6.40, 8.00}, {-35.47, 10.51, 8.00}, {-32.73, 19.43, 8.00},
+ {-29.30, 26.29, 8.00}, {-24.50, 33.83, 8.00}, {-19.01, 41.37, 8.00}, {-14.21, 46.17, 8.00}, {-12.16, 47.54, 8.00},
+ {-4.61, 49.60, 8.00}, {4.99, 49.60, 8.00}, {12.53, 47.54, 8.00}, {14.59, 46.17, 8.00}, {19.39, 41.37, 8.00},
+ {24.87, 33.83, 8.00}, {29.67, 26.29, 8.00}, {33.10, 19.43, 8.00}, {35.84, 10.51, 8.00}, {36.53, 6.40, 8.00},
+ {36.53, -21.03, 8.00}, {34.47, -32.00, 8.00}, {32.42, -37.49, 8.00}, {30.36, -40.91, 8.00}, {24.19, -46.40, 8.00},
+ {18.02, -49.14, 8.00}, {6.36, -51.20, 8.00}, {-5.98, -51.20, 8.00},
+};
+
struct Alert {
QString text1;
QString text2;
@@ -103,6 +113,13 @@ typedef struct UIScene {
// lead
QPointF lead_vertices[2];
+ // DMoji state
+ float driver_pose_vals[3];
+ float driver_pose_diff[3];
+ float driver_pose_sins[3];
+ float driver_pose_coss[3];
+ vec3 face_kpts_draw[std::size(default_face_kpts_3d)];
+
float light_sensor;
bool started, ignition, is_metric, map_on_left, longitudinal_control;
uint64_t started_frame;
@@ -181,8 +198,11 @@ public slots:
};
void ui_update_params(UIState *s);
-int get_path_length_idx(const cereal::ModelDataV2::XYZTData::Reader &line, const float path_height);
-void update_model(UIState *s, const cereal::ModelDataV2::Reader &model);
-void update_leads(UIState *s, const cereal::RadarState::Reader &radar_state, const cereal::ModelDataV2::XYZTData::Reader &line);
-void update_line_data(const UIState *s, const cereal::ModelDataV2::XYZTData::Reader &line,
+int get_path_length_idx(const cereal::XYZTData::Reader &line, const float path_height);
+void update_model(UIState *s,
+ const cereal::ModelDataV2::Reader &model,
+ const cereal::UiPlan::Reader &plan);
+void update_dmonitoring(UIState *s, const cereal::DriverStateV2::Reader &driverstate, float dm_fade_state, bool is_rhd);
+void update_leads(UIState *s, const cereal::RadarState::Reader &radar_state, const cereal::XYZTData::Reader &line);
+void update_line_data(const UIState *s, const cereal::XYZTData::Reader &line,
float y_off, float z_off, QPolygonF *pvd, int max_idx, bool allow_invert);
diff --git a/selfdrive/updated.py b/selfdrive/updated.py
index 9da2a05a11..2cb7d1c13b 100755
--- a/selfdrive/updated.py
+++ b/selfdrive/updated.py
@@ -423,6 +423,9 @@ def main() -> None:
wait_helper = WaitTimeHelper()
wait_helper.only_check_for_update = True
+ # invalidate old finalized update
+ set_consistent_flag(False)
+
# Run the update loop
while True:
wait_helper.ready_event.clear()
diff --git a/system/camerad/SConscript b/system/camerad/SConscript
index ddc763b53d..3ecc3f6d72 100644
--- a/system/camerad/SConscript
+++ b/system/camerad/SConscript
@@ -2,17 +2,13 @@ Import('env', 'arch', 'cereal', 'messaging', 'common', 'gpucommon', 'visionipc')
libs = ['m', 'pthread', common, 'jpeg', 'OpenCL', 'yuv', cereal, messaging, 'zmq', 'capnp', 'kj', visionipc, gpucommon, 'atomic']
-cenv = env.Clone()
-cenv['CPPPATH'].append('include/')
-
-camera_obj = cenv.Object(['cameras/camera_qcom2.cc', 'cameras/camera_common.cc', 'cameras/camera_util.cc'])
-cenv.Program('camerad', [
+camera_obj = env.Object(['cameras/camera_qcom2.cc', 'cameras/camera_common.cc', 'cameras/camera_util.cc'])
+env.Program('camerad', [
'main.cc',
camera_obj,
], LIBS=libs)
if GetOption("test") and arch == "x86_64":
- cenv.Program('test/ae_gray_test', [
- 'test/ae_gray_test.cc',
- camera_obj,
- ], LIBS=libs)
+ env.Program('test/ae_gray_test',
+ ['test/ae_gray_test.cc', camera_obj],
+ LIBS=libs)
diff --git a/system/camerad/cameras/camera_common.cc b/system/camerad/cameras/camera_common.cc
index 30e2810ec4..7ee3738057 100644
--- a/system/camerad/cameras/camera_common.cc
+++ b/system/camerad/cameras/camera_common.cc
@@ -167,7 +167,7 @@ void fill_frame_data(cereal::FrameData::Builder &framed, const FrameMetadata &fr
framed.setExposureValPercent(perc);
if (c->camera_id == CAMERA_ID_AR0231) {
- framed.setSensor(cereal::FrameData::ImageSensor::AR0321);
+ framed.setSensor(cereal::FrameData::ImageSensor::AR0231);
} else if (c->camera_id == CAMERA_ID_OX03C10) {
framed.setSensor(cereal::FrameData::ImageSensor::OX03C10);
}
diff --git a/system/camerad/cameras/camera_qcom2.cc b/system/camerad/cameras/camera_qcom2.cc
index 091b0d91d9..92b3bde413 100644
--- a/system/camerad/cameras/camera_qcom2.cc
+++ b/system/camerad/cameras/camera_qcom2.cc
@@ -60,15 +60,15 @@ CameraInfo cameras_supported[CAMERA_ID_MAX] = {
const float DC_GAIN_AR0231 = 2.5;
const float DC_GAIN_OX03C10 = 7.32;
-const float DC_GAIN_ON_GREY_AR0231= 0.2;
+const float DC_GAIN_ON_GREY_AR0231 = 0.2;
const float DC_GAIN_OFF_GREY_AR0231 = 0.3;
-const float DC_GAIN_ON_GREY_OX03C10= 0.25;
-const float DC_GAIN_OFF_GREY_OX03C10 = 0.35;
+const float DC_GAIN_ON_GREY_OX03C10 = 0.9;
+const float DC_GAIN_OFF_GREY_OX03C10 = 1.0;
const int DC_GAIN_MIN_WEIGHT_AR0231 = 0;
const int DC_GAIN_MAX_WEIGHT_AR0231 = 1;
-const int DC_GAIN_MIN_WEIGHT_OX03C10 = 16;
-const int DC_GAIN_MAX_WEIGHT_OX03C10 = 32;
+const int DC_GAIN_MIN_WEIGHT_OX03C10 = 1; // always on is fine
+const int DC_GAIN_MAX_WEIGHT_OX03C10 = 1;
const float TARGET_GREY_FACTOR_AR0231 = 1.0;
const float TARGET_GREY_FACTOR_OX03C10 = 0.02;
@@ -104,8 +104,8 @@ const int ANALOG_GAIN_MIN_IDX_OX03C10 = 0x0;
const int ANALOG_GAIN_REC_IDX_OX03C10 = 0x11; // 2.5x
const int ANALOG_GAIN_MAX_IDX_OX03C10 = 0x36;
const int ANALOG_GAIN_COST_DELTA_OX03C10 = -1;
-const float ANALOG_GAIN_COST_LOW_OX03C10 = 0.05;
-const float ANALOG_GAIN_COST_HIGH_OX03C10 = 0.8;
+const float ANALOG_GAIN_COST_LOW_OX03C10 = 0.4;
+const float ANALOG_GAIN_COST_HIGH_OX03C10 = 6.4;
const int EXPOSURE_TIME_MIN_AR0231 = 2; // with HDR, fastest ss
const int EXPOSURE_TIME_MAX_AR0231 = 0x0855; // with HDR, slowest ss, 40ms
@@ -1041,6 +1041,30 @@ void CameraState::handle_camera_event(void *evdat) {
}
}
+void CameraState::update_exposure_score(float desired_ev, int exp_t, int exp_g_idx, float exp_gain) {
+ float score = 1e6;
+ if (camera_id == CAMERA_ID_AR0231) {
+ // Cost of ev diff
+ score = std::abs(desired_ev - (exp_t * exp_gain)) * 10;
+ // Cost of absolute gain
+ float m = exp_g_idx > analog_gain_rec_idx ? analog_gain_cost_high : analog_gain_cost_low;
+ score += std::abs(exp_g_idx - (int)analog_gain_rec_idx) * m;
+ // Cost of changing gain
+ score += std::abs(exp_g_idx - gain_idx) * (score + 1.0) / 10.0;
+ } else if (camera_id == CAMERA_ID_OX03C10) {
+ score = std::abs(desired_ev - (exp_t * exp_gain));
+ float m = exp_g_idx > analog_gain_rec_idx ? analog_gain_cost_high : analog_gain_cost_low;
+ score += std::abs(exp_g_idx - (int)analog_gain_rec_idx) * m;
+ score += ((1 - analog_gain_cost_delta) + analog_gain_cost_delta * (exp_g_idx - analog_gain_min_idx) / (analog_gain_max_idx - analog_gain_min_idx)) * std::abs(exp_g_idx - gain_idx) * 5.0;
+ }
+
+ if (score < best_ev_score) {
+ new_exp_t = exp_t;
+ new_exp_g = exp_g_idx;
+ best_ev_score = score;
+ }
+}
+
void CameraState::set_camera_exposure(float grey_frac) {
if (!enabled) return;
const float dt = 0.05;
@@ -1066,9 +1090,9 @@ void CameraState::set_camera_exposure(float grey_frac) {
float k = (1.0 - k_ev) / 3.0;
desired_ev = (k * cur_ev[0]) + (k * cur_ev[1]) + (k * cur_ev[2]) + (k_ev * desired_ev);
- float best_ev_score = 1e6;
- int new_g = 0;
- int new_t = 0;
+ best_ev_score = 1e6;
+ new_exp_g = 0;
+ new_exp_t = 0;
// Hysteresis around high conversion gain
// We usually want this on since it results in lower noise, but turn off in very bright day scenes
@@ -1095,8 +1119,8 @@ void CameraState::set_camera_exposure(float grey_frac) {
gain_idx = std::stoi(gain_bytes);
exposure_time = std::stoi(time_bytes);
- new_g = gain_idx;
- new_t = exposure_time;
+ new_exp_g = gain_idx;
+ new_exp_t = exposure_time;
enable_dc_gain = false;
} else {
// Simple brute force optimizer to choose sensor parameters
@@ -1112,23 +1136,7 @@ void CameraState::set_camera_exposure(float grey_frac) {
continue;
}
- // Compute error to desired ev
- float score = std::abs(desired_ev - (t * gain)) * 10;
-
- // Going below recommended gain needs lower penalty to not overexpose
- float m = g > analog_gain_rec_idx ? analog_gain_cost_high : analog_gain_cost_low;
- score += std::abs(g - (int)analog_gain_rec_idx) * m;
-
- // LOGE("cam: %d - gain: %d, t: %d (%.2f), score %.2f, score + gain %.2f, %.3f, %.3f", camera_num, g, t, desired_ev / gain, score, score + std::abs(g - gain_idx) * (score + 1.0) / 10.0, desired_ev, min_ev);
-
- // Small penalty on changing gain
- score += ((1 - analog_gain_cost_delta) + analog_gain_cost_delta * (g - analog_gain_min_idx) / (analog_gain_max_idx - analog_gain_min_idx)) * std::abs(g - gain_idx) * (score + 1.0) / 10.0;
-
- if (score < best_ev_score) {
- new_t = t;
- new_g = g;
- best_ev_score = score;
- }
+ update_exposure_score(desired_ev, t, g, gain);
}
}
@@ -1137,9 +1145,9 @@ void CameraState::set_camera_exposure(float grey_frac) {
measured_grey_fraction = grey_frac;
target_grey_fraction = target_grey;
- analog_gain_frac = sensor_analog_gains[new_g];
- gain_idx = new_g;
- exposure_time = new_t;
+ analog_gain_frac = sensor_analog_gains[new_exp_g];
+ gain_idx = new_exp_g;
+ exposure_time = new_exp_t;
dc_gain_enabled = enable_dc_gain;
float gain = analog_gain_frac * (1 + dc_gain_weight * (dc_gain_factor-1) / dc_gain_max_weight);
@@ -1156,7 +1164,7 @@ void CameraState::set_camera_exposure(float grey_frac) {
// LOGE("ae - camera %d, cur_t %.5f, sof %.5f, dt %.5f", camera_num, 1e-9 * nanos_since_boot(), 1e-9 * buf.cur_frame_data.timestamp_sof, 1e-9 * (nanos_since_boot() - buf.cur_frame_data.timestamp_sof));
if (camera_id == CAMERA_ID_AR0231) {
- uint16_t analog_gain_reg = 0xFF00 | (new_g << 4) | new_g;
+ uint16_t analog_gain_reg = 0xFF00 | (new_exp_g << 4) | new_exp_g;
struct i2c_random_wr_payload exp_reg_array[] = {
{0x3366, analog_gain_reg},
{0x3362, (uint16_t)(dc_gain_enabled ? 0x1 : 0x0)},
@@ -1164,15 +1172,16 @@ void CameraState::set_camera_exposure(float grey_frac) {
};
sensors_i2c(exp_reg_array, sizeof(exp_reg_array)/sizeof(struct i2c_random_wr_payload), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, true);
} else if (camera_id == CAMERA_ID_OX03C10) {
- // t_HCG + t_LCG + t_VS on LPD, t_SPD on SPD
- uint32_t hcg_time = std::max((dc_gain_weight * exposure_time / dc_gain_max_weight), 0);
- uint32_t lcg_time = std::max(((dc_gain_max_weight - dc_gain_weight) * exposure_time / dc_gain_max_weight), 0);
- // uint32_t spd_time = std::max(hcg_time / 16, (uint32_t)exposure_time_min);
- uint32_t vs_time = std::min(std::max((uint32_t)exposure_time / 128, VS_TIME_MIN_OX03C10), VS_TIME_MAX_OX03C10);
- uint32_t spd_time = vs_time;
-
- uint32_t real_gain = ox03c10_analog_gains_reg[new_g];
+ // t_HCG&t_LCG + t_VS on LPD, t_SPD on SPD
+ uint32_t hcg_time = exposure_time;
+ uint32_t lcg_time = hcg_time;
+ uint32_t spd_time = exposure_time_max + VS_TIME_MAX_OX03C10;
+ uint32_t vs_time = std::min(std::max((uint32_t)exposure_time / 40, VS_TIME_MIN_OX03C10), VS_TIME_MAX_OX03C10);
+
+ uint32_t real_gain = ox03c10_analog_gains_reg[new_exp_g];
uint32_t min_gain = ox03c10_analog_gains_reg[0];
+ uint32_t spd_gain = 0xF00;
+
struct i2c_random_wr_payload exp_reg_array[] = {
{0x3501, hcg_time>>8}, {0x3502, hcg_time&0xFF},
{0x3581, lcg_time>>8}, {0x3582, lcg_time&0xFF},
@@ -1181,7 +1190,7 @@ void CameraState::set_camera_exposure(float grey_frac) {
{0x3508, real_gain>>8}, {0x3509, real_gain&0xFF},
{0x3588, min_gain>>8}, {0x3589, min_gain&0xFF},
- {0x3548, min_gain>>8}, {0x3549, min_gain&0xFF},
+ {0x3548, spd_gain>>8}, {0x3549, spd_gain&0xFF},
{0x35c8, min_gain>>8}, {0x35c9, min_gain&0xFF},
};
sensors_i2c(exp_reg_array, sizeof(exp_reg_array)/sizeof(struct i2c_random_wr_payload), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, false);
diff --git a/system/camerad/cameras/camera_qcom2.h b/system/camerad/cameras/camera_qcom2.h
index 9f0c3743f1..9e0109ab20 100644
--- a/system/camerad/cameras/camera_qcom2.h
+++ b/system/camerad/cameras/camera_qcom2.h
@@ -47,6 +47,9 @@ public:
float cur_ev[3];
float min_ev, max_ev;
+ float best_ev_score;
+ int new_exp_g;
+ int new_exp_t;
float measured_grey_fraction;
float target_grey_fraction;
@@ -58,6 +61,7 @@ public:
int camera_num;
void handle_camera_event(void *evdat);
+ void update_exposure_score(float desired_ev, int exp_t, int exp_g_idx, float exp_gain);
void set_camera_exposure(float grey_frac);
void sensors_start();
diff --git a/system/camerad/cameras/sensor2_i2c.h b/system/camerad/cameras/sensor2_i2c.h
index ab51059d9a..83fcb8f7a9 100644
--- a/system/camerad/cameras/sensor2_i2c.h
+++ b/system/camerad/cameras/sensor2_i2c.h
@@ -126,7 +126,7 @@ struct i2c_random_wr_payload init_array_ox03c10[] = {
{0x3219, 0x08},
{0x3506, 0x20}, {0x3507, 0x00}, // hcg fine exposure
- {0x350a, 0x04}, {0x350b, 0x00}, {0x350c, 0x00}, // hcg digital gain
+ {0x350a, 0x01}, {0x350b, 0x00}, {0x350c, 0x00}, // hcg digital gain
{0x3586, 0x40}, {0x3587, 0x00}, // lcg fine exposure
{0x358a, 0x01}, {0x358b, 0x00}, {0x358c, 0x00}, // lcg digital gain
@@ -711,11 +711,11 @@ struct i2c_random_wr_payload init_array_ox03c10[] = {
{0x4221, 0x03}, // this is changed from 1 -> 3
// DCG exposure coarse
- {0x3501, 0x01}, {0x3502, 0xc8},
+ // {0x3501, 0x01}, {0x3502, 0xc8},
// SPD exposure coarse
- {0x3541, 0x01}, {0x3542, 0xc8},
+ // {0x3541, 0x01}, {0x3542, 0xc8},
// VS exposure coarse
- {0x35c1, 0x00}, {0x35c2, 0x01},
+ // {0x35c1, 0x00}, {0x35c2, 0x01},
// crc reference
{0x420e, 0x66}, {0x420f, 0x5d}, {0x4210, 0xa8}, {0x4211, 0x55},
diff --git a/system/camerad/test/test_camerad.py b/system/camerad/test/test_camerad.py
index 6c2ef1c7bc..f03c531b20 100755
--- a/system/camerad/test/test_camerad.py
+++ b/system/camerad/test/test_camerad.py
@@ -1,6 +1,7 @@
#!/usr/bin/env python3
import time
import unittest
+import numpy as np
from collections import defaultdict
import cereal.messaging as messaging
@@ -10,8 +11,10 @@ from selfdrive.manager.process_config import managed_processes
from system.hardware import TICI
TEST_TIMESPAN = 30
-LAG_FRAME_TOLERANCE = {log.FrameData.ImageSensor.ar0321: 0.5, # ARs use synced pulses for frame starts
+LAG_FRAME_TOLERANCE = {log.FrameData.ImageSensor.ar0231: 0.5, # ARs use synced pulses for frame starts
log.FrameData.ImageSensor.ox03c10: 1.0} # OXs react to out-of-sync at next frame
+FRAME_DELTA_TOLERANCE = {log.FrameData.ImageSensor.ar0231: 1.0,
+ log.FrameData.ImageSensor.ox03c10: 1.0}
CAMERAS = ('roadCameraState', 'driverCameraState', 'wideRoadCameraState')
@@ -36,10 +39,16 @@ class TestCamerad(unittest.TestCase):
managed_processes['camerad'].stop()
cls.log_by_frame_id = defaultdict(list)
+ cls.sensor_type = None
for cam, msgs in cls.logs.items():
+ if cls.sensor_type is None:
+ cls.sensor_type = getattr(msgs[0], msgs[0].which()).sensor.raw
expected_frames = service_list[cam].frequency * TEST_TIMESPAN
assert expected_frames*0.95 < len(msgs) < expected_frames*1.05, f"unexpected frame count {cam}: {expected_frames=}, got {len(msgs)}"
+ dts = np.abs(np.diff([getattr(m, m.which()).timestampSof/1e6 for m in msgs]) - 1000/service_list[cam].frequency)
+ assert (dts < FRAME_DELTA_TOLERANCE[cls.sensor_type]).all(), f"{cam} dts(ms) out of spec: max diff {dts.max()}, 99 percentile {np.percentile(dts, 99)}"
+
for m in msgs:
cls.log_by_frame_id[getattr(m, m.which()).frameId].append(m)
@@ -64,17 +73,16 @@ class TestCamerad(unittest.TestCase):
assert len(skips) == 0, f"Found frame skips, missing cameras for the following frames: {skips}"
def test_frame_sync(self):
- sensor_type = [getattr(msgs[0], msgs[0].which()).sensor for frame_id, msgs in self.log_by_frame_id.items()][0].raw
frame_times = {frame_id: [getattr(m, m.which()).timestampSof for m in msgs] for frame_id, msgs in self.log_by_frame_id.items()}
diffs = {frame_id: (max(ts) - min(ts))/1e6 for frame_id, ts in frame_times.items()}
def get_desc(fid, diff):
cam_times = [(m.which(), getattr(m, m.which()).timestampSof/1e6) for m in self.log_by_frame_id[fid]]
return (diff, cam_times)
- laggy_frames = {k: get_desc(k, v) for k, v in diffs.items() if v > LAG_FRAME_TOLERANCE[sensor_type]}
+ laggy_frames = {k: get_desc(k, v) for k, v in diffs.items() if v > LAG_FRAME_TOLERANCE[self.sensor_type]}
def in_tol(diff):
- return 50 - LAG_FRAME_TOLERANCE[sensor_type] < diff and diff < 50 + LAG_FRAME_TOLERANCE[sensor_type]
+ return 50 - LAG_FRAME_TOLERANCE[self.sensor_type] < diff and diff < 50 + LAG_FRAME_TOLERANCE[self.sensor_type]
if len(laggy_frames) != 0 and all( in_tol(laggy_frames[lf][0]) for lf in laggy_frames):
print("TODO: handle camera out of sync")
else:
diff --git a/system/camerad/test/test_exposure.py b/system/camerad/test/test_exposure.py
index 8cce7e7ffa..201b205c4f 100755
--- a/system/camerad/test/test_exposure.py
+++ b/system/camerad/test/test_exposure.py
@@ -6,16 +6,13 @@ import numpy as np
from selfdrive.test.helpers import with_processes
from system.camerad.snapshot.snapshot import get_snapshots
-from system.hardware import TICI
-
TEST_TIME = 45
REPEAT = 5
class TestCamerad(unittest.TestCase):
@classmethod
def setUpClass(cls):
- if not TICI:
- raise unittest.SkipTest
+ pass
def _numpy_rgb2gray(self, im):
ret = np.clip(im[:,:,2] * 0.114 + im[:,:,1] * 0.587 + im[:,:,0] * 0.299, 0, 255).astype(np.uint8)
@@ -37,13 +34,11 @@ class TestCamerad(unittest.TestCase):
start = time.time()
while time.time() - start < TEST_TIME and passed < REPEAT:
rpic, dpic = get_snapshots(frame="roadCameraState", front_frame="driverCameraState")
+ wpic, _ = get_snapshots(frame="wideRoadCameraState")
res = self._is_exposure_okay(rpic)
res = res and self._is_exposure_okay(dpic)
-
- if TICI:
- wpic, _ = get_snapshots(frame="wideRoadCameraState")
- res = res and self._is_exposure_okay(wpic)
+ res = res and self._is_exposure_okay(wpic)
if passed > 0 and not res:
passed = -passed # fails test if any failure after first sus
diff --git a/system/hardware/base.h b/system/hardware/base.h
index f6e0b42d73..6cfc1d8743 100644
--- a/system/hardware/base.h
+++ b/system/hardware/base.h
@@ -16,6 +16,8 @@ public:
static int get_voltage() { return 0; };
static int get_current() { return 0; };
+ static std::string get_serial() { return "cccccc"; }
+
static void reboot() {}
static void poweroff() {}
static void set_brightness(int percent) {}
diff --git a/system/hardware/tici/amplifier.py b/system/hardware/tici/amplifier.py
old mode 100755
new mode 100644
index a8b2798630..8233834d11
--- a/system/hardware/tici/amplifier.py
+++ b/system/hardware/tici/amplifier.py
@@ -1,4 +1,3 @@
-#!/usr/bin/env python
from smbus2 import SMBus
from collections import namedtuple
@@ -63,11 +62,43 @@ BASE_CONFIG = [
AmpConfig("Zero-crossing detection disabled", 0b0, 0x49, 5, 0b00100000),
]
-BASE_CONFIG += configs_from_eq_params(0x84, EQParams(0x274F, 0xC0FF, 0x3BF9, 0x0B3C, 0x1656))
-BASE_CONFIG += configs_from_eq_params(0x8E, EQParams(0x1009, 0xC6BF, 0x2952, 0x1C97, 0x30DF))
-BASE_CONFIG += configs_from_eq_params(0x98, EQParams(0x0F75, 0xCBE5, 0x0ED2, 0x2528, 0x3E42))
-BASE_CONFIG += configs_from_eq_params(0xA2, EQParams(0x091F, 0x3D4C, 0xCE11, 0x1266, 0x2807))
-BASE_CONFIG += configs_from_eq_params(0xAC, EQParams(0x0A9E, 0x3F20, 0xE573, 0x0A8B, 0x3A3B))
+CONFIGS = {
+ "tici": [
+ *configs_from_eq_params(0x84, EQParams(0x274F, 0xC0FF, 0x3BF9, 0x0B3C, 0x1656)),
+ *configs_from_eq_params(0x8E, EQParams(0x1009, 0xC6BF, 0x2952, 0x1C97, 0x30DF)),
+ *configs_from_eq_params(0x98, EQParams(0x0F75, 0xCBE5, 0x0ED2, 0x2528, 0x3E42)),
+ *configs_from_eq_params(0xA2, EQParams(0x091F, 0x3D4C, 0xCE11, 0x1266, 0x2807)),
+ *configs_from_eq_params(0xAC, EQParams(0x0A9E, 0x3F20, 0xE573, 0x0A8B, 0x3A3B)),
+ ],
+ "tizi": [
+ AmpConfig("Left speaker output from left DAC", 0b1, 0x2B, 0, 0b11111111),
+ AmpConfig("Left Speaker Mixer Gain", 0b00, 0x2D, 0, 0b00000011),
+ AmpConfig("Left speaker output volume", 0x1F, 0x3D, 0, 0b00011111),
+ AmpConfig("Right speaker output volume", 0x1F, 0x3E, 0, 0b00011111),
+ AmpConfig("DAI1 attenuation (DV1)", 0x4, 0x2F, 0, 0b00001111),
+ AmpConfig("DAI2 attenuation (DV2)", 0x4, 0x31, 0, 0b00001111),
+ AmpConfig("DAI2: DC blocking", 0b0, 0x20, 0, 0b00000001),
+ AmpConfig("ALC enable", 0b0, 0x43, 7, 0b10000000),
+ AmpConfig("DAI2 EQ attenuation", 0x2, 0x32, 0, 0b00001111),
+ AmpConfig("Excursion limiter upper corner freq", 0b001, 0x41, 4, 0b01110000),
+ AmpConfig("Excursion limiter threshold", 0b100, 0x42, 0, 0b00001111),
+ AmpConfig("Distortion limit (THDCLP)", 0x0, 0x46, 4, 0b11110000),
+ AmpConfig("Distortion limiter release time constant", 0b1, 0x46, 0, 0b00000001),
+ AmpConfig("Left DAC input mixer: DAI1 left", 0b0, 0x22, 7, 0b10000000),
+ AmpConfig("Left DAC input mixer: DAI1 right", 0b0, 0x22, 6, 0b01000000),
+ AmpConfig("Left DAC input mixer: DAI2 left", 0b1, 0x22, 5, 0b00100000),
+ AmpConfig("Left DAC input mixer: DAI2 right", 0b0, 0x22, 4, 0b00010000),
+ AmpConfig("Right DAC input mixer: DAI2 left", 0b0, 0x22, 1, 0b00000010),
+ AmpConfig("Right DAC input mixer: DAI2 right", 0b1, 0x22, 0, 0b00000001),
+ AmpConfig("Volume adjustment smoothing disabled", 0b1, 0x49, 6, 0b01000000),
+
+ *configs_from_eq_params(0x84, EQParams(0x3084, 0xC023, 0x3D60, 0x042B, 0x1222)),
+ *configs_from_eq_params(0x8E, EQParams(0x2FB2, 0xC05C, 0x3BD3, 0x06C5, 0x16BB)),
+ *configs_from_eq_params(0x98, EQParams(0x21F5, 0xDF73, 0x2DFE, 0x371A, 0x2C80)),
+ *configs_from_eq_params(0xA2, EQParams(0x2A5A, 0x0AD0, 0x14FA, 0x3F14, 0x3C76)),
+ *configs_from_eq_params(0xAC, EQParams(0x1577, 0x3FAE, 0xEE60, 0x0664, 0x3D86)),
+ ],
+}
class Amplifier:
AMP_I2C_BUS = 0
@@ -91,14 +122,13 @@ class Amplifier:
def set_global_shutdown(self, amp_disabled):
self.set_config(AmpConfig("Global shutdown", 0b0 if amp_disabled else 0b1, 0x51, 7, 0b10000000))
- def initialize_configuration(self):
+ def initialize_configuration(self, model):
self.set_global_shutdown(amp_disabled=True)
for config in BASE_CONFIG:
self.set_config(config)
- self.set_global_shutdown(amp_disabled=False)
-
+ for config in CONFIGS[model]:
+ self.set_config(config)
-if __name__ == "__main__":
- Amplifier(debug=True).initialize_configuration()
+ self.set_global_shutdown(amp_disabled=False)
diff --git a/system/hardware/tici/hardware.h b/system/hardware/tici/hardware.h
index d388f9c48a..5f6fb2dc50 100644
--- a/system/hardware/tici/hardware.h
+++ b/system/hardware/tici/hardware.h
@@ -21,13 +21,32 @@ public:
static int get_voltage() { return std::atoi(util::read_file("/sys/class/hwmon/hwmon1/in1_input").c_str()); };
static int get_current() { return std::atoi(util::read_file("/sys/class/hwmon/hwmon1/curr1_input").c_str()); };
+ static std::string get_serial() {
+ static std::string serial("");
+ if (serial.empty()) {
+ std::ifstream stream("/proc/cmdline");
+ std::string cmdline;
+ std::getline(stream, cmdline);
+
+ auto start = cmdline.find("serialno=");
+ if (start == std::string::npos) {
+ serial = "cccccc";
+ } else {
+ auto end = cmdline.find(" ", start + 9);
+ serial = cmdline.substr(start + 9, end - start - 9);
+ }
+ }
+ return serial;
+ }
static void reboot() { std::system("sudo reboot"); };
static void poweroff() { std::system("sudo poweroff"); };
static void set_brightness(int percent) {
+ std::string max = util::read_file("/sys/class/backlight/panel0-backlight/max_brightness");
+
std::ofstream brightness_control("/sys/class/backlight/panel0-backlight/brightness");
if (brightness_control.is_open()) {
- brightness_control << (percent * (int)(1023/100.)) << "\n";
+ brightness_control << (int)(percent * (std::stof(max)/100.)) << "\n";
brightness_control.close();
}
};
diff --git a/system/hardware/tici/hardware.py b/system/hardware/tici/hardware.py
index b5f5e00410..9c1cc930c1 100644
--- a/system/hardware/tici/hardware.py
+++ b/system/hardware/tici/hardware.py
@@ -85,6 +85,16 @@ class Tici(HardwareBase):
def amplifier(self):
return Amplifier()
+ @cached_property
+ def model(self):
+ with open("/sys/firmware/devicetree/base/model") as f:
+ model = f.read().strip('\x00')
+ model = model.split('comma ')[-1]
+ # TODO: remove this with AGNOS 7+
+ if model.startswith('Qualcomm'):
+ model = 'tici'
+ return model
+
def get_os_version(self):
with open("/VERSION") as f:
return f.read().strip()
@@ -385,15 +395,22 @@ class Tici(HardwareBase):
def set_screen_brightness(self, percentage):
try:
+ with open("/sys/class/backlight/panel0-backlight/max_brightness") as f:
+ max_brightness = float(f.read().strip())
+
+ val = int(percentage * (max_brightness / 100.))
with open("/sys/class/backlight/panel0-backlight/brightness", "w") as f:
- f.write(str(int(percentage * 10.23)))
+ f.write(str(val))
except Exception:
pass
def get_screen_brightness(self):
try:
+ with open("/sys/class/backlight/panel0-backlight/max_brightness") as f:
+ max_brightness = float(f.read().strip())
+
with open("/sys/class/backlight/panel0-backlight/brightness") as f:
- return int(float(f.read()) / 10.23)
+ return int(float(f.read()) / (max_brightness / 100.))
except Exception:
return 0
@@ -401,7 +418,7 @@ class Tici(HardwareBase):
# amplifier, 100mW at idle
self.amplifier.set_global_shutdown(amp_disabled=powersave_enabled)
if not powersave_enabled:
- self.amplifier.initialize_configuration()
+ self.amplifier.initialize_configuration(self.model)
# *** CPU config ***
@@ -430,7 +447,7 @@ class Tici(HardwareBase):
return 0
def initialize_hardware(self):
- self.amplifier.initialize_configuration()
+ self.amplifier.initialize_configuration(self.model)
# Allow thermald to write engagement status to kmsg
os.system("sudo chmod a+w /dev/kmsg")
diff --git a/system/micd.py b/system/micd.py
index a56140e3b9..97ba0c262e 100755
--- a/system/micd.py
+++ b/system/micd.py
@@ -1,5 +1,4 @@
#!/usr/bin/env python3
-import sounddevice as sd
import numpy as np
from cereal import messaging
@@ -84,11 +83,11 @@ class Mic:
self.measurements = self.measurements[FFT_SAMPLES:]
- def micd_thread(self, device=None):
- if device is None:
- device = "sysdefault"
+ def micd_thread(self):
+ # sounddevice must be imported after forking processes
+ import sounddevice as sd # pylint: disable=import-outside-toplevel
- with sd.InputStream(device=device, channels=1, samplerate=SAMPLE_RATE, callback=self.callback) as stream:
+ with sd.InputStream(channels=1, samplerate=SAMPLE_RATE, callback=self.callback) as stream:
cloudlog.info(f"micd stream started: {stream.samplerate=} {stream.channels=} {stream.dtype=} {stream.device=}")
while True:
self.update()
diff --git a/system/version.py b/system/version.py
index 6031531556..55f80afa35 100644
--- a/system/version.py
+++ b/system/version.py
@@ -7,7 +7,7 @@ from functools import lru_cache
from common.basedir import BASEDIR
from system.swaglog import cloudlog
-RELEASE_BRANCHES = ['release3-staging', 'dashcam3-staging', 'release3', 'dashcam3']
+RELEASE_BRANCHES = ['release3-staging', 'dashcam3-staging', 'release3', 'dashcam3', 'nightly']
TESTED_BRANCHES = RELEASE_BRANCHES + ['devel', 'devel-staging']
training_version: bytes = b"0.2.0"
diff --git a/pyextra/.gitignore b/third_party/.gitignore
similarity index 100%
rename from pyextra/.gitignore
rename to third_party/.gitignore
diff --git a/third_party/SConscript b/third_party/SConscript
index e5bbfaa07a..e8d1789ee0 100644
--- a/third_party/SConscript
+++ b/third_party/SConscript
@@ -4,3 +4,5 @@ env.Library('json11', ['json11/json11.cpp'], CCFLAGS=env['CCFLAGS'] + ['-Wno-unq
env.Append(CPPPATH=[Dir('json11')])
env.Library('kaitai', ['kaitai/kaitaistream.cpp'], CPPDEFINES=['KS_STR_ENCODING_NONE'])
+
+SConscript(['cluster/SConscript'])
diff --git a/pyextra/acados_template/.gitignore b/third_party/acados/acados_template/.gitignore
similarity index 100%
rename from pyextra/acados_template/.gitignore
rename to third_party/acados/acados_template/.gitignore
diff --git a/pyextra/acados_template/__init__.py b/third_party/acados/acados_template/__init__.py
similarity index 100%
rename from pyextra/acados_template/__init__.py
rename to third_party/acados/acados_template/__init__.py
diff --git a/pyextra/acados_template/acados_layout.json b/third_party/acados/acados_template/acados_layout.json
similarity index 100%
rename from pyextra/acados_template/acados_layout.json
rename to third_party/acados/acados_template/acados_layout.json
diff --git a/pyextra/acados_template/acados_model.py b/third_party/acados/acados_template/acados_model.py
similarity index 100%
rename from pyextra/acados_template/acados_model.py
rename to third_party/acados/acados_template/acados_model.py
diff --git a/pyextra/acados_template/acados_ocp.py b/third_party/acados/acados_template/acados_ocp.py
similarity index 100%
rename from pyextra/acados_template/acados_ocp.py
rename to third_party/acados/acados_template/acados_ocp.py
diff --git a/pyextra/acados_template/acados_ocp_solver.py b/third_party/acados/acados_template/acados_ocp_solver.py
similarity index 100%
rename from pyextra/acados_template/acados_ocp_solver.py
rename to third_party/acados/acados_template/acados_ocp_solver.py
diff --git a/pyextra/acados_template/acados_ocp_solver_pyx.pyx b/third_party/acados/acados_template/acados_ocp_solver_pyx.pyx
similarity index 100%
rename from pyextra/acados_template/acados_ocp_solver_pyx.pyx
rename to third_party/acados/acados_template/acados_ocp_solver_pyx.pyx
diff --git a/pyextra/acados_template/acados_sim.py b/third_party/acados/acados_template/acados_sim.py
similarity index 100%
rename from pyextra/acados_template/acados_sim.py
rename to third_party/acados/acados_template/acados_sim.py
diff --git a/pyextra/acados_template/acados_sim_layout.json b/third_party/acados/acados_template/acados_sim_layout.json
similarity index 100%
rename from pyextra/acados_template/acados_sim_layout.json
rename to third_party/acados/acados_template/acados_sim_layout.json
diff --git a/pyextra/acados_template/acados_sim_solver.py b/third_party/acados/acados_template/acados_sim_solver.py
similarity index 100%
rename from pyextra/acados_template/acados_sim_solver.py
rename to third_party/acados/acados_template/acados_sim_solver.py
diff --git a/pyextra/acados_template/acados_solver_common.pxd b/third_party/acados/acados_template/acados_solver_common.pxd
similarity index 100%
rename from pyextra/acados_template/acados_solver_common.pxd
rename to third_party/acados/acados_template/acados_solver_common.pxd
diff --git a/pyextra/acados_template/builders.py b/third_party/acados/acados_template/builders.py
similarity index 100%
rename from pyextra/acados_template/builders.py
rename to third_party/acados/acados_template/builders.py
diff --git a/pyextra/acados_template/c_templates_tera/CMakeLists.in.txt b/third_party/acados/acados_template/c_templates_tera/CMakeLists.in.txt
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/CMakeLists.in.txt
rename to third_party/acados/acados_template/c_templates_tera/CMakeLists.in.txt
diff --git a/pyextra/acados_template/c_templates_tera/CPPLINT.cfg b/third_party/acados/acados_template/c_templates_tera/CPPLINT.cfg
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/CPPLINT.cfg
rename to third_party/acados/acados_template/c_templates_tera/CPPLINT.cfg
diff --git a/pyextra/acados_template/c_templates_tera/Makefile.in b/third_party/acados/acados_template/c_templates_tera/Makefile.in
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/Makefile.in
rename to third_party/acados/acados_template/c_templates_tera/Makefile.in
diff --git a/pyextra/acados_template/c_templates_tera/acados_mex_create.in.c b/third_party/acados/acados_template/c_templates_tera/acados_mex_create.in.c
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/acados_mex_create.in.c
rename to third_party/acados/acados_template/c_templates_tera/acados_mex_create.in.c
diff --git a/pyextra/acados_template/c_templates_tera/acados_mex_free.in.c b/third_party/acados/acados_template/c_templates_tera/acados_mex_free.in.c
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/acados_mex_free.in.c
rename to third_party/acados/acados_template/c_templates_tera/acados_mex_free.in.c
diff --git a/pyextra/acados_template/c_templates_tera/acados_mex_set.in.c b/third_party/acados/acados_template/c_templates_tera/acados_mex_set.in.c
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/acados_mex_set.in.c
rename to third_party/acados/acados_template/c_templates_tera/acados_mex_set.in.c
diff --git a/pyextra/acados_template/c_templates_tera/acados_mex_solve.in.c b/third_party/acados/acados_template/c_templates_tera/acados_mex_solve.in.c
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/acados_mex_solve.in.c
rename to third_party/acados/acados_template/c_templates_tera/acados_mex_solve.in.c
diff --git a/pyextra/acados_template/c_templates_tera/acados_sim_solver.in.c b/third_party/acados/acados_template/c_templates_tera/acados_sim_solver.in.c
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/acados_sim_solver.in.c
rename to third_party/acados/acados_template/c_templates_tera/acados_sim_solver.in.c
diff --git a/pyextra/acados_template/c_templates_tera/acados_sim_solver.in.h b/third_party/acados/acados_template/c_templates_tera/acados_sim_solver.in.h
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/acados_sim_solver.in.h
rename to third_party/acados/acados_template/c_templates_tera/acados_sim_solver.in.h
diff --git a/pyextra/acados_template/c_templates_tera/acados_sim_solver_sfun.in.c b/third_party/acados/acados_template/c_templates_tera/acados_sim_solver_sfun.in.c
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/acados_sim_solver_sfun.in.c
rename to third_party/acados/acados_template/c_templates_tera/acados_sim_solver_sfun.in.c
diff --git a/pyextra/acados_template/c_templates_tera/acados_solver.in.c b/third_party/acados/acados_template/c_templates_tera/acados_solver.in.c
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/acados_solver.in.c
rename to third_party/acados/acados_template/c_templates_tera/acados_solver.in.c
diff --git a/pyextra/acados_template/c_templates_tera/acados_solver.in.h b/third_party/acados/acados_template/c_templates_tera/acados_solver.in.h
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/acados_solver.in.h
rename to third_party/acados/acados_template/c_templates_tera/acados_solver.in.h
diff --git a/pyextra/acados_template/c_templates_tera/acados_solver.in.pxd b/third_party/acados/acados_template/c_templates_tera/acados_solver.in.pxd
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/acados_solver.in.pxd
rename to third_party/acados/acados_template/c_templates_tera/acados_solver.in.pxd
diff --git a/pyextra/acados_template/c_templates_tera/acados_solver_sfun.in.c b/third_party/acados/acados_template/c_templates_tera/acados_solver_sfun.in.c
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/acados_solver_sfun.in.c
rename to third_party/acados/acados_template/c_templates_tera/acados_solver_sfun.in.c
diff --git a/pyextra/acados_template/c_templates_tera/cost_y_0_fun.in.h b/third_party/acados/acados_template/c_templates_tera/cost_y_0_fun.in.h
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/cost_y_0_fun.in.h
rename to third_party/acados/acados_template/c_templates_tera/cost_y_0_fun.in.h
diff --git a/pyextra/acados_template/c_templates_tera/cost_y_e_fun.in.h b/third_party/acados/acados_template/c_templates_tera/cost_y_e_fun.in.h
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/cost_y_e_fun.in.h
rename to third_party/acados/acados_template/c_templates_tera/cost_y_e_fun.in.h
diff --git a/pyextra/acados_template/c_templates_tera/cost_y_fun.in.h b/third_party/acados/acados_template/c_templates_tera/cost_y_fun.in.h
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/cost_y_fun.in.h
rename to third_party/acados/acados_template/c_templates_tera/cost_y_fun.in.h
diff --git a/pyextra/acados_template/c_templates_tera/external_cost.in.h b/third_party/acados/acados_template/c_templates_tera/external_cost.in.h
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/external_cost.in.h
rename to third_party/acados/acados_template/c_templates_tera/external_cost.in.h
diff --git a/pyextra/acados_template/c_templates_tera/external_cost_0.in.h b/third_party/acados/acados_template/c_templates_tera/external_cost_0.in.h
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/external_cost_0.in.h
rename to third_party/acados/acados_template/c_templates_tera/external_cost_0.in.h
diff --git a/pyextra/acados_template/c_templates_tera/external_cost_e.in.h b/third_party/acados/acados_template/c_templates_tera/external_cost_e.in.h
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/external_cost_e.in.h
rename to third_party/acados/acados_template/c_templates_tera/external_cost_e.in.h
diff --git a/pyextra/acados_template/c_templates_tera/h_constraint.in.h b/third_party/acados/acados_template/c_templates_tera/h_constraint.in.h
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/h_constraint.in.h
rename to third_party/acados/acados_template/c_templates_tera/h_constraint.in.h
diff --git a/pyextra/acados_template/c_templates_tera/h_e_constraint.in.h b/third_party/acados/acados_template/c_templates_tera/h_e_constraint.in.h
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/h_e_constraint.in.h
rename to third_party/acados/acados_template/c_templates_tera/h_e_constraint.in.h
diff --git a/pyextra/acados_template/c_templates_tera/main.in.c b/third_party/acados/acados_template/c_templates_tera/main.in.c
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/main.in.c
rename to third_party/acados/acados_template/c_templates_tera/main.in.c
diff --git a/pyextra/acados_template/c_templates_tera/main_mex.in.c b/third_party/acados/acados_template/c_templates_tera/main_mex.in.c
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/main_mex.in.c
rename to third_party/acados/acados_template/c_templates_tera/main_mex.in.c
diff --git a/pyextra/acados_template/c_templates_tera/main_sim.in.c b/third_party/acados/acados_template/c_templates_tera/main_sim.in.c
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/main_sim.in.c
rename to third_party/acados/acados_template/c_templates_tera/main_sim.in.c
diff --git a/pyextra/acados_template/c_templates_tera/make_main_mex.in.m b/third_party/acados/acados_template/c_templates_tera/make_main_mex.in.m
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/make_main_mex.in.m
rename to third_party/acados/acados_template/c_templates_tera/make_main_mex.in.m
diff --git a/pyextra/acados_template/c_templates_tera/make_mex.in.m b/third_party/acados/acados_template/c_templates_tera/make_mex.in.m
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/make_mex.in.m
rename to third_party/acados/acados_template/c_templates_tera/make_mex.in.m
diff --git a/pyextra/acados_template/c_templates_tera/make_sfun.in.m b/third_party/acados/acados_template/c_templates_tera/make_sfun.in.m
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/make_sfun.in.m
rename to third_party/acados/acados_template/c_templates_tera/make_sfun.in.m
diff --git a/pyextra/acados_template/c_templates_tera/make_sfun_sim.in.m b/third_party/acados/acados_template/c_templates_tera/make_sfun_sim.in.m
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/make_sfun_sim.in.m
rename to third_party/acados/acados_template/c_templates_tera/make_sfun_sim.in.m
diff --git a/pyextra/acados_template/c_templates_tera/mex_solver.in.m b/third_party/acados/acados_template/c_templates_tera/mex_solver.in.m
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/mex_solver.in.m
rename to third_party/acados/acados_template/c_templates_tera/mex_solver.in.m
diff --git a/pyextra/acados_template/c_templates_tera/model.in.h b/third_party/acados/acados_template/c_templates_tera/model.in.h
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/model.in.h
rename to third_party/acados/acados_template/c_templates_tera/model.in.h
diff --git a/pyextra/acados_template/c_templates_tera/phi_constraint.in.h b/third_party/acados/acados_template/c_templates_tera/phi_constraint.in.h
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/phi_constraint.in.h
rename to third_party/acados/acados_template/c_templates_tera/phi_constraint.in.h
diff --git a/pyextra/acados_template/c_templates_tera/phi_e_constraint.in.h b/third_party/acados/acados_template/c_templates_tera/phi_e_constraint.in.h
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/phi_e_constraint.in.h
rename to third_party/acados/acados_template/c_templates_tera/phi_e_constraint.in.h
diff --git a/pyextra/acados_template/generate_c_code_constraint.py b/third_party/acados/acados_template/generate_c_code_constraint.py
similarity index 100%
rename from pyextra/acados_template/generate_c_code_constraint.py
rename to third_party/acados/acados_template/generate_c_code_constraint.py
diff --git a/pyextra/acados_template/generate_c_code_discrete_dynamics.py b/third_party/acados/acados_template/generate_c_code_discrete_dynamics.py
similarity index 100%
rename from pyextra/acados_template/generate_c_code_discrete_dynamics.py
rename to third_party/acados/acados_template/generate_c_code_discrete_dynamics.py
diff --git a/pyextra/acados_template/generate_c_code_explicit_ode.py b/third_party/acados/acados_template/generate_c_code_explicit_ode.py
similarity index 100%
rename from pyextra/acados_template/generate_c_code_explicit_ode.py
rename to third_party/acados/acados_template/generate_c_code_explicit_ode.py
diff --git a/pyextra/acados_template/generate_c_code_external_cost.py b/third_party/acados/acados_template/generate_c_code_external_cost.py
similarity index 100%
rename from pyextra/acados_template/generate_c_code_external_cost.py
rename to third_party/acados/acados_template/generate_c_code_external_cost.py
diff --git a/pyextra/acados_template/generate_c_code_gnsf.py b/third_party/acados/acados_template/generate_c_code_gnsf.py
similarity index 100%
rename from pyextra/acados_template/generate_c_code_gnsf.py
rename to third_party/acados/acados_template/generate_c_code_gnsf.py
diff --git a/pyextra/acados_template/generate_c_code_implicit_ode.py b/third_party/acados/acados_template/generate_c_code_implicit_ode.py
similarity index 100%
rename from pyextra/acados_template/generate_c_code_implicit_ode.py
rename to third_party/acados/acados_template/generate_c_code_implicit_ode.py
diff --git a/pyextra/acados_template/generate_c_code_nls_cost.py b/third_party/acados/acados_template/generate_c_code_nls_cost.py
similarity index 100%
rename from pyextra/acados_template/generate_c_code_nls_cost.py
rename to third_party/acados/acados_template/generate_c_code_nls_cost.py
diff --git a/pyextra/acados_template/simulink_default_opts.json b/third_party/acados/acados_template/simulink_default_opts.json
similarity index 100%
rename from pyextra/acados_template/simulink_default_opts.json
rename to third_party/acados/acados_template/simulink_default_opts.json
diff --git a/pyextra/acados_template/utils.py b/third_party/acados/acados_template/utils.py
similarity index 100%
rename from pyextra/acados_template/utils.py
rename to third_party/acados/acados_template/utils.py
diff --git a/third_party/acados/build.sh b/third_party/acados/build.sh
index 0481e8159b..9b18b2b67d 100755
--- a/third_party/acados/build.sh
+++ b/third_party/acados/build.sh
@@ -43,11 +43,10 @@ mkdir -p $INSTALL_DIR
rm $DIR/acados_repo/lib/*.json
-rm -rf $DIR/include
+rm -rf $DIR/include $DIR/acados_template
cp -r $DIR/acados_repo/include $DIR
cp -r $DIR/acados_repo/lib $INSTALL_DIR
-rm -rf $DIR/../../pyextra/acados_template
-cp -r $DIR/acados_repo/interfaces/acados_template/acados_template $DIR/../../pyextra
+cp -r $DIR/acados_repo/interfaces/acados_template/acados_template $DIR/
#pip3 install -e $DIR/acados/interfaces/acados_template
# build tera
diff --git a/third_party/bootstrap/.gitignore b/third_party/bootstrap/.gitignore
new file mode 100644
index 0000000000..ac06c0cf85
--- /dev/null
+++ b/third_party/bootstrap/.gitignore
@@ -0,0 +1 @@
+/icons/
diff --git a/third_party/bootstrap/bootstrap-icons.svg b/third_party/bootstrap/bootstrap-icons.svg
new file mode 100644
index 0000000000..61f2720db4
--- /dev/null
+++ b/third_party/bootstrap/bootstrap-icons.svg
@@ -0,0 +1 @@
+
\ No newline at end of file
diff --git a/third_party/bootstrap/pull.sh b/third_party/bootstrap/pull.sh
new file mode 100755
index 0000000000..0b03b4db9e
--- /dev/null
+++ b/third_party/bootstrap/pull.sh
@@ -0,0 +1,14 @@
+#!/bin/bash
+set -e
+
+DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null && pwd )"
+cd $DIR
+
+if [ ! -d icons/ ]; then
+ git clone https://github.com/twbs/icons/
+fi
+
+cd icons
+git fetch --all
+git checkout d5aa187483a1b0b186f87adcfa8576350d970d98
+cp bootstrap-icons.svg ../
diff --git a/selfdrive/controls/lib/cluster/.gitignore b/third_party/cluster/.gitignore
similarity index 100%
rename from selfdrive/controls/lib/cluster/.gitignore
rename to third_party/cluster/.gitignore
diff --git a/selfdrive/controls/lib/cluster/LICENSE b/third_party/cluster/LICENSE
similarity index 100%
rename from selfdrive/controls/lib/cluster/LICENSE
rename to third_party/cluster/LICENSE
diff --git a/selfdrive/controls/lib/cluster/README b/third_party/cluster/README
similarity index 100%
rename from selfdrive/controls/lib/cluster/README
rename to third_party/cluster/README
diff --git a/selfdrive/controls/lib/cluster/SConscript b/third_party/cluster/SConscript
similarity index 100%
rename from selfdrive/controls/lib/cluster/SConscript
rename to third_party/cluster/SConscript
diff --git a/selfdrive/controls/lib/cluster/__init__.py b/third_party/cluster/__init__.py
similarity index 100%
rename from selfdrive/controls/lib/cluster/__init__.py
rename to third_party/cluster/__init__.py
diff --git a/selfdrive/controls/lib/cluster/fastcluster.cpp b/third_party/cluster/fastcluster.cpp
similarity index 100%
rename from selfdrive/controls/lib/cluster/fastcluster.cpp
rename to third_party/cluster/fastcluster.cpp
diff --git a/selfdrive/controls/lib/cluster/fastcluster.h b/third_party/cluster/fastcluster.h
similarity index 100%
rename from selfdrive/controls/lib/cluster/fastcluster.h
rename to third_party/cluster/fastcluster.h
diff --git a/selfdrive/controls/lib/cluster/fastcluster_R_dm.cpp b/third_party/cluster/fastcluster_R_dm.cpp
similarity index 100%
rename from selfdrive/controls/lib/cluster/fastcluster_R_dm.cpp
rename to third_party/cluster/fastcluster_R_dm.cpp
diff --git a/selfdrive/controls/lib/cluster/fastcluster_dm.cpp b/third_party/cluster/fastcluster_dm.cpp
similarity index 100%
rename from selfdrive/controls/lib/cluster/fastcluster_dm.cpp
rename to third_party/cluster/fastcluster_dm.cpp
diff --git a/selfdrive/controls/lib/cluster/fastcluster_py.py b/third_party/cluster/fastcluster_py.py
similarity index 100%
rename from selfdrive/controls/lib/cluster/fastcluster_py.py
rename to third_party/cluster/fastcluster_py.py
diff --git a/selfdrive/controls/lib/cluster/test.cpp b/third_party/cluster/test.cpp
similarity index 100%
rename from selfdrive/controls/lib/cluster/test.cpp
rename to third_party/cluster/test.cpp
diff --git a/system/camerad/include/media/cam_cpas.h b/third_party/linux/include/media/cam_cpas.h
similarity index 100%
rename from system/camerad/include/media/cam_cpas.h
rename to third_party/linux/include/media/cam_cpas.h
diff --git a/system/camerad/include/media/cam_defs.h b/third_party/linux/include/media/cam_defs.h
similarity index 100%
rename from system/camerad/include/media/cam_defs.h
rename to third_party/linux/include/media/cam_defs.h
diff --git a/system/camerad/include/media/cam_fd.h b/third_party/linux/include/media/cam_fd.h
similarity index 100%
rename from system/camerad/include/media/cam_fd.h
rename to third_party/linux/include/media/cam_fd.h
diff --git a/system/camerad/include/media/cam_icp.h b/third_party/linux/include/media/cam_icp.h
similarity index 100%
rename from system/camerad/include/media/cam_icp.h
rename to third_party/linux/include/media/cam_icp.h
diff --git a/system/camerad/include/media/cam_isp.h b/third_party/linux/include/media/cam_isp.h
similarity index 100%
rename from system/camerad/include/media/cam_isp.h
rename to third_party/linux/include/media/cam_isp.h
diff --git a/system/camerad/include/media/cam_isp_ife.h b/third_party/linux/include/media/cam_isp_ife.h
similarity index 100%
rename from system/camerad/include/media/cam_isp_ife.h
rename to third_party/linux/include/media/cam_isp_ife.h
diff --git a/system/camerad/include/media/cam_isp_vfe.h b/third_party/linux/include/media/cam_isp_vfe.h
similarity index 100%
rename from system/camerad/include/media/cam_isp_vfe.h
rename to third_party/linux/include/media/cam_isp_vfe.h
diff --git a/system/camerad/include/media/cam_jpeg.h b/third_party/linux/include/media/cam_jpeg.h
similarity index 100%
rename from system/camerad/include/media/cam_jpeg.h
rename to third_party/linux/include/media/cam_jpeg.h
diff --git a/system/camerad/include/media/cam_lrme.h b/third_party/linux/include/media/cam_lrme.h
similarity index 100%
rename from system/camerad/include/media/cam_lrme.h
rename to third_party/linux/include/media/cam_lrme.h
diff --git a/system/camerad/include/media/cam_req_mgr.h b/third_party/linux/include/media/cam_req_mgr.h
similarity index 100%
rename from system/camerad/include/media/cam_req_mgr.h
rename to third_party/linux/include/media/cam_req_mgr.h
diff --git a/system/camerad/include/media/cam_sensor.h b/third_party/linux/include/media/cam_sensor.h
similarity index 100%
rename from system/camerad/include/media/cam_sensor.h
rename to third_party/linux/include/media/cam_sensor.h
diff --git a/system/camerad/include/media/cam_sensor_cmn_header.h b/third_party/linux/include/media/cam_sensor_cmn_header.h
similarity index 100%
rename from system/camerad/include/media/cam_sensor_cmn_header.h
rename to third_party/linux/include/media/cam_sensor_cmn_header.h
diff --git a/system/camerad/include/media/cam_sync.h b/third_party/linux/include/media/cam_sync.h
similarity index 100%
rename from system/camerad/include/media/cam_sync.h
rename to third_party/linux/include/media/cam_sync.h
diff --git a/system/camerad/include/msm_cam_sensor.h b/third_party/linux/include/msm_cam_sensor.h
similarity index 100%
rename from system/camerad/include/msm_cam_sensor.h
rename to third_party/linux/include/msm_cam_sensor.h
diff --git a/system/camerad/include/msm_camsensor_sdk.h b/third_party/linux/include/msm_camsensor_sdk.h
similarity index 100%
rename from system/camerad/include/msm_camsensor_sdk.h
rename to third_party/linux/include/msm_camsensor_sdk.h
diff --git a/selfdrive/modeld/thneed/include/msm_kgsl.h b/third_party/linux/include/msm_kgsl.h
similarity index 100%
rename from selfdrive/modeld/thneed/include/msm_kgsl.h
rename to third_party/linux/include/msm_kgsl.h
diff --git a/system/camerad/include/msmb_camera.h b/third_party/linux/include/msmb_camera.h
similarity index 100%
rename from system/camerad/include/msmb_camera.h
rename to third_party/linux/include/msmb_camera.h
diff --git a/system/camerad/include/msmb_isp.h b/third_party/linux/include/msmb_isp.h
similarity index 100%
rename from system/camerad/include/msmb_isp.h
rename to third_party/linux/include/msmb_isp.h
diff --git a/system/camerad/include/msmb_ispif.h b/third_party/linux/include/msmb_ispif.h
similarity index 100%
rename from system/camerad/include/msmb_ispif.h
rename to third_party/linux/include/msmb_ispif.h
diff --git a/tinygrad_repo b/tinygrad_repo
index 8e22d5ee67..2e1d47b166 160000
--- a/tinygrad_repo
+++ b/tinygrad_repo
@@ -1 +1 @@
-Subproject commit 8e22d5ee675277181e1eff644dde9e844fc40fce
+Subproject commit 2e1d47b16625ff343516287cdd9e4bcb26f5c4ef
diff --git a/tools/cabana/README.md b/tools/cabana/README.md
index dd131880a6..db247c39c5 100644
--- a/tools/cabana/README.md
+++ b/tools/cabana/README.md
@@ -8,13 +8,18 @@ Cabana is a tool developed to view raw CAN data. One use for this is creating an
```bash
$ ./cabana -h
-Usage: ./cabana [options] route
+Usage: ./_cabana [options] route
Options:
-h, --help Displays this help.
--demo use a demo route instead of providing your own
--qcam load qcamera
+ --ecam load wide road camera
+ --stream read can messages from live streaming
+ --zmq the ip address on which to receive zmq messages
--data_dir local directory with routes
+ --no-vipc do not output video
+ --dbc dbc file to open
Arguments:
route the drive to replay. find your drives at
diff --git a/tools/cabana/SConscript b/tools/cabana/SConscript
index 52fe9e346d..ddd6208c07 100644
--- a/tools/cabana/SConscript
+++ b/tools/cabana/SConscript
@@ -8,18 +8,32 @@ base_libs = [common, messaging, cereal, visionipc, transformations, 'zmq',
if arch == "Darwin":
base_frameworks.append('OpenCL')
+ base_frameworks.append('QtCharts')
else:
base_libs.append('OpenCL')
+ base_libs.append('Qt5Charts')
+
+qt_libs = ['qt_util'] + base_libs
-qt_libs = ['qt_util', 'Qt5Charts'] + base_libs
cabana_libs = [widgets, cereal, messaging, visionipc, replay_lib, opendbc,'avutil', 'avcodec', 'avformat', 'bz2', 'curl', 'yuv'] + qt_libs
cabana_env = qt_env.Clone()
+opendbc_path = '-DOPENDBC_FILE_PATH=\'"%s"\'' % (cabana_env.Dir("../../opendbc").abspath)
+cabana_env['CXXFLAGS'] += [opendbc_path]
+
+# build assets
+assets = "assets/assets.cc"
+assets_src = "assets/assets.qrc"
+cabana_env.Command(assets, assets_src, f"rcc $SOURCES -o $TARGET")
+cabana_env.Depends(assets, Glob('/assets/*', exclude=[assets, assets_src, "assets/assets.o"]))
prev_moc_path = cabana_env['QT_MOCHPREFIX']
cabana_env['QT_MOCHPREFIX'] = os.path.dirname(prev_moc_path) + '/cabana/moc_'
-cabana_lib = cabana_env.Library("cabana_lib", ['mainwin.cc', 'binaryview.cc', 'chartswidget.cc', 'historylog.cc', 'videowidget.cc', 'signaledit.cc', 'dbcmanager.cc',
- 'canmessages.cc', 'commands.cc', 'messageswidget.cc', 'settings.cc', 'detailwidget.cc'], LIBS=cabana_libs, FRAMEWORKS=base_frameworks)
-cabana_env.Program('_cabana', ['cabana.cc', cabana_lib], LIBS=cabana_libs, FRAMEWORKS=base_frameworks)
+cabana_lib = cabana_env.Library("cabana_lib", ['mainwin.cc', 'streams/livestream.cc', 'streams/abstractstream.cc', 'streams/replaystream.cc', 'binaryview.cc', 'chartswidget.cc', 'historylog.cc', 'videowidget.cc', 'signaledit.cc', 'dbcmanager.cc',
+ 'commands.cc', 'messageswidget.cc', 'route.cc', 'settings.cc', 'util.cc', 'detailwidget.cc', 'tools/findsimilarbits.cc'], LIBS=cabana_libs, FRAMEWORKS=base_frameworks)
+cabana_env.Program('_cabana', ['cabana.cc', cabana_lib, assets], LIBS=cabana_libs, FRAMEWORKS=base_frameworks)
+
+if arch == "Darwin":
+ cabana_env.Execute('install_name_tool -change opendbc/can/libdbc.dylib @loader_path/../../opendbc/can/libdbc.dylib ./_cabana')
if GetOption('test'):
cabana_env.Program('tests/_test_cabana', ['tests/test_runner.cc', 'tests/test_cabana.cc', cabana_lib], LIBS=[cabana_libs])
diff --git a/tools/cabana/assets/.gitignore b/tools/cabana/assets/.gitignore
new file mode 100644
index 0000000000..283034ca8b
--- /dev/null
+++ b/tools/cabana/assets/.gitignore
@@ -0,0 +1 @@
+*.cc
diff --git a/tools/cabana/assets/assets.qrc b/tools/cabana/assets/assets.qrc
new file mode 100644
index 0000000000..6a8e5a3414
--- /dev/null
+++ b/tools/cabana/assets/assets.qrc
@@ -0,0 +1,6 @@
+
+
+ ../../../third_party/bootstrap/bootstrap-icons.svg
+ cabana-icon.png
+
+
diff --git a/tools/cabana/assets/cabana-icon.png b/tools/cabana/assets/cabana-icon.png
new file mode 100644
index 0000000000..86add806fd
Binary files /dev/null and b/tools/cabana/assets/cabana-icon.png differ
diff --git a/tools/cabana/binaryview.cc b/tools/cabana/binaryview.cc
index b98c75d452..120a85a330 100644
--- a/tools/cabana/binaryview.cc
+++ b/tools/cabana/binaryview.cc
@@ -1,16 +1,22 @@
#include "tools/cabana/binaryview.h"
+#include
+
#include
#include
#include
#include
+#include
+#include
#include
-#include "tools/cabana/canmessages.h"
+#include "tools/cabana/commands.h"
+#include "tools/cabana/signaledit.h"
// BinaryView
const int CELL_HEIGHT = 36;
+const int VERTICAL_HEADER_WIDTH = 30;
inline int get_bit_index(const QModelIndex &index, bool little_endian) {
return index.row() * 8 + (little_endian ? 7 - index.column() : index.column());
@@ -26,17 +32,111 @@ BinaryView::BinaryView(QWidget *parent) : QTableView(parent) {
verticalHeader()->setSectionResizeMode(QHeaderView::Fixed);
verticalHeader()->setDefaultSectionSize(CELL_HEIGHT);
horizontalHeader()->hide();
- setFrameShape(QFrame::NoFrame);
setShowGrid(false);
setMouseTracking(true);
- setSizeAdjustPolicy(QAbstractScrollArea::AdjustToContents);
- setSizePolicy(QSizePolicy::Preferred, QSizePolicy::Fixed);
+ setHorizontalScrollBarPolicy(Qt::ScrollBarAlwaysOff);
+
+ QObject::connect(dbc(), &DBCManager::DBCFileChanged, this, &BinaryView::refresh);
+ QObject::connect(UndoStack::instance(), &QUndoStack::indexChanged, this, &BinaryView::refresh);
+
+ addShortcuts();
+ setWhatsThis(R"(
+ Binary View
+
+ Shortcuts
+ Delete Signal:
+ x ,
+ Backspace ,
+ Delete
+ Change endianness: e
+ Change singedness: s
+ Open chart:
+ c ,
+ p ,
+ g
+ )");
+}
+
+void BinaryView::addShortcuts() {
+ // Delete (x, backspace, delete)
+ QShortcut *shortcut_delete_x = new QShortcut(QKeySequence(Qt::Key_X), this);
+ QShortcut *shortcut_delete_backspace = new QShortcut(QKeySequence(Qt::Key_Backspace), this);
+ QShortcut *shortcut_delete_delete = new QShortcut(QKeySequence(Qt::Key_Delete), this);
+ QObject::connect(shortcut_delete_delete, &QShortcut::activated, shortcut_delete_x, &QShortcut::activated);
+ QObject::connect(shortcut_delete_backspace, &QShortcut::activated, shortcut_delete_x, &QShortcut::activated);
+ QObject::connect(shortcut_delete_x, &QShortcut::activated, [=]{
+ if (hovered_sig != nullptr) {
+ emit removeSignal(hovered_sig);
+ hovered_sig = nullptr;
+ }
+ });
+
+ // Change endianness (e)
+ QShortcut *shortcut_endian = new QShortcut(QKeySequence(Qt::Key_E), this);
+ QObject::connect(shortcut_endian, &QShortcut::activated, [=]{
+ if (hovered_sig != nullptr) {
+ const Signal *hovered_sig_prev = hovered_sig;
+ Signal s = *hovered_sig;
+ s.is_little_endian = !s.is_little_endian;
+ emit editSignal(hovered_sig, s);
+
+ hovered_sig = nullptr;
+ highlight(hovered_sig_prev);
+ }
+ });
+
+ // Change signedness (s)
+ QShortcut *shortcut_sign = new QShortcut(QKeySequence(Qt::Key_S), this);
+ QObject::connect(shortcut_sign, &QShortcut::activated, [=]{
+ if (hovered_sig != nullptr) {
+ const Signal *hovered_sig_prev = hovered_sig;
+ Signal s = *hovered_sig;
+ s.is_signed = !s.is_signed;
+ emit editSignal(hovered_sig, s);
+
+ hovered_sig = nullptr;
+ highlight(hovered_sig_prev);
+ }
+ });
+
+ // Open chart (c, p, g)
+ QShortcut *shortcut_plot = new QShortcut(QKeySequence(Qt::Key_P), this);
+ QShortcut *shortcut_plot_g = new QShortcut(QKeySequence(Qt::Key_G), this);
+ QShortcut *shortcut_plot_c = new QShortcut(QKeySequence(Qt::Key_C), this);
+ QObject::connect(shortcut_plot_g, &QShortcut::activated, shortcut_plot, &QShortcut::activated);
+ QObject::connect(shortcut_plot_c, &QShortcut::activated, shortcut_plot, &QShortcut::activated);
+ QObject::connect(shortcut_plot, &QShortcut::activated, [=]{
+ if (hovered_sig != nullptr) {
+ emit showChart(model->msg_id, hovered_sig, true, false);
+ }
+ });
+}
+
+QSize BinaryView::minimumSizeHint() const {
+ return {(horizontalHeader()->minimumSectionSize() + 1) * 9 + VERTICAL_HEADER_WIDTH + 2,
+ CELL_HEIGHT * std::min(model->rowCount(), 10) + 2};
}
void BinaryView::highlight(const Signal *sig) {
if (sig != hovered_sig) {
+ for (int i = 0; i < model->items.size(); ++i) {
+ auto &item_sigs = model->items[i].sigs;
+ if ((sig && item_sigs.contains(sig)) || (hovered_sig && item_sigs.contains(hovered_sig))) {
+ auto index = model->index(i / model->columnCount(), i % model->columnCount());
+ emit model->dataChanged(index, index, {Qt::DisplayRole});
+ }
+ }
+
+ if (sig && underMouse()) {
+ QString tooltip = tr(R"(%1
+ Size:%2 LE:%3 SGD:%4
+ )").arg(sig->name).arg(sig->size).arg(sig->is_little_endian ? "Y" : "N").arg(sig->is_signed ? "Y" : "N");
+ QToolTip::showText(QCursor::pos(), tooltip, this, rect());
+ } else {
+ QToolTip::showText(QCursor::pos(), "", this, rect());
+ }
+
hovered_sig = sig;
- model->dataChanged(model->index(0, 0), model->index(model->rowCount() - 1, model->columnCount() - 1));
emit signalHovered(hovered_sig);
}
}
@@ -65,7 +165,7 @@ void BinaryView::mousePressEvent(QMouseEvent *event) {
if (bit_idx == s->lsb || bit_idx == s->msb) {
anchor_index = model->bitIndex(bit_idx == s->lsb ? s->msb : s->lsb, true);
resize_sig = s;
- delegate->selection_color = item->bg_color;
+ delegate->selection_color = getColor(s);
break;
}
}
@@ -78,7 +178,6 @@ void BinaryView::highlightPosition(const QPoint &pos) {
auto item = (BinaryViewModel::Item *)index.internalPointer();
const Signal *sig = item->sigs.isEmpty() ? nullptr : item->sigs.back();
highlight(sig);
- QToolTip::showText(pos, sig ? sig->name.c_str() : "", this, rect());
}
}
@@ -112,14 +211,19 @@ void BinaryView::leaveEvent(QEvent *event) {
QTableView::leaveEvent(event);
}
-void BinaryView::setMessage(const QString &message_id) {
- model->setMessage(message_id);
+void BinaryView::setMessage(const MessageId &message_id) {
+ model->msg_id = message_id;
+ verticalScrollBar()->setValue(0);
+ refresh();
+}
+
+void BinaryView::refresh() {
clearSelection();
anchor_index = QModelIndex();
resize_sig = nullptr;
hovered_sig = nullptr;
+ model->refresh();
highlightPosition(QCursor::pos());
- updateState();
}
QSet BinaryView::getOverlappingSignals() const {
@@ -144,40 +248,40 @@ std::tuple BinaryView::getSelection(QModelIndex index) {
// BinaryViewModel
-void BinaryViewModel::setMessage(const QString &message_id) {
+void BinaryViewModel::refresh() {
beginResetModel();
- msg_id = message_id;
items.clear();
- if ((dbc_msg = dbc()->msg(msg_id))) {
+ if (auto dbc_msg = dbc()->msg(msg_id)) {
row_count = dbc_msg->size;
items.resize(row_count * column_count);
- int i = 0;
for (auto sig : dbc_msg->getSignals()) {
auto [start, end] = getSignalRange(sig);
for (int j = start; j <= end; ++j) {
int bit_index = sig->is_little_endian ? bigEndianBitIndex(j) : j;
int idx = column_count * (bit_index / 8) + bit_index % 8;
if (idx >= items.size()) {
- qWarning() << "signal " << sig->name.c_str() << "out of bounds.start_bit:" << sig->start_bit << "size:" << sig->size;
+ qWarning() << "signal " << sig->name << "out of bounds.start_bit:" << sig->start_bit << "size:" << sig->size;
break;
}
if (j == start) sig->is_little_endian ? items[idx].is_lsb = true : items[idx].is_msb = true;
if (j == end) sig->is_little_endian ? items[idx].is_msb = true : items[idx].is_lsb = true;
- items[idx].bg_color = getColor(i);
+ items[idx].bg_color = getColor(sig);
items[idx].sigs.push_back(sig);
}
- ++i;
}
} else {
row_count = can->lastMessage(msg_id).dat.size();
items.resize(row_count * column_count);
}
endResetModel();
+ updateState();
}
void BinaryViewModel::updateState() {
auto prev_items = items;
- const auto &binary = can->lastMessage(msg_id).dat;
+ const auto &last_msg = can->lastMessage(msg_id);
+ const auto &binary = last_msg.dat;
+
// data size may changed.
if (binary.size() > row_count) {
beginInsertRows({}, row_count, binary.size() - 1);
@@ -185,23 +289,30 @@ void BinaryViewModel::updateState() {
items.resize(row_count * column_count);
endInsertRows();
}
- char hex[3] = {'\0'};
+
+ double max_f = 255.0;
+ double factor = 0.25;
+ double scaler = max_f / log2(1.0 + factor);
for (int i = 0; i < binary.size(); ++i) {
- for (int j = 0; j < column_count - 1; ++j) {
- items[i * column_count + j].val = ((binary[i] >> (7 - j)) & 1) != 0 ? '1' : '0';
+ for (int j = 0; j < 8; ++j) {
+ auto &item = items[i * column_count + j];
+ item.val = ((binary[i] >> (7 - j)) & 1) != 0 ? '1' : '0';
+ // Bit update frequency based highlighting
+ double offset = !item.sigs.empty() ? 50 : 0;
+ auto n = last_msg.bit_change_counts[i][7 - j];
+ double min_f = n == 0 ? offset : offset + 25;
+ double alpha = std::clamp(offset + log2(1.0 + factor * (double)n / (double)last_msg.count) * scaler, min_f, max_f);
+ item.bg_color.setAlpha(alpha);
}
- hex[0] = toHex(binary[i] >> 4);
- hex[1] = toHex(binary[i] & 0xf);
- items[i * column_count + 8].val = hex;
+ items[i * column_count + 8].val = toHex(binary[i]);
+ items[i * column_count + 8].bg_color = last_msg.colors[i];
}
- for (int i = binary.size(); i < row_count; ++i) {
- for (int j = 0; j < column_count; ++j) {
- items[i * column_count + j].val = "-";
- }
+ for (int i = binary.size() * column_count; i < items.size(); ++i) {
+ items[i].val = "-";
}
- for (int i = 0; i < row_count * column_count; ++i) {
- if (i >= prev_items.size() || prev_items[i].val != items[i].val) {
+ for (int i = 0; i < items.size(); ++i) {
+ if (i >= prev_items.size() || prev_items[i].val != items[i].val || prev_items[i].bg_color != items[i].bg_color) {
auto idx = index(i / column_count, i % column_count);
emit dataChanged(idx, idx);
}
@@ -212,7 +323,7 @@ QVariant BinaryViewModel::headerData(int section, Qt::Orientation orientation, i
if (orientation == Qt::Vertical) {
switch (role) {
case Qt::DisplayRole: return section;
- case Qt::SizeHintRole: return QSize(30, 0);
+ case Qt::SizeHintRole: return QSize(VERTICAL_HEADER_WIDTH, 0);
case Qt::TextAlignmentRole: return Qt::AlignCenter;
}
}
@@ -227,6 +338,17 @@ BinaryItemDelegate::BinaryItemDelegate(QObject *parent) : QStyledItemDelegate(pa
hex_font.setBold(true);
}
+bool BinaryItemDelegate::isSameColor(const QModelIndex &index, int dx, int dy) const {
+ QModelIndex index2 = index.sibling(index.row() + dy, index.column() + dx);
+ if (!index2.isValid()) {
+ return false;
+ }
+ auto color1 = ((const BinaryViewModel::Item *)index.internalPointer())->bg_color;
+ auto color2 = ((const BinaryViewModel::Item *)index2.internalPointer())->bg_color;
+ // Ignore alpha
+ return (color1.red() == color2.red()) && (color2.green() == color2.green()) && (color1.blue() == color2.blue());
+}
+
void BinaryItemDelegate::paint(QPainter *painter, const QStyleOptionViewItem &option, const QModelIndex &index) const {
auto item = (const BinaryViewModel::Item *)index.internalPointer();
BinaryView *bin_view = (BinaryView *)parent();
@@ -234,18 +356,75 @@ void BinaryItemDelegate::paint(QPainter *painter, const QStyleOptionViewItem &op
if (index.column() == 8) {
painter->setFont(hex_font);
+ painter->fillRect(option.rect, item->bg_color);
} else if (option.state & QStyle::State_Selected) {
painter->fillRect(option.rect, selection_color);
painter->setPen(option.palette.color(QPalette::BrightText));
- } else if (!item->sigs.isEmpty() && (!bin_view->selectionModel()->hasSelection() || !item->sigs.contains(bin_view->resize_sig))) {
- painter->fillRect(option.rect, item->bg_color);
- painter->setPen(item->sigs.contains(bin_view->hovered_sig) ? option.palette.color(QPalette::BrightText) : Qt::black);
+ } else if (!bin_view->selectionModel()->hasSelection() || !item->sigs.contains(bin_view->resize_sig)) { // not resizing
+ QColor bg = item->bg_color;
+ if (bin_view->hovered_sig && item->sigs.contains(bin_view->hovered_sig)) {
+ bg.setAlpha(255);
+ painter->fillRect(option.rect, bg.darker(125)); // 4/5x brightness
+ painter->setPen(option.palette.color(QPalette::BrightText));
+ } else {
+ if (item->sigs.size() > 0) {
+ drawBorder(painter, option, index);
+ bg.setAlpha(std::max(50, bg.alpha()));
+ }
+ painter->fillRect(option.rect, bg);
+ painter->setPen(option.palette.color(QPalette::Text));
+ }
}
painter->drawText(option.rect, Qt::AlignCenter, item->val);
if (item->is_msb || item->is_lsb) {
painter->setFont(small_font);
- painter->drawText(option.rect, Qt::AlignHCenter | Qt::AlignBottom, item->is_msb ? "MSB" : "LSB");
+ painter->drawText(option.rect.adjusted(8, 0, -8, -3), Qt::AlignRight | Qt::AlignBottom, item->is_msb ? "M" : "L");
}
painter->restore();
}
+
+// Draw border on edge of signal
+void BinaryItemDelegate::drawBorder(QPainter* painter, const QStyleOptionViewItem &option, const QModelIndex &index) const {
+ auto item = (const BinaryViewModel::Item *)index.internalPointer();
+ QColor border_color = item->bg_color;
+ border_color.setAlphaF(1.0);
+
+ bool draw_left = !isSameColor(index, -1, 0);
+ bool draw_top = !isSameColor(index, 0, -1);
+ bool draw_right = !isSameColor(index, 1, 0);
+ bool draw_bottom = !isSameColor(index, 0, 1);
+
+ const int spacing = 2;
+ QRect rc = option.rect.adjusted(draw_left * 3, draw_top * spacing, draw_right * -3, draw_bottom * -spacing);
+ QRegion subtract;
+ if (!draw_top) {
+ if (!draw_left && !isSameColor(index, -1, -1)) {
+ subtract += QRect{rc.left(), rc.top(), 3, spacing};
+ } else if (!draw_right && !isSameColor(index, 1, -1)) {
+ subtract += QRect{rc.right() - 2, rc.top(), 3, spacing};
+ }
+ }
+ if (!draw_bottom) {
+ if (!draw_left && !isSameColor(index, -1, 1)) {
+ subtract += QRect{rc.left(), rc.bottom() - (spacing - 1), 3, spacing};
+ } else if (!draw_right && !isSameColor(index, 1, 1)) {
+ subtract += QRect{rc.right() - 2, rc.bottom() - (spacing - 1), 3, spacing};
+ }
+ }
+
+ painter->setPen(QPen(border_color, 1));
+ if (draw_left) painter->drawLine(rc.topLeft(), rc.bottomLeft());
+ if (draw_right) painter->drawLine(rc.topRight(), rc.bottomRight());
+ if (draw_bottom) painter->drawLine(rc.bottomLeft(), rc.bottomRight());
+ if (draw_top) painter->drawLine(rc.topLeft(), rc.topRight());
+
+ painter->setClipRegion(QRegion(rc).subtracted(subtract));
+ if (!subtract.isEmpty()) {
+ // fill gaps inside corners.
+ painter->setPen(QPen(border_color, 2));
+ for (auto &r : subtract) {
+ painter->drawRect(r);
+ }
+ }
+}
diff --git a/tools/cabana/binaryview.h b/tools/cabana/binaryview.h
index e936efc658..681ac1fbf3 100644
--- a/tools/cabana/binaryview.h
+++ b/tools/cabana/binaryview.h
@@ -7,12 +7,16 @@
#include
#include "tools/cabana/dbcmanager.h"
+#include "tools/cabana/streams/abstractstream.h"
+using namespace dbcmanager;
class BinaryItemDelegate : public QStyledItemDelegate {
public:
BinaryItemDelegate(QObject *parent);
void paint(QPainter *painter, const QStyleOptionViewItem &option, const QModelIndex &index) const override;
void setSelectionColor(const QColor &color) { selection_color = color; }
+ bool isSameColor(const QModelIndex &index, int dx, int dy) const;
+ void drawBorder(QPainter* painter, const QStyleOptionViewItem &option, const QModelIndex &index) const;
QFont small_font, hex_font;
QColor selection_color;
@@ -21,7 +25,7 @@ public:
class BinaryViewModel : public QAbstractTableModel {
public:
BinaryViewModel(QObject *parent) : QAbstractTableModel(parent) {}
- void setMessage(const QString &message_id);
+ void refresh();
void updateState();
QVariant headerData(int section, Qt::Orientation orientation, int role = Qt::DisplayRole) const override;
QVariant data(const QModelIndex &index, int role = Qt::DisplayRole) const { return {}; }
@@ -36,17 +40,15 @@ public:
}
struct Item {
- QColor bg_color = QApplication::style()->standardPalette().color(QPalette::Base);
+ QColor bg_color = QColor(102, 86, 169, 0);
bool is_msb = false;
bool is_lsb = false;
- QString val = "0";
+ QString val = "-";
QList sigs;
};
std::vector items;
-private:
- QString msg_id;
- const DBCMsg *dbc_msg = nullptr;
+ MessageId msg_id;
int row_count = 0;
const int column_count = 9;
};
@@ -56,18 +58,24 @@ class BinaryView : public QTableView {
public:
BinaryView(QWidget *parent = nullptr);
- void setMessage(const QString &message_id);
+ void setMessage(const MessageId &message_id);
void highlight(const Signal *sig);
QSet getOverlappingSignals() const;
inline void updateState() { model->updateState(); }
+ QSize minimumSizeHint() const override;
signals:
void signalClicked(const Signal *sig);
void signalHovered(const Signal *sig);
void addSignal(int start_bit, int size, bool little_endian);
void resizeSignal(const Signal *sig, int from, int size);
+ void removeSignal(const Signal *sig);
+ void editSignal(const Signal *origin_s, Signal &s);
+ void showChart(const MessageId &id, const Signal *sig, bool show, bool merge);
private:
+ void addShortcuts();
+ void refresh();
std::tuple getSelection(QModelIndex index);
void setSelection(const QRect &rect, QItemSelectionModel::SelectionFlags flags) override;
void mousePressEvent(QMouseEvent *event) override;
diff --git a/tools/cabana/cabana.cc b/tools/cabana/cabana.cc
index 51418e293f..5c182f435f 100644
--- a/tools/cabana/cabana.cc
+++ b/tools/cabana/cabana.cc
@@ -4,10 +4,17 @@
#include "common/prefix.h"
#include "selfdrive/ui/qt/util.h"
#include "tools/cabana/mainwin.h"
+#include "tools/cabana/route.h"
+#include "tools/cabana/streams/livestream.h"
+#include "tools/cabana/streams/replaystream.h"
int main(int argc, char *argv[]) {
+ QCoreApplication::setApplicationName("Cabana");
+ QCoreApplication::setAttribute(Qt::AA_ShareOpenGLContexts);
initApp(argc, argv);
QApplication app(argc, argv);
+ app.setApplicationDisplayName("Cabana");
+ app.setWindowIcon(QIcon(":cabana-icon.png"));
QCommandLineParser cmd_parser;
cmd_parser.addHelpOption();
@@ -15,29 +22,58 @@ int main(int argc, char *argv[]) {
cmd_parser.addOption({"demo", "use a demo route instead of providing your own"});
cmd_parser.addOption({"qcam", "load qcamera"});
cmd_parser.addOption({"ecam", "load wide road camera"});
+ cmd_parser.addOption({"stream", "read can messages from live streaming"});
+ cmd_parser.addOption({"zmq", "the ip address on which to receive zmq messages", "zmq"});
cmd_parser.addOption({"data_dir", "local directory with routes", "data_dir"});
+ cmd_parser.addOption({"no-vipc", "do not output video"});
+ cmd_parser.addOption({"dbc", "dbc file to open", "dbc"});
cmd_parser.process(app);
- const QStringList args = cmd_parser.positionalArguments();
- if (args.empty() && !cmd_parser.isSet("demo")) {
- cmd_parser.showHelp();
- }
+ std::unique_ptr op_prefix;
+ std::unique_ptr stream;
+
+ if (cmd_parser.isSet("stream")) {
+ stream.reset(new LiveStream(&app, cmd_parser.value("zmq")));
+ } else {
+ // TODO: Remove when OpenpilotPrefix supports ZMQ
+#ifndef __APPLE__
+ op_prefix.reset(new OpenpilotPrefix());
+#endif
+ uint32_t replay_flags = REPLAY_FLAG_NONE;
+ if (cmd_parser.isSet("ecam")) {
+ replay_flags |= REPLAY_FLAG_ECAM;
+ } else if (cmd_parser.isSet("qcam")) {
+ replay_flags |= REPLAY_FLAG_QCAMERA;
+ } else if (cmd_parser.isSet("no-vipc")) {
+ replay_flags |= REPLAY_FLAG_NO_VIPC;
+ }
+
+ const QStringList args = cmd_parser.positionalArguments();
+ QString route;
+ if (args.size() > 0) {
+ route = args.first();
+ } else if (cmd_parser.isSet("demo")) {
+ route = DEMO_ROUTE;
+ }
- const QString route = args.empty() ? DEMO_ROUTE : args.first();
- uint32_t replay_flags = REPLAY_FLAG_NONE;
- if (cmd_parser.isSet("ecam")) {
- replay_flags |= REPLAY_FLAG_ECAM;
- } else if (cmd_parser.isSet("qcam")) {
- replay_flags |= REPLAY_FLAG_QCAMERA;
+ auto replay_stream = new ReplayStream(replay_flags, &app);
+ stream.reset(replay_stream);
+ if (route.isEmpty()) {
+ if (OpenRouteDialog dlg(nullptr); !dlg.exec()) {
+ return 0;
+ }
+ } else if (!replay_stream->loadRoute(route, cmd_parser.value("data_dir"))) {
+ return 0;
+ }
}
- OpenpilotPrefix op_prefix;
- CANMessages p(&app);
- int ret = 0;
- if (p.loadRoute(route, cmd_parser.value("data_dir"), replay_flags)) {
- MainWindow w;
- w.showMaximized();
- ret = app.exec();
+ MainWindow w;
+
+ // Load DBC
+ if (cmd_parser.isSet("dbc")) {
+ w.loadFile(cmd_parser.value("dbc"));
}
- return ret;
+
+ w.show();
+ return app.exec();
}
diff --git a/tools/cabana/canmessages.cc b/tools/cabana/canmessages.cc
deleted file mode 100644
index ad3ee80e3d..0000000000
--- a/tools/cabana/canmessages.cc
+++ /dev/null
@@ -1,96 +0,0 @@
-#include "tools/cabana/canmessages.h"
-#include "tools/cabana/dbcmanager.h"
-
-CANMessages *can = nullptr;
-
-CANMessages::CANMessages(QObject *parent) : QObject(parent) {
- can = this;
- QObject::connect(this, &CANMessages::received, this, &CANMessages::process, Qt::QueuedConnection);
- QObject::connect(&settings, &Settings::changed, this, &CANMessages::settingChanged);
-}
-
-CANMessages::~CANMessages() {
- replay->stop();
-}
-
-static bool event_filter(const Event *e, void *opaque) {
- CANMessages *c = (CANMessages *)opaque;
- return c->eventFilter(e);
-}
-
-bool CANMessages::loadRoute(const QString &route, const QString &data_dir, uint32_t replay_flags) {
- replay = new Replay(route, {"can", "roadEncodeIdx", "wideRoadEncodeIdx", "carParams"}, {}, nullptr, replay_flags, data_dir, this);
- replay->setSegmentCacheLimit(settings.cached_segment_limit);
- replay->installEventFilter(event_filter, this);
- QObject::connect(replay, &Replay::seekedTo, this, &CANMessages::seekedTo);
- QObject::connect(replay, &Replay::segmentsMerged, this, &CANMessages::eventsMerged);
- QObject::connect(replay, &Replay::streamStarted, this, &CANMessages::streamStarted);
- if (replay->load()) {
- const auto &segments = replay->route()->segments();
- if (std::none_of(segments.begin(), segments.end(), [](auto &s) { return s.second.rlog.length() > 0; })) {
- qWarning() << "no rlogs in route" << route;
- return false;
- }
- replay->start();
- return true;
- }
- return false;
-}
-
-void CANMessages::process(QHash *messages) {
- for (auto it = messages->begin(); it != messages->end(); ++it) {
- can_msgs[it.key()] = it.value();
- }
- emit updated();
- emit msgsReceived(messages);
- delete messages;
- processing = false;
-}
-
-bool CANMessages::eventFilter(const Event *event) {
- static std::unique_ptr new_msgs = std::make_unique>();
- static double prev_update_ts = 0;
-
- if (event->which == cereal::Event::Which::CAN) {
- double current_sec = replay->currentSeconds();
- if (counters_begin_sec == 0 || counters_begin_sec >= current_sec) {
- new_msgs->clear();
- counters.clear();
- counters_begin_sec = current_sec;
- }
-
- auto can_events = event->event.getCan();
- for (const auto &c : can_events) {
- QString id = QString("%1:%2").arg(c.getSrc()).arg(c.getAddress(), 1, 16);
- CanData &data = (*new_msgs)[id];
- data.ts = current_sec;
- data.dat = QByteArray((char *)c.getDat().begin(), c.getDat().size());
- data.count = ++counters[id];
- if (double delta = (current_sec - counters_begin_sec); delta > 0) {
- data.freq = data.count / delta;
- }
- }
-
- double ts = millis_since_boot();
- if ((ts - prev_update_ts) > (1000.0 / settings.fps) && !processing && !new_msgs->isEmpty()) {
- // delay posting CAN message if UI thread is busy
- processing = true;
- prev_update_ts = ts;
- // use pointer to avoid data copy in queued connection.
- emit received(new_msgs.release());
- new_msgs.reset(new QHash);
- new_msgs->reserve(100);
- }
- }
- return true;
-}
-
-void CANMessages::seekTo(double ts) {
- replay->seekTo(std::max(double(0), ts), false);
- counters_begin_sec = 0;
- emit updated();
-}
-
-void CANMessages::settingChanged() {
- replay->setSegmentCacheLimit(settings.cached_segment_limit);
-}
diff --git a/tools/cabana/canmessages.h b/tools/cabana/canmessages.h
deleted file mode 100644
index 4dac4fe9df..0000000000
--- a/tools/cabana/canmessages.h
+++ /dev/null
@@ -1,79 +0,0 @@
-#pragma once
-
-#include
-
-#include
-#include
-
-#include "opendbc/can/common_dbc.h"
-#include "tools/cabana/settings.h"
-#include "tools/replay/replay.h"
-
-struct CanData {
- double ts = 0.;
- uint32_t count = 0;
- uint32_t freq = 0;
- QByteArray dat;
-};
-
-class CANMessages : public QObject {
- Q_OBJECT
-
-public:
- CANMessages(QObject *parent);
- ~CANMessages();
- bool loadRoute(const QString &route, const QString &data_dir, uint32_t replay_flags = REPLAY_FLAG_NONE);
- void seekTo(double ts);
- bool eventFilter(const Event *event);
-
- inline QString routeName() const { return replay->route()->name(); }
- inline QString carFingerprint() const { return replay->carFingerprint().c_str(); }
- inline VisionStreamType visionStreamType() const { return replay->hasFlag(REPLAY_FLAG_ECAM) ? VISION_STREAM_WIDE_ROAD : VISION_STREAM_ROAD; }
- inline double totalSeconds() const { return replay->totalSeconds(); }
- inline double routeStartTime() const { return replay->routeStartTime() / (double)1e9; }
- inline double currentSec() const { return replay->currentSeconds(); }
- inline const CanData &lastMessage(const QString &id) { return can_msgs[id]; }
-
- inline const Route* route() const { return replay->route(); }
- inline const std::vector *events() const { return replay->events(); }
- inline void setSpeed(float speed) { replay->setSpeed(speed); }
- inline bool isPaused() const { return replay->isPaused(); }
- inline void pause(bool pause) { replay->pause(pause); }
- inline const std::vector> getTimeline() { return replay->getTimeline(); }
-
-signals:
- void seekedTo(double sec);
- void streamStarted();
- void eventsMerged();
- void updated();
- void msgsReceived(const QHash *);
- void received(QHash *);
-
-public:
- QMap can_msgs;
-
-protected:
- void process(QHash *);
- void settingChanged();
-
- Replay *replay = nullptr;
- std::atomic counters_begin_sec = 0;
- std::atomic processing = false;
- QHash counters;
-};
-
-inline QString toHex(const QByteArray &dat) {
- return dat.toHex(' ').toUpper();
-}
-inline char toHex(uint value) {
- return "0123456789ABCDEF"[value & 0xF];
-}
-
-inline const QString &getColor(int i) {
- // TODO: add more colors
- static const QString SIGNAL_COLORS[] = {"#9FE2BF", "#40E0D0", "#6495ED", "#CCCCFF", "#FF7F50", "#FFBF00"};
- return SIGNAL_COLORS[i % std::size(SIGNAL_COLORS)];
-}
-
-// A global pointer referring to the unique CANMessages object
-extern CANMessages *can;
diff --git a/tools/cabana/chartswidget.cc b/tools/cabana/chartswidget.cc
index bc28666a34..2c27fbd8b9 100644
--- a/tools/cabana/chartswidget.cc
+++ b/tools/cabana/chartswidget.cc
@@ -1,85 +1,121 @@
#include "tools/cabana/chartswidget.h"
+#include
+#include
#include
-#include
+#include
+#include
#include
#include
+#include
+#include
#include
+#include
#include
-#include
#include
#include
+const int MAX_COLUMN_COUNT = 4;
// ChartsWidget
-ChartsWidget::ChartsWidget(QWidget *parent) : QWidget(parent) {
+ChartsWidget::ChartsWidget(QWidget *parent) : QFrame(parent) {
+ setFrameStyle(QFrame::StyledPanel | QFrame::Plain);
QVBoxLayout *main_layout = new QVBoxLayout(this);
main_layout->setContentsMargins(0, 0, 0, 0);
// toolbar
QToolBar *toolbar = new QToolBar(tr("Charts"), this);
- title_label = new QLabel();
- title_label->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Preferred);
- toolbar->addWidget(title_label);
- show_all_values_btn = toolbar->addAction("");
- toolbar->addWidget(range_label = new QLabel());
- reset_zoom_btn = toolbar->addAction("⟲");
- reset_zoom_btn->setToolTip(tr("Reset zoom (drag on chart to zoom X-Axis)"));
- remove_all_btn = toolbar->addAction("✖");
- remove_all_btn->setToolTip(tr("Remove all charts"));
+ int icon_size = style()->pixelMetric(QStyle::PM_SmallIconSize);
+ toolbar->setIconSize({icon_size, icon_size});
+
+ QAction *new_plot_btn = toolbar->addAction(utils::icon("file-plus"), tr("New Plot"));
+ toolbar->addWidget(title_label = new QLabel());
+ title_label->setContentsMargins(0, 0, style()->pixelMetric(QStyle::PM_LayoutHorizontalSpacing), 0);
+
+ QMenu *menu = new QMenu(this);
+ for (int i = 0; i < MAX_COLUMN_COUNT; ++i) {
+ menu->addAction(tr("%1").arg(i + 1), [=]() { setColumnCount(i + 1); });
+ }
+ columns_action = toolbar->addAction("");
+ columns_action->setMenu(menu);
+ qobject_cast(toolbar->widgetForAction(columns_action))->setPopupMode(QToolButton::InstantPopup);
+
+ QLabel *stretch_label = new QLabel(this);
+ stretch_label->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Preferred);
+ toolbar->addWidget(stretch_label);
+
+ range_lb_action = toolbar->addWidget(range_lb = new QLabel(this));
+ range_slider = new QSlider(Qt::Horizontal, this);
+ range_slider->setMaximumWidth(200);
+ range_slider->setToolTip(tr("Set the chart range"));
+ range_slider->setRange(1, settings.max_cached_minutes * 60);
+ range_slider->setSingleStep(1);
+ range_slider->setPageStep(60); // 1 min
+ range_slider_action = toolbar->addWidget(range_slider);
+
+ reset_zoom_action = toolbar->addAction(utils::icon("zoom-out"), tr("Reset Zoom"));
+ qobject_cast(toolbar->widgetForAction(reset_zoom_action))->setToolButtonStyle(Qt::ToolButtonTextBesideIcon);
+
+ remove_all_btn = toolbar->addAction(utils::icon("x"), tr("Remove all charts"));
dock_btn = toolbar->addAction("");
main_layout->addWidget(toolbar);
// charts
+ charts_layout = new QGridLayout();
+ charts_layout->setSpacing(10);
+
QWidget *charts_container = new QWidget(this);
- charts_layout = new QVBoxLayout(charts_container);
- charts_layout->addStretch();
+ QVBoxLayout *charts_main_layout = new QVBoxLayout(charts_container);
+ charts_main_layout->setContentsMargins(0, 0, 0, 0);
+ charts_main_layout->addLayout(charts_layout);
+ charts_main_layout->addStretch(0);
QScrollArea *charts_scroll = new QScrollArea(this);
+ charts_scroll->setFrameStyle(QFrame::NoFrame);
charts_scroll->setWidgetResizable(true);
charts_scroll->setWidget(charts_container);
charts_scroll->setHorizontalScrollBarPolicy(Qt::ScrollBarAlwaysOff);
main_layout->addWidget(charts_scroll);
- max_chart_range = settings.max_chart_x_range;
- use_dark_theme = palette().color(QPalette::WindowText).value() > palette().color(QPalette::Background).value();
+ // init settings
+ use_dark_theme = QApplication::palette().color(QPalette::WindowText).value() >
+ QApplication::palette().color(QPalette::Background).value();
+ column_count = std::clamp(settings.chart_column_count, 1, MAX_COLUMN_COUNT);
+ max_chart_range = std::clamp(settings.chart_range, 1, settings.max_cached_minutes * 60);
+ display_range = {0, max_chart_range};
+ range_slider->setValue(max_chart_range);
updateToolBar();
QObject::connect(dbc(), &DBCManager::DBCFileChanged, this, &ChartsWidget::removeAll);
- QObject::connect(can, &CANMessages::eventsMerged, this, &ChartsWidget::eventsMerged);
- QObject::connect(can, &CANMessages::updated, this, &ChartsWidget::updateState);
- QObject::connect(show_all_values_btn, &QAction::triggered, this, &ChartsWidget::showAllData);
+ QObject::connect(can, &AbstractStream::eventsMerged, this, &ChartsWidget::eventsMerged);
+ QObject::connect(can, &AbstractStream::updated, this, &ChartsWidget::updateState);
+ QObject::connect(range_slider, &QSlider::valueChanged, this, &ChartsWidget::setMaxChartRange);
+ QObject::connect(new_plot_btn, &QAction::triggered, this, &ChartsWidget::newChart);
QObject::connect(remove_all_btn, &QAction::triggered, this, &ChartsWidget::removeAll);
- QObject::connect(reset_zoom_btn, &QAction::triggered, this, &ChartsWidget::zoomReset);
+ QObject::connect(reset_zoom_action, &QAction::triggered, this, &ChartsWidget::zoomReset);
+ QObject::connect(&settings, &Settings::changed, this, &ChartsWidget::settingChanged);
QObject::connect(dock_btn, &QAction::triggered, [this]() {
emit dock(!docking);
docking = !docking;
updateToolBar();
});
-}
-void ChartsWidget::eventsMerged() {
- if (auto events = can->events(); events && !events->empty()) {
- event_range.first = (events->front()->mono_time / (double)1e9) - can->routeStartTime();
- event_range.second = (events->back()->mono_time / (double)1e9) - can->routeStartTime();
- updateState();
- }
+ setWhatsThis(tr(R"(
+ Chart view
+
+ )"));
}
-void ChartsWidget::updateDisplayRange() {
- auto prev_range = display_range;
- double current_sec = can->currentSec();
- if (current_sec < display_range.first || current_sec >= (display_range.second - 5)) {
- // reached the end, or seeked to a timestamp out of range.
- display_range.first = current_sec - 5;
- }
- display_range.first = std::floor(std::max(display_range.first, event_range.first) * 10.0) / 10.0;
- display_range.second = std::floor(std::min(display_range.first + max_chart_range, event_range.second) * 10.0) / 10.0;
- if (prev_range != display_range) {
+void ChartsWidget::eventsMerged() {
+ {
+ assert(!can->liveStreaming());
QFutureSynchronizer future_synchronizer;
- for (auto c : charts)
- future_synchronizer.addFuture(QtConcurrent::run(c, &ChartView::setEventsRange, display_range));
+ const auto events = can->events();
+ for (auto c : charts) {
+ future_synchronizer.addFuture(QtConcurrent::run(c, &ChartView::updateSeries, nullptr, events, true));
+ }
}
+ updateState();
}
void ChartsWidget::zoomIn(double min, double max) {
@@ -97,80 +133,150 @@ void ChartsWidget::zoomReset() {
void ChartsWidget::updateState() {
if (charts.isEmpty()) return;
+ const auto events = can->events();
+ if (can->liveStreaming()) {
+ // appends incoming events to the end of series
+ for (auto c : charts) {
+ c->updateSeries(nullptr, events, false);
+ }
+ }
+
+ const double cur_sec = can->currentSec();
if (!is_zoomed) {
- updateDisplayRange();
- } else if (can->currentSec() < zoomed_range.first || can->currentSec() >= zoomed_range.second) {
+ double pos = (cur_sec - display_range.first) / std::max(1.0, (display_range.second - display_range.first));
+ if (pos < 0 || pos > 0.8) {
+ display_range.first = std::max(0.0, cur_sec - max_chart_range * 0.1);
+ }
+ double max_event_sec = events->empty() ? 0 : (events->back()->mono_time / 1e9 - can->routeStartTime());
+ double max_sec = std::min(std::floor(display_range.first + max_chart_range), max_event_sec);
+ display_range.first = std::max(0.0, max_sec - max_chart_range);
+ display_range.second = display_range.first + max_chart_range;
+ } else if (cur_sec < zoomed_range.first || cur_sec >= zoomed_range.second) {
+ // loop in zoommed range
can->seekTo(zoomed_range.first);
}
const auto &range = is_zoomed ? zoomed_range : display_range;
- setUpdatesEnabled(false);
for (auto c : charts) {
- c->setDisplayRange(range.first, range.second);
- c->scene()->invalidate({}, QGraphicsScene::ForegroundLayer);
+ c->updatePlot(cur_sec, range.first, range.second);
}
- setUpdatesEnabled(true);
}
-void ChartsWidget::showAllData() {
- bool switch_to_show_all = max_chart_range == settings.max_chart_x_range;
- max_chart_range = switch_to_show_all ? settings.cached_segment_limit * 60
- : settings.max_chart_x_range;
- max_chart_range = std::min(max_chart_range, (uint32_t)can->totalSeconds());
+void ChartsWidget::setMaxChartRange(int value) {
+ max_chart_range = settings.chart_range = value;
updateToolBar();
updateState();
}
void ChartsWidget::updateToolBar() {
- int min_range = std::min(settings.max_chart_x_range, (int)can->totalSeconds());
- bool displaying_all = max_chart_range != min_range;
- show_all_values_btn->setText(tr("%1 minutes").arg(max_chart_range / 60));
- show_all_values_btn->setToolTip(tr("Click to display %1 data").arg(displaying_all ? tr("%1 minutes").arg(min_range / 60) : tr("ALL cached")));
- show_all_values_btn->setVisible(!is_zoomed);
+ title_label->setText(tr("Charts: %1").arg(charts.size()));
+ columns_action->setText(tr("Column: %1").arg(column_count));
+ range_lb->setText(QString("Range: %1:%2 ").arg(max_chart_range / 60, 2, 10, QLatin1Char('0')).arg(max_chart_range % 60, 2, 10, QLatin1Char('0')));
+ range_lb_action->setVisible(!is_zoomed);
+ range_slider_action->setVisible(!is_zoomed);
+ reset_zoom_action->setVisible(is_zoomed);
+ reset_zoom_action->setText(is_zoomed ? tr("Zoomin: %1-%2").arg(zoomed_range.first, 0, 'f', 1).arg(zoomed_range.second, 0, 'f', 1) : "");
remove_all_btn->setEnabled(!charts.isEmpty());
- reset_zoom_btn->setEnabled(is_zoomed);
- range_label->setText(is_zoomed ? tr("%1 - %2").arg(zoomed_range.first, 0, 'f', 2).arg(zoomed_range.second, 0, 'f', 2) : "");
- title_label->setText(charts.size() > 0 ? tr("Charts (%1)").arg(charts.size()) : tr("Charts"));
- dock_btn->setText(docking ? "⬈" : "⬋");
+ dock_btn->setIcon(utils::icon(docking ? "arrow-up-right-square" : "arrow-down-left-square"));
dock_btn->setToolTip(docking ? tr("Undock charts") : tr("Dock charts"));
}
-ChartView *ChartsWidget::findChart(const QString &id, const Signal *sig) {
+void ChartsWidget::settingChanged() {
+ range_slider->setRange(1, settings.max_cached_minutes * 60);
+ for (auto c : charts) {
+ c->setFixedHeight(settings.chart_height);
+ c->setSeriesType((SeriesType)settings.chart_series_type);
+ }
+}
+
+ChartView *ChartsWidget::findChart(const MessageId &id, const Signal *sig) {
for (auto c : charts)
if (c->hasSeries(id, sig)) return c;
return nullptr;
}
-void ChartsWidget::showChart(const QString &id, const Signal *sig, bool show, bool merge) {
- setUpdatesEnabled(false);
- if (show) {
- ChartView *chart = merge && charts.size() > 0 ? charts.back() : nullptr;
- if (!chart) {
- chart = new ChartView(this);
- chart->chart()->setTheme(use_dark_theme ? QChart::QChart::ChartThemeDark : QChart::ChartThemeLight);
- chart->setEventsRange(display_range);
- auto range = is_zoomed ? zoomed_range : display_range;
- chart->setDisplayRange(range.first, range.second);
- QObject::connect(chart, &ChartView::remove, [=]() { removeChart(chart); });
- QObject::connect(chart, &ChartView::zoomIn, this, &ChartsWidget::zoomIn);
- QObject::connect(chart, &ChartView::zoomReset, this, &ChartsWidget::zoomReset);
- QObject::connect(chart, &ChartView::seriesRemoved, this, &ChartsWidget::seriesChanged);
- QObject::connect(chart, &ChartView::seriesAdded, this, &ChartsWidget::seriesChanged);
- charts_layout->insertWidget(0, chart);
- charts.push_back(chart);
- }
+ChartView *ChartsWidget::createChart() {
+ auto chart = new ChartView(this);
+ chart->setFixedHeight(settings.chart_height);
+ chart->setMinimumWidth(CHART_MIN_WIDTH);
+ chart->setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::Fixed);
+ chart->chart()->setTheme(use_dark_theme ? QChart::QChart::ChartThemeDark : QChart::ChartThemeLight);
+ QObject::connect(chart, &ChartView::remove, [=]() { removeChart(chart); });
+ QObject::connect(chart, &ChartView::zoomIn, this, &ChartsWidget::zoomIn);
+ QObject::connect(chart, &ChartView::zoomReset, this, &ChartsWidget::zoomReset);
+ QObject::connect(chart, &ChartView::seriesRemoved, this, &ChartsWidget::seriesChanged);
+ QObject::connect(chart, &ChartView::seriesAdded, this, &ChartsWidget::seriesChanged);
+ QObject::connect(chart, &ChartView::axisYLabelWidthChanged, this, &ChartsWidget::alignCharts);
+ charts.push_back(chart);
+ updateLayout();
+ return chart;
+}
+
+void ChartsWidget::showChart(const MessageId &id, const Signal *sig, bool show, bool merge) {
+ ChartView *chart = findChart(id, sig);
+ if (show && !chart) {
+ chart = merge && charts.size() > 0 ? charts.back() : createChart();
chart->addSeries(id, sig);
- } else if (ChartView *chart = findChart(id, sig)) {
- chart->removeSeries(id, sig);
+ updateState();
+ } else if (!show && chart) {
+ chart->removeIf([&](auto &s) { return s.msg_id == id && s.sig == sig; });
}
updateToolBar();
- setUpdatesEnabled(true);
+}
+
+void ChartsWidget::setColumnCount(int n) {
+ n = std::clamp(n, 1, MAX_COLUMN_COUNT);
+ if (column_count != n) {
+ column_count = settings.chart_column_count = n;
+ updateToolBar();
+ updateLayout();
+ }
+}
+
+void ChartsWidget::updateLayout() {
+ int n = MAX_COLUMN_COUNT;
+ for (; n > 1; --n) {
+ if ((n * CHART_MIN_WIDTH + (n - 1) * charts_layout->spacing()) < charts_layout->geometry().width()) break;
+ }
+
+ bool show_column_cb = n > 1;
+ columns_action->setVisible(show_column_cb);
+
+ n = std::min(column_count, n);
+ if (charts.size() != charts_layout->count() || n != current_column_count) {
+ current_column_count = n;
+ charts_layout->parentWidget()->setUpdatesEnabled(false);
+ for (int i = 0; i < charts.size(); ++i) {
+ charts_layout->addWidget(charts[charts.size() - i - 1], i / n, i % n);
+ }
+ QTimer::singleShot(0, [this]() { charts_layout->parentWidget()->setUpdatesEnabled(true); });
+ }
+}
+
+void ChartsWidget::resizeEvent(QResizeEvent *event) {
+ QWidget::resizeEvent(event);
+ updateLayout();
+}
+
+void ChartsWidget::newChart() {
+ SeriesSelector dlg(tr("New Chart"), this);
+ if (dlg.exec() == QDialog::Accepted) {
+ auto items = dlg.seletedItems();
+ if (!items.isEmpty()) {
+ auto c = createChart();
+ for (auto it : items) {
+ c->addSeries(it->msg_id, it->sig);
+ }
+ }
+ }
}
void ChartsWidget::removeChart(ChartView *chart) {
charts.removeOne(chart);
chart->deleteLater();
updateToolBar();
+ alignCharts();
+ updateLayout();
emit seriesChanged();
}
@@ -183,6 +289,17 @@ void ChartsWidget::removeAll() {
emit seriesChanged();
}
+void ChartsWidget::alignCharts() {
+ int plot_left = 0;
+ for (auto c : charts) {
+ plot_left = std::max(plot_left, c->y_label_width);
+ }
+ plot_left = std::max((plot_left / 10) * 10 + 10, 50);
+ for (auto c : charts) {
+ c->updatePlotArea(plot_left);
+ }
+}
+
bool ChartsWidget::eventFilter(QObject *obj, QEvent *event) {
if (obj != this && event->type() == QEvent::Close) {
emit dock_btn->triggered();
@@ -194,84 +311,106 @@ bool ChartsWidget::eventFilter(QObject *obj, QEvent *event) {
// ChartView
ChartView::ChartView(QWidget *parent) : QChartView(nullptr, parent) {
+ series_type = (SeriesType)settings.chart_series_type;
QChart *chart = new QChart();
- chart->setBackgroundRoundness(0);
+ chart->setBackgroundVisible(false);
axis_x = new QValueAxis(this);
axis_y = new QValueAxis(this);
chart->addAxis(axis_x, Qt::AlignBottom);
chart->addAxis(axis_y, Qt::AlignLeft);
+ chart->legend()->layout()->setContentsMargins(16, 0, 40, 0);
chart->legend()->setShowToolTips(true);
- chart->layout()->setContentsMargins(0, 0, 0, 0);
- chart->setMargins(QMargins(20, 11, 11, 11));
-
- QToolButton *remove_btn = new QToolButton();
- remove_btn->setText("X");
- remove_btn->setAutoRaise(true);
- remove_btn->setToolTip(tr("Remove Chart"));
- close_btn_proxy = new QGraphicsProxyWidget(chart);
- close_btn_proxy->setWidget(remove_btn);
- close_btn_proxy->setZValue(chart->zValue() + 11);
+ chart->setMargins({0, 0, 0, 0});
- QToolButton *manage_btn = new QToolButton();
- manage_btn->setText("🔧");
- manage_btn->setAutoRaise(true);
- manage_btn->setToolTip(tr("Manage series"));
- manage_btn_proxy = new QGraphicsProxyWidget(chart);
- manage_btn_proxy->setWidget(manage_btn);
- manage_btn_proxy->setZValue(chart->zValue() + 11);
+ background = new QGraphicsRectItem(chart);
+ background->setBrush(QApplication::palette().color(QPalette::Base));
+ background->setPen(Qt::NoPen);
+ background->setZValue(chart->zValue() - 1);
setChart(chart);
+
+ createToolButtons();
setRenderHint(QPainter::Antialiasing);
- setRubberBand(QChartView::HorizontalRubberBand);
- updateFromSettings();
+ // TODO: enable zoomIn/seekTo in live streaming mode.
+ setRubberBand(can->liveStreaming() ? QChartView::NoRubberBand : QChartView::HorizontalRubberBand);
QObject::connect(dbc(), &DBCManager::signalRemoved, this, &ChartView::signalRemoved);
QObject::connect(dbc(), &DBCManager::signalUpdated, this, &ChartView::signalUpdated);
QObject::connect(dbc(), &DBCManager::msgRemoved, this, &ChartView::msgRemoved);
QObject::connect(dbc(), &DBCManager::msgUpdated, this, &ChartView::msgUpdated);
- QObject::connect(&settings, &Settings::changed, this, &ChartView::updateFromSettings);
+}
+
+void ChartView::createToolButtons() {
+ move_icon = new QGraphicsPixmapItem(utils::icon("grip-horizontal"), chart());
+ move_icon->setToolTip(tr("Drag and drop to combine charts"));
+
+ QToolButton *remove_btn = toolButton("x", tr("Remove Chart"));
+ close_btn_proxy = new QGraphicsProxyWidget(chart());
+ close_btn_proxy->setWidget(remove_btn);
+ close_btn_proxy->setZValue(chart()->zValue() + 11);
+
+ // series types
+ QMenu *menu = new QMenu(this);
+ auto change_series_group = new QActionGroup(menu);
+ change_series_group->setExclusive(true);
+ QStringList types{tr("line"), tr("Step Line"), tr("Scatter")};
+ for (int i = 0; i < types.size(); ++i) {
+ QAction *act = new QAction(types[i], change_series_group);
+ act->setData(i);
+ act->setCheckable(true);
+ act->setChecked(i == (int)series_type);
+ menu->addAction(act);
+ }
+ menu->addSeparator();
+ menu->addAction(tr("Manage series"), this, &ChartView::manageSeries);
+
+ QToolButton *manage_btn = toolButton("list", "");
+ manage_btn->setMenu(menu);
+ manage_btn->setPopupMode(QToolButton::InstantPopup);
+ manage_btn_proxy = new QGraphicsProxyWidget(chart());
+ manage_btn_proxy->setWidget(manage_btn);
+ manage_btn_proxy->setZValue(chart()->zValue() + 11);
+
QObject::connect(remove_btn, &QToolButton::clicked, this, &ChartView::remove);
- QObject::connect(manage_btn, &QToolButton::clicked, this, &ChartView::manageSeries);
+ QObject::connect(change_series_group, &QActionGroup::triggered, [this](QAction *action) {
+ setSeriesType((SeriesType)action->data().toInt());
+ });
}
-void ChartView::addSeries(const QString &msg_id, const Signal *sig) {
- QLineSeries *series = new QLineSeries(this);
- series->setUseOpenGL(true);
- chart()->addSeries(series);
- series->attachAxis(axis_x);
- series->attachAxis(axis_y);
- auto [source, address] = DBCManager::parseId(msg_id);
- sigs.push_back({.msg_id = msg_id, .address = address, .source = source, .sig = sig, .series = series});
+void ChartView::addSeries(const MessageId &msg_id, const Signal *sig) {
+ if (hasSeries(msg_id, sig)) return;
+
+ QXYSeries *series = createSeries(series_type, getColor(sig));
+ sigs.push_back({.msg_id = msg_id, .sig = sig, .series = series});
updateTitle();
updateSeries(sig);
- updateAxisY();
+ updateSeriesPoints();
emit seriesAdded(msg_id, sig);
}
-void ChartView::removeSeries(const QString &msg_id, const Signal *sig) {
- auto it = std::find_if(sigs.begin(), sigs.end(), [&](auto &s) { return s.msg_id == msg_id && s.sig == sig; });
- if (it != sigs.end()) {
- it = removeSeries(it);
- }
-}
-
-bool ChartView::hasSeries(const QString &msg_id, const Signal *sig) const {
+bool ChartView::hasSeries(const MessageId &msg_id, const Signal *sig) const {
return std::any_of(sigs.begin(), sigs.end(), [&](auto &s) { return s.msg_id == msg_id && s.sig == sig; });
}
-QList::iterator ChartView::removeSeries(const QList::iterator &it) {
- chart()->removeSeries(it->series);
- it->series->deleteLater();
- QString msg_id = it->msg_id;
- const Signal *sig = it->sig;
- auto ret = sigs.erase(it);
- emit seriesRemoved(msg_id, sig);
- if (!sigs.isEmpty()) {
- updateAxisY();
- } else {
+void ChartView::removeIf(std::function predicate) {
+ int prev_size = sigs.size();
+ for (auto it = sigs.begin(); it != sigs.end(); /**/) {
+ if (predicate(*it)) {
+ chart()->removeSeries(it->series);
+ it->series->deleteLater();
+ auto msg_id = it->msg_id;
+ auto sig = it->sig;
+ it = sigs.erase(it);
+ emit seriesRemoved(msg_id, sig);
+ } else {
+ ++it;
+ }
+ }
+ if (sigs.empty()) {
emit remove();
+ } else if (sigs.size() != prev_size) {
+ updateAxisY();
}
- return ret;
}
void ChartView::signalUpdated(const Signal *sig) {
@@ -279,176 +418,209 @@ void ChartView::signalUpdated(const Signal *sig) {
updateTitle();
// TODO: don't update series if only name changed.
updateSeries(sig);
- updateAxisY();
- }
-}
-
-void ChartView::signalRemoved(const Signal *sig) {
- for (auto it = sigs.begin(); it != sigs.end(); /**/) {
- it = (it->sig == sig) ? removeSeries(it) : ++it;
}
}
void ChartView::msgUpdated(uint32_t address) {
- if (std::any_of(sigs.begin(), sigs.end(), [=](auto &s) { return s.address == address; }))
+ if (std::any_of(sigs.begin(), sigs.end(), [=](auto &s) { return s.msg_id.address == address; }))
updateTitle();
}
-void ChartView::msgRemoved(uint32_t address) {
- for (auto it = sigs.begin(); it != sigs.end(); /**/) {
- it = (it->address == address) ? removeSeries(it) : ++it;
- }
-}
-
void ChartView::manageSeries() {
- SeriesSelector dlg(this);
+ SeriesSelector dlg(tr("Mange Chart"), this);
for (auto &s : sigs) {
- dlg.addSeries(s.msg_id, msgName(s.msg_id), QString::fromStdString(s.sig->name));
+ dlg.addSelected(s.msg_id, s.sig);
}
-
- int ret = dlg.exec();
- if (ret == QDialog::Accepted) {
- QList series_list = dlg.series();
- if (series_list.isEmpty()) {
- emit remove();
- } else {
- for (auto &s : series_list) {
- if (auto m = dbc()->msg(s[0])) {
- auto it = m->sigs.find(s[2]);
- if (it != m->sigs.end() && !hasSeries(s[0], &(it->second))) {
- addSeries(s[0], &(it->second));
- }
- }
- }
- for (auto it = sigs.begin(); it != sigs.end(); /**/) {
- bool exists = std::any_of(series_list.cbegin(), series_list.cend(), [&](auto &s) {
- return s[0] == it->msg_id && s[2] == it->sig->name.c_str();
- });
- it = exists ? ++it : removeSeries(it);
- }
+ if (dlg.exec() == QDialog::Accepted) {
+ auto items = dlg.seletedItems();
+ for (auto s : items) {
+ addSeries(s->msg_id, s->sig);
}
+ removeIf([&](auto &s) {
+ return std::none_of(items.cbegin(), items.cend(), [&](auto &it) { return s.msg_id == it->msg_id && s.sig == it->sig; });
+ });
}
}
void ChartView::resizeEvent(QResizeEvent *event) {
+ updatePlotArea(align_to);
+ int top_margin = style()->pixelMetric(QStyle::PM_LayoutTopMargin);
+ int spacing = style()->pixelMetric(QStyle::PM_LayoutHorizontalSpacing);
+ int x = event->size().width() - close_btn_proxy->size().width() - style()->pixelMetric(QStyle::PM_LayoutRightMargin);
+ close_btn_proxy->setPos(x, top_margin);
+ manage_btn_proxy->setPos(x - manage_btn_proxy->size().width() - spacing, top_margin);
+ move_icon->setPos(style()->pixelMetric(QStyle::PM_LayoutLeftMargin), top_margin);
QChartView::resizeEvent(event);
- int x = event->size().width() - close_btn_proxy->size().width() - 11;
- close_btn_proxy->setPos(x, 8);
- manage_btn_proxy->setPos(x - manage_btn_proxy->size().width() - 5, 8);
}
-void ChartView::updateTitle() {
- for (auto &s : sigs) {
- s.series->setName(QString("%1 %2 %3").arg(s.sig->name.c_str()).arg(msgName(s.msg_id)).arg(s.msg_id));
+void ChartView::updatePlotArea(int left) {
+ QRect r = rect();
+ if (align_to != left || r != background->rect()) {
+ align_to = left;
+ background->setRect(r);
+ chart()->legend()->setGeometry(QRect(r.left(), r.top(), r.width(), 45));
+ chart()->setPlotArea(QRect(align_to, r.top() + 45, r.width() - align_to - 36, r.height() - 80));
+ chart()->layout()->invalidate();
}
}
-void ChartView::updateFromSettings() {
- setFixedHeight(settings.chart_height);
-}
-
-void ChartView::setEventsRange(const std::pair &range) {
- if (range != events_range) {
- events_range = range;
- updateSeries();
+void ChartView::updateTitle() {
+ for (QLegendMarker *marker : chart()->legend()->markers()) {
+ QObject::connect(marker, &QLegendMarker::clicked, this, &ChartView::handleMarkerClicked, Qt::UniqueConnection);
+ }
+ for (auto &s : sigs) {
+ auto decoration = s.series->isVisible() ? "none" : "line-through";
+ s.series->setName(QString("%2 %3 %4").arg(decoration, s.sig->name, msgName(s.msg_id), s.msg_id.toString()));
}
}
-void ChartView::setDisplayRange(double min, double max) {
+void ChartView::updatePlot(double cur, double min, double max) {
+ cur_sec = cur;
if (min != axis_x->min() || max != axis_x->max()) {
axis_x->setRange(min, max);
updateAxisY();
+ updateSeriesPoints();
}
+
+ scene()->invalidate({}, QGraphicsScene::ForegroundLayer);
}
-void ChartView::adjustChartMargins() {
- // TODO: Remove hardcoded aligned_pos
- const int aligned_pos = 60;
- if ((int)chart()->plotArea().left() != aligned_pos) {
- const float left_margin = chart()->margins().left() + aligned_pos - chart()->plotArea().left();
- chart()->setMargins(QMargins(left_margin, 11, 11, 11));
- scene()->invalidate({}, QGraphicsScene::ForegroundLayer);
+void ChartView::updateSeriesPoints() {
+ // Show points when zoomed in enough
+ for (auto &s : sigs) {
+ auto begin = std::lower_bound(s.vals.begin(), s.vals.end(), axis_x->min(), [](auto &p, double x) { return p.x() < x; });
+ auto end = std::lower_bound(begin, s.vals.end(), axis_x->max(), [](auto &p, double x) { return p.x() < x; });
+
+ int num_points = std::max(end - begin, 1);
+ int pixels_per_point = width() / num_points;
+
+ if (series_type == SeriesType::Scatter) {
+ ((QScatterSeries *)s.series)->setMarkerSize(std::clamp(pixels_per_point / 3, 2, 8));
+ } else {
+ s.series->setPointsVisible(pixels_per_point > 20);
+ }
}
}
-void ChartView::updateSeries(const Signal *sig) {
- auto events = can->events();
- if (!events || sigs.isEmpty()) return;
-
+void ChartView::updateSeries(const Signal *sig, const std::vector *events, bool clear) {
+ events = events ? events : can->events();
for (auto &s : sigs) {
if (!sig || s.sig == sig) {
- s.vals.clear();
- s.vals.reserve((events_range.second - events_range.first) * 1000); // [n]seconds * 1000hz
- s.min_y = std::numeric_limits::max();
- s.max_y = std::numeric_limits::lowest();
-
- double route_start_time = can->routeStartTime();
- Event begin_event(cereal::Event::Which::INIT_DATA, (route_start_time + events_range.first) * 1e9);
- auto begin = std::lower_bound(events->begin(), events->end(), &begin_event, Event::lessThan());
- double end_ns = (route_start_time + events_range.second) * 1e9;
-
- for (auto it = begin; it != events->end() && (*it)->mono_time <= end_ns; ++it) {
- if ((*it)->which == cereal::Event::Which::CAN) {
- for (const auto &c : (*it)->event.getCan()) {
- if (s.source == c.getSrc() && s.address == c.getAddress()) {
- auto dat = c.getDat();
- double value = get_raw_value((uint8_t *)dat.begin(), dat.size(), *s.sig);
- double ts = ((*it)->mono_time / (double)1e9) - route_start_time; // seconds
- s.vals.push_back({ts, value});
-
- if (value < s.min_y) s.min_y = value;
- if (value > s.max_y) s.max_y = value;
+ if (clear) {
+ s.vals.clear();
+ s.step_vals.clear();
+ s.vals.reserve(settings.max_cached_minutes * 60 * 100); // [n]seconds * 100hz
+ s.step_vals.reserve(settings.max_cached_minutes * 60 * 100 * 2);
+ s.last_value_mono_time = 0;
+ }
+ s.series->setColor(getColor(s.sig));
+
+ struct Chunk {
+ std::vector::const_iterator first, second;
+ QVector vals;
+ QVector step_vals;
+ };
+ // split into one minitue chunks
+ QVector chunks;
+ Event begin_event(cereal::Event::Which::INIT_DATA, s.last_value_mono_time);
+ auto begin = std::upper_bound(events->begin(), events->end(), &begin_event, Event::lessThan());
+ for (auto it = begin, second = begin; it != events->end(); it = second) {
+ second = std::lower_bound(it, events->end(), (*it)->mono_time + 1e9 * 60, [](auto &e, uint64_t ts) { return e->mono_time < ts; });
+ chunks.push_back({it, second});
+ }
+
+ QtConcurrent::blockingMap(chunks, [&](Chunk &chunk) {
+ chunk.vals.reserve(60 * 100); // 100 hz
+ chunk.step_vals.reserve(60 * 100 * 2); // 100 hz
+ double route_start_time = can->routeStartTime();
+ for (auto it = chunk.first; it != chunk.second; ++it) {
+ if ((*it)->which == cereal::Event::Which::CAN) {
+ for (const auto &c : (*it)->event.getCan()) {
+ if (s.msg_id.address == c.getAddress() && s.msg_id.source == c.getSrc()) {
+ auto dat = c.getDat();
+ double value = get_raw_value((uint8_t *)dat.begin(), dat.size(), *s.sig);
+ double ts = ((*it)->mono_time / (double)1e9) - route_start_time; // seconds
+ chunk.vals.push_back({ts, value});
+ if (!chunk.step_vals.empty()) {
+ chunk.step_vals.push_back({ts, chunk.step_vals.back().y()});
+ }
+ chunk.step_vals.push_back({ts,value});
+ }
}
}
}
+ });
+ for (auto &c : chunks) {
+ s.vals.append(c.vals);
+ if (!c.step_vals.empty()) {
+ if (!s.step_vals.empty()) {
+ s.step_vals.append({c.step_vals.first().x(), s.step_vals.back().y()});
+ }
+ s.step_vals.append(c.step_vals);
+ }
+ }
+ if (events->size()) {
+ s.last_value_mono_time = events->back()->mono_time;
}
- s.series->replace(s.vals);
+ s.series->replace(series_type == SeriesType::StepLine ? s.step_vals : s.vals);
}
}
+ updateAxisY();
}
// auto zoom on yaxis
void ChartView::updateAxisY() {
if (sigs.isEmpty()) return;
- double min_y = std::numeric_limits::max();
- double max_y = std::numeric_limits::lowest();
- if (events_range == std::pair{axis_x->min(), axis_x->max()}) {
- for (auto &s : sigs) {
- if (s.min_y < min_y) min_y = s.min_y;
- if (s.max_y > max_y) max_y = s.max_y;
+ double min = std::numeric_limits::max();
+ double max = std::numeric_limits