Merge remote-tracking branch 'upstream/master' into big-test-models

pull/29291/head
Shane Smiskol 3 years ago
commit 10778ebc60
  1. 2
      .github/workflows/selfdrive_tests.yaml
  2. 2
      .github/workflows/tools_tests.yaml
  3. 44
      Jenkinsfile
  4. 37
      RELEASES.md
  5. 11
      SConstruct
  6. 2
      body
  7. 2
      cereal
  8. 3
      common/params.cc
  9. 9
      common/util.cc
  10. 1
      common/util.h
  11. 2
      common/version.h
  12. 122
      docs/CARS.md
  13. 2
      launch_env.sh
  14. 2
      panda
  15. 63
      poetry.lock
  16. 1
      pyproject.toml
  17. 4
      release/files_common
  18. BIN
      selfdrive/assets/fonts/JetBrainsMono-Medium.ttf
  19. 4
      selfdrive/assets/img_couch.svg
  20. 10
      selfdrive/assets/img_experimental.svg
  21. 4
      selfdrive/assets/img_experimental_grey.svg
  22. 4
      selfdrive/assets/img_experimental_white.svg
  23. 4
      selfdrive/boardd/SConscript
  24. 18
      selfdrive/boardd/boardd.cc
  25. 289
      selfdrive/boardd/panda.cc
  26. 45
      selfdrive/boardd/panda.h
  27. 232
      selfdrive/boardd/panda_comms.cc
  28. 80
      selfdrive/boardd/panda_comms.h
  29. 287
      selfdrive/boardd/spi.cc
  30. 13
      selfdrive/car/body/values.py
  31. 1
      selfdrive/car/docs.py
  32. 10
      selfdrive/car/docs_definitions.py
  33. 16
      selfdrive/car/gm/carstate.py
  34. 17
      selfdrive/car/gm/interface.py
  35. 23
      selfdrive/car/gm/values.py
  36. 14
      selfdrive/car/honda/carcontroller.py
  37. 52
      selfdrive/car/honda/values.py
  38. 7
      selfdrive/car/hyundai/carcontroller.py
  39. 48
      selfdrive/car/hyundai/carstate.py
  40. 3
      selfdrive/car/hyundai/hyundaican.py
  41. 27
      selfdrive/car/hyundai/interface.py
  42. 78
      selfdrive/car/hyundai/values.py
  43. 6
      selfdrive/car/interfaces.py
  44. 3
      selfdrive/car/subaru/values.py
  45. 4
      selfdrive/car/tests/routes.py
  46. 21
      selfdrive/car/tests/test_car_interfaces.py
  47. 4
      selfdrive/car/tests/test_models.py
  48. 6
      selfdrive/car/torque_data/override.yaml
  49. 2
      selfdrive/car/torque_data/params.yaml
  50. 2
      selfdrive/car/torque_data/substitute.yaml
  51. 3
      selfdrive/car/toyota/carstate.py
  52. 15
      selfdrive/car/toyota/interface.py
  53. 9
      selfdrive/car/toyota/values.py
  54. 1
      selfdrive/car/volkswagen/carstate.py
  55. 10
      selfdrive/car/volkswagen/interface.py
  56. 94
      selfdrive/car/volkswagen/values.py
  57. 62
      selfdrive/controls/controlsd.py
  58. 2
      selfdrive/controls/lib/desire_helper.py
  59. 143
      selfdrive/controls/lib/drive_helpers.py
  60. 1
      selfdrive/controls/lib/events.py
  61. 8
      selfdrive/controls/lib/latcontrol_torque.py
  62. 1
      selfdrive/controls/lib/longcontrol.py
  63. 21
      selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py
  64. 28
      selfdrive/controls/lib/longitudinal_planner.py
  65. 121
      selfdrive/controls/tests/test_cruise_speed.py
  66. 2
      selfdrive/controls/tests/test_following_distance.py
  67. 1
      selfdrive/locationd/laikad.py
  68. 12
      selfdrive/locationd/liblocationd.cc
  69. 93
      selfdrive/locationd/locationd.cc
  70. 12
      selfdrive/locationd/locationd.h
  71. 2
      selfdrive/locationd/paramsd.py
  72. 4
      selfdrive/locationd/torqued.py
  73. 1
      selfdrive/loggerd/loggerd.h
  74. 1
      selfdrive/loggerd/tests/test_logger.cc
  75. 6
      selfdrive/manager/test/test_manager.py
  76. 11
      selfdrive/modeld/models/driving.cc
  77. 9
      selfdrive/modeld/models/driving.h
  78. 4
      selfdrive/modeld/models/supercombo.onnx
  79. 6
      selfdrive/monitoring/driver_monitor.py
  80. 133
      selfdrive/sensord/sensors/lsm6ds3_accel.cc
  81. 18
      selfdrive/sensord/sensors/lsm6ds3_accel.h
  82. 115
      selfdrive/sensord/sensors/lsm6ds3_gyro.cc
  83. 12
      selfdrive/sensord/sensors/lsm6ds3_gyro.h
  84. 5
      selfdrive/sensord/tests/test_sensord.py
  85. 12
      selfdrive/test/longitudinal_maneuvers/maneuver.py
  86. 19
      selfdrive/test/longitudinal_maneuvers/plant.py
  87. 13
      selfdrive/test/longitudinal_maneuvers/test_longitudinal.py
  88. 2
      selfdrive/test/process_replay/model_replay_ref_commit
  89. 2
      selfdrive/test/process_replay/ref_commit
  90. 4
      selfdrive/test/process_replay/test_processes.py
  91. 2
      selfdrive/ui/SConscript
  92. 19
      selfdrive/ui/qt/home.cc
  93. 5
      selfdrive/ui/qt/home.h
  94. 1
      selfdrive/ui/qt/offroad/driverview.cc
  95. 76
      selfdrive/ui/qt/offroad/experimental_mode.cc
  96. 31
      selfdrive/ui/qt/offroad/experimental_mode.h
  97. 2
      selfdrive/ui/qt/offroad/networking.cc
  98. 86
      selfdrive/ui/qt/offroad/settings.cc
  99. 5
      selfdrive/ui/qt/offroad/settings.h
  100. 2
      selfdrive/ui/qt/offroad/software_settings.cc
  101. Some files were not shown because too many files have changed in this diff Show More

@ -7,7 +7,7 @@ on:
pull_request:
concurrency:
group: ${{ github.workflow }}-${{ github.ref != 'refs/heads/master' && github.ref || github.run_id }}-${{ github.event_name }}
group: ${{ github.event_name == 'push' && github.ref == 'refs/heads/master' && github.run_id || github.head_ref || github.ref }}-${{ github.workflow }}-${{ github.event_name }}
cancel-in-progress: true
env:

@ -7,7 +7,7 @@ on:
pull_request:
concurrency:
group: ${{ github.workflow }}-${{ github.ref != 'refs/heads/master' && github.ref || github.run_id }}-${{ github.event_name }}
group: ${{ github.event_name == 'push' && github.ref == 'refs/heads/master' && github.run_id || github.head_ref || github.ref }}-${{ github.workflow }}-${{ github.event_name }}
cancel-in-progress: true
env:

44
Jenkinsfile vendored

@ -59,7 +59,7 @@ pipeline {
branch 'devel-staging'
}
steps {
phone_steps("tici", [
phone_steps("tici-needs-can", [
["build release3-staging & dashcam3-staging", "PUSH=1 $SOURCE_DIR/release/build_release.sh"],
])
}
@ -111,7 +111,7 @@ pipeline {
R3_PUSH = "${env.BRANCH_NAME == 'master' ? '1' : ' '}"
}
steps {
phone_steps("tici", [
phone_steps("tici-needs-can", [
["build master-ci", "cd $SOURCE_DIR/release && TARGET_DIR=$TEST_DIR EXTRA_FILES='tools/' ./build_devel.sh"],
["build openpilot", "cd selfdrive/manager && ./build.py"],
["check dirty", "release/check-dirty.sh"],
@ -122,25 +122,44 @@ pipeline {
}
}
stage('loopback-tests') {
agent { docker { image 'ghcr.io/commaai/alpine-ssh'; args '--user=root' } }
steps {
phone_steps("tici-loopback", [
["build openpilot", "cd selfdrive/manager && ./build.py"],
["test boardd loopback", "python selfdrive/boardd/tests/test_boardd_loopback.py"],
])
}
}
stage('HW + Unit Tests') {
agent { docker { image 'ghcr.io/commaai/alpine-ssh'; args '--user=root' } }
steps {
phone_steps("tici2", [
phone_steps("tici-common", [
["build", "cd selfdrive/manager && ./build.py"],
["test power draw", "python system/hardware/tici/test_power_draw.py"],
["test boardd loopback", "python selfdrive/boardd/tests/test_boardd_loopback.py"],
["test loggerd", "python selfdrive/loggerd/tests/test_loggerd.py"],
["test encoder", "LD_LIBRARY_PATH=/usr/local/lib python selfdrive/loggerd/tests/test_encoder.py"],
["test sensord", "python selfdrive/sensord/tests/test_sensord.py"],
["test pigeond", "python selfdrive/sensord/tests/test_pigeond.py"],
])
}
}
stage('camerad') {
stage('camerad-ar') {
agent { docker { image 'ghcr.io/commaai/alpine-ssh'; args '--user=root' } }
steps {
phone_steps("tici-ar0321", [
["build", "cd selfdrive/manager && ./build.py"],
["test camerad", "python system/camerad/test/test_camerad.py"],
["test exposure", "python system/camerad/test/test_exposure.py"],
])
}
}
stage('camerad-ox') {
agent { docker { image 'ghcr.io/commaai/alpine-ssh'; args '--user=root' } }
steps {
phone_steps("tici-party", [
phone_steps("tici-ox03c10", [
["build", "cd selfdrive/manager && ./build.py"],
["test camerad", "python system/camerad/test/test_camerad.py"],
["test exposure", "python system/camerad/test/test_exposure.py"],
@ -148,27 +167,32 @@ pipeline {
}
}
stage('sensord (LSM-C)') {
stage('sensord') {
agent { docker { image 'ghcr.io/commaai/alpine-ssh'; args '--user=root' } }
steps {
phone_steps("tici-lsmc", [
["build", "cd selfdrive/manager && ./build.py"],
["test sensord", "cd selfdrive/sensord/tests && python -m unittest test_sensord.py"],
])
phone_steps("tici-bmx-lsm", [
["build", "cd selfdrive/manager && ./build.py"],
["test sensord", "cd selfdrive/sensord/tests && python -m unittest test_sensord.py"],
])
}
}
stage('replay') {
agent { docker { image 'ghcr.io/commaai/alpine-ssh'; args '--user=root' } }
steps {
phone_steps("tici3", [
phone_steps("tici-common", [
["build", "cd selfdrive/manager && ./build.py"],
["model replay", "cd selfdrive/test/process_replay && ./model_replay.py"],
])
}
}
}
}
}
}
}

@ -1,21 +1,40 @@
Version 0.8.17 (2022-XX-XX)
Version 0.9.1 (2022-12-XX)
========================
* New driving model
* Internal feature space accuracy increased tenfold during training, this makes the model dramatically more accurate.
* New driver monitoring model
* New end-to-end distracted trigger
* Self-tuning torque lateral controller parameters
* Parameters learned live for each car
Version 0.9.0 (2022-11-21)
========================
* New driving model
* Internal feature space information content increased tenfold during training to ~700 bits, which makes the model dramatically more accurate
* Less reliance on previous frames makes model more reactive and snappy
* Trained in new reprojective simulator
* Trained in 36 hours from scratch, compared to one week for previous releases
* Training now simulates both lateral and longitudinal behavior, which allows openpilot to slow down for turns, stop at traffic lights, and more in experimental mode
* Experimental driving mode
* End-to-end longitudinal control
* Stops for traffic lights and stop signs
* Slows down for turns
* openpilot defaults to chill mode, enable experimental mode in settings
* Driver monitoring updates
* New bigger model with added end-to-end distracted trigger
* Reduced false positives during driver calibration
* Self-tuning torque controller: learns parameters live for each car
* Torque controller used on all Toyota, Lexus, Hyundai, Kia, and Genesis models
* UI updates
* Multi-language in navigation
* Matched speeds shown on car's dash
* Multi-language in navigation
* Improved update experience
* Border turns grey while overriding steering
* Added button to bookmark events while driving; view them later in comma connect
* AGNOS 6
* Bookmark events while driving; view them in comma connect
* New onroad visualization for experimental mode
* tools: new and improved cabana thanks to deanlee!
* Experimental longitudinal support for Volkswagen, CAN-FD Hyundai, and new GM models
* Genesis GV70 2022-23 support thanks to zunichky and sunnyhaibin!
* Hyundai Santa Cruz 2021-22 support thanks to sunnyhaibin!
* Kia Sportage 2023 support thanks to sunnyhaibin!
* Kia Sportage Hybrid 2023 support thanks to sunnyhaibin!
* Kia Stinger 2022 support thanks to sunnyhaibin!
Version 0.8.16 (2022-08-26)
========================

@ -298,12 +298,15 @@ if arch == "Darwin":
qt_env["FRAMEWORKS"] += [f"Qt{m}" for m in qt_modules] + ["OpenGL"]
qt_env.AppendENVPath('PATH', os.path.join(qt_env['QTDIR'], "bin"))
else:
qt_env['QTDIR'] = "/usr"
qt_install_prefix = subprocess.check_output(['qmake', '-query', 'QT_INSTALL_PREFIX'], encoding='utf8').strip()
qt_install_headers = subprocess.check_output(['qmake', '-query', 'QT_INSTALL_HEADERS'], encoding='utf8').strip()
qt_env['QTDIR'] = qt_install_prefix
qt_dirs = [
f"/usr/include/{real_arch}-linux-gnu/qt5",
f"/usr/include/{real_arch}-linux-gnu/qt5/QtGui/5.12.8/QtGui",
f"{qt_install_headers}",
f"{qt_install_headers}/QtGui/5.12.8/QtGui",
]
qt_dirs += [f"/usr/include/{real_arch}-linux-gnu/qt5/Qt{m}" for m in qt_modules]
qt_dirs += [f"{qt_install_headers}/Qt{m}" for m in qt_modules]
qt_libs = [f"Qt5{m}" for m in qt_modules]
if arch == "larch64":

@ -1 +1 @@
Subproject commit 04aeb30ce0bb14759989cd374158233877e1e151
Subproject commit dc780f858c1ef641471d09b72569e199e3e10acb

@ -1 +1 @@
Subproject commit 1d25fc3f202d5ddeee97848480323e9b14f9bdfa
Subproject commit 3bae09cf6527674d7eda3a9956242aad94a8f3d2

@ -102,7 +102,8 @@ std::unordered_map<std::string, uint32_t> keys = {
{"DashcamOverride", PERSISTENT},
{"DisableLogging", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_ON},
{"DisablePowerDown", PERSISTENT},
{"EndToEndLong", PERSISTENT},
{"ExperimentalMode", PERSISTENT},
{"ExperimentalModeConfirmed", PERSISTENT},
{"ExperimentalLongitudinalEnabled", PERSISTENT}, // WARNING: THIS MAY DISABLE AEB
{"DisableUpdates", PERSISTENT},
{"DisengageOnAccelerator", PERSISTENT},

@ -1,5 +1,6 @@
#include "common/util.h"
#include <sys/ioctl.h>
#include <sys/stat.h>
#include <dirent.h>
@ -149,6 +150,14 @@ int safe_fflush(FILE *stream) {
return ret;
}
int safe_ioctl(int fd, unsigned long request, void *argp) {
int ret;
do {
ret = ioctl(fd, request, argp);
} while ((ret == -1) && (errno == EINTR));
return ret;
}
std::string readlink(const std::string &path) {
char buff[4096];
ssize_t len = ::readlink(path.c_str(), buff, sizeof(buff)-1);

@ -86,6 +86,7 @@ int write_file(const char* path, const void* data, size_t size, int flags = O_WR
FILE* safe_fopen(const char* filename, const char* mode);
size_t safe_fwrite(const void * ptr, size_t size, size_t count, FILE * stream);
int safe_fflush(FILE *stream);
int safe_ioctl(int fd, unsigned long request, void *argp);
std::string readlink(const std::string& path);
bool file_exists(const std::string& fn);

@ -1 +1 @@
#define COMMA_VERSION "0.8.17"
#define COMMA_VERSION "0.9.1"

@ -4,19 +4,19 @@
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.
# 211 Supported Cars
# 215 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|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Nidec|
|Acura|RDX 2016-18|AcuraWatch Plus|openpilot|25 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Nidec|
|Acura|RDX 2019-22|All|openpilot available[<sup>1</sup>](#footnotes)|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch A|
|Audi|A3 2014-19|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW|
|Audi|A3 Sportback e-tron 2017-18|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW|
|Audi|Q2 2018|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW|
|Audi|Q3 2020-21|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW|
|Audi|RS3 2018|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW|
|Audi|S3 2015-17|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW|
|Audi|A3 2014-19|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,8</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Audi|A3 Sportback e-tron 2017-18|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,8</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Audi|Q2 2018|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,8</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Audi|Q3 2019-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,8</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Audi|RS3 2018|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,8</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Audi|S3 2015-17|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,8</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Cadillac|Escalade ESV 2016[<sup>3</sup>](#footnotes)|Adaptive Cruise Control (ACC) & LKAS|openpilot|0 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|OBD-II|
|Chevrolet|Bolt EUV 2022-23|Premier or Premier Redline Trim without Super Cruise Package|openpilot available[<sup>1</sup>](#footnotes)|3 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|GM|
|Chevrolet|Silverado 1500 2020-21|Safety Package II|openpilot available[<sup>1</sup>](#footnotes)|3 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|GM|
@ -31,6 +31,7 @@ A supported vehicle is one that just works when you install a comma three. All s
|Genesis|G70 2020|All|openpilot available[<sup>1</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai F|
|Genesis|G80 2017-19|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai H|
|Genesis|G90 2017-18|All|openpilot available[<sup>1</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C|
|Genesis|GV70 2022-23|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai L|
|GMC|Acadia 2018[<sup>3</sup>](#footnotes)|Adaptive Cruise Control (ACC)|openpilot|0 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|OBD-II|
|GMC|Sierra 1500 2020-21|Driver Alert Package II|openpilot available[<sup>1</sup>](#footnotes)|3 mph|6 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|GM|
|Honda|Accord 2018-22|All|openpilot available[<sup>1</sup>](#footnotes)|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Honda Bosch A|
@ -59,8 +60,8 @@ A supported vehicle is one that just works when you install a comma three. All s
|Hyundai|Elantra Hybrid 2021-23|Smart Cruise Control (SCC)|openpilot available[<sup>1</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai K|
|Hyundai|Genesis 2015-16|Smart Cruise Control (SCC)|Stock|19 mph|37 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai J|
|Hyundai|i30 2019|Smart Cruise Control (SCC)|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai E|
|Hyundai|Ioniq 5 (with HDA II) 2022|Highway Driving Assist II|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai Q|
|Hyundai|Ioniq 5 (without HDA II) 2022|Highway Driving Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai K|
|Hyundai|Ioniq 5 (with HDA II) 2022-23|Highway Driving Assist II|openpilot available[<sup>1</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai Q|
|Hyundai|Ioniq 5 (without HDA II) 2022-23|Highway Driving Assist|openpilot available[<sup>1</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai K|
|Hyundai|Ioniq Electric 2019|Smart Cruise Control (SCC)|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C|
|Hyundai|Ioniq Electric 2020|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai H|
|Hyundai|Ioniq Hybrid 2017-19|Smart Cruise Control (SCC)|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C|
@ -72,6 +73,7 @@ A supported vehicle is one that just works when you install a comma three. All s
|Hyundai|Kona Electric 2022|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai O|
|Hyundai|Kona Hybrid 2020|Smart Cruise Control (SCC)|openpilot available[<sup>1</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai I|
|Hyundai|Palisade 2020-22|All|openpilot available[<sup>1</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai H|
|Hyundai|Santa Cruz 2021-22|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai N|
|Hyundai|Santa Fe 2019-20|All|openpilot available[<sup>1</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai D|
|Hyundai|Santa Fe 2021-22|All|openpilot available[<sup>1</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai L|
|Hyundai|Santa Fe Hybrid 2022|All|openpilot available[<sup>1</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai L|
@ -81,13 +83,13 @@ A supported vehicle is one that just works when you install a comma three. All s
|Hyundai|Sonata Hybrid 2020-22|All|openpilot available[<sup>1</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai A|
|Hyundai|Tucson 2021|Smart Cruise Control (SCC)|openpilot available[<sup>1</sup>](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai L|
|Hyundai|Tucson Diesel 2019|Smart Cruise Control (SCC)|openpilot available[<sup>1</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai L|
|Hyundai|Tucson Hybrid 2022|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai N|
|Hyundai|Tucson Hybrid 2022|All|openpilot available[<sup>1</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai N|
|Hyundai|Veloster 2019-20|Smart Cruise Control (SCC)|Stock|5 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai E|
|Jeep|Grand Cherokee 2016-18|Adaptive Cruise Control (ACC)|Stock|0 mph|9 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|FCA|
|Jeep|Grand Cherokee 2019-21|Adaptive Cruise Control (ACC)|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|FCA|
|Kia|Ceed 2019|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai E|
|Kia|EV6 (with HDA II) 2022|Highway Driving Assist II|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai P|
|Kia|EV6 (without HDA II) 2022|Highway Driving Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai L|
|Kia|EV6 (with HDA II) 2022|Highway Driving Assist II|openpilot available[<sup>1</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai P|
|Kia|EV6 (without HDA II) 2022|Highway Driving Assist|openpilot available[<sup>1</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai L|
|Kia|Forte 2019-21|Smart Cruise Control (SCC)|openpilot available[<sup>1</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai G|
|Kia|K5 2021-22|Smart Cruise Control (SCC)|openpilot available[<sup>1</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai A|
|Kia|Niro EV 2019|All|openpilot available[<sup>1</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai H|
@ -102,9 +104,11 @@ A supported vehicle is one that just works when you install a comma three. All s
|Kia|Seltos 2021|Smart Cruise Control (SCC)|openpilot available[<sup>1</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai A|
|Kia|Sorento 2018|Advanced Smart Cruise Control|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C|
|Kia|Sorento 2019|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai E|
|Kia|Sportage Hybrid 2023|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai N|
|Kia|Sportage 2023|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai N|
|Kia|Sportage Hybrid 2023|Smart Cruise Control (SCC)|openpilot available[<sup>1</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai N|
|Kia|Stinger 2018-20|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai C|
|Kia|Telluride 2020|All|openpilot available[<sup>1</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai H|
|Kia|Stinger 2022|All|openpilot available[<sup>1</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai K|
|Kia|Telluride 2020-22|All|openpilot available[<sup>1</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Hyundai H|
|Lexus|CT Hybrid 2017-18|Lexus Safety System+|openpilot available[<sup>2</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Toyota|
|Lexus|ES 2019-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Toyota|
|Lexus|ES Hybrid 2017-18|Lexus Safety System+|openpilot available[<sup>2</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Toyota|
@ -129,8 +133,8 @@ A supported vehicle is one that just works when you install a comma three. All s
|Nissan|Rogue 2018-20|ProPILOT Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Nissan A|
|Nissan|X-Trail 2017|ProPILOT Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Nissan A|
|Ram|1500 2019-22|Adaptive Cruise Control (ACC)|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Ram|
|SEAT|Ateca 2018|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW|
|SEAT|Leon 2014-20|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW|
|SEAT|Ateca 2018|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,8</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|SEAT|Leon 2014-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,8</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Subaru|Ascent 2019-21|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Subaru A|
|Subaru|Crosstrek 2018-19|EyeSight Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Subaru A|
|Subaru|Crosstrek 2020-21|EyeSight Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Subaru A|
@ -141,13 +145,13 @@ A supported vehicle is one that just works when you install a comma three. All s
|Subaru|Outback 2020-22|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Subaru B|
|Subaru|XV 2018-19|EyeSight Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Subaru A|
|Subaru|XV 2020-21|EyeSight Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Subaru A|
|Škoda|Kamiq 2021[<sup>6</sup>](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW|
|Škoda|Karoq 2019-21[<sup>8</sup>](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW|
|Škoda|Kodiaq 2018-19|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW|
|Škoda|Octavia 2015, 2018-19|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW|
|Škoda|Octavia RS 2016|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW|
|Škoda|Scala 2020|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW|
|Škoda|Superb 2015-18|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW|
|Škoda|Kamiq 2021[<sup>6</sup>](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,8</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533[<sup>9</sup>](#footnotes)|
|Škoda|Karoq 2019-21|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,8</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Škoda|Kodiaq 2018-19|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,8</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Škoda|Octavia 2015, 2018-19|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,8</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Škoda|Octavia RS 2016|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,8</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Škoda|Scala 2020|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,8</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533[<sup>9</sup>](#footnotes)|
|Škoda|Superb 2015-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,8</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Toyota|Alphard 2019-20|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Toyota|
|Toyota|Alphard Hybrid 2021|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Toyota|
|Toyota|Avalon 2016|Toyota Safety Sense P|openpilot available[<sup>2</sup>](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Toyota|
@ -164,7 +168,7 @@ A supported vehicle is one that just works when you install a comma three. All s
|Toyota|Camry Hybrid 2021-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Toyota|
|Toyota|Corolla 2017-19|All|openpilot available[<sup>2</sup>](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Toyota|
|Toyota|Corolla 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Toyota|
|Toyota|Corolla Cross (Non-US only) 2020-21|All|openpilot|17 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Toyota|
|Toyota|Corolla Cross (Non-US only) 2020-23|All|openpilot|17 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Toyota|
|Toyota|Corolla Cross Hybrid (Non-US only) 2020-22|All|openpilot|17 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Toyota|
|Toyota|Corolla Hatchback 2019-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Toyota|
|Toyota|Corolla Hybrid 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Toyota|
@ -188,48 +192,48 @@ A supported vehicle is one that just works when you install a comma three. All s
|Toyota|RAV4 Hybrid 2019-21|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Toyota|
|Toyota|RAV4 Hybrid 2022|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|Toyota|
|Toyota|Sienna 2018-20|All|openpilot available[<sup>2</sup>](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|Toyota|
|Volkswagen|Arteon 2018-22[<sup>8,9</sup>](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|Arteon eHybrid 2020-22[<sup>8,9</sup>](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|Arteon R 2020-22[<sup>8,9</sup>](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|Atlas 2018-23[<sup>8</sup>](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|Atlas Cross Sport 2021-22[<sup>8</sup>](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|California 2021[<sup>8</sup>](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|Caravelle 2020[<sup>8</sup>](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|CC 2018-22[<sup>8,9</sup>](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|e-Golf 2014-20|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW|
|Volkswagen|Golf 2015-20[<sup>9</sup>](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW|
|Volkswagen|Golf Alltrack 2015-19|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW|
|Volkswagen|Golf GTD 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW|
|Volkswagen|Golf GTE 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW|
|Volkswagen|Golf GTI 2015-21|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW|
|Volkswagen|Golf R 2015-19[<sup>9</sup>](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW|
|Volkswagen|Golf SportsVan 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW|
|Volkswagen|Jetta 2018-22[<sup>8</sup>](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|Jetta GLI 2021-22[<sup>8</sup>](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|Passat 2015-22[<sup>7,8,9</sup>](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|Passat Alltrack 2015-22[<sup>8</sup>](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|Passat GTE 2015-22[<sup>8,9</sup>](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|Polo 2020-22[<sup>8</sup>](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|Polo GTI 2020-22[<sup>8</sup>](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|T-Cross 2021[<sup>8</sup>](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|T-Roc 2021[<sup>8</sup>](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|Taos 2022[<sup>8</sup>](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|Teramont 2018-22[<sup>8</sup>](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|Teramont Cross Sport 2021-22[<sup>8</sup>](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|Teramont X 2021-22[<sup>8</sup>](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|Tiguan 2019-22[<sup>8</sup>](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|Touran 2017|Adaptive Cruise Control (ACC) & Lane Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|VW|
|Volkswagen|Arteon 2018-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,8</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|Arteon eHybrid 2020-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,8</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|Arteon R 2020-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,8</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|Atlas 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,8</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|Atlas Cross Sport 2021-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,8</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|California 2021|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,8</sup>](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|Caravelle 2020|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,8</sup>](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|CC 2018-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,8</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|e-Golf 2014-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,8</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|Golf 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,8</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|Golf Alltrack 2015-19|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,8</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|Golf GTD 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,8</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|Golf GTE 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,8</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|Golf GTI 2015-21|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,8</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|Golf R 2015-19|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,8</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|Golf SportsVan 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,8</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|Jetta 2018-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,8</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|Jetta GLI 2021-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,8</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|Passat 2015-22[<sup>7</sup>](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,8</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|Passat Alltrack 2015-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,8</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|Passat GTE 2015-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,8</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|Polo 2020-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,8</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533[<sup>9</sup>](#footnotes)|
|Volkswagen|Polo GTI 2020-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,8</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533[<sup>9</sup>](#footnotes)|
|Volkswagen|T-Cross 2021|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,8</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533[<sup>9</sup>](#footnotes)|
|Volkswagen|T-Roc 2021|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,8</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533[<sup>9</sup>](#footnotes)|
|Volkswagen|Taos 2022|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,8</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|Teramont 2018-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,8</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|Teramont Cross Sport 2021-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,8</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|Teramont X 2021-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,8</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|Tiguan 2019-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,8</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
|Volkswagen|Touran 2017|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[<sup>1,8</sup>](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|J533|
<a id="footnotes"></a>
<sup>1</sup>Experimental openpilot longitudinal control is available behind a toggle; the toggle is only available in non-release branches such as `master-ci`. Using openpilot longitudinal may disable Automatic Emergency Braking (AEB). <br />
<sup>2</sup>When the Driver Support Unit (DSU) is disconnected, openpilot Adaptive Cruise Control (ACC) will replace stock Adaptive Cruise Control (ACC). <b><i>NOTE: disconnecting the DSU disables Automatic Emergency Braking (AEB).</i></b> <br />
<sup>1</sup>Experimental openpilot longitudinal control is available behind a toggle; the toggle is only available in non-release branches such as `devel` or `master-ci`. <br />
<sup>2</sup>By 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. <b><i>NOTE: disconnecting the DSU disables Automatic Emergency Braking (AEB).</i></b> <br />
<sup>3</sup>Requires a <a href="https://github.com/commaai/openpilot/wiki/GM#hardware">community built ASCM harness</a>. <b><i>NOTE: disconnecting the ASCM disables Automatic Emergency Braking (AEB).</i></b> <br />
<sup>4</sup>2019 Honda Civic 1.6L Diesel Sedan does not have ALC below 12mph. <br />
<sup>5</sup>openpilot operates above 28mph for Camry 4CYL L, 4CYL LE and 4CYL SE which don't have Full-Speed Range Dynamic Radar Cruise Control. <br />
<sup>6</sup>Not including the China market Kamiq, which is based on the (currently) unsupported PQ34 platform. <br />
<sup>7</sup>Refers only to the MQB-based European B8 Passat, not the NMS Passat in the USA/China/Mideast markets. <br />
<sup>8</sup>Model-years 2021 and beyond may have a new camera harness design, which isn't yet available from the comma store. Before ordering, remove the Lane Assist camera cover and check to see if the connector is black (older design) or light brown (newer design). In the interim, if your car has a J533 connector CAN gateway inside the dashboard, choose "VW J533 Development" from the vehicle drop-down for a suitable harness. (Some newer models are also observed to not have a J533 connector.) <br />
<sup>9</sup>Includes versions with extra rear cargo space (may be called Variant, Estate, SportWagen, Shooting Brake, etc.) <br />
<sup>8</sup>Only available for vehicles using a gateway (J533) harness. At this time, vehicles using a camera harness are limited to using stock ACC. <br />
<sup>9</sup>Model-years 2022 and beyond may have a combined CAN gateway and BCM, which is supported by openpilot in software, but doesn't yet have a harness available from the comma store. <br />
## Community Maintained Cars
Although they're not upstream, the community has openpilot running on other makes and models. See the 'Community Supported Models' section of each make [on our wiki](https://wiki.comma.ai/).

@ -7,7 +7,7 @@ export OPENBLAS_NUM_THREADS=1
export VECLIB_MAXIMUM_THREADS=1
if [ -z "$AGNOS_VERSION" ]; then
export AGNOS_VERSION="6.1"
export AGNOS_VERSION="6.2"
fi
if [ -z "$PASSIVE" ]; then

@ -1 +1 @@
Subproject commit 9147cba1af0a8d72379242eb1ce0bfd42ab8075e
Subproject commit 2e90b6f308dc09bf1734f6cb5cc990cb8149486d

63
poetry.lock generated

@ -230,7 +230,7 @@ python-versions = ">=3.5"
dev = ["cloudpickle", "coverage[toml] (>=5.0.2)", "furo", "hypothesis", "mypy (>=0.900,!=0.940)", "pre-commit", "pympler", "pytest (>=4.3.0)", "pytest-mypy-plugins", "sphinx", "sphinx-notfound-page", "zope.interface"]
docs = ["furo", "sphinx", "sphinx-notfound-page", "zope.interface"]
tests = ["cloudpickle", "coverage[toml] (>=5.0.2)", "hypothesis", "mypy (>=0.900,!=0.940)", "pympler", "pytest (>=4.3.0)", "pytest-mypy-plugins", "zope.interface"]
tests_no_zope = ["cloudpickle", "coverage[toml] (>=5.0.2)", "hypothesis", "mypy (>=0.900,!=0.940)", "pympler", "pytest (>=4.3.0)", "pytest-mypy-plugins"]
tests-no-zope = ["cloudpickle", "coverage[toml] (>=5.0.2)", "hypothesis", "mypy (>=0.900,!=0.940)", "pympler", "pytest (>=4.3.0)", "pytest-mypy-plugins"]
[[package]]
name = "av"
@ -531,7 +531,7 @@ optional = false
python-versions = ">=3.6.0"
[package.extras]
unicode_backport = ["unicodedata2"]
unicode-backport = ["unicodedata2"]
[[package]]
name = "cleo"
@ -1410,7 +1410,7 @@ notebook = ["ipywidgets", "notebook"]
parallel = ["ipyparallel"]
qtconsole = ["qtconsole"]
test = ["pytest (<7.1)", "pytest-asyncio", "testpath"]
test_extra = ["curio", "matplotlib (!=3.2.0)", "nbformat", "numpy (>=1.19)", "pandas", "pytest (<7.1)", "pytest-asyncio", "testpath", "trio"]
test-extra = ["curio", "matplotlib (!=3.2.0)", "nbformat", "numpy (>=1.19)", "pandas", "pytest (<7.1)", "pytest-asyncio", "testpath", "trio"]
[[package]]
name = "ipython-genutils"
@ -1459,9 +1459,9 @@ python-versions = ">=3.6.1,<4.0"
[package.extras]
colors = ["colorama (>=0.4.3,<0.5.0)"]
pipfile_deprecated_finder = ["pipreqs", "requirementslib"]
pipfile-deprecated-finder = ["pipreqs", "requirementslib"]
plugins = ["setuptools"]
requirements_deprecated_finder = ["pip-api", "pipreqs"]
requirements-deprecated-finder = ["pip-api", "pipreqs"]
[[package]]
name = "itsdangerous"
@ -1892,7 +1892,7 @@ mdurl = ">=0.1,<1.0"
[package.extras]
benchmarking = ["psutil", "pytest", "pytest-benchmark (>=3.2,<4.0)"]
code_style = ["pre-commit (==2.6)"]
code-style = ["pre-commit (==2.6)"]
compare = ["commonmark (>=0.9.1,<0.10.0)", "markdown (>=3.3.6,<3.4.0)", "mistletoe (>=0.8.1,<0.9.0)", "mistune (>=2.0.2,<2.1.0)", "panflute (>=2.1.3,<2.2.0)"]
linkify = ["linkify-it-py (>=1.0,<2.0)"]
plugins = ["mdit-py-plugins"]
@ -1959,7 +1959,7 @@ python-versions = ">=3.7"
markdown-it-py = ">=1.0.0,<3.0.0"
[package.extras]
code_style = ["pre-commit"]
code-style = ["pre-commit"]
rtd = ["attrs", "myst-parser (>=0.16.1,<0.17.0)", "sphinx-book-theme (>=0.1.0,<0.2.0)"]
testing = ["coverage", "pytest", "pytest-cov", "pytest-regressions"]
@ -2169,7 +2169,7 @@ sphinx = ">=4,<6"
typing-extensions = "*"
[package.extras]
code_style = ["pre-commit (>=2.12,<3.0)"]
code-style = ["pre-commit (>=2.12,<3.0)"]
linkify = ["linkify-it-py (>=1.0,<2.0)"]
rtd = ["ipython", "sphinx-book-theme", "sphinx-design", "sphinxcontrib.mermaid (>=0.7.1,<0.8.0)", "sphinxext-opengraph (>=0.6.3,<0.7.0)", "sphinxext-rediraffe (>=0.2.7,<0.3.0)"]
testing = ["beautifulsoup4", "coverage[toml]", "pytest (>=6,<7)", "pytest-cov", "pytest-param-files (>=0.3.4,<0.4.0)", "pytest-regressions", "sphinx (<5.2)", "sphinx-pytest"]
@ -3193,7 +3193,7 @@ optional = false
python-versions = ">=3.6"
[package.extras]
asyncio_client = ["aiohttp (>=3.4)"]
asyncio-client = ["aiohttp (>=3.4)"]
client = ["requests (>=2.21.0)", "websocket-client (>=0.54.0)"]
[[package]]
@ -3217,7 +3217,7 @@ bidict = ">=0.21.0"
python-engineio = ">=4.3.0"
[package.extras]
asyncio_client = ["aiohttp (>=3.4)"]
asyncio-client = ["aiohttp (>=3.4)"]
client = ["requests (>=2.21.0)", "websocket-client (>=0.54.0)"]
[[package]]
@ -3393,7 +3393,7 @@ urllib3 = ">=1.21.1,<1.27"
[package.extras]
socks = ["PySocks (>=1.5.6,!=1.5.7)"]
use_chardet_on_py3 = ["chardet (>=3.0.2,<6)"]
use-chardet-on-py3 = ["chardet (>=3.0.2,<6)"]
[[package]]
name = "requests-oauthlib"
@ -3584,7 +3584,7 @@ falcon = ["falcon (>=1.4)"]
fastapi = ["fastapi (>=0.79.0)"]
flask = ["blinker (>=1.1)", "flask (>=0.11)"]
httpx = ["httpx (>=0.16.0)"]
pure_eval = ["asttokens", "executing", "pure-eval"]
pure-eval = ["asttokens", "executing", "pure-eval"]
pyspark = ["pyspark (>=2.4.4)"]
quart = ["blinker (>=1.1)", "quart (>=0.16.1)"]
rq = ["rq (>=0.6)"]
@ -3834,6 +3834,14 @@ python-versions = ">=3.5"
lint = ["docutils-stubs", "flake8", "mypy"]
test = ["pytest"]
[[package]]
name = "spidev"
version = "3.6"
description = "Python bindings for Linux SPI access through spidev"
category = "main"
optional = false
python-versions = "*"
[[package]]
name = "sqlalchemy"
version = "1.4.42"
@ -3850,19 +3858,19 @@ aiomysql = ["aiomysql", "greenlet (!=0.4.17)"]
aiosqlite = ["aiosqlite", "greenlet (!=0.4.17)", "typing_extensions (!=3.10.0.1)"]
asyncio = ["greenlet (!=0.4.17)"]
asyncmy = ["asyncmy (>=0.2.3,!=0.2.4)", "greenlet (!=0.4.17)"]
mariadb_connector = ["mariadb (>=1.0.1,!=1.1.2)"]
mariadb-connector = ["mariadb (>=1.0.1,!=1.1.2)"]
mssql = ["pyodbc"]
mssql_pymssql = ["pymssql"]
mssql_pyodbc = ["pyodbc"]
mssql-pymssql = ["pymssql"]
mssql-pyodbc = ["pyodbc"]
mypy = ["mypy (>=0.910)", "sqlalchemy2-stubs"]
mysql = ["mysqlclient (>=1.4.0)", "mysqlclient (>=1.4.0,<2)"]
mysql_connector = ["mysql-connector-python"]
mysql-connector = ["mysql-connector-python"]
oracle = ["cx_oracle (>=7)", "cx_oracle (>=7,<8)"]
postgresql = ["psycopg2 (>=2.7)"]
postgresql_asyncpg = ["asyncpg", "greenlet (!=0.4.17)"]
postgresql_pg8000 = ["pg8000 (>=1.16.6,!=1.29.0)"]
postgresql_psycopg2binary = ["psycopg2-binary"]
postgresql_psycopg2cffi = ["psycopg2cffi"]
postgresql-asyncpg = ["asyncpg", "greenlet (!=0.4.17)"]
postgresql-pg8000 = ["pg8000 (>=1.16.6,!=1.29.0)"]
postgresql-psycopg2binary = ["psycopg2-binary"]
postgresql-psycopg2cffi = ["psycopg2cffi"]
pymysql = ["pymysql", "pymysql (<1)"]
sqlcipher = ["sqlcipher3_binary"]
@ -4378,7 +4386,7 @@ testing = ["coverage (>=5.0.3)", "zope.event", "zope.testing"]
[metadata]
lock-version = "1.1"
python-versions = "~3.8"
content-hash = "76f06d46b1c308e59968994e42193599d8ba3cab6d552460c9c48f282313b64d"
content-hash = "d2854112975a9d83a9540175b2d430487e40e0292d48a1ba6c591db60a08c136"
[metadata.files]
adal = [
@ -5384,6 +5392,7 @@ gevent = [
{file = "gevent-22.10.1-cp310-cp310-win_amd64.whl", hash = "sha256:d2ea4ce36c09355379bc038be2bd50118f97d2eb6381b7096de4d05aa4c3e241"},
{file = "gevent-22.10.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:3e73c9f71aa2a6795ecbec9b57282b002375e863e283558feb87b62840c8c1ac"},
{file = "gevent-22.10.1-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:5bc3758f0dc95007c1780d28a9fd2150416a79c50f308f62a674d78a845ea1b9"},
{file = "gevent-22.10.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:03c10ca0beeab0c6be516030471ea630447ddd1f649d3335e5b162097cd4130a"},
{file = "gevent-22.10.1-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:fe2c0ff095171c49f78f1d4e6dc89fa58253783c7b6dccab9f1d76e2ee391f10"},
{file = "gevent-22.10.1-cp36-cp36m-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:d18fcc324f39a3b21795022eb47c7752d6e4f4ed89d8cca41f1cc604553265b3"},
{file = "gevent-22.10.1-cp36-cp36m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:06ea39c70ce166c4a1d4386c7fae96cb8d84ad799527b3378406051104d15443"},
@ -6554,6 +6563,11 @@ pillow-avif-plugin = [
{file = "pillow_avif_plugin-1.2.2-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:017e5e52cb4320414e8ce3e2089eae2cb87c22c73ff6012b17ae326fc5753b20"},
{file = "pillow_avif_plugin-1.2.2-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:2a57136d4866de5dc80cfb24d66655955fbdd87acf1d11d88c8dc2ab41023e46"},
{file = "pillow_avif_plugin-1.2.2-cp310-cp310-win_amd64.whl", hash = "sha256:f339511d0fccb69e3a5e3af39f8fe6700b0a07279015006ea56f8f49e7fecff4"},
{file = "pillow_avif_plugin-1.2.2-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:05e821ecd90bb0b8d2dc7610625372cc47de9cb893d09662528bad572f669d1c"},
{file = "pillow_avif_plugin-1.2.2-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d33886a5f9796fe9a8a3bc25ccfdeba7db119adb50b7004f1928a14b07d0213a"},
{file = "pillow_avif_plugin-1.2.2-cp311-cp311-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:75b7ed186c2f740dd26e556f6a966c59a170b70263e429a2c81920fe444da8a7"},
{file = "pillow_avif_plugin-1.2.2-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:a11aef6b79078b8dad25c928e5871c146ab94424472851d5bf539ba62abde9ac"},
{file = "pillow_avif_plugin-1.2.2-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:10696c536d68a14cefea3b98edb8d5a7ae29e8e07458f1d59c5d1cd780a8bf2a"},
{file = "pillow_avif_plugin-1.2.2-cp36-cp36m-macosx_10_10_x86_64.whl", hash = "sha256:1a7291d6a5fb7336e72685a31d193e0b3a6bee9986c9ac4d8bd4b68dbe6d4f7f"},
{file = "pillow_avif_plugin-1.2.2-cp36-cp36m-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:14b9c5dbf237e7dc12f69819ea181a457b3bd4f59f8cd71d028d3635fd3bcab4"},
{file = "pillow_avif_plugin-1.2.2-cp36-cp36m-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:799cbfbeee831332d280c80df9ce16b5c3b1224c318264e97e89df8da32e870e"},
@ -6942,11 +6956,13 @@ pyprof2calltree = [
]
pyproj = [
{file = "pyproj-3.4.0-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:f343725566267a296b09ee7e591894f1fdc90f84f8ad5ec476aeb53bd4479c07"},
{file = "pyproj-3.4.0-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:5816807ca0bdc7256558770c6206a6783a3f02bcf844f94ee245f197bb5f7285"},
{file = "pyproj-3.4.0-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e7e609903572a56cca758bbaee5c1663c3e829ddce5eec4f368e68277e37022b"},
{file = "pyproj-3.4.0-cp310-cp310-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:4fd425ee8b6781c249c7adb7daa2e6c41ce573afabe4f380f5eecd913b56a3be"},
{file = "pyproj-3.4.0-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:954b068136518b3174d0a99448056e97af62b63392a95c420894f7de2229dae6"},
{file = "pyproj-3.4.0-cp310-cp310-win_amd64.whl", hash = "sha256:4a23d84c5ffc383c7d9f0bde3a06fc1f6697b1b96725597f8f01e7b4bef0a2b5"},
{file = "pyproj-3.4.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:1f9c100fd0fd80edbc7e4daa303600a8cbef6f0de43d005617acb38276b88dc0"},
{file = "pyproj-3.4.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:aa5171f700f174777a9e9ed8f4655583243967c0f9cf2c90e3f54e54ff740134"},
{file = "pyproj-3.4.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:9a496d9057b2128db9d733e66b206f2d5954bbae6b800d412f562d780561478c"},
{file = "pyproj-3.4.0-cp311-cp311-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:52e54796e2d9554a5eb8f11df4748af1fbbc47f76aa234d6faf09216a84554c5"},
{file = "pyproj-3.4.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:a454a7c4423faa2a14e939d08ef293ee347fa529c9df79022b0585a6e1d8310c"},
@ -6957,6 +6973,7 @@ pyproj = [
{file = "pyproj-3.4.0-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f80adda8c54b84271a93829477a01aa57bc178c834362e9f74e1de1b5033c74c"},
{file = "pyproj-3.4.0-cp38-cp38-win_amd64.whl", hash = "sha256:221d8939685e0c43ee594c9f04b6a73a10e8e1cc0e85f28be0b4eb2f1bc8777d"},
{file = "pyproj-3.4.0-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:d94afed99f31673d3d19fe750283621e193e2a53ca9e0443bf9d092c3905833b"},
{file = "pyproj-3.4.0-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:0fff9c3a991508f16027be27d153f6c5583d03799443639d13c681e60f49e2d7"},
{file = "pyproj-3.4.0-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:3b85acf09e5a9e35cd9ee72989793adb7089b4e611be02a43d3d0bda50ad116b"},
{file = "pyproj-3.4.0-cp39-cp39-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:45554f47d1a12a84b0620e4abc08a2a1b5d9f273a4759eaef75e74788ec7162a"},
{file = "pyproj-3.4.0-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:12f62c20656ac9b6076ebb213e9a635d52f4f01fef95310121d337e62e910cb6"},
@ -7537,6 +7554,10 @@ sphinxcontrib-serializinghtml = [
{file = "sphinxcontrib-serializinghtml-1.1.5.tar.gz", hash = "sha256:aa5f6de5dfdf809ef505c4895e51ef5c9eac17d0f287933eb49ec495280b6952"},
{file = "sphinxcontrib_serializinghtml-1.1.5-py2.py3-none-any.whl", hash = "sha256:352a9a00ae864471d3a7ead8d7d79f5fc0b57e8b3f95e9867eb9eb28999b92fd"},
]
spidev = [
{file = "spidev-3.6-cp39-cp39-linux_armv7l.whl", hash = "sha256:280abc00a1ef7780ef62c3f294f52a2527b6c47d8c269fea98664970bcaf6da5"},
{file = "spidev-3.6.tar.gz", hash = "sha256:14dbc37594a4aaef85403ab617985d3c3ef464d62bc9b769ef552db53701115b"},
]
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"},

@ -55,6 +55,7 @@ tqdm = "^4.64.0"
urllib3 = "^1.26.10"
utm = "^0.7.0"
websocket_client = "^1.3.3"
spidev = "^3.6"
[tool.poetry.group.dev.dependencies]

@ -90,8 +90,12 @@ selfdrive/boardd/boardd_api_impl.pyx
selfdrive/boardd/can_list_to_can_capnp.cc
selfdrive/boardd/panda.cc
selfdrive/boardd/panda.h
selfdrive/boardd/spi.cc
selfdrive/boardd/panda_comms.h
selfdrive/boardd/panda_comms.cc
selfdrive/boardd/set_time.py
selfdrive/boardd/pandad.py
selfdrive/boardd/tests/test_boardd_loopback.py
selfdrive/car/__init__.py
selfdrive/car/docs_definitions.py

@ -0,0 +1,4 @@
<?xml version="1.0" encoding="utf-8"?>
<svg viewBox="0 0 300 300" xmlns="http://www.w3.org/2000/svg">
<path d="M 278.364 122.673 C 282.129 126.545 284.418 132.064 284.5 137.465 L 284.5 200.562 C 284.419 205.963 282.129 211.48 278.364 215.352 C 274.492 219.119 268.972 221.407 263.571 221.488 L 259.262 221.488 L 259.262 238.417 C 259.128 241.171 257.425 244.12 255.107 245.614 C 252.655 246.875 249.249 246.874 246.796 245.613 C 244.48 244.12 242.777 241.171 242.643 238.417 L 242.643 221.488 L 57.357 221.488 L 57.357 238.417 C 57.223 241.171 55.519 244.121 53.203 245.614 C 50.75 246.875 47.344 246.875 44.892 245.614 C 42.575 244.12 40.872 241.171 40.738 238.417 L 40.738 221.488 L 36.427 221.488 C 31.027 221.407 25.508 219.119 21.636 215.352 C 17.871 211.48 15.582 205.961 15.5 200.56 L 15.5 137.463 C 15.581 132.062 17.871 126.545 21.636 122.673 C 25.508 118.906 31.029 116.618 36.429 116.536 L 40.738 116.536 L 40.738 87.024 C 40.426 78.719 43.434 70.271 48.95 64.028 C 54.579 57.887 62.818 53.986 71.131 53.441 L 228.982 53.444 C 237.295 53.989 245.421 57.888 251.05 64.028 C 256.566 70.272 259.574 78.719 259.262 87.024 L 259.262 116.536 L 263.573 116.536 C 268.974 116.618 274.492 118.906 278.364 122.673 Z M 60.911 75.581 C 58.147 78.782 56.932 82.617 57.35 86.825 L 57.357 118.356 C 60.791 119.893 63.643 122.022 66.115 125.423 C 68.512 128.877 69.916 133.256 69.976 137.46 L 69.976 167.014 L 230.024 167.014 L 230.024 137.466 C 230.084 133.262 231.488 128.877 233.884 125.423 C 236.357 122.021 239.208 119.892 242.643 118.356 L 242.643 86.988 C 243.06 82.779 241.852 78.782 239.089 75.581 C 236.438 72.283 232.951 70.432 228.785 70.059 L 71.215 70.059 C 67.049 70.433 63.563 72.283 60.911 75.581 Z M 33.383 203.605 C 34.241 204.572 35.14 204.944 36.431 204.87 L 53.357 204.87 L 53.357 137.465 C 53.432 136.174 53.06 135.278 52.093 134.42 C 51.236 133.454 50.336 133.08 49.046 133.155 L 36.429 133.155 C 35.139 133.08 34.295 133.506 33.382 134.419 C 32.47 135.332 32.044 136.176 32.119 137.466 L 32.119 200.56 C 32.044 201.851 32.416 202.747 33.383 203.605 Z M 69.976 204.87 L 230.024 204.87 L 230.024 183.631 L 69.976 183.631 L 69.976 204.87 Z M 267.881 137.465 C 267.956 136.174 267.584 135.278 266.618 134.419 C 265.758 133.453 264.86 133.08 263.57 133.155 L 250.953 133.155 C 249.663 133.08 248.766 133.452 247.908 134.419 C 246.941 135.277 246.568 136.176 246.643 137.466 L 246.643 204.87 L 263.571 204.87 C 264.862 204.944 265.759 204.572 266.616 203.606 C 267.583 202.748 267.956 201.849 267.881 200.559 L 267.881 137.465 Z" fill="black" style="stroke-width: 4px; vector-effect: non-scaling-stroke; fill-opacity: 0.4;"/>
</svg>

After

Width:  |  Height:  |  Size: 2.6 KiB

@ -0,0 +1,10 @@
<svg width="300" height="300" viewBox="0 0 300 300" fill="none" xmlns="http://www.w3.org/2000/svg">
<path d="M182.019 181.218C123.429 239.83 67.543 258.769 54.9241 245.243C51.3182 241.636 51.3182 236.226 51.3182 231.717C51.3182 207.37 74.7548 160.481 124.331 114.489C129.74 109.98 129.74 101.864 125.233 96.454C120.725 91.0438 112.612 91.0438 107.204 95.5525C95.4866 106.373 85.5713 117.194 76.5569 128.016C51.3181 89.242 45.9096 61.2866 54.0213 52.2701C63.9367 42.351 100.894 50.4672 144.162 82.9291C157.683 92.8482 171.203 104.57 183.823 117.196C193.738 127.115 203.654 137.936 211.767 148.757C202.754 160.48 192.838 170.399 182.021 181.22L182.019 181.218ZM246.019 54.0753C255.033 63.0928 248.724 91.9498 225.287 128.918C217.174 118.999 209.062 109.982 200.048 100.063C191.034 91.0451 181.119 82.0274 171.204 73.9125C209.064 49.5654 237.006 45.0578 246.019 54.0753ZM264.048 36.04C243.316 15.3002 200.047 24.318 150.471 58.5842C100.894 24.317 56.7244 15.3005 35.9947 36.04C15.2627 56.7799 24.2771 99.1619 59.4313 149.66C38.6993 179.417 26.0793 208.272 26.0793 231.718C26.0793 247.949 32.3888 257.868 36.896 263.278C45.0091 271.394 54.9244 275 67.5433 275C105.403 275 158.583 241.635 200.049 200.157C209.063 191.14 218.077 181.22 225.288 171.301C249.625 209.176 255.034 237.128 246.02 246.144C238.809 253.357 218.076 250.653 193.739 238.028C187.43 235.322 180.218 237.127 176.613 243.438C173.008 249.75 175.712 256.965 182.022 260.571C200.951 270.49 218.979 274.999 232.501 274.999C245.121 274.999 255.036 271.391 263.148 263.277C283.88 242.537 274.866 199.252 240.612 149.657C272.163 105.473 286.583 59.4852 264.05 36.0397L264.048 36.04Z" fill="url(#paint0_radial_1352_397)"/>
<path d="M175.414 154.169C175.414 171.6 161.29 185.729 143.866 185.729C126.441 185.729 112.317 171.6 112.317 154.169C112.317 136.738 126.441 122.609 143.866 122.609C161.29 122.609 175.414 136.738 175.414 154.169Z" fill="#E11C1C"/>
<defs>
<radialGradient id="paint0_radial_1352_397" cx="0" cy="0" r="1" gradientUnits="userSpaceOnUse" gradientTransform="translate(150 150) rotate(90) scale(125)">
<stop offset="0.135417" stop-color="#E11C1C"/>
<stop offset="1" stop-color="#FF8C22"/>
</radialGradient>
</defs>
</svg>

After

Width:  |  Height:  |  Size: 2.1 KiB

@ -0,0 +1,4 @@
<svg width="300" height="300" viewBox="0 0 300 300" fill="none" xmlns="http://www.w3.org/2000/svg">
<path d="M182.019 181.218C123.429 239.83 67.543 258.769 54.9241 245.243C51.3182 241.636 51.3182 236.226 51.3182 231.717C51.3182 207.37 74.7548 160.481 124.331 114.489C129.74 109.98 129.74 101.864 125.233 96.454C120.725 91.0438 112.612 91.0438 107.204 95.5525C95.4866 106.373 85.5713 117.194 76.5569 128.016C51.3181 89.242 45.9096 61.2866 54.0213 52.2701C63.9367 42.351 100.894 50.4672 144.162 82.9291C157.683 92.8482 171.203 104.57 183.823 117.196C193.738 127.115 203.654 137.936 211.767 148.757C202.754 160.48 192.838 170.399 182.021 181.22L182.019 181.218ZM246.019 54.0753C255.033 63.0928 248.724 91.9498 225.287 128.918C217.174 118.999 209.062 109.982 200.048 100.063C191.034 91.0451 181.119 82.0274 171.204 73.9125C209.064 49.5654 237.006 45.0578 246.019 54.0753ZM264.048 36.04C243.316 15.3002 200.047 24.318 150.471 58.5842C100.894 24.317 56.7244 15.3005 35.9947 36.04C15.2627 56.7799 24.2771 99.1619 59.4313 149.66C38.6993 179.417 26.0793 208.272 26.0793 231.718C26.0793 247.949 32.3888 257.868 36.896 263.278C45.0091 271.394 54.9244 275 67.5433 275C105.403 275 158.583 241.635 200.049 200.157C209.063 191.14 218.077 181.22 225.288 171.301C249.625 209.176 255.034 237.128 246.02 246.144C238.809 253.357 218.076 250.653 193.739 238.028C187.43 235.322 180.218 237.127 176.613 243.438C173.008 249.75 175.712 256.965 182.022 260.571C200.951 270.49 218.979 274.999 232.501 274.999C245.121 274.999 255.036 271.391 263.148 263.277C283.88 242.537 274.866 199.252 240.612 149.657C272.163 105.473 286.583 59.4852 264.05 36.0397L264.048 36.04Z" fill="black" fill-opacity="0.36"/>
<path d="M175.414 154.169C175.414 171.6 161.29 185.729 143.866 185.729C126.441 185.729 112.317 171.6 112.317 154.169C112.317 136.738 126.441 122.609 143.866 122.609C161.29 122.609 175.414 136.738 175.414 154.169Z" fill="black" fill-opacity="0.36"/>
</svg>

After

Width:  |  Height:  |  Size: 1.9 KiB

@ -0,0 +1,4 @@
<svg width="300" height="300" viewBox="0 0 300 300" fill="none" xmlns="http://www.w3.org/2000/svg">
<path d="M182.019 181.218C123.429 239.83 67.543 258.769 54.9241 245.243C51.3182 241.636 51.3182 236.226 51.3182 231.717C51.3182 207.37 74.7548 160.481 124.331 114.489C129.74 109.98 129.74 101.864 125.233 96.454C120.725 91.0438 112.612 91.0438 107.204 95.5525C95.4866 106.373 85.5713 117.194 76.5569 128.016C51.3181 89.242 45.9096 61.2866 54.0213 52.2701C63.9367 42.351 100.894 50.4672 144.162 82.9291C157.683 92.8482 171.203 104.57 183.823 117.196C193.738 127.115 203.654 137.936 211.767 148.757C202.754 160.48 192.838 170.399 182.021 181.22L182.019 181.218ZM246.019 54.0753C255.033 63.0928 248.724 91.9498 225.287 128.918C217.174 118.999 209.062 109.982 200.048 100.063C191.034 91.0451 181.119 82.0274 171.204 73.9125C209.064 49.5654 237.006 45.0578 246.019 54.0753ZM264.048 36.04C243.316 15.3002 200.047 24.318 150.471 58.5842C100.894 24.317 56.7244 15.3005 35.9947 36.04C15.2627 56.7799 24.2771 99.1619 59.4313 149.66C38.6993 179.417 26.0793 208.272 26.0793 231.718C26.0793 247.949 32.3888 257.868 36.896 263.278C45.0091 271.394 54.9244 275 67.5433 275C105.403 275 158.583 241.635 200.049 200.157C209.063 191.14 218.077 181.22 225.288 171.301C249.625 209.176 255.034 237.128 246.02 246.144C238.809 253.357 218.076 250.653 193.739 238.028C187.43 235.322 180.218 237.127 176.613 243.438C173.008 249.75 175.712 256.965 182.022 260.571C200.951 270.49 218.979 274.999 232.501 274.999C245.121 274.999 255.036 271.391 263.148 263.277C283.88 242.537 274.866 199.252 240.612 149.657C272.163 105.473 286.583 59.4852 264.05 36.0397L264.048 36.04Z" fill="white"/>
<path d="M175.414 154.169C175.414 171.6 161.29 185.729 143.866 185.729C126.441 185.729 112.317 171.6 112.317 154.169C112.317 136.738 126.441 122.609 143.866 122.609C161.29 122.609 175.414 136.738 175.414 154.169Z" fill="white"/>
</svg>

After

Width:  |  Height:  |  Size: 1.8 KiB

@ -1,9 +1,9 @@
Import('env', 'envCython', 'common', 'cereal', 'messaging')
libs = ['usb-1.0', common, cereal, messaging, 'pthread', 'zmq', 'capnp', 'kj']
env.Program('boardd', ['main.cc', 'boardd.cc', 'panda.cc'], LIBS=libs)
env.Program('boardd', ['main.cc', 'boardd.cc', 'panda.cc', 'panda_comms.cc', 'spi.cc'], LIBS=libs)
env.Library('libcan_list_to_can_capnp', ['can_list_to_can_capnp.cc'])
envCython.Program('boardd_api_impl.so', 'boardd_api_impl.pyx', LIBS=["can_list_to_can_capnp", 'capnp', 'kj'] + envCython["LIBS"])
if GetOption('test'):
env.Program('tests/test_boardd_usbprotocol', ['tests/test_boardd_usbprotocol.cc', 'panda.cc'], LIBS=libs)
env.Program('tests/test_boardd_usbprotocol', ['tests/test_boardd_usbprotocol.cc', 'panda.cc', 'panda_comms.cc', 'spi.cc'], LIBS=libs)

@ -19,8 +19,6 @@
#include <future>
#include <thread>
#include <libusb-1.0/libusb.h>
#include "cereal/gen/cpp/car.capnp.h"
#include "cereal/messaging/messaging.h"
#include "common/params.h"
@ -67,7 +65,7 @@ static std::string get_time_str(const struct tm &time) {
bool check_all_connected(const std::vector<Panda *> &pandas) {
for (const auto& panda : pandas) {
if (!panda->connected) {
if (!panda->connected()) {
do_exit = true;
return false;
}
@ -184,7 +182,7 @@ bool safety_setter_thread(std::vector<Panda *> pandas) {
return true;
}
Panda *usb_connect(std::string serial="", uint32_t index=0) {
Panda *connect(std::string serial="", uint32_t index=0) {
std::unique_ptr<Panda> panda;
try {
panda = std::make_unique<Panda>(serial, (index * PANDA_BUS_CNT));
@ -227,9 +225,9 @@ void can_send_thread(std::vector<Panda *> 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->usb_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->usb_serial).c_str());
LOGT("sendcan sent to panda: %s", (panda->hw_serial).c_str());
}
}
}
@ -357,7 +355,7 @@ std::optional<bool> send_panda_states(PubMaster *pm, const std::vector<Panda *>
}
#endif
if (!panda->comms_healthy) {
if (!panda->comms_healthy()) {
evt.setValid(false);
}
@ -433,7 +431,7 @@ void send_peripheral_state(PubMaster *pm, Panda *panda) {
// build msg
MessageBuilder msg;
auto evt = msg.initEvent();
evt.setValid(panda->comms_healthy);
evt.setValid(panda->comms_healthy());
auto ps = evt.initPeripheralState();
ps.setPandaType(panda->hw_type);
@ -526,7 +524,7 @@ void peripheral_control_thread(Panda *panda, bool no_fan_control) {
FirstOrderFilter integ_lines_filter(0, 30.0, 0.05);
while (!do_exit && panda->connected) {
while (!do_exit && panda->connected()) {
cnt++;
sm.update(1000); // TODO: what happens if EINTR is sent while in sm.update?
@ -595,7 +593,7 @@ void boardd_main_thread(std::vector<std::string> serials) {
// connect to all provided serials
std::vector<Panda *> pandas;
for (int i = 0; i < serials.size() && !do_exit; /**/) {
Panda *p = usb_connect(serials[i], i);
Panda *p = connect(serials[i], i);
if (!p) {
// send empty pandaState & peripheralState and try again
send_empty_panda_state(&pm);

@ -4,76 +4,20 @@
#include <cassert>
#include <stdexcept>
#include <vector>
#include "cereal/messaging/messaging.h"
#include "panda/board/dlc_to_len.h"
#include "common/gpio.h"
#include "common/swaglog.h"
#include "common/util.h"
static int init_usb_ctx(libusb_context **context) {
assert(context != nullptr);
int err = libusb_init(context);
if (err != 0) {
LOGE("libusb initialization error");
return err;
}
#if LIBUSB_API_VERSION >= 0x01000106
libusb_set_option(*context, LIBUSB_OPTION_LOG_LEVEL, LIBUSB_LOG_LEVEL_INFO);
#else
libusb_set_debug(*context, 3);
#endif
return err;
}
Panda::Panda(std::string serial, uint32_t bus_offset) : bus_offset(bus_offset) {
// init libusb
ssize_t num_devices;
libusb_device **dev_list = NULL;
int err = init_usb_ctx(&ctx);
if (err != 0) { goto fail; }
// connect by serial
num_devices = libusb_get_device_list(ctx, &dev_list);
if (num_devices < 0) { goto fail; }
for (size_t i = 0; i < num_devices; ++i) {
libusb_device_descriptor desc;
libusb_get_device_descriptor(dev_list[i], &desc);
if (desc.idVendor == 0xbbaa && desc.idProduct == 0xddcc) {
int ret = libusb_open(dev_list[i], &dev_handle);
if (dev_handle == NULL || ret < 0) { goto fail; }
unsigned char desc_serial[26] = { 0 };
ret = libusb_get_string_descriptor_ascii(dev_handle, desc.iSerialNumber, desc_serial, std::size(desc_serial));
if (ret < 0) { goto fail; }
usb_serial = std::string((char *)desc_serial, ret).c_str();
if (serial.empty() || serial == usb_serial) {
break;
}
libusb_close(dev_handle);
dev_handle = NULL;
}
}
if (dev_handle == NULL) goto fail;
libusb_free_device_list(dev_list, 1);
dev_list = nullptr;
if (libusb_kernel_driver_active(dev_handle, 0) == 1) {
libusb_detach_kernel_driver(dev_handle, 0);
// TODO: support SPI here one day...
if (serial.find("spi") != std::string::npos) {
handle = std::make_unique<PandaSpiHandle>(serial);
} else {
handle = std::make_unique<PandaUsbHandle>(serial);
}
err = libusb_set_configuration(dev_handle, 1);
if (err != 0) { goto fail; }
err = libusb_claim_interface(dev_handle, 0);
if (err != 0) { goto fail; }
hw_type = get_hw_type();
assert((hw_type != cereal::PandaState::PandaType::WHITE_PANDA) &&
@ -83,194 +27,44 @@ Panda::Panda(std::string serial, uint32_t bus_offset) : bus_offset(bus_offset) {
(hw_type == cereal::PandaState::PandaType::DOS);
return;
fail:
if (dev_list != NULL) {
libusb_free_device_list(dev_list, 1);
}
cleanup();
throw std::runtime_error("Error connecting to panda");
}
Panda::~Panda() {
std::lock_guard lk(usb_lock);
cleanup();
connected = false;
bool Panda::connected() {
return handle->connected;
}
void Panda::cleanup() {
if (dev_handle) {
libusb_release_interface(dev_handle, 0);
libusb_close(dev_handle);
}
if (ctx) {
libusb_exit(ctx);
}
bool Panda::comms_healthy() {
return handle->comms_healthy;
}
std::vector<std::string> Panda::list() {
// init libusb
ssize_t num_devices;
libusb_context *context = NULL;
libusb_device **dev_list = NULL;
std::vector<std::string> serials;
int err = init_usb_ctx(&context);
if (err != 0) { return serials; }
num_devices = libusb_get_device_list(context, &dev_list);
if (num_devices < 0) {
LOGE("libusb can't get device list");
goto finish;
}
for (size_t i = 0; i < num_devices; ++i) {
libusb_device *device = dev_list[i];
libusb_device_descriptor desc;
libusb_get_device_descriptor(device, &desc);
if (desc.idVendor == 0xbbaa && desc.idProduct == 0xddcc) {
libusb_device_handle *handle = NULL;
int ret = libusb_open(device, &handle);
if (ret < 0) { goto finish; }
unsigned char desc_serial[26] = { 0 };
ret = libusb_get_string_descriptor_ascii(handle, desc.iSerialNumber, desc_serial, std::size(desc_serial));
libusb_close(handle);
if (ret < 0) { goto finish; }
serials.push_back(std::string((char *)desc_serial, ret).c_str());
}
}
finish:
if (dev_list != NULL) {
libusb_free_device_list(dev_list, 1);
}
if (context) {
libusb_exit(context);
}
return serials;
}
void Panda::handle_usb_issue(int err, const char func[]) {
LOGE_100("usb error %d \"%s\" in %s", err, libusb_strerror((enum libusb_error)err), func);
if (err == LIBUSB_ERROR_NO_DEVICE) {
LOGE("lost connection");
connected = false;
}
// TODO: check other errors, is simply retrying okay?
}
int Panda::usb_write(uint8_t bRequest, uint16_t wValue, uint16_t wIndex, unsigned int timeout) {
int err;
const uint8_t bmRequestType = LIBUSB_ENDPOINT_OUT | LIBUSB_REQUEST_TYPE_VENDOR | LIBUSB_RECIPIENT_DEVICE;
if (!connected) {
return LIBUSB_ERROR_NO_DEVICE;
}
std::lock_guard lk(usb_lock);
do {
err = libusb_control_transfer(dev_handle, bmRequestType, bRequest, wValue, wIndex, NULL, 0, timeout);
if (err < 0) handle_usb_issue(err, __func__);
} while (err < 0 && connected);
return err;
}
int Panda::usb_read(uint8_t bRequest, uint16_t wValue, uint16_t wIndex, unsigned char *data, uint16_t wLength, unsigned int timeout) {
int err;
const uint8_t bmRequestType = LIBUSB_ENDPOINT_IN | LIBUSB_REQUEST_TYPE_VENDOR | LIBUSB_RECIPIENT_DEVICE;
if (!connected) {
return LIBUSB_ERROR_NO_DEVICE;
}
std::lock_guard lk(usb_lock);
do {
err = libusb_control_transfer(dev_handle, bmRequestType, bRequest, wValue, wIndex, data, wLength, timeout);
if (err < 0) handle_usb_issue(err, __func__);
} while (err < 0 && connected);
return err;
}
int Panda::usb_bulk_write(unsigned char endpoint, unsigned char* data, int length, unsigned int timeout) {
int err;
int transferred = 0;
if (!connected) {
return 0;
}
std::lock_guard lk(usb_lock);
do {
// Try sending can messages. If the receive buffer on the panda is full it will NAK
// and libusb will try again. After 5ms, it will time out. We will drop the messages.
err = libusb_bulk_transfer(dev_handle, endpoint, data, length, &transferred, timeout);
if (err == LIBUSB_ERROR_TIMEOUT) {
LOGW("Transmit buffer full");
break;
} else if (err != 0 || length != transferred) {
handle_usb_issue(err, __func__);
}
} while(err != 0 && connected);
return transferred;
}
int Panda::usb_bulk_read(unsigned char endpoint, unsigned char* data, int length, unsigned int timeout) {
int err;
int transferred = 0;
if (!connected) {
return 0;
}
std::lock_guard lk(usb_lock);
do {
err = libusb_bulk_transfer(dev_handle, endpoint, data, length, &transferred, timeout);
if (err == LIBUSB_ERROR_TIMEOUT) {
break; // timeout is okay to exit, recv still happened
} else if (err == LIBUSB_ERROR_OVERFLOW) {
comms_healthy = false;
LOGE_100("overflow got 0x%x", transferred);
} else if (err != 0) {
handle_usb_issue(err, __func__);
}
} while(err != 0 && connected);
return transferred;
return PandaUsbHandle::list();
}
void Panda::set_safety_model(cereal::CarParams::SafetyModel safety_model, uint16_t safety_param) {
usb_write(0xdc, (uint16_t)safety_model, safety_param);
handle->control_write(0xdc, (uint16_t)safety_model, safety_param);
}
void Panda::set_alternative_experience(uint16_t alternative_experience) {
usb_write(0xdf, alternative_experience, 0);
handle->control_write(0xdf, alternative_experience, 0);
}
cereal::PandaState::PandaType Panda::get_hw_type() {
unsigned char hw_query[1] = {0};
usb_read(0xc1, 0, 0, hw_query, 1);
handle->control_read(0xc1, 0, 0, hw_query, 1);
return (cereal::PandaState::PandaType)(hw_query[0]);
}
void Panda::set_rtc(struct tm sys_time) {
// tm struct has year defined as years since 1900
usb_write(0xa1, (uint16_t)(1900 + sys_time.tm_year), 0);
usb_write(0xa2, (uint16_t)(1 + sys_time.tm_mon), 0);
usb_write(0xa3, (uint16_t)sys_time.tm_mday, 0);
// usb_write(0xa4, (uint16_t)(1 + sys_time.tm_wday), 0);
usb_write(0xa5, (uint16_t)sys_time.tm_hour, 0);
usb_write(0xa6, (uint16_t)sys_time.tm_min, 0);
usb_write(0xa7, (uint16_t)sys_time.tm_sec, 0);
handle->control_write(0xa1, (uint16_t)(1900 + sys_time.tm_year), 0);
handle->control_write(0xa2, (uint16_t)(1 + sys_time.tm_mon), 0);
handle->control_write(0xa3, (uint16_t)sys_time.tm_mday, 0);
// handle->control_write(0xa4, (uint16_t)(1 + sys_time.tm_wday), 0);
handle->control_write(0xa5, (uint16_t)sys_time.tm_hour, 0);
handle->control_write(0xa6, (uint16_t)sys_time.tm_min, 0);
handle->control_write(0xa7, (uint16_t)sys_time.tm_sec, 0);
}
struct tm Panda::get_rtc() {
@ -284,7 +78,7 @@ struct tm Panda::get_rtc() {
uint8_t second;
} rtc_time = {0};
usb_read(0xa0, 0, 0, (unsigned char*)&rtc_time, sizeof(rtc_time));
handle->control_read(0xa0, 0, 0, (unsigned char*)&rtc_time, sizeof(rtc_time));
struct tm new_time = { 0 };
new_time.tm_year = rtc_time.year - 1900; // tm struct has year defined as years since 1900
@ -298,70 +92,70 @@ struct tm Panda::get_rtc() {
}
void Panda::set_fan_speed(uint16_t fan_speed) {
usb_write(0xb1, fan_speed, 0);
handle->control_write(0xb1, fan_speed, 0);
}
uint16_t Panda::get_fan_speed() {
uint16_t fan_speed_rpm = 0;
usb_read(0xb2, 0, 0, (unsigned char*)&fan_speed_rpm, sizeof(fan_speed_rpm));
handle->control_read(0xb2, 0, 0, (unsigned char*)&fan_speed_rpm, sizeof(fan_speed_rpm));
return fan_speed_rpm;
}
void Panda::set_ir_pwr(uint16_t ir_pwr) {
usb_write(0xb0, ir_pwr, 0);
handle->control_write(0xb0, ir_pwr, 0);
}
std::optional<health_t> Panda::get_state() {
health_t health {0};
int err = usb_read(0xd2, 0, 0, (unsigned char*)&health, sizeof(health));
int err = handle->control_read(0xd2, 0, 0, (unsigned char*)&health, sizeof(health));
return err >= 0 ? std::make_optional(health) : std::nullopt;
}
std::optional<can_health_t> Panda::get_can_state(uint16_t can_number) {
can_health_t can_health {0};
int err = usb_read(0xc2, can_number, 0, (unsigned char*)&can_health, sizeof(can_health));
int err = handle->control_read(0xc2, can_number, 0, (unsigned char*)&can_health, sizeof(can_health));
return err >= 0 ? std::make_optional(can_health) : std::nullopt;
}
void Panda::set_loopback(bool loopback) {
usb_write(0xe5, loopback, 0);
handle->control_write(0xe5, loopback, 0);
}
std::optional<std::vector<uint8_t>> Panda::get_firmware_version() {
std::vector<uint8_t> fw_sig_buf(128);
int read_1 = usb_read(0xd3, 0, 0, &fw_sig_buf[0], 64);
int read_2 = usb_read(0xd4, 0, 0, &fw_sig_buf[64], 64);
int read_1 = handle->control_read(0xd3, 0, 0, &fw_sig_buf[0], 64);
int read_2 = handle->control_read(0xd4, 0, 0, &fw_sig_buf[64], 64);
return ((read_1 == 64) && (read_2 == 64)) ? std::make_optional(fw_sig_buf) : std::nullopt;
}
std::optional<std::string> Panda::get_serial() {
char serial_buf[17] = {'\0'};
int err = usb_read(0xd0, 0, 0, (uint8_t*)serial_buf, 16);
int err = handle->control_read(0xd0, 0, 0, (uint8_t*)serial_buf, 16);
return err >= 0 ? std::make_optional(serial_buf) : std::nullopt;
}
void Panda::set_power_saving(bool power_saving) {
usb_write(0xe7, power_saving, 0);
handle->control_write(0xe7, power_saving, 0);
}
void Panda::enable_deepsleep() {
usb_write(0xfb, 0, 0);
handle->control_write(0xfb, 0, 0);
}
void Panda::send_heartbeat(bool engaged) {
usb_write(0xf3, engaged, 0);
handle->control_write(0xf3, engaged, 0);
}
void Panda::set_can_speed_kbps(uint16_t bus, uint16_t speed) {
usb_write(0xde, bus, (speed * 10));
handle->control_write(0xde, bus, (speed * 10));
}
void Panda::set_data_speed_kbps(uint16_t bus, uint16_t speed) {
usb_write(0xf9, bus, (speed * 10));
handle->control_write(0xf9, bus, (speed * 10));
}
void Panda::set_canfd_non_iso(uint16_t bus, bool non_iso) {
usb_write(0xfc, bus, non_iso);
handle->control_write(0xfc, bus, non_iso);
}
static uint8_t len_to_dlc(uint8_t len) {
@ -399,8 +193,7 @@ void Panda::pack_can_buffer(const capnp::List<cereal::CanData>::Reader &can_data
}
auto can_data = cmsg.getDat();
uint8_t data_len_code = len_to_dlc(can_data.size());
assert(can_data.size() <= ((hw_type == cereal::PandaState::PandaType::RED_PANDA ||
hw_type == cereal::PandaState::PandaType::RED_PANDA_V2) ? 64 : 8));
assert(can_data.size() <= 64);
assert(can_data.size() == dlc_to_len[data_len_code]);
can_header header;
@ -423,14 +216,14 @@ void Panda::pack_can_buffer(const capnp::List<cereal::CanData>::Reader &can_data
void Panda::can_send(capnp::List<cereal::CanData>::Reader can_data_list) {
pack_can_buffer(can_data_list, [=](uint8_t* data, size_t size) {
usb_bulk_write(3, data, size, 5);
handle->bulk_write(3, data, size, 5);
});
}
bool Panda::can_receive(std::vector<can_frame>& out_vec) {
uint8_t data[RECV_SIZE];
int recv = usb_bulk_read(0x81, (uint8_t*)data, RECV_SIZE);
if (!comms_healthy) {
int recv = handle->bulk_read(0x81, (uint8_t*)data, RECV_SIZE);
if (!comms_healthy()) {
return false;
}
if (recv == RECV_SIZE) {
@ -445,7 +238,7 @@ bool Panda::unpack_can_buffer(uint8_t *data, int size, std::vector<can_frame> &o
for (int i = 0; i < size; i += USBPACKET_MAX_SIZE) {
if (data[i] != i / USBPACKET_MAX_SIZE) {
LOGE("CAN: MALFORMED USB RECV PACKET");
comms_healthy = false;
handle->comms_healthy = false;
return false;
}
int chunk_len = std::min(USBPACKET_MAX_SIZE, (size - i));

@ -1,26 +1,26 @@
#pragma once
#include <atomic>
#include <cstdint>
#include <ctime>
#include <functional>
#include <list>
#include <mutex>
#include <memory>
#include <optional>
#include <vector>
#include <libusb-1.0/libusb.h>
#include "cereal/gen/cpp/car.capnp.h"
#include "cereal/gen/cpp/log.capnp.h"
#include "panda/board/health.h"
#include "selfdrive/boardd/panda_comms.h"
#define TIMEOUT 0
#define PANDA_CAN_CNT 3
#define PANDA_BUS_CNT 4
#define RECV_SIZE (0x4000U)
#define USB_TX_SOFT_LIMIT (0x100U)
#define USBPACKET_MAX_SIZE (0x40)
#define RECV_SIZE (0x4000U)
#define CANPACKET_HEAD_SIZE 5U
#define CANPACKET_MAX_SIZE 72U
#define CANPACKET_REJECTED (0xC0U)
@ -37,41 +37,32 @@ struct __attribute__((packed)) can_header {
};
struct can_frame {
long address;
std::string dat;
long busTime;
long src;
long address;
std::string dat;
long busTime;
long src;
};
class Panda {
private:
libusb_context *ctx = NULL;
libusb_device_handle *dev_handle = NULL;
std::mutex usb_lock;
private:
std::unique_ptr<PandaCommsHandle> handle;
std::vector<uint8_t> recv_buf;
void handle_usb_issue(int err, const char func[]);
void cleanup();
public:
public:
Panda(std::string serial="", uint32_t bus_offset=0);
~Panda();
std::string usb_serial;
std::atomic<bool> connected = true;
std::atomic<bool> comms_healthy = true;
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();
// Static functions
static std::vector<std::string> list();
// HW communication
int usb_write(uint8_t bRequest, uint16_t wValue, uint16_t wIndex, unsigned int timeout=TIMEOUT);
int usb_read(uint8_t bRequest, uint16_t wValue, uint16_t wIndex, unsigned char *data, uint16_t wLength, unsigned int timeout=TIMEOUT);
int usb_bulk_write(unsigned char endpoint, unsigned char* data, int length, unsigned int timeout=TIMEOUT);
int usb_bulk_read(unsigned char endpoint, unsigned char* data, int length, unsigned int timeout=TIMEOUT);
// Panda functionality
cereal::PandaState::PandaType get_hw_type();
void set_safety_model(cereal::CarParams::SafetyModel safety_model, uint16_t safety_param=0U);

@ -0,0 +1,232 @@
#include "selfdrive/boardd/panda.h"
#include <cassert>
#include <stdexcept>
#include "common/swaglog.h"
static int init_usb_ctx(libusb_context **context) {
assert(context != nullptr);
int err = libusb_init(context);
if (err != 0) {
LOGE("libusb initialization error");
return err;
}
#if LIBUSB_API_VERSION >= 0x01000106
libusb_set_option(*context, LIBUSB_OPTION_LOG_LEVEL, LIBUSB_LOG_LEVEL_INFO);
#else
libusb_set_debug(*context, 3);
#endif
return err;
}
PandaUsbHandle::PandaUsbHandle(std::string serial) : PandaCommsHandle(serial) {
// init libusb
ssize_t num_devices;
libusb_device **dev_list = NULL;
int err = init_usb_ctx(&ctx);
if (err != 0) { goto fail; }
// connect by serial
num_devices = libusb_get_device_list(ctx, &dev_list);
if (num_devices < 0) { goto fail; }
for (size_t i = 0; i < num_devices; ++i) {
libusb_device_descriptor desc;
libusb_get_device_descriptor(dev_list[i], &desc);
if (desc.idVendor == 0xbbaa && desc.idProduct == 0xddcc) {
int ret = libusb_open(dev_list[i], &dev_handle);
if (dev_handle == NULL || ret < 0) { goto fail; }
unsigned char desc_serial[26] = { 0 };
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);
if (serial.empty() || serial == hw_serial) {
break;
}
libusb_close(dev_handle);
dev_handle = NULL;
}
}
if (dev_handle == NULL) goto fail;
libusb_free_device_list(dev_list, 1);
dev_list = nullptr;
if (libusb_kernel_driver_active(dev_handle, 0) == 1) {
libusb_detach_kernel_driver(dev_handle, 0);
}
err = libusb_set_configuration(dev_handle, 1);
if (err != 0) { goto fail; }
err = libusb_claim_interface(dev_handle, 0);
if (err != 0) { goto fail; }
return;
fail:
if (dev_list != NULL) {
libusb_free_device_list(dev_list, 1);
}
cleanup();
throw std::runtime_error("Error connecting to panda");
}
PandaUsbHandle::~PandaUsbHandle() {
std::lock_guard lk(hw_lock);
cleanup();
connected = false;
}
void PandaUsbHandle::cleanup() {
if (dev_handle) {
libusb_release_interface(dev_handle, 0);
libusb_close(dev_handle);
}
if (ctx) {
libusb_exit(ctx);
}
}
std::vector<std::string> PandaUsbHandle::list() {
// init libusb
ssize_t num_devices;
libusb_context *context = NULL;
libusb_device **dev_list = NULL;
std::vector<std::string> serials;
int err = init_usb_ctx(&context);
if (err != 0) { return serials; }
num_devices = libusb_get_device_list(context, &dev_list);
if (num_devices < 0) {
LOGE("libusb can't get device list");
goto finish;
}
for (size_t i = 0; i < num_devices; ++i) {
libusb_device *device = dev_list[i];
libusb_device_descriptor desc;
libusb_get_device_descriptor(device, &desc);
if (desc.idVendor == 0xbbaa && desc.idProduct == 0xddcc) {
libusb_device_handle *handle = NULL;
int ret = libusb_open(device, &handle);
if (ret < 0) { goto finish; }
unsigned char desc_serial[26] = { 0 };
ret = libusb_get_string_descriptor_ascii(handle, desc.iSerialNumber, desc_serial, std::size(desc_serial));
libusb_close(handle);
if (ret < 0) { goto finish; }
serials.push_back(std::string((char *)desc_serial, ret).c_str());
}
}
finish:
if (dev_list != NULL) {
libusb_free_device_list(dev_list, 1);
}
if (context) {
libusb_exit(context);
}
return serials;
}
void PandaUsbHandle::handle_usb_issue(int err, const char func[]) {
LOGE_100("usb error %d \"%s\" in %s", err, libusb_strerror((enum libusb_error)err), func);
if (err == LIBUSB_ERROR_NO_DEVICE) {
LOGE("lost connection");
connected = false;
}
// TODO: check other errors, is simply retrying okay?
}
int PandaUsbHandle::control_write(uint8_t bRequest, uint16_t wValue, uint16_t wIndex, unsigned int timeout) {
int err;
const uint8_t bmRequestType = LIBUSB_ENDPOINT_OUT | LIBUSB_REQUEST_TYPE_VENDOR | LIBUSB_RECIPIENT_DEVICE;
if (!connected) {
return LIBUSB_ERROR_NO_DEVICE;
}
std::lock_guard lk(hw_lock);
do {
err = libusb_control_transfer(dev_handle, bmRequestType, bRequest, wValue, wIndex, NULL, 0, timeout);
if (err < 0) handle_usb_issue(err, __func__);
} while (err < 0 && connected);
return err;
}
int PandaUsbHandle::control_read(uint8_t bRequest, uint16_t wValue, uint16_t wIndex, unsigned char *data, uint16_t wLength, unsigned int timeout) {
int err;
const uint8_t bmRequestType = LIBUSB_ENDPOINT_IN | LIBUSB_REQUEST_TYPE_VENDOR | LIBUSB_RECIPIENT_DEVICE;
if (!connected) {
return LIBUSB_ERROR_NO_DEVICE;
}
std::lock_guard lk(hw_lock);
do {
err = libusb_control_transfer(dev_handle, bmRequestType, bRequest, wValue, wIndex, data, wLength, timeout);
if (err < 0) handle_usb_issue(err, __func__);
} while (err < 0 && connected);
return err;
}
int PandaUsbHandle::bulk_write(unsigned char endpoint, unsigned char* data, int length, unsigned int timeout) {
int err;
int transferred = 0;
if (!connected) {
return 0;
}
std::lock_guard lk(hw_lock);
do {
// Try sending can messages. If the receive buffer on the panda is full it will NAK
// and libusb will try again. After 5ms, it will time out. We will drop the messages.
err = libusb_bulk_transfer(dev_handle, endpoint, data, length, &transferred, timeout);
if (err == LIBUSB_ERROR_TIMEOUT) {
LOGW("Transmit buffer full");
break;
} else if (err != 0 || length != transferred) {
handle_usb_issue(err, __func__);
}
} while(err != 0 && connected);
return transferred;
}
int PandaUsbHandle::bulk_read(unsigned char endpoint, unsigned char* data, int length, unsigned int timeout) {
int err;
int transferred = 0;
if (!connected) {
return 0;
}
std::lock_guard lk(hw_lock);
do {
err = libusb_bulk_transfer(dev_handle, endpoint, data, length, &transferred, timeout);
if (err == LIBUSB_ERROR_TIMEOUT) {
break; // timeout is okay to exit, recv still happened
} else if (err == LIBUSB_ERROR_OVERFLOW) {
comms_healthy = false;
LOGE_100("overflow got 0x%x", transferred);
} else if (err != 0) {
handle_usb_issue(err, __func__);
}
} while(err != 0 && connected);
return transferred;
}

@ -0,0 +1,80 @@
#pragma once
#include <mutex>
#include <atomic>
#include <cstdint>
#include <vector>
#include <linux/spi/spidev.h>
#include <libusb-1.0/libusb.h>
#define TIMEOUT 0
#define SPI_BUF_SIZE 1024
const bool PANDA_NO_RETRY = getenv("PANDA_NO_RETRY");
// comms base class
class PandaCommsHandle {
public:
PandaCommsHandle(std::string serial) {};
virtual ~PandaCommsHandle() {};
virtual void cleanup() = 0;
std::atomic<bool> connected = true;
std::atomic<bool> comms_healthy = true;
static std::vector<std::string> list();
// HW communication
virtual int control_write(uint8_t request, uint16_t param1, uint16_t param2, unsigned int timeout=TIMEOUT) = 0;
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 {
public:
PandaUsbHandle(std::string serial);
~PandaUsbHandle();
int control_write(uint8_t request, uint16_t param1, uint16_t param2, unsigned int timeout=TIMEOUT);
int control_read(uint8_t request, uint16_t param1, uint16_t param2, unsigned char *data, uint16_t length, unsigned int timeout=TIMEOUT);
int bulk_write(unsigned char endpoint, unsigned char* data, int length, unsigned int timeout=TIMEOUT);
int bulk_read(unsigned char endpoint, unsigned char* data, int length, unsigned int timeout=TIMEOUT);
void cleanup();
static std::vector<std::string> list();
private:
libusb_context *ctx = NULL;
libusb_device_handle *dev_handle = NULL;
std::vector<uint8_t> recv_buf;
void handle_usb_issue(int err, const char func[]);
};
class PandaSpiHandle : public PandaCommsHandle {
public:
PandaSpiHandle(std::string serial);
~PandaSpiHandle();
int control_write(uint8_t request, uint16_t param1, uint16_t param2, unsigned int timeout=TIMEOUT);
int control_read(uint8_t request, uint16_t param1, uint16_t param2, unsigned char *data, uint16_t length, unsigned int timeout=TIMEOUT);
int bulk_write(unsigned char endpoint, unsigned char* data, int length, unsigned int timeout=TIMEOUT);
int bulk_read(unsigned char endpoint, unsigned char* data, int length, unsigned int timeout=TIMEOUT);
void cleanup();
static std::vector<std::string> list();
private:
int spi_fd = -1;
uint8_t tx_buf[SPI_BUF_SIZE];
uint8_t rx_buf[SPI_BUF_SIZE];
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);
};

@ -0,0 +1,287 @@
#include <sys/ioctl.h>
#include <linux/spi/spidev.h>
#include <cassert>
#include <cmath>
#include <cstring>
#include "common/util.h"
#include "common/swaglog.h"
#include "panda/board/comms_definitions.h"
#include "selfdrive/boardd/panda_comms.h"
#define SPI_SYNC 0x5AU
#define SPI_HACK 0x79U
#define SPI_DACK 0x85U
#define SPI_NACK 0x1FU
#define SPI_CHECKSUM_START 0xABU
struct __attribute__((packed)) spi_header {
uint8_t sync;
uint8_t endpoint;
uint16_t tx_len;
uint16_t max_rx_len;
};
PandaSpiHandle::PandaSpiHandle(std::string serial) : PandaCommsHandle(serial) {
LOGD("opening SPI panda: %s", serial.c_str());
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);
if (spi_fd < 0) {
LOGE("failed opening SPI device %d", err);
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);
goto fail;
}
err = util::safe_ioctl(spi_fd, SPI_IOC_WR_MAX_SPEED_HZ, &spi_speed);
if (err < 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) {
LOGE("failed setting SPI bits per word");
goto fail;
}
return;
fail:
cleanup();
throw std::runtime_error("Error connecting to panda");
}
PandaSpiHandle::~PandaSpiHandle() {
std::lock_guard lk(hw_lock);
cleanup();
}
void PandaSpiHandle::cleanup() {
if (spi_fd != -1) {
close(spi_fd);
spi_fd = -1;
}
}
int PandaSpiHandle::control_write(uint8_t request, uint16_t param1, uint16_t param2, unsigned int timeout) {
ControlPacket_t packet = {
.request = request,
.param1 = param1,
.param2 = param2,
.length = 0
};
return spi_transfer_retry(0, (uint8_t *) &packet, sizeof(packet), NULL, 0);
}
int PandaSpiHandle::control_read(uint8_t request, uint16_t param1, uint16_t param2, unsigned char *data, uint16_t length, unsigned int timeout) {
ControlPacket_t packet = {
.request = request,
.param1 = param1,
.param2 = param2,
.length = length
};
return spi_transfer_retry(0, (uint8_t *) &packet, sizeof(packet), data, length);
}
int PandaSpiHandle::bulk_write(unsigned char endpoint, unsigned char* data, int length, unsigned int timeout) {
return bulk_transfer(endpoint, data, length, NULL, 0);
}
int PandaSpiHandle::bulk_read(unsigned char endpoint, unsigned char* data, int length, unsigned int timeout) {
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;
int ret = 0;
uint16_t length = (tx_data != NULL) ? tx_len : rx_len;
for (int i = 0; i < (int)std::ceil((float)length / xfer_size); i++) {
int d;
if (tx_data != NULL) {
int len = std::min(xfer_size, tx_len - (xfer_size * i));
d = spi_transfer_retry(endpoint, tx_data + (xfer_size * i), len, NULL, 0);
} else {
d = spi_transfer_retry(endpoint, NULL, 0, rx_data + (xfer_size * i), xfer_size);
}
if (d < 0) {
LOGE("SPI: bulk transfer failed with %d", d);
comms_healthy = false;
return -1;
}
ret += d;
if ((rx_data != NULL) && d < xfer_size) {
break;
}
}
return ret;
}
std::vector<std::string> PandaSpiHandle::list() {
// TODO: list all pandas available over SPI
return {};
}
void add_checksum(uint8_t *data, int data_len) {
data[data_len] = SPI_CHECKSUM_START;
for (int i=0; i < data_len; i++) {
data[data_len] ^= data[i];
}
}
bool check_checksum(uint8_t *data, int data_len) {
uint8_t checksum = SPI_CHECKSUM_START;
for (uint16_t i = 0U; i < data_len; i++) {
checksum ^= data[i];
}
return checksum == 0U;
}
int PandaSpiHandle::spi_transfer_retry(uint8_t endpoint, uint8_t *tx_data, uint16_t tx_len, uint8_t *rx_data, uint16_t max_rx_len) {
int ret;
std::lock_guard lk(hw_lock);
do {
// TODO: handle error
ret = spi_transfer(endpoint, tx_data, tx_len, rx_data, max_rx_len);
} while (ret < 0 && connected && !PANDA_NO_RETRY);
return ret;
}
int PandaSpiHandle::wait_for_ack(spi_ioc_transfer &transfer, uint8_t ack) {
// TODO: add timeout?
while (true) {
int ret = util::safe_ioctl(spi_fd, SPI_IOC_MESSAGE(1), &transfer);
if (ret < 0) {
LOGE("SPI: failed to send ACK request");
return ret;
}
if (rx_buf[0] == ack) {
break;
} else if (rx_buf[0] == SPI_NACK) {
LOGW("SPI: got NACK");
return -1;
}
}
return 0;
}
int PandaSpiHandle::spi_transfer(uint8_t endpoint, uint8_t *tx_data, uint16_t tx_len, uint8_t *rx_data, uint16_t max_rx_len) {
int ret;
uint16_t rx_data_len;
// needs to be less, since we need to have space for the checksum
assert(tx_len < SPI_BUF_SIZE);
assert(max_rx_len < SPI_BUF_SIZE);
spi_header header = {
.sync = SPI_SYNC,
.endpoint = endpoint,
.tx_len = tx_len,
.max_rx_len = max_rx_len
};
spi_ioc_transfer transfer = {
.tx_buf = (uint64_t)tx_buf,
.rx_buf = (uint64_t)rx_buf
};
// Send header
memcpy(tx_buf, &header, sizeof(header));
add_checksum(tx_buf, sizeof(header));
transfer.len = sizeof(header) + 1;
ret = util::safe_ioctl(spi_fd, SPI_IOC_MESSAGE(1), &transfer);
if (ret < 0) {
LOGE("SPI: failed to send header");
goto transfer_fail;
}
// Wait for (N)ACK
tx_buf[0] = 0x12;
transfer.len = 1;
ret = wait_for_ack(transfer, SPI_HACK);
if (ret < 0) {
goto transfer_fail;
}
// Send data
if (tx_data != NULL) {
memcpy(tx_buf, tx_data, tx_len);
}
add_checksum(tx_buf, tx_len);
transfer.len = tx_len + 1;
ret = util::safe_ioctl(spi_fd, SPI_IOC_MESSAGE(1), &transfer);
if (ret < 0) {
LOGE("SPI: failed to send data");
goto transfer_fail;
}
// Wait for (N)ACK
tx_buf[0] = 0xab;
transfer.len = 1;
ret = wait_for_ack(transfer, SPI_DACK);
if (ret < 0) {
goto transfer_fail;
}
// Read data len
transfer.len = 2;
transfer.rx_buf = (uint64_t)(rx_buf + 1);
ret = util::safe_ioctl(spi_fd, SPI_IOC_MESSAGE(1), &transfer);
if (ret < 0) {
LOGE("SPI: failed to read rx data len");
goto transfer_fail;
}
rx_data_len = *(uint16_t *)(rx_buf+1);
assert(rx_data_len < SPI_BUF_SIZE);
// Read data
transfer.len = rx_data_len + 1;
transfer.rx_buf = (uint64_t)(rx_buf + 2 + 1);
ret = util::safe_ioctl(spi_fd, SPI_IOC_MESSAGE(1), &transfer);
if (ret < 0) {
LOGE("SPI: failed to read rx data");
goto transfer_fail;
}
if (!check_checksum(rx_buf, rx_data_len + 4)) {
LOGE("SPI: bad checksum");
goto transfer_fail;
}
if (rx_data != NULL) {
memcpy(rx_data, rx_buf + 3, rx_data_len);
}
return rx_data_len;
transfer_fail:
return ret;
}

@ -26,6 +26,12 @@ CAR_INFO: Dict[str, CarInfo] = {
CAR.BODY: CarInfo("comma body", package="All"),
}
FINGERPRINTS = {
CAR.BODY: [{
513: 8, 516: 8, 514: 3, 515: 4,
}],
}
FW_QUERY_CONFIG = FwQueryConfig(
requests=[
Request(
@ -40,10 +46,13 @@ FW_VERSIONS = {
CAR.BODY: {
(Ecu.engine, 0x720, None): [
b'0.0.01',
b'02/27/2022'
b'02/27/2022',
b'0.3.00a',
],
# git hash of the firmware used
(Ecu.debug, 0x721, None): [
b'166bd860' # git hash of the firmware used
b'166bd860',
b'dc780f85',
],
},
}

@ -40,6 +40,7 @@ def get_all_car_info() -> List[CarInfo]:
for _car_info in car_info:
if not hasattr(_car_info, "row"):
_car_info.init_make(CP)
_car_info.init(CP, footnotes)
all_car_info.append(_car_info)

@ -73,12 +73,11 @@ CarFootnote = namedtuple("CarFootnote", ["text", "column", "docs_only"], default
class CommonFootnote(Enum):
EXP_LONG_AVAIL = CarFootnote(
"Experimental openpilot longitudinal control is available behind a toggle; the toggle is only available in non-release branches such as `master-ci`. " +
"Using openpilot longitudinal may disable Automatic Emergency Braking (AEB).",
"Experimental openpilot longitudinal control is available behind a toggle; the toggle is only available in non-release branches such as `devel` or `master-ci`. ",
Column.LONGITUDINAL, docs_only=True)
EXP_LONG_DSU = CarFootnote(
"When the Driver Support Unit (DSU) is disconnected, openpilot Adaptive Cruise Control (ACC) will replace " +
"stock Adaptive Cruise Control (ACC). <b><i>NOTE: disconnecting the DSU disables Automatic Emergency Braking (AEB).</i></b>",
"By 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. <b><i>NOTE: disconnecting the DSU disables Automatic Emergency Braking (AEB).</i></b>",
Column.LONGITUDINAL)
@ -173,6 +172,9 @@ class CarInfo:
return self
def init_make(self, CP: car.CarParams):
"""CarInfo subclasses can add make-specific logic for harness selection, footnotes, etc."""
def get_detail_sentence(self, CP):
if not CP.notCar:
sentence_builder = "openpilot upgrades your <strong>{car_model}</strong> with automated lane centering{alc} and adaptive cruise control{acc}."

@ -51,16 +51,19 @@ class CarState(CarStateBase):
else:
ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(pt_cp.vl["ECMPRDNL2"]["PRNDL2"], None))
# Some Volt 2016-17 have loose brake pedal push rod retainers which causes the ECM to believe
# that the brake is being intermittently pressed without user interaction.
# To avoid a cruise fault we need to match the ECM's brake pressed signal and threshold
# https://static.nhtsa.gov/odi/tsbs/2017/MC-10137629-9999.pdf
ret.brake = pt_cp.vl["ECMAcceleratorPos"]["BrakePedalPos"]
ret.brakePressed = ret.brake >= 8
if self.CP.networkLocation == NetworkLocation.fwdCamera:
ret.brakePressed = pt_cp.vl["ECMEngineStatus"]["BrakePressed"] != 0
else:
# Some Volt 2016-17 have loose brake pedal push rod retainers which causes the ECM to believe
# that the brake is being intermittently pressed without user interaction.
# To avoid a cruise fault we need to use a conservative brake position threshold
# https://static.nhtsa.gov/odi/tsbs/2017/MC-10137629-9999.pdf
ret.brakePressed = ret.brake >= 8
# Regen braking is braking
if self.CP.transmissionType == TransmissionType.direct:
ret.brakePressed = ret.brakePressed or pt_cp.vl["EBCMRegenPaddle"]["RegenPaddle"] != 0
ret.regenBraking = pt_cp.vl["EBCMRegenPaddle"]["RegenPaddle"] != 0
ret.gas = pt_cp.vl["AcceleratorPedal2"]["AcceleratorPedal2"] / 254.
ret.gasPressed = ret.gas > 1e-5
@ -154,6 +157,7 @@ class CarState(CarStateBase):
("TractionControlOn", "ESPStatus"),
("ParkBrake", "VehicleIgnitionAlt"),
("CruiseMainOn", "ECMEngineStatus"),
("BrakePressed", "ECMEngineStatus"),
]
checks = [

@ -211,17 +211,20 @@ class CarInterface(CarInterfaceBase):
ret = self.CS.update(self.cp, self.cp_cam, self.cp_loopback)
if self.CS.cruise_buttons != self.CS.prev_cruise_buttons and self.CS.prev_cruise_buttons != CruiseButtons.INIT:
be = create_button_event(self.CS.cruise_buttons, self.CS.prev_cruise_buttons, BUTTONS_DICT, CruiseButtons.UNPRESS)
buttonEvents = [create_button_event(self.CS.cruise_buttons, self.CS.prev_cruise_buttons, BUTTONS_DICT, CruiseButtons.UNPRESS)]
# Handle ACCButtons changing buttons mid-press
if self.CS.cruise_buttons != CruiseButtons.UNPRESS and self.CS.prev_cruise_buttons != CruiseButtons.UNPRESS:
buttonEvents.append(create_button_event(CruiseButtons.UNPRESS, self.CS.prev_cruise_buttons, BUTTONS_DICT, CruiseButtons.UNPRESS))
# Suppress resume button if we're resuming from stop so we don't adjust speed.
if be.type == ButtonType.accelCruise and (ret.cruiseState.enabled and ret.standstill):
be.type = ButtonType.unknown
ret.buttonEvents = [be]
ret.buttonEvents = buttonEvents
# The ECM allows enabling on falling edge of set, but only rising edge of resume
events = self.create_common_events(ret, extra_gears=[GearShifter.sport, GearShifter.low,
GearShifter.eco, GearShifter.manumatic],
pcm_enable=self.CP.pcmCruise)
pcm_enable=self.CP.pcmCruise, enable_buttons=(ButtonType.decelCruise,))
if not self.CP.pcmCruise:
if any(b.type == ButtonType.accelCruise and b.pressed for b in ret.buttonEvents):
events.add(EventName.buttonEnable)
# Enabling at a standstill with brake is allowed
# TODO: verify 17 Volt can enable for the first time at a stop and allow for all GMs

@ -1,5 +1,5 @@
from collections import defaultdict
from dataclasses import dataclass, field
from dataclasses import dataclass
from enum import Enum
from typing import Dict, List, Union
@ -84,25 +84,30 @@ class Footnote(Enum):
@dataclass
class GMCarInfo(CarInfo):
package: str = "Adaptive Cruise Control (ACC)"
harness: Enum = Harness.obd_ii
footnotes: List[Enum] = field(default_factory=lambda: [Footnote.OBD_II])
def init_make(self, CP: car.CarParams):
if CP.networkLocation == car.CarParams.NetworkLocation.fwdCamera:
self.harness = Harness.gm
else:
self.harness = Harness.obd_ii
self.footnotes.append(Footnote.OBD_II)
CAR_INFO: Dict[str, Union[GMCarInfo, List[GMCarInfo]]] = {
CAR.HOLDEN_ASTRA: GMCarInfo("Holden Astra 2017"),
CAR.VOLT: GMCarInfo("Chevrolet Volt 2017-18", min_enable_speed=0),
CAR.VOLT: GMCarInfo("Chevrolet Volt 2017-18", min_enable_speed=0, video_link="https://youtu.be/QeMCN_4TFfQ"),
CAR.CADILLAC_ATS: GMCarInfo("Cadillac ATS Premium Performance 2018"),
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_ESV: GMCarInfo("Cadillac Escalade ESV 2016", "Adaptive Cruise Control (ACC) & LKAS"),
CAR.BOLT_EV: GMCarInfo("Chevrolet Bolt EV 2022-23", footnotes=[], harness=Harness.gm),
CAR.BOLT_EUV: GMCarInfo("Chevrolet Bolt EUV 2022-23", "Premier or Premier Redline Trim without Super Cruise Package", "https://youtu.be/xvwzGMUA210", footnotes=[], harness=Harness.gm),
CAR.BOLT_EV: GMCarInfo("Chevrolet Bolt EV 2022-23"),
CAR.BOLT_EUV: GMCarInfo("Chevrolet Bolt EUV 2022-23", "Premier or Premier Redline Trim without Super Cruise Package", "https://youtu.be/xvwzGMUA210"),
CAR.SILVERADO: [
GMCarInfo("Chevrolet Silverado 1500 2020-21", "Safety Package II", footnotes=[], harness=Harness.gm),
GMCarInfo("GMC Sierra 1500 2020-21", "Driver Alert Package II", footnotes=[], harness=Harness.gm),
GMCarInfo("Chevrolet Silverado 1500 2020-21", "Safety Package II"),
GMCarInfo("GMC Sierra 1500 2020-21", "Driver Alert Package II", "https://youtu.be/5HbNoBLzRwE"),
],
CAR.EQUINOX: GMCarInfo("Chevrolet Equinox 2019-22", footnotes=[], harness=Harness.gm),
CAR.EQUINOX: GMCarInfo("Chevrolet Equinox 2019-22"),
}

@ -99,6 +99,12 @@ HUDData = namedtuple("HUDData",
"lanes_visible", "fcw", "acc_alert", "steer_required"])
def rate_limit_steer(new_steer, last_steer):
# TODO just hardcoded ramp to min/max in 0.33s for all Honda
MAX_DELTA = 3 * DT_CTRL
return clip(new_steer, last_steer - MAX_DELTA, last_steer + MAX_DELTA)
class CarController:
def __init__(self, dbc_name, CP, VM):
self.CP = CP
@ -116,6 +122,7 @@ class CarController:
self.speed = 0.0
self.gas = 0.0
self.brake = 0.0
self.last_steer = 0.0
def update(self, CC, CS):
actuators = CC.actuators
@ -130,6 +137,10 @@ class CarController:
accel = 0.0
gas, brake = 0.0, 0.0
# *** rate limit steer ***
limited_steer = rate_limit_steer(actuators.steer, self.last_steer)
self.last_steer = limited_steer
# *** apply brake hysteresis ***
pre_limit_brake, self.braking, self.brake_steady = actuator_hysteresis(brake, self.braking, self.brake_steady,
CS.out.vEgo, self.CP.carFingerprint)
@ -143,7 +154,7 @@ class CarController:
# **** process the car messages ****
# steer torque is converted back to CAN reference (positive when steering right)
apply_steer = int(interp(-actuators.steer * self.params.STEER_MAX,
apply_steer = int(interp(-limited_steer * self.params.STEER_MAX,
self.params.STEER_LOOKUP_BP, self.params.STEER_LOOKUP_V))
# Send CAN commands
@ -250,6 +261,7 @@ class CarController:
new_actuators.accel = self.accel
new_actuators.gas = self.gas
new_actuators.brake = self.brake
new_actuators.steer = self.last_steer
self.frame += 1
return new_actuators, can_sends

@ -106,40 +106,46 @@ class Footnote(Enum):
class HondaCarInfo(CarInfo):
package: str = "Honda Sensing"
def init_make(self, CP: car.CarParams):
if CP.carFingerprint in HONDA_BOSCH:
self.harness = Harness.bosch_b if CP.carFingerprint in HONDA_BOSCH_RADARLESS else Harness.bosch_a
else:
self.harness = Harness.nidec
CAR_INFO: Dict[str, Optional[Union[HondaCarInfo, List[HondaCarInfo]]]] = {
CAR.ACCORD: [
HondaCarInfo("Honda Accord 2018-22", "All", "https://www.youtube.com/watch?v=mrUwlj3Mi58", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch_a),
HondaCarInfo("Honda Inspire 2018", "All", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch_a),
HondaCarInfo("Honda Accord 2018-22", "All", "https://www.youtube.com/watch?v=mrUwlj3Mi58", min_steer_speed=3. * CV.MPH_TO_MS),
HondaCarInfo("Honda Inspire 2018", "All", min_steer_speed=3. * CV.MPH_TO_MS),
],
CAR.ACCORDH: HondaCarInfo("Honda Accord Hybrid 2018-22", "All", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch_a),
CAR.CIVIC: HondaCarInfo("Honda Civic 2016-18", min_steer_speed=12. * CV.MPH_TO_MS, harness=Harness.nidec, video_link="https://youtu.be/-IkImTe1NYE"),
CAR.ACCORDH: HondaCarInfo("Honda Accord Hybrid 2018-22", "All", min_steer_speed=3. * CV.MPH_TO_MS),
CAR.CIVIC: HondaCarInfo("Honda Civic 2016-18", min_steer_speed=12. * CV.MPH_TO_MS, video_link="https://youtu.be/-IkImTe1NYE"),
CAR.CIVIC_BOSCH: [
HondaCarInfo("Honda Civic 2019-21", "All", "https://www.youtube.com/watch?v=4Iz1Mz5LGF8", [Footnote.CIVIC_DIESEL], 2. * CV.MPH_TO_MS, harness=Harness.bosch_a),
HondaCarInfo("Honda Civic Hatchback 2017-21", min_steer_speed=12. * CV.MPH_TO_MS, harness=Harness.bosch_a),
HondaCarInfo("Honda Civic 2019-21", "All", "https://www.youtube.com/watch?v=4Iz1Mz5LGF8", [Footnote.CIVIC_DIESEL], 2. * CV.MPH_TO_MS),
HondaCarInfo("Honda Civic Hatchback 2017-21", min_steer_speed=12. * CV.MPH_TO_MS),
],
CAR.CIVIC_BOSCH_DIESEL: None, # same platform
CAR.CIVIC_2022: [
HondaCarInfo("Honda Civic 2022", "All", harness=Harness.bosch_b),
HondaCarInfo("Honda Civic Hatchback 2022", "All", harness=Harness.bosch_b),
HondaCarInfo("Honda Civic 2022", "All"),
HondaCarInfo("Honda Civic Hatchback 2022", "All"),
],
CAR.ACURA_ILX: HondaCarInfo("Acura ILX 2016-19", "AcuraWatch Plus", min_steer_speed=25. * CV.MPH_TO_MS, harness=Harness.nidec),
CAR.CRV: HondaCarInfo("Honda CR-V 2015-16", "Touring Trim", min_steer_speed=12. * CV.MPH_TO_MS, harness=Harness.nidec),
CAR.CRV_5G: HondaCarInfo("Honda CR-V 2017-22", min_steer_speed=12. * CV.MPH_TO_MS, harness=Harness.bosch_a),
CAR.ACURA_ILX: HondaCarInfo("Acura ILX 2016-19", "AcuraWatch Plus", min_steer_speed=25. * CV.MPH_TO_MS),
CAR.CRV: HondaCarInfo("Honda CR-V 2015-16", "Touring Trim", min_steer_speed=12. * CV.MPH_TO_MS),
CAR.CRV_5G: HondaCarInfo("Honda CR-V 2017-22", min_steer_speed=12. * CV.MPH_TO_MS),
CAR.CRV_EU: None, # HondaCarInfo("Honda CR-V EU", "Touring"), # Euro version of CRV Touring
CAR.CRV_HYBRID: HondaCarInfo("Honda CR-V Hybrid 2017-19", min_steer_speed=12. * CV.MPH_TO_MS, harness=Harness.bosch_a),
CAR.FIT: HondaCarInfo("Honda Fit 2018-20", min_steer_speed=12. * CV.MPH_TO_MS, harness=Harness.nidec),
CAR.FREED: HondaCarInfo("Honda Freed 2020", min_steer_speed=12. * CV.MPH_TO_MS, harness=Harness.nidec),
CAR.HRV: HondaCarInfo("Honda HR-V 2019-22", min_steer_speed=12. * CV.MPH_TO_MS, harness=Harness.nidec),
CAR.ODYSSEY: HondaCarInfo("Honda Odyssey 2018-20", harness=Harness.nidec),
CAR.CRV_HYBRID: HondaCarInfo("Honda CR-V Hybrid 2017-19", min_steer_speed=12. * CV.MPH_TO_MS),
CAR.FIT: HondaCarInfo("Honda Fit 2018-20", min_steer_speed=12. * CV.MPH_TO_MS),
CAR.FREED: HondaCarInfo("Honda Freed 2020", min_steer_speed=12. * CV.MPH_TO_MS),
CAR.HRV: HondaCarInfo("Honda HR-V 2019-22", min_steer_speed=12. * CV.MPH_TO_MS),
CAR.ODYSSEY: HondaCarInfo("Honda Odyssey 2018-20"),
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, harness=Harness.nidec),
CAR.ACURA_RDX_3G: HondaCarInfo("Acura RDX 2019-22", "All", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch_a),
CAR.PILOT: HondaCarInfo("Honda Pilot 2016-22", min_steer_speed=12. * CV.MPH_TO_MS, harness=Harness.nidec),
CAR.PASSPORT: HondaCarInfo("Honda Passport 2019-21", "All", min_steer_speed=12. * CV.MPH_TO_MS, harness=Harness.nidec),
CAR.RIDGELINE: HondaCarInfo("Honda Ridgeline 2017-22", min_steer_speed=12. * CV.MPH_TO_MS, harness=Harness.nidec),
CAR.INSIGHT: HondaCarInfo("Honda Insight 2019-22", "All", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch_a),
CAR.HONDA_E: HondaCarInfo("Honda e 2020", "All", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch_a),
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.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),
}
FW_QUERY_CONFIG = FwQueryConfig(

@ -85,7 +85,7 @@ class CarController:
# *** common hyundai stuff ***
# tester present - w/ no response (keeps relevant ECU disabled)
if self.frame % 100 == 0 and self.CP.openpilotLongitudinalControl:
if self.frame % 100 == 0 and not (self.CP.flags & HyundaiFlags.CANFD_CAMERA_SCC.value) and self.CP.openpilotLongitudinalControl:
addr, bus = 0x7d0, 0
if self.CP.flags & HyundaiFlags.CANFD_HDA2.value:
addr, bus = 0x730, 5
@ -122,7 +122,8 @@ class CarController:
can_sends.append(hyundaicanfd.create_lfahda_cluster(self.packer, self.CP, CC.enabled))
if self.CP.openpilotLongitudinalControl:
can_sends.extend(hyundaicanfd.create_adrv_messages(self.packer, self.frame))
if hda2:
can_sends.extend(hyundaicanfd.create_adrv_messages(self.packer, self.frame))
if self.frame % 2 == 0:
can_sends.append(hyundaicanfd.create_acc_control(self.packer, self.CP, CC.enabled, self.accel_last, accel, stopping, CC.cruiseControl.override,
set_speed_in_units))
@ -175,7 +176,7 @@ class CarController:
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_K5_2021, CAR.IONIQ_HEV_2022, CAR.SANTA_FE_HEV_2022, CAR.GENESIS_G70_2020, CAR.SANTA_FE_PHEV_2022, CAR.KIA_STINGER_2022):
can_sends.append(hyundaican.create_lfahda_mfc(self.packer, CC.enabled))
# 5 Hz ACC options

@ -21,8 +21,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"
if CP.carFingerprint in CANFD_CAR:
self.shifter_values = can_define.dv["GEAR_SHIFTER"]["GEAR"]
self.shifter_values = can_define.dv[self.gear_msg_canfd]["GEAR"]
elif self.CP.carFingerprint in FEATURES["use_cluster_gears"]:
self.shifter_values = can_define.dv["CLU15"]["CF_Clu_Gear"]
elif self.CP.carFingerprint in FEATURES["use_tcu_gears"]:
@ -154,17 +155,21 @@ class CarState(CarStateBase):
def update_canfd(self, cp, cp_cam):
ret = car.CarState.new_message()
if self.CP.carFingerprint in EV_CAR:
ret.gas = cp.vl["ACCELERATOR"]["ACCELERATOR_PEDAL"] / 255.
elif self.CP.carFingerprint in HYBRID_CAR:
ret.gas = cp.vl["ACCELERATOR_ALT"]["ACCELERATOR_PEDAL"] / 1023.
ret.gasPressed = ret.gas > 1e-5
if self.CP.carFingerprint in (EV_CAR | HYBRID_CAR):
if self.CP.carFingerprint in EV_CAR:
ret.gas = cp.vl["ACCELERATOR"]["ACCELERATOR_PEDAL"] / 255.
else:
ret.gas = cp.vl["ACCELERATOR_ALT"]["ACCELERATOR_PEDAL"] / 1023.
ret.gasPressed = ret.gas > 1e-5
else:
ret.gasPressed = bool(cp.vl["ACCELERATOR_BRAKE_ALT"]["ACCELERATOR_PEDAL_PRESSED"])
ret.brakePressed = cp.vl["TCS"]["DriverBraking"] == 1
ret.doorOpen = cp.vl["DOORS_SEATBELTS"]["DRIVER_DOOR_OPEN"] == 1
ret.seatbeltUnlatched = cp.vl["DOORS_SEATBELTS"]["DRIVER_SEATBELT_LATCHED"] == 0
gear = cp.vl["GEAR_SHIFTER"]["GEAR"]
gear = cp.vl[self.gear_msg_canfd]["GEAR"]
ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(gear))
# TODO: figure out positions
@ -195,7 +200,7 @@ class CarState(CarStateBase):
self.is_metric = cp.vl["CLUSTER_INFO"]["DISTANCE_UNIT"] != 1
if not self.CP.openpilotLongitudinalControl:
speed_factor = CV.KPH_TO_MS if self.is_metric else CV.MPH_TO_MS
cp_cruise_info = cp if self.CP.flags & HyundaiFlags.CANFD_HDA2 else cp_cam
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)
@ -411,13 +416,14 @@ 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"
signals = [
("WHEEL_SPEED_1", "WHEEL_SPEEDS"),
("WHEEL_SPEED_2", "WHEEL_SPEEDS"),
("WHEEL_SPEED_3", "WHEEL_SPEEDS"),
("WHEEL_SPEED_4", "WHEEL_SPEEDS"),
("GEAR", "GEAR_SHIFTER"),
("GEAR", gear_msg),
("STEERING_RATE", "STEERING_SENSORS"),
("STEERING_ANGLE", "STEERING_SENSORS"),
@ -442,8 +448,7 @@ class CarState(CarStateBase):
checks = [
("WHEEL_SPEEDS", 100),
("GEAR_SHIFTER", 100),
("BRAKE", 100),
(gear_msg, 100),
("STEERING_SENSORS", 100),
("MDPS", 100),
("TCS", 50),
@ -462,7 +467,7 @@ class CarState(CarStateBase):
("BLINDSPOTS_REAR_CORNERS", 20),
]
if CP.flags & HyundaiFlags.CANFD_HDA2 and not CP.openpilotLongitudinalControl:
if not (CP.flags & HyundaiFlags.CANFD_CAMERA_SCC.value) and not CP.openpilotLongitudinalControl:
signals += [
("ACCMode", "SCC_CONTROL"),
("VSetDis", "SCC_CONTROL"),
@ -486,17 +491,26 @@ class CarState(CarStateBase):
checks += [
("ACCELERATOR_ALT", 100),
]
else:
signals += [
("ACCELERATOR_PEDAL_PRESSED", "ACCELERATOR_BRAKE_ALT"),
]
checks += [
("ACCELERATOR_BRAKE_ALT", 100),
]
bus = 5 if CP.flags & HyundaiFlags.CANFD_HDA2 else 4
return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, bus)
@staticmethod
def get_cam_can_parser_canfd(CP):
signals = []
checks = []
if CP.flags & HyundaiFlags.CANFD_HDA2:
signals = [(f"BYTE{i}", "CAM_0x2a4") for i in range(3, 24)]
checks = [("CAM_0x2a4", 20)]
else:
signals = [
signals += [(f"BYTE{i}", "CAM_0x2a4") for i in range(3, 24)]
checks += [("CAM_0x2a4", 20)]
elif CP.flags & HyundaiFlags.CANFD_CAMERA_SCC:
signals += [
("COUNTER", "SCC_CONTROL"),
("NEW_SIGNAL_1", "SCC_CONTROL"),
("MainMode_ACC", "SCC_CONTROL"),
@ -509,7 +523,7 @@ class CarState(CarStateBase):
("VSetDis", "SCC_CONTROL"),
]
checks = [
checks += [
("SCC_CONTROL", 50),
]

@ -20,7 +20,8 @@ def create_lkas11(packer, frame, car_fingerprint, apply_steer, steer_req,
if car_fingerprint in (CAR.SONATA, CAR.PALISADE, CAR.KIA_NIRO_EV, CAR.KIA_NIRO_HEV_2021, CAR.SANTA_FE,
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.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):
values["CF_Lkas_LdwsActivemode"] = int(left_lane) + (int(right_lane) << 1)
values["CF_Lkas_LdwsOpt_USM"] = 2

@ -2,7 +2,7 @@
from cereal import car
from panda import Panda
from common.conversions import Conversions as CV
from selfdrive.car.hyundai.values import HyundaiFlags, CAR, DBC, CANFD_CAR, CAMERA_SCC_CAR, EV_CAR, HYBRID_CAR, LEGACY_SAFETY_MODE_CAR, Buttons, CarControllerParams
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, CarControllerParams
from selfdrive.car.hyundai.radar_interface import RADAR_START_ADDR
from selfdrive.car import STD_CARGO_KG, create_button_event, scale_rot_inertia, scale_tire_stiffness, gen_empty_fingerprint, get_safety_config
from selfdrive.car.interfaces import CarInterfaceBase
@ -41,6 +41,11 @@ 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
if 0x130 not in fingerprint[4]:
ret.flags |= HyundaiFlags.CANFD_ALT_GEARS.value
if candidate not in CANFD_RADAR_SCC_CAR:
ret.flags |= HyundaiFlags.CANFD_CAMERA_SCC.value
ret.steerActuatorDelay = 0.1 # Default delay
ret.steerLimitTimer = 0.4
@ -120,6 +125,10 @@ class CarInterface(CarInterfaceBase):
ret.wheelbase = 2.756
ret.steerRatio = 16.
tire_stiffness_factor = 0.385
elif candidate == CAR.SANTA_CRUZ_1ST_GEN:
ret.mass = 1870. + STD_CARGO_KG # weight from Limited trim - the only supported trim
ret.wheelbase = 3.000
ret.steerRatio = 14.2 # steering ratio according to Hyundai News https://www.hyundainews.com/assets/documents/original/48035-2022SantaCruzProductGuideSpecsv2081521.pdf
# Kia
elif candidate == CAR.KIA_SORENTO:
@ -138,6 +147,10 @@ class CarInterface(CarInterfaceBase):
ret.wheelbase = 2.63
ret.steerRatio = 14.56
tire_stiffness_factor = 1
elif candidate == CAR.KIA_SPORTAGE_5TH_GEN:
ret.mass = 1700. + STD_CARGO_KG # weight from SX and above trims, average of FWD and AWD versions
ret.wheelbase = 2.756
ret.steerRatio = 13.6 # steering ratio according to Kia News https://www.kiamedia.com/us/en/models/sportage/2023/specifications
elif candidate in (CAR.KIA_OPTIMA_G4, CAR.KIA_OPTIMA_G4_FL, CAR.KIA_OPTIMA_H):
ret.mass = 3558. * CV.LB_TO_KG
ret.wheelbase = 2.80
@ -145,7 +158,7 @@ class CarInterface(CarInterfaceBase):
tire_stiffness_factor = 0.5
if candidate == CAR.KIA_OPTIMA_G4:
ret.minSteerSpeed = 32 * CV.MPH_TO_MS
elif candidate == CAR.KIA_STINGER:
elif candidate in (CAR.KIA_STINGER, CAR.KIA_STINGER_2022):
ret.mass = 1825. + STD_CARGO_KG
ret.wheelbase = 2.78
ret.steerRatio = 14.4 * 1.15 # 15% higher at the center seems reasonable
@ -189,6 +202,10 @@ class CarInterface(CarInterfaceBase):
ret.mass = 3673.0 * CV.LB_TO_KG + STD_CARGO_KG
ret.wheelbase = 2.83
ret.steerRatio = 12.9
elif candidate == CAR.GENESIS_GV70_1ST_GEN:
ret.mass = 1950. + STD_CARGO_KG
ret.wheelbase = 2.87
ret.steerRatio = 14.6
elif candidate == CAR.GENESIS_G80:
ret.mass = 2060. + STD_CARGO_KG
ret.wheelbase = 3.01
@ -202,7 +219,7 @@ class CarInterface(CarInterfaceBase):
if candidate in CANFD_CAR:
ret.longitudinalTuning.kpV = [0.1]
ret.longitudinalTuning.kiV = [0.0]
ret.experimentalLongitudinalAvailable = bool(ret.flags & HyundaiFlags.CANFD_HDA2)
ret.experimentalLongitudinalAvailable = candidate in (HYBRID_CAR | EV_CAR) and candidate not in CANFD_RADAR_SCC_CAR
else:
ret.longitudinalTuning.kpV = [0.5]
ret.longitudinalTuning.kiV = [0.0]
@ -233,6 +250,8 @@ class CarInterface(CarInterfaceBase):
ret.safetyConfigs[1].safetyParam |= Panda.FLAG_HYUNDAI_CANFD_HDA2
if ret.flags & HyundaiFlags.CANFD_ALT_BUTTONS:
ret.safetyConfigs[1].safetyParam |= Panda.FLAG_HYUNDAI_CANFD_ALT_BUTTONS
if ret.flags & HyundaiFlags.CANFD_CAMERA_SCC:
ret.safetyConfigs[1].safetyParam |= Panda.FLAG_HYUNDAI_CAMERA_SCC
else:
if candidate in LEGACY_SAFETY_MODE_CAR:
# these cars require a special panda safety mode due to missing counters and checksums in the messages
@ -264,7 +283,7 @@ class CarInterface(CarInterfaceBase):
@staticmethod
def init(CP, logcan, sendcan):
if CP.openpilotLongitudinalControl:
if CP.openpilotLongitudinalControl and not (CP.flags & HyundaiFlags.CANFD_CAMERA_SCC.value):
addr, bus = 0x7d0, 0
if CP.flags & HyundaiFlags.CANFD_HDA2.value:
addr, bus = 0x730, 5

@ -47,6 +47,8 @@ class CarControllerParams:
class HyundaiFlags(IntFlag):
CANFD_HDA2 = 1
CANFD_ALT_BUTTONS = 2
CANFD_ALT_GEARS = 4
CANFD_CAMERA_SCC = 8
class CAR:
@ -77,6 +79,7 @@ class CAR:
SONATA_HYBRID = "HYUNDAI SONATA HYBRID 2021"
IONIQ_5 = "HYUNDAI IONIQ 5 2022"
TUCSON_HYBRID_4TH_GEN = "HYUNDAI TUCSON HYBRID 4TH GEN"
SANTA_CRUZ_1ST_GEN = "HYUNDAI SANTA CRUZ 1ST GEN"
# Kia
KIA_FORTE = "KIA FORTE E 2018 & GT 2021"
@ -88,15 +91,18 @@ class CAR:
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_SPORTAGE_HYBRID_5TH_GEN = "KIA SPORTAGE HYBRID 5TH GEN"
KIA_STINGER = "KIA STINGER GT2 2018"
KIA_STINGER_2022 = "KIA STINGER 2022"
KIA_CEED = "KIA CEED INTRO ED 2019"
KIA_EV6 = "KIA EV6 2022"
# Genesis
GENESIS_G70 = "GENESIS G70 2018"
GENESIS_G70_2020 = "GENESIS G70 2020"
GENESIS_GV70_1ST_GEN = "GENESIS GV70 1ST GEN"
GENESIS_G80 = "GENESIS G80 2017"
GENESIS_G90 = "GENESIS G90 2017"
@ -137,15 +143,16 @@ CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = {
],
CAR.PALISADE: [
HyundaiCarInfo("Hyundai Palisade 2020-22", "All", "https://youtu.be/TAnDqjF4fDY?t=456", harness=Harness.hyundai_h),
HyundaiCarInfo("Kia Telluride 2020", "All", harness=Harness.hyundai_h),
HyundaiCarInfo("Kia Telluride 2020-22", "All", harness=Harness.hyundai_h),
],
CAR.VELOSTER: HyundaiCarInfo("Hyundai Veloster 2019-20", min_enable_speed=5. * CV.MPH_TO_MS, harness=Harness.hyundai_e),
CAR.SONATA_HYBRID: HyundaiCarInfo("Hyundai Sonata Hybrid 2020-22", "All", harness=Harness.hyundai_a),
CAR.IONIQ_5: [
HyundaiCarInfo("Hyundai Ioniq 5 (without HDA II) 2022" , "Highway Driving Assist", harness=Harness.hyundai_k),
HyundaiCarInfo("Hyundai Ioniq 5 (with HDA II) 2022", "Highway Driving Assist II", harness=Harness.hyundai_q),
HyundaiCarInfo("Hyundai Ioniq 5 (without HDA II) 2022-23" , "Highway Driving Assist", harness=Harness.hyundai_k),
HyundaiCarInfo("Hyundai Ioniq 5 (with HDA II) 2022-23", "Highway Driving Assist II", harness=Harness.hyundai_q),
],
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", "Smart Cruise Control (SCC)", harness=Harness.hyundai_n),
# Kia
CAR.KIA_FORTE: HyundaiCarInfo("Kia Forte 2019-21", harness=Harness.hyundai_g),
@ -168,12 +175,14 @@ CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = {
HyundaiCarInfo("Kia Optima Hybrid 2019"),
],
CAR.KIA_SELTOS: HyundaiCarInfo("Kia Seltos 2021", harness=Harness.hyundai_a),
CAR.KIA_SPORTAGE_5TH_GEN: HyundaiCarInfo("Kia Sportage 2023", "Smart Cruise Control (SCC)", harness=Harness.hyundai_n),
CAR.KIA_SORENTO: [
HyundaiCarInfo("Kia Sorento 2018", "Advanced Smart Cruise Control", "https://www.youtube.com/watch?v=Fkh3s6WHJz8", harness=Harness.hyundai_c),
HyundaiCarInfo("Kia Sorento 2019", video_link="https://www.youtube.com/watch?v=Fkh3s6WHJz8", harness=Harness.hyundai_e),
],
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),
CAR.KIA_CEED: HyundaiCarInfo("Kia Ceed 2019", harness=Harness.hyundai_e),
CAR.KIA_EV6: [
HyundaiCarInfo("Kia EV6 (without HDA II) 2022", "Highway Driving Assist", harness=Harness.hyundai_l),
@ -183,6 +192,7 @@ CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = {
# Genesis
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_G90: HyundaiCarInfo("Genesis G90 2017-18", "All", harness=Harness.hyundai_c),
}
@ -460,6 +470,7 @@ FW_VERSIONS = {
b'\xf1\x82DNBWN5TMDCXXXG2E',
b'\xf1\x82DNCVN5GMCCXXXF0A',
b'\xf1\x82DNCVN5GMCCXXXG2B',
b'\xf1\x870\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\xf1\x81HM6M1_0a0_J10',
b'\xf1\x870\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\xf1\x82DNDWN5TMDCXXXJ1A',
b'\xf1\x87391162M003',
b'\xf1\x87391162M013',
@ -484,6 +495,7 @@ FW_VERSIONS = {
b'\xf1\x8756310L0010\x00\xf1\x00DN8 MDPS C 1.00 1.01 56310L0010\x00 4DNAC101',
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',
],
(Ecu.fwdCamera, 0x7c4, None): [
b'\xf1\x00DN8 MFC AT KOR LHD 1.00 1.02 99211-L1000 190422',
@ -504,6 +516,7 @@ FW_VERSIONS = {
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\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',
b'\xf1\x87SAKFBA2926554GJ2VefVww\x87xwwwww\x88\x87xww\x87wTo\xfb\xffvUo\xff\x8d\x16\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v',
b'\xf1\x87SAKFBA3030524GJ2UVugww\x97yx\x88\x87\x88vw\x87gww\x87wto\xf9\xfffUo\xff\xa2\x0c\xf1\x81U903\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v',
@ -779,6 +792,23 @@ FW_VERSIONS = {
b'\xf1\x00bcsh8p54 E21\x00\x00\x00\x00\x00\x00\x00SCK0T33NB0\x88\xa2\xe6\xf0',
],
},
CAR.KIA_STINGER_2022: {
(Ecu.fwdRadar, 0x7d0, None): [
b'\xf1\x00CK__ SCC F-CUP 1.00 1.00 99110-J5500 ',
],
(Ecu.engine, 0x7e0, None): [
b'\xf1\x81640R0051\x00\x00\x00\x00\x00\x00\x00\x00',
],
(Ecu.eps, 0x7d4, None): [
b'\xf1\x00CK MDPS R 1.00 5.03 57700-J5380 4C2VR503',
],
(Ecu.fwdCamera, 0x7c4, None): [
b'\xf1\x00CK MFC AT AUS RHD 1.00 1.00 99211-J5500 210622',
],
(Ecu.transmission, 0x7e1, None): [
b'\xf1\x87VCNLF11383972DK1vffV\x99\x99\x89\x98\x86eUU\x88wg\x89vfff\x97fff\x99\x87o\xff"\xc1\xf1\x81E30\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 E30\x00\x00\x00\x00\x00\x00\x00SCK0T33GH0\xbe`\xfb\xc6',
],
},
CAR.PALISADE: {
(Ecu.fwdRadar, 0x7d0, None): [
b'\xf1\x00LX2_ SCC F-CUP 1.00 1.04 99110-S8100 ',
@ -1052,6 +1082,7 @@ FW_VERSIONS = {
b'\xf1\x8758520-K4010\xf1\x00OS IEB \x02 101 \x11\x13 58520-K4010',
b'\xf1\x8758520-K4010\xf1\x00OS IEB \x04 101 \x11\x13 58520-K4010',
b'\xf1\x8758520-K4010\xf1\x00OS IEB \x03 101 \x11\x13 58520-K4010',
b'\xf1\x00OS IEB \r 102"\x05\x16 58520-K4010',
# TODO: these return from the MULTI request, above return from LONG
b'\x01\x04\x7f\xff\xff\xf8\xff\xff\x00\x00\x01\xd3\x00\x00\x00\x00\xff\xb7\xff\xee\xff\xe0\x00\xc0\xc0\xfc\xd5\xfc\x00\x00U\x10\xffP\xf5\xff\xfd\x00\x00\x00\x00\xfc\x00\x01',
b'\x01\x04\x7f\xff\xff\xf8\xff\xff\x00\x00\x01\xdb\x00\x00\x00\x00\xff\xb1\xff\xd9\xff\xd2\x00\xc0\xc0\xfc\xd5\xfc\x00\x00U\x10\xff\xd6\xf5\x00\x06\x00\x00\x00\x14\xfd\x00\x04',
@ -1061,10 +1092,12 @@ FW_VERSIONS = {
b'\xf1\x00OSP LKA AT CND LHD 1.00 1.02 99211-J9110 802',
b'\xf1\x00OSP LKA AT EUR RHD 1.00 1.02 99211-J9110 802',
b'\xf1\x00OSP LKA AT AUS RHD 1.00 1.04 99211-J9200 904',
b'\xf1\x00OSP LKA AT EUR LHD 1.00 1.04 99211-J9200 904',
],
(Ecu.eps, 0x7D4, None): [
b'\xf1\x00OSP MDPS C 1.00 1.02 56310K4260\x00 4OEPC102',
b'\xf1\x00OSP MDPS C 1.00 1.02 56310/K4970 4OEPC102',
b'\xf1\x00OSP MDPS C 1.00 1.02 56310/K4271 4OEPC102',
],
(Ecu.fwdRadar, 0x7D0, None): [
b'\xf1\x00YB__ FCA ----- 1.00 1.01 99110-K4500 \x00\x00\x00',
@ -1366,6 +1399,7 @@ FW_VERSIONS = {
b'\xf1\x00CV1 MFC AT USA LHD 1.00 1.05 99210-CV000 211027',
b'\xf1\x00CV1 MFC AT USA LHD 1.00 1.06 99210-CV000 220328',
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',
],
},
CAR.IONIQ_5: {
@ -1376,6 +1410,7 @@ FW_VERSIONS = {
(Ecu.fwdCamera, 0x7c4, None): [
b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.02 99211-GI010 211206',
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',
],
},
CAR.TUCSON_HYBRID_4TH_GEN: {
@ -1395,6 +1430,32 @@ FW_VERSIONS = {
b'\xf1\x00NQ5__ 1.01 1.03 99110-CH000 ',
],
},
CAR.SANTA_CRUZ_1ST_GEN: {
(Ecu.fwdCamera, 0x7c4, None): [
b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-CW000 14M',
],
(Ecu.fwdRadar, 0x7d0, None): [
b'\xf1\x00NX4__ 1.00 1.00 99110-K5000 ',
],
},
CAR.KIA_SPORTAGE_5TH_GEN: {
(Ecu.fwdCamera, 0x7c4, None): [
b'\xf1\x00NQ5 FR_CMR AT USA LHD 1.00 1.00 99211-P1030 662',
b'\xf1\x00NQ5 FR_CMR AT USA LHD 1.00 1.00 99211-P1040 663',
],
(Ecu.fwdRadar, 0x7d0, None): [
b'\xf1\x00NQ5__ 1.00 1.02 99110-P1000 ',
b'\xf1\x00NQ5__ 1.00 1.03 99110-P1000 ',
],
},
CAR.GENESIS_GV70_1ST_GEN: {
(Ecu.fwdCamera, 0x7c4, None): [
b'\xf1\x00JK1 MFC AT USA LHD 1.00 1.04 99211-AR000 210204',
],
(Ecu.fwdRadar, 0x7d0, None): [
b'\xf1\x00JK1_ SCC FHCUP 1.00 1.02 99110-AR000 ',
],
},
}
CHECKSUM = {
@ -1409,10 +1470,13 @@ FEATURES = {
"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},
"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},
}
CANFD_CAR = {CAR.KIA_EV6, CAR.IONIQ_5, CAR.TUCSON_HYBRID_4TH_GEN, CAR.KIA_SPORTAGE_HYBRID_5TH_GEN}
CANFD_CAR = {CAR.KIA_EV6, CAR.IONIQ_5, 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}
# The radar does SCC on these cars when HDA I, rather than the camera
CANFD_RADAR_SCC_CAR = {CAR.GENESIS_GV70_1ST_GEN, }
# The camera does SCC on these cars, rather than the radar
CAMERA_SCC_CAR = {CAR.KONA_EV_2022, }
@ -1451,6 +1515,7 @@ DBC = {
CAR.KIA_SELTOS: dbc_dict('hyundai_kia_generic', None),
CAR.KIA_SORENTO: dbc_dict('hyundai_kia_generic', None), # Has 0x5XX messages, but different format
CAR.KIA_STINGER: dbc_dict('hyundai_kia_generic', None),
CAR.KIA_STINGER_2022: dbc_dict('hyundai_kia_generic', None),
CAR.KONA: dbc_dict('hyundai_kia_generic', None),
CAR.KONA_EV: dbc_dict('hyundai_kia_generic', None),
CAR.KONA_EV_2022: dbc_dict('hyundai_kia_generic', None),
@ -1469,5 +1534,8 @@ DBC = {
CAR.SONATA_HYBRID: dbc_dict('hyundai_kia_generic', 'hyundai_kia_mando_front_radar_generated'),
CAR.TUCSON_HYBRID_4TH_GEN: dbc_dict('hyundai_canfd', None),
CAR.IONIQ_5: dbc_dict('hyundai_canfd', None),
CAR.SANTA_CRUZ_1ST_GEN: dbc_dict('hyundai_canfd', None),
CAR.KIA_SPORTAGE_5TH_GEN: dbc_dict('hyundai_canfd', None),
CAR.KIA_SPORTAGE_HYBRID_5TH_GEN: dbc_dict('hyundai_canfd', None),
CAR.GENESIS_GV70_1ST_GEN: dbc_dict('hyundai_canfd', None),
}

@ -23,7 +23,7 @@ TorqueFromLateralAccelCallbackType = Callable[[float, car.CarParams.LateralTorqu
MAX_CTRL_SPEED = (V_CRUISE_MAX + 4) * CV.KPH_TO_MS
ACCEL_MAX = 2.0
ACCEL_MIN = -3.5
FRICTION_THRESHOLD = 0.2
FRICTION_THRESHOLD = 0.3
TORQUE_PARAMS_PATH = os.path.join(BASEDIR, 'selfdrive/car/torque_data/params.yaml')
TORQUE_OVERRIDE_PATH = os.path.join(BASEDIR, 'selfdrive/car/torque_data/override.yaml')
@ -250,8 +250,8 @@ class CarInterfaceBase(ABC):
# Enable OP long on falling edge of enable buttons (defaults to accelCruise and decelCruise, overridable per-port)
if not self.CP.pcmCruise and (b.type in enable_buttons and not b.pressed):
events.add(EventName.buttonEnable)
# Disable on rising edge of cancel for both stock and OP long
if b.type == ButtonType.cancel and b.pressed:
# Disable on rising and falling edge of cancel for both stock and OP long
if b.type == ButtonType.cancel:
events.add(EventName.buttonCancel)
# Handle permanent and temporary steering faults

@ -196,6 +196,7 @@ FW_VERSIONS = {
b'\xaa!dt\a',
b'\xc5!ar\a',
b'\xbe!as\a',
b'\xc5!as\x07',
b'\xc5!ds\a',
b'\xc5!`s\a',
b'\xaa!au\a',
@ -460,6 +461,7 @@ FW_VERSIONS = {
b'\xa1 \x08\x02',
b'\xa1 \x06\x02',
b'\xa1 \x08\x00',
b'\xa1 "\t\x00',
],
(Ecu.eps, 0x746, None): [
b'\x9b\xc0\x10\x00',
@ -481,6 +483,7 @@ FW_VERSIONS = {
b'\xe2"`p\x07',
b'\xf1\x82\xe2,\xa0@\x07',
b'\xbc"`q\x07',
b'\xe3,\xa0@\x07',
],
(Ecu.transmission, 0x7e1, None): [
b'\xa5\xfe\xf7@\x00',

@ -81,7 +81,9 @@ routes = [
CarTestRoute("6fe86b4e410e4c37|2020-07-22--16-27-13", HYUNDAI.HYUNDAI_GENESIS),
CarTestRoute("70c5bec28ec8e345|2020-08-08--12-22-23", HYUNDAI.GENESIS_G70),
CarTestRoute("ca4de5b12321bd98|2022-10-18--21-15-59", HYUNDAI.GENESIS_GV70_1ST_GEN),
CarTestRoute("6b301bf83f10aa90|2020-11-22--16-45-07", HYUNDAI.GENESIS_G80),
CarTestRoute("f0709d2bc6ca451f|2022-10-15--08-13-54", HYUNDAI.SANTA_CRUZ_1ST_GEN),
CarTestRoute("4dbd55df87507948|2022-03-01--09-45-38", HYUNDAI.SANTA_FE),
CarTestRoute("bf43d9df2b660eb0|2021-09-23--14-16-37", HYUNDAI.SANTA_FE_2022),
CarTestRoute("37398f32561a23ad|2021-11-18--00-11-35", HYUNDAI.SANTA_FE_HEV_2022),
@ -109,6 +111,7 @@ routes = [
CarTestRoute("ff973b941a69366f|2022-07-28--22-01-19", HYUNDAI.KONA_EV_2022, segment=11),
CarTestRoute("49f3c13141b6bc87|2021-07-28--08-05-13", HYUNDAI.KONA_HEV),
CarTestRoute("5dddcbca6eb66c62|2020-07-26--13-24-19", HYUNDAI.KIA_STINGER),
CarTestRoute("5b50b883a4259afb|2022-11-09--15-00-42", HYUNDAI.KIA_STINGER_2022),
CarTestRoute("d624b3d19adce635|2020-08-01--14-59-12", HYUNDAI.VELOSTER),
CarTestRoute("d545129f3ca90f28|2022-10-19--09-22-54", HYUNDAI.KIA_EV6), # HDA2
CarTestRoute("68d6a96e703c00c9|2022-09-10--16-09-39", HYUNDAI.KIA_EV6), # HDA1
@ -117,6 +120,7 @@ routes = [
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("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),
CarTestRoute("734ef96182ddf940|2022-10-02--16-41-44", HYUNDAI.ELANTRA), # 2019 Elantra GT
CarTestRoute("82e9cdd3f43bf83e|2021-05-15--02-42-51", HYUNDAI.ELANTRA_2021),

@ -34,15 +34,18 @@ class TestCarInterfaces(unittest.TestCase):
self.assertGreater(car_params.maxLateralAccel, 0)
if car_params.steerControlType != car.CarParams.SteerControlType.angle:
tuning = car_params.lateralTuning.which()
if tuning == 'pid':
self.assertTrue(len(car_params.lateralTuning.pid.kpV))
elif tuning == 'torque':
kf = car_params.lateralTuning.torque.kf
self.assertTrue(not math.isnan(kf) and kf > 0)
self.assertTrue(not math.isnan(car_params.lateralTuning.torque.friction))
elif tuning == 'indi':
self.assertTrue(len(car_params.lateralTuning.indi.outerLoopGainV))
tune = car_params.lateralTuning
if tune.which() == 'pid':
self.assertTrue(not math.isnan(tune.pid.kf) and tune.pid.kf > 0)
self.assertTrue(len(tune.pid.kpV) > 0 and len(tune.pid.kpV) == len(tune.pid.kpBP))
self.assertTrue(len(tune.pid.kiV) > 0 and len(tune.pid.kiV) == len(tune.pid.kiBP))
elif tune.which() == 'torque':
self.assertTrue(not math.isnan(tune.torque.kf) and tune.torque.kf > 0)
self.assertTrue(not math.isnan(tune.torque.friction))
elif tune.which() == 'indi':
self.assertTrue(len(tune.indi.outerLoopGainV))
# Run car interface
CC = car.CarControl.new_message()

@ -263,8 +263,8 @@ class TestCarModelBase(unittest.TestCase):
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:
brake_pressed = False
safety_brake_pressed = self.safety.get_brake_pressed_prev() or self.safety.get_regen_braking_prev()
checks['brakePressed'] += brake_pressed != safety_brake_pressed
checks['brakePressed'] += brake_pressed != self.safety.get_brake_pressed_prev()
checks['regenBraking'] += CS.regenBraking != self.safety.get_regen_braking_prev()
if self.CP.pcmCruise:
# On most pcmCruise cars, openpilot's state is always tied to the PCM's cruise state.

@ -30,8 +30,10 @@ CHEVROLET SILVERADO 1500 2020: [1.9, 1.9, 0.112]
CHEVROLET EQUINOX 2019: [2.0, 2.0, 0.05]
VOLKSWAGEN PASSAT NMS: [2.5, 2.5, 0.1]
VOLKSWAGEN SHARAN 2ND GEN: [2.5, 2.5, 0.1]
HYUNDAI TUCSON HYBRID 4TH GEN: [2.5, 2.5, 0.0]
KIA SPORTAGE HYBRID 5TH GEN: [2.5, 2.5, 0.0]
HYUNDAI SANTA CRUZ 1ST GEN: [2.7, 2.7, 0.1]
KIA SPORTAGE 5TH GEN: [2.7, 2.7, 0.1]
KIA SPORTAGE HYBRID 5TH GEN: [2.5, 2.5, 0.1]
GENESIS GV70 1ST GEN: [2.42, 2.42, 0.1]
# Dashcam or fallback configured as ideal car
mock: [10.0, 10, 0.0]

@ -25,6 +25,7 @@ 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 IONIQ ELECTRIC LIMITED 2019: [1.7662975472852054, 1.613755614526594, 0.17087579756306276]
HYUNDAI IONIQ PHEV 2020: [3.2928700076638537, 2.1193482926455656, 0.12463700961468778]
@ -37,6 +38,7 @@ HYUNDAI SANTA FE PlUG-IN HYBRID 2022: [1.6953050513611045, 1.5837614296206861, 0
HYUNDAI SONATA 2019: [2.2200457811703953, 1.2967330275895228, 0.14039920986586393]
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]
KIA EV6 2022: [3.2, 3.0, 0.05]

@ -35,9 +35,9 @@ HYUNDAI IONIQ HYBRID 2020-2022: HYUNDAI IONIQ PLUG-IN HYBRID 2019
HYUNDAI IONIQ ELECTRIC 2020: HYUNDAI IONIQ PLUG-IN HYBRID 2019
HYUNDAI ELANTRA 2017: HYUNDAI SONATA 2019
HYUNDAI ELANTRA HYBRID 2021: HYUNDAI SONATA 2020
HYUNDAI ELANTRA 2021: HYUNDAI SONATA 2020
HYUNDAI TUCSON 2019: HYUNDAI SANTA FE 2019
HYUNDAI SANTA FE 2022: HYUNDAI SANTA FE HYBRID 2022
KIA STINGER 2022: KIA STINGER GT2 2018
GENESIS G90 2017: GENESIS G70 2018
GENESIS G80 2017: GENESIS G70 2018
GENESIS G70 2020: HYUNDAI SONATA 2020

@ -15,6 +15,8 @@ class CarState(CarStateBase):
can_define = CANDefine(DBC[CP.carFingerprint]["pt"])
self.shifter_values = can_define.dv["GEAR_PACKET"]["GEAR"]
self.eps_torque_scale = EPS_SCALE[CP.carFingerprint] / 100.
self.cluster_speed_hyst_gap = CV.KPH_TO_MS / 2.
self.cluster_min_speed = CV.KPH_TO_MS / 2.
# On cars with cp.vl["STEER_TORQUE_SENSOR"]["STEER_ANGLE"]
# the signal is zeroed to where the steering angle is at start.
@ -52,6 +54,7 @@ class CarState(CarStateBase):
)
ret.vEgoRaw = mean([ret.wheelSpeeds.fl, ret.wheelSpeeds.fr, ret.wheelSpeeds.rl, ret.wheelSpeeds.rr])
ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw)
ret.vEgoCluster = ret.vEgo * 1.015 # minimum of all the cars
ret.standstill = ret.vEgoRaw == 0

@ -110,6 +110,21 @@ class CarInterface(CarInterfaceBase):
ret.steerRatio = 14.3
tire_stiffness_factor = 0.7933
ret.mass = 3585. * CV.LB_TO_KG + STD_CARGO_KG # Average between ICE and Hybrid
ret.lateralTuning.init('pid')
ret.lateralTuning.pid.kiBP = [0.0]
ret.lateralTuning.pid.kpBP = [0.0]
ret.lateralTuning.pid.kpV = [0.6]
ret.lateralTuning.pid.kiV = [0.1]
ret.lateralTuning.pid.kf = 0.00007818594
# 2019+ RAV4 TSS2 uses two different steering racks and specific tuning seems to be necessary.
# See https://github.com/commaai/openpilot/pull/21429#issuecomment-873652891
for fw in car_fw:
if fw.ecu == "eps" and (fw.fwVersion.startswith(b'\x02') or fw.fwVersion in [b'8965B42181\x00\x00\x00\x00\x00\x00']):
ret.lateralTuning.pid.kpV = [0.15]
ret.lateralTuning.pid.kiV = [0.05]
ret.lateralTuning.pid.kf = 0.00004
break
elif candidate in (CAR.COROLLA_TSS2, CAR.COROLLAH_TSS2):
stop_and_go = True

@ -119,7 +119,7 @@ CAR_INFO: Dict[str, Union[ToyotaCarInfo, List[ToyotaCarInfo]]] = {
CAR.COROLLA: ToyotaCarInfo("Toyota Corolla 2017-19"),
CAR.COROLLA_TSS2: [
ToyotaCarInfo("Toyota Corolla 2020-22", video_link="https://www.youtube.com/watch?v=_66pXk0CBYA"),
ToyotaCarInfo("Toyota Corolla Cross (Non-US only) 2020-21", min_enable_speed=7.5),
ToyotaCarInfo("Toyota Corolla Cross (Non-US only) 2020-23", min_enable_speed=7.5),
ToyotaCarInfo("Toyota Corolla Hatchback 2019-22", video_link="https://www.youtube.com/watch?v=_66pXk0CBYA"),
],
CAR.COROLLAH_TSS2: [
@ -713,6 +713,7 @@ FW_VERSIONS = {
},
CAR.COROLLA_TSS2: {
(Ecu.engine, 0x700, None): [
b'\x01896630A22000\x00\x00\x00\x00',
b'\x01896630ZG2000\x00\x00\x00\x00',
b'\x01896630ZG5000\x00\x00\x00\x00',
b'\x01896630ZG5100\x00\x00\x00\x00',
@ -792,6 +793,7 @@ FW_VERSIONS = {
b'F152602191\x00\x00\x00\x00\x00\x00',
b'\x01F152612862\x00\x00\x00\x00\x00\x00',
b'\x01F152612B91\x00\x00\x00\x00\x00\x00',
b'\x01F15260A070\x00\x00\x00\x00\x00\x00',
],
(Ecu.fwdRadar, 0x750, 0xf): [
b'\x018821F3301100\x00\x00\x00\x00',
@ -809,6 +811,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'\x028646F1601300\x00\x00\x00\x008646G2601400\x00\x00\x00\x00',
],
},
CAR.COROLLAH_TSS2: {
@ -818,6 +821,7 @@ FW_VERSIONS = {
b'\x01896637621000\x00\x00\x00\x00',
b'\x01896637624000\x00\x00\x00\x00',
b'\x01896637626000\x00\x00\x00\x00',
b'\x01896637639000\x00\x00\x00\x00',
b'\x01896637648000\x00\x00\x00\x00',
b'\x01896637643000\x00\x00\x00\x00',
b'\x02896630A07000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00',
@ -1011,6 +1015,7 @@ FW_VERSIONS = {
b'\x01F15264873500\x00\x00\x00\x00',
b'\x01F152648C6300\x00\x00\x00\x00',
b'\x01F152648J4000\x00\x00\x00\x00',
b'\x01F152648J5000\x00\x00\x00\x00',
b'\x01F152648J6000\x00\x00\x00\x00',
],
(Ecu.engine, 0x700, None): [
@ -1018,6 +1023,7 @@ FW_VERSIONS = {
b'\x01896630EA1000\x00\x00\x00\x00',
b'\x01896630EE4000\x00\x00\x00\x00',
b'\x01896630EE4100\x00\x00\x00\x00',
b'\x01896630EE5000\x00\x00\x00\x00',
b'\x01896630EE6000\x00\x00\x00\x00',
b'\x02896630E66000\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00',
b'\x02896630E66100\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00',
@ -1389,6 +1395,7 @@ FW_VERSIONS = {
b'\x02896634A14001\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00',
b'\x02896634A23000\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
b'\x02896634A23001\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00',
b'\x02896634A23101\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00',
b'\x02896634A14001\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00',
b'\x02896634A14101\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00',
],

@ -12,6 +12,7 @@ class CarState(CarStateBase):
super().__init__(CP)
self.CCP = CarControllerParams(CP)
self.button_states = {button.event_type: False for button in self.CCP.BUTTONS}
self.esp_hold_confirmation = False
def create_button_events(self, pt_cp, buttons):
button_events = []

@ -27,12 +27,14 @@ class CarInterface(CarInterfaceBase):
ret.carName = "volkswagen"
ret.radarOffCan = True
use_off_car_defaults = len(fingerprint[0]) == 0 # Pick sensible carParams during offline doc generation/CI jobs
if candidate in PQ_CARS:
# Set global PQ35/PQ46/NMS parameters
ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.volkswagenPq)]
ret.enableBsm = 0x3BA in fingerprint[0] # SWA_1
if 0x440 in fingerprint[0] or len(fingerprint[0]) == 0: # Getriebe_1, or empty FP for CI/docs generation
if 0x440 in fingerprint[0] or use_off_car_defaults: # Getriebe_1
ret.transmissionType = TransmissionType.automatic
else:
ret.transmissionType = TransmissionType.manual
@ -55,7 +57,7 @@ class CarInterface(CarInterfaceBase):
ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.volkswagen)]
ret.enableBsm = 0x30F in fingerprint[0] # SWA_01
if 0xAD in fingerprint[0] or len(fingerprint[0]) == 0: # Getriebe_11, or empty FP for CI/docs generation
if 0xAD in fingerprint[0] or use_off_car_defaults: # Getriebe_11
ret.transmissionType = TransmissionType.automatic
elif 0x187 in fingerprint[0]: # EV_Gearshift
ret.transmissionType = TransmissionType.direct
@ -81,8 +83,8 @@ class CarInterface(CarInterfaceBase):
# Global longitudinal tuning defaults, can be overridden per-vehicle
ret.experimentalLongitudinalAvailable = ret.networkLocation == NetworkLocation.gateway and False # Disabled for now
if experimental_long and False: # Disabled for now
ret.experimentalLongitudinalAvailable = ret.networkLocation == NetworkLocation.gateway or use_off_car_defaults
if experimental_long:
# Proof-of-concept, prep for E2E only. No radar points available. Panda ALLOW_DEBUG firmware required.
ret.openpilotLongitudinalControl = True
ret.safetyConfigs[0].safetyParam |= Panda.FLAG_VOLKSWAGEN_LONG_CONTROL

@ -151,75 +151,76 @@ class Footnote(Enum):
PASSAT = CarFootnote(
"Refers only to the MQB-based European B8 Passat, not the NMS Passat in the USA/China/Mideast markets.",
Column.MODEL)
VW_HARNESS = CarFootnote(
"Model-years 2021 and beyond may have a new camera harness design, which isn't yet available from the comma " +
"store. Before ordering, remove the Lane Assist camera cover and check to see if the connector is black " +
"(older design) or light brown (newer design). In the interim, if your car has a J533 connector CAN gateway " +
"inside the dashboard, choose \"VW J533 Development\" from the vehicle drop-down for a suitable harness. " +
"(Some newer models are also observed to not have a J533 connector.)",
Column.MODEL)
VW_VARIANT = CarFootnote(
"Includes versions with extra rear cargo space (may be called Variant, Estate, SportWagen, Shooting Brake, etc.)",
Column.MODEL)
VW_EXP_LONG = CarFootnote (
"Only available for vehicles using a gateway (J533) harness. At this time, vehicles using a camera harness " +
"are limited to using stock ACC.",
Column.LONGITUDINAL)
VW_MQB_A0 = CarFootnote(
"Model-years 2022 and beyond may have a combined CAN gateway and BCM, which is supported by openpilot " +
"in software, but doesn't yet have a harness available from the comma store.",
Column.HARNESS)
@dataclass
class VWCarInfo(CarInfo):
package: str = "Adaptive Cruise Control (ACC) & Lane Assist"
harness: Enum = Harness.vw
harness: Enum = Harness.j533
def init_make(self, CP: car.CarParams):
self.footnotes.insert(0, Footnote.VW_EXP_LONG)
CAR_INFO: Dict[str, Union[VWCarInfo, List[VWCarInfo]]] = {
CAR.ARTEON_MK1: [
VWCarInfo("Volkswagen Arteon 2018-22", footnotes=[Footnote.VW_HARNESS, Footnote.VW_VARIANT], harness=Harness.j533, video_link="https://youtu.be/FAomFKPFlDA"),
VWCarInfo("Volkswagen Arteon R 2020-22", footnotes=[Footnote.VW_HARNESS, Footnote.VW_VARIANT], harness=Harness.j533, video_link="https://youtu.be/FAomFKPFlDA"),
VWCarInfo("Volkswagen Arteon eHybrid 2020-22", footnotes=[Footnote.VW_HARNESS, Footnote.VW_VARIANT], harness=Harness.j533, video_link="https://youtu.be/FAomFKPFlDA"),
VWCarInfo("Volkswagen CC 2018-22", footnotes=[Footnote.VW_HARNESS, Footnote.VW_VARIANT], harness=Harness.j533, video_link="https://youtu.be/FAomFKPFlDA"),
VWCarInfo("Volkswagen Arteon 2018-22", video_link="https://youtu.be/FAomFKPFlDA"),
VWCarInfo("Volkswagen Arteon R 2020-22", video_link="https://youtu.be/FAomFKPFlDA"),
VWCarInfo("Volkswagen Arteon eHybrid 2020-22", video_link="https://youtu.be/FAomFKPFlDA"),
VWCarInfo("Volkswagen CC 2018-22", video_link="https://youtu.be/FAomFKPFlDA"),
],
CAR.ATLAS_MK1: [
VWCarInfo("Volkswagen Atlas 2018-23", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533),
VWCarInfo("Volkswagen Atlas Cross Sport 2021-22", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533),
VWCarInfo("Volkswagen Teramont 2018-22", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533),
VWCarInfo("Volkswagen Teramont Cross Sport 2021-22", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533),
VWCarInfo("Volkswagen Teramont X 2021-22", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533),
VWCarInfo("Volkswagen Atlas 2018-23"),
VWCarInfo("Volkswagen Atlas Cross Sport 2021-22"),
VWCarInfo("Volkswagen Teramont 2018-22"),
VWCarInfo("Volkswagen Teramont Cross Sport 2021-22"),
VWCarInfo("Volkswagen Teramont X 2021-22"),
],
CAR.GOLF_MK7: [
VWCarInfo("Volkswagen e-Golf 2014-20"),
VWCarInfo("Volkswagen Golf 2015-20", footnotes=[Footnote.VW_VARIANT]),
VWCarInfo("Volkswagen Golf 2015-20"),
VWCarInfo("Volkswagen Golf Alltrack 2015-19"),
VWCarInfo("Volkswagen Golf GTD 2015-20"),
VWCarInfo("Volkswagen Golf GTE 2015-20"),
VWCarInfo("Volkswagen Golf GTI 2015-21"),
VWCarInfo("Volkswagen Golf R 2015-19", footnotes=[Footnote.VW_VARIANT]),
VWCarInfo("Volkswagen Golf R 2015-19"),
VWCarInfo("Volkswagen Golf SportsVan 2015-20"),
],
CAR.JETTA_MK7: [
VWCarInfo("Volkswagen Jetta 2018-22", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533),
VWCarInfo("Volkswagen Jetta GLI 2021-22", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533),
VWCarInfo("Volkswagen Jetta 2018-22"),
VWCarInfo("Volkswagen Jetta GLI 2021-22"),
],
CAR.PASSAT_MK8: [
VWCarInfo("Volkswagen Passat 2015-22", footnotes=[Footnote.VW_HARNESS, Footnote.PASSAT, Footnote.VW_VARIANT], harness=Harness.j533),
VWCarInfo("Volkswagen Passat Alltrack 2015-22", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533),
VWCarInfo("Volkswagen Passat GTE 2015-22", footnotes=[Footnote.VW_HARNESS, Footnote.VW_VARIANT], harness=Harness.j533),
VWCarInfo("Volkswagen Passat 2015-22", footnotes=[Footnote.PASSAT]),
VWCarInfo("Volkswagen Passat Alltrack 2015-22"),
VWCarInfo("Volkswagen Passat GTE 2015-22"),
],
CAR.PASSAT_NMS: VWCarInfo("Volkswagen Passat NMS 2017-22", harness=Harness.j533),
CAR.PASSAT_NMS: VWCarInfo("Volkswagen Passat NMS 2017-22"),
CAR.POLO_MK6: [
VWCarInfo("Volkswagen Polo 2020-22", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533),
VWCarInfo("Volkswagen Polo GTI 2020-22", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533),
VWCarInfo("Volkswagen Polo 2020-22", footnotes=[Footnote.VW_MQB_A0]),
VWCarInfo("Volkswagen Polo GTI 2020-22", footnotes=[Footnote.VW_MQB_A0]),
],
CAR.SHARAN_MK2: [
VWCarInfo("Volkswagen Sharan 2018-22", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533),
VWCarInfo("SEAT Alhambra 2018-20", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533),
VWCarInfo("Volkswagen Sharan 2018-22"),
VWCarInfo("SEAT Alhambra 2018-20"),
],
CAR.TAOS_MK1: VWCarInfo("Volkswagen Taos 2022", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533),
CAR.TCROSS_MK1: VWCarInfo("Volkswagen T-Cross 2021", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533),
CAR.TIGUAN_MK2: VWCarInfo("Volkswagen Tiguan 2019-22", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533),
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.TOURAN_MK2: VWCarInfo("Volkswagen Touran 2017"),
CAR.TRANSPORTER_T61: [
VWCarInfo("Volkswagen Caravelle 2020", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533),
VWCarInfo("Volkswagen California 2021", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533),
VWCarInfo("Volkswagen Caravelle 2020"),
VWCarInfo("Volkswagen California 2021"),
],
CAR.TROC_MK1: VWCarInfo("Volkswagen T-Roc 2021", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533),
CAR.TROC_MK1: VWCarInfo("Volkswagen T-Roc 2021", footnotes=[Footnote.VW_MQB_A0]),
CAR.AUDI_A3_MK3: [
VWCarInfo("Audi A3 2014-19"),
VWCarInfo("Audi A3 Sportback e-tron 2017-18"),
@ -227,14 +228,14 @@ CAR_INFO: Dict[str, Union[VWCarInfo, List[VWCarInfo]]] = {
VWCarInfo("Audi S3 2015-17"),
],
CAR.AUDI_Q2_MK1: VWCarInfo("Audi Q2 2018"),
CAR.AUDI_Q3_MK2: VWCarInfo("Audi Q3 2020-21"),
CAR.AUDI_Q3_MK2: VWCarInfo("Audi Q3 2019-23"),
CAR.SEAT_ATECA_MK1: VWCarInfo("SEAT Ateca 2018"),
CAR.SEAT_LEON_MK3: VWCarInfo("SEAT Leon 2014-20"),
CAR.SKODA_KAMIQ_MK1: VWCarInfo("Škoda Kamiq 2021", footnotes=[Footnote.KAMIQ]),
CAR.SKODA_KAROQ_MK1: VWCarInfo("Škoda Karoq 2019-21", footnotes=[Footnote.VW_HARNESS]),
CAR.SKODA_KAMIQ_MK1: VWCarInfo("Škoda Kamiq 2021", footnotes=[Footnote.VW_MQB_A0, Footnote.KAMIQ]),
CAR.SKODA_KAROQ_MK1: VWCarInfo("Škoda Karoq 2019-21"),
CAR.SKODA_KODIAQ_MK1: VWCarInfo("Škoda Kodiaq 2018-19"),
CAR.SKODA_SCALA_MK1: VWCarInfo("Škoda Scala 2020"),
CAR.SKODA_SUPERB_MK3: VWCarInfo("Škoda Superb 2015-18"),
CAR.SKODA_SCALA_MK1: VWCarInfo("Škoda Scala 2020", footnotes=[Footnote.VW_MQB_A0]),
CAR.SKODA_SUPERB_MK3: VWCarInfo("Škoda Superb 2015-22"),
CAR.SKODA_OCTAVIA_MK3: [
VWCarInfo("Škoda Octavia 2015, 2018-19"),
VWCarInfo("Škoda Octavia RS 2016"),
@ -872,20 +873,24 @@ FW_VERSIONS = {
CAR.AUDI_Q3_MK2: {
(Ecu.engine, 0x7e0, None): [
b'\xf1\x8705E906018N \xf1\x899970',
b'\xf1\x8705L906022M \xf1\x890901',
b'\xf1\x8783A906259 \xf1\x890001',
b'\xf1\x8783A906259 \xf1\x890005',
],
(Ecu.transmission, 0x7e1, None): [
b'\xf1\x8709G927158CN\xf1\x893608',
b'\xf1\x870GC300045D \xf1\x892802',
b'\xf1\x870GC300046F \xf1\x892701',
],
(Ecu.srs, 0x715, None): [
b'\xf1\x875Q0959655BF\xf1\x890403\xf1\x82\x1321211111211200311121232152219321422111',
b'\xf1\x875Q0959655CC\xf1\x890421\xf1\x82\x131111111111120031111224118A119321532111',
b'\xf1\x875Q0959655CC\xf1\x890421\xf1\x82\x131111111111120031111237116A119321532111',
],
(Ecu.eps, 0x712, None): [
b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567G6000300',
b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567G6000800',
b'\xf1\x875QF909144B \xf1\x895582\xf1\x82\x0571G60533A1',
],
(Ecu.fwdRadar, 0x757, None): [
b'\xf1\x872Q0907572R \xf1\x890372',
@ -1061,6 +1066,7 @@ FW_VERSIONS = {
},
CAR.SKODA_SUPERB_MK3: {
(Ecu.engine, 0x7e0, None): [
b'\xf1\x8704L906026ET\xf1\x891343',
b'\xf1\x8704L906026FP\xf1\x891196',
b'\xf1\x8704L906026KB\xf1\x894071',
b'\xf1\x8704L906026KD\xf1\x894798',
@ -1071,9 +1077,11 @@ FW_VERSIONS = {
b'\xf1\x870CW300042H \xf1\x891601',
b'\xf1\x870D9300011T \xf1\x894801',
b'\xf1\x870D9300012 \xf1\x894940',
b'\xf1\x870D9300041H \xf1\x894905',
b'\xf1\x870GC300043 \xf1\x892301',
],
(Ecu.srs, 0x715, None): [
b'\xf1\x875Q0959655AE\xf1\x890130\xf1\x82\x12111200111121001121110012211292221111',
b'\xf1\x875Q0959655AE\xf1\x890130\xf1\x82\022111200111121001121118112231292221111',
b'\xf1\x875Q0959655AK\xf1\x890130\xf1\x82\022111200111121001121110012211292221111',
b'\xf1\x875Q0959655BH\xf1\x890336\xf1\x82\02331310031313100313131013141319331413100',

@ -12,12 +12,11 @@ import cereal.messaging as messaging
from common.conversions import Conversions as CV
from panda import ALTERNATIVE_EXPERIENCE
from system.swaglog import cloudlog
from system.version import is_tested_branch, get_short_branch
from system.version import is_release_branch, get_short_branch
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 V_CRUISE_INITIAL, update_v_cruise, initialize_v_cruise
from selfdrive.controls.lib.drive_helpers import get_lag_adjusted_curvature
from selfdrive.controls.lib.drive_helpers import VCruiseHelper, get_lag_adjusted_curvature
from selfdrive.controls.lib.latcontrol import LatControl
from selfdrive.controls.lib.longcontrol import LongControl
from selfdrive.controls.lib.latcontrol_pid import LatControlPID
@ -49,7 +48,6 @@ Desire = log.LateralPlan.Desire
LaneChangeState = log.LateralPlan.LaneChangeState
LaneChangeDirection = log.LateralPlan.LaneChangeDirection
EventName = car.CarEvent.EventName
ButtonEvent = car.CarState.ButtonEvent
ButtonType = car.CarState.ButtonEvent.Type
SafetyModel = car.CarParams.SafetyModel
@ -134,7 +132,7 @@ class Controls:
safety_config.safetyModel = car.CarParams.SafetyModel.noOutput
self.CP.safetyConfigs = [safety_config]
if is_tested_branch():
if is_release_branch():
self.CP.experimentalLongitudinalAvailable = False
# Write CarParams for radard
@ -147,7 +145,7 @@ class Controls:
if not self.CP.experimentalLongitudinalAvailable:
self.params.remove("ExperimentalLongitudinalEnabled")
if not self.CP.openpilotLongitudinalControl:
self.params.remove("EndToEndLong")
self.params.remove("ExperimentalMode")
self.CC = car.CarControl.new_message()
self.CS_prev = car.CarState.new_message()
@ -173,9 +171,6 @@ class Controls:
self.active = False
self.can_rcv_timeout = False
self.soft_disable_timer = 0
self.v_cruise_kph = V_CRUISE_INITIAL
self.v_cruise_cluster_kph = V_CRUISE_INITIAL
self.v_cruise_kph_last = 0
self.mismatch_counter = 0
self.cruise_mismatch_counter = 0
self.can_rcv_timeout_counter = 0
@ -185,11 +180,11 @@ class Controls:
self.events_prev = []
self.current_alert_types = [ET.PERMANENT]
self.logged_comm_issue = None
self.button_timers = {ButtonEvent.Type.decelCruise: 0, ButtonEvent.Type.accelCruise: 0}
self.last_actuators = car.CarControl.Actuators.new_message()
self.steer_limited = False
self.desired_curvature = 0.0
self.desired_curvature_rate = 0.0
self.v_cruise_helper = VCruiseHelper(self.CP)
# TODO: no longer necessary, aside from process replay
self.sm['liveParameters'].valid = True
@ -219,7 +214,7 @@ class Controls:
controls_state = Params().get("ReplayControlsState")
if controls_state is not None:
controls_state = log.ControlsState.from_bytes(controls_state)
self.v_cruise_kph = controls_state.vCruise
self.v_cruise_helper.v_cruise_kph = controls_state.vCruise
if any(ps.controlsAllowed for ps in self.sm['pandaStates']):
self.state = State.enabled
@ -245,12 +240,13 @@ class Controls:
# Block resume if cruise never previously enabled
resume_pressed = any(be.type in (ButtonType.accelCruise, ButtonType.resumeCruise) for be in CS.buttonEvents)
if not self.CP.pcmCruise and self.v_cruise_kph == V_CRUISE_INITIAL and resume_pressed:
if not self.CP.pcmCruise and not self.v_cruise_helper.v_cruise_initialized and resume_pressed:
self.events.add(EventName.resumeBlocked)
# Disable on rising edge of accelerator or brake. Also disable on brake when speed > 0
if (CS.gasPressed and not self.CS_prev.gasPressed and self.disengage_on_accelerator) or \
(CS.brakePressed and (not self.CS_prev.brakePressed or not CS.standstill)):
(CS.brakePressed and (not self.CS_prev.brakePressed or not CS.standstill)) or \
(CS.regenBraking and (not self.CS_prev.regenBraking or not CS.standstill)):
self.events.add(EventName.pedalPressed)
if CS.gasPressed:
@ -477,20 +473,7 @@ class Controls:
def state_transition(self, CS):
"""Compute conditional state transitions and execute actions on state transitions"""
self.v_cruise_kph_last = self.v_cruise_kph
if CS.cruiseState.available:
# if stock cruise is completely disabled, then we can use our own set speed logic
if not self.CP.pcmCruise:
self.v_cruise_kph = update_v_cruise(self.v_cruise_kph, CS.vEgo, CS.gasPressed, CS.buttonEvents,
self.button_timers, self.enabled, self.is_metric)
self.v_cruise_cluster_kph = self.v_cruise_kph
else:
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_helper.update_v_cruise(CS, self.enabled, self.is_metric)
# decrement the soft disable timer at every step, as it's reset on
# entrance in SOFT_DISABLING state
@ -568,9 +551,7 @@ class Controls:
else:
self.state = State.enabled
self.current_alert_types.append(ET.ENABLE)
if not self.CP.pcmCruise:
self.v_cruise_kph = initialize_v_cruise(CS.vEgo, CS.buttonEvents, self.v_cruise_kph_last)
self.v_cruise_cluster_kph = self.v_cruise_kph
self.v_cruise_helper.initialize_v_cruise(CS)
# Check if openpilot is engaged and actuators are enabled
self.enabled = self.state in ENABLED_STATES
@ -618,7 +599,7 @@ class Controls:
if not self.joystick_mode:
# accel PID loop
pid_accel_limits = self.CI.get_pid_accel_limits(self.CP, CS.vEgo, self.v_cruise_kph * CV.KPH_TO_MS)
pid_accel_limits = self.CI.get_pid_accel_limits(self.CP, CS.vEgo, self.v_cruise_helper.v_cruise_kph * CV.KPH_TO_MS)
t_since_plan = (self.sm.frame - self.sm.rcv_frame['longitudinalPlan']) * DT_CTRL
actuators.accel = self.LoC.update(CC.longActive, CS, long_plan, pid_accel_limits, t_since_plan)
@ -682,16 +663,6 @@ class Controls:
return CC, lac_log
def update_button_timers(self, buttonEvents):
# increment timer for buttons still pressed
for k in self.button_timers:
if self.button_timers[k] > 0:
self.button_timers[k] += 1
for b in buttonEvents:
if b.type.raw in self.button_timers:
self.button_timers[b.type.raw] = 1 if b.pressed else 0
def publish_logs(self, CS, start_time, CC, lac_log):
"""Send actuators and hud commands to the car, send controlsstate and MPC logging"""
@ -714,7 +685,7 @@ class Controls:
CC.cruiseControl.resume = self.enabled and CS.cruiseState.standstill and speeds[-1] > 0.1
hudControl = CC.hudControl
hudControl.setSpeed = float(self.v_cruise_cluster_kph * CV.KPH_TO_MS)
hudControl.setSpeed = float(self.v_cruise_helper.v_cruise_cluster_kph * CV.KPH_TO_MS)
hudControl.speedVisible = self.enabled
hudControl.lanesVisible = self.enabled
hudControl.leadVisible = self.sm['longitudinalPlan'].hasLead
@ -797,8 +768,8 @@ class Controls:
controlsState.engageable = not self.events.any(ET.NO_ENTRY)
controlsState.longControlState = self.LoC.long_control_state
controlsState.vPid = float(self.LoC.v_pid)
controlsState.vCruise = float(self.v_cruise_kph)
controlsState.vCruiseCluster = float(self.v_cruise_cluster_kph)
controlsState.vCruise = float(self.v_cruise_helper.v_cruise_kph)
controlsState.vCruiseCluster = float(self.v_cruise_helper.v_cruise_cluster_kph)
controlsState.upAccelCmd = float(self.LoC.pid.p)
controlsState.uiAccelCmd = float(self.LoC.pid.i)
controlsState.ufAccelCmd = float(self.LoC.pid.f)
@ -806,6 +777,7 @@ class Controls:
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
lat_tuning = self.CP.lateralTuning.which()
if self.joystick_mode:
@ -879,7 +851,6 @@ class Controls:
self.publish_logs(CS, start_time, CC, lac_log)
self.prof.checkpoint("Sent")
self.update_button_timers(CS.buttonEvents)
self.CS_prev = CS
def controlsd_thread(self):
@ -888,6 +859,7 @@ class Controls:
self.rk.monitor_time()
self.prof.display()
def main(sm=None, pm=None, logcan=None):
controls = Controls(sm, pm, logcan)
controls.controlsd_thread()

@ -5,7 +5,7 @@ from common.realtime import DT_MDL
LaneChangeState = log.LateralPlan.LaneChangeState
LaneChangeDirection = log.LateralPlan.LaneChangeDirection
LANE_CHANGE_SPEED_MIN = 15 * CV.MPH_TO_MS
LANE_CHANGE_SPEED_MIN = 20 * CV.MPH_TO_MS
LANE_CHANGE_TIME_MAX = 10.
DESIRES = {

@ -12,6 +12,7 @@ V_CRUISE_MAX = 145 # kph
V_CRUISE_MIN = 8 # kph
V_CRUISE_ENABLE_MIN = 40 # kph
V_CRUISE_INITIAL = 255 # kph
IMPERIAL_INCREMENT = 1.6 # should be CV.MPH_TO_KPH, but this causes rounding errors
MIN_SPEED = 1.0
LAT_MPC_N = 16
@ -22,6 +23,7 @@ CAR_ROTATION_RADIUS = 0.0
# EU guidelines
MAX_LATERAL_JERK = 5.0
ButtonEvent = car.CarState.ButtonEvent
ButtonType = car.CarState.ButtonEvent.Type
CRUISE_LONG_PRESS = 50
CRUISE_NEAREST_FUNC = {
@ -34,68 +36,121 @@ CRUISE_INTERVAL_SIGN = {
}
def apply_deadzone(error, deadzone):
if error > deadzone:
error -= deadzone
elif error < - deadzone:
error += deadzone
else:
error = 0.
return error
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_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
def update_v_cruise(self, CS, enabled, is_metric):
self.v_cruise_kph_last = self.v_cruise_kph
if CS.cruiseState.available:
if not self.CP.pcmCruise:
# if stock cruise is completely disabled, then we can use our own set speed logic
self._update_v_cruise_non_pcm(CS, enabled, is_metric)
self.v_cruise_cluster_kph = self.v_cruise_kph
self.update_button_timers(CS, enabled)
else:
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
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
# would have the effect of both enabling and changing speed is checked after the state transition
if not enabled:
return
def rate_limit(new_value, last_value, dw_step, up_step):
return clip(new_value, last_value + dw_step, last_value + up_step)
long_press = False
button_type = None
v_cruise_delta = 1. if is_metric else IMPERIAL_INCREMENT
def update_v_cruise(v_cruise_kph, v_ego, gas_pressed, buttonEvents, button_timers, enabled, metric):
# handle button presses. TODO: this should be in state_control, but a decelCruise press
# would have the effect of both enabling and changing speed is checked after the state transition
if not enabled:
return v_cruise_kph
for b in CS.buttonEvents:
if b.type.raw in self.button_timers and not b.pressed:
if self.button_timers[b.type.raw] > CRUISE_LONG_PRESS:
return # end long press
button_type = b.type.raw
break
else:
for k in self.button_timers.keys():
if self.button_timers[k] and self.button_timers[k] % CRUISE_LONG_PRESS == 0:
button_type = k
long_press = True
break
long_press = False
button_type = None
if button_type is None:
return
# should be CV.MPH_TO_KPH, but this causes rounding errors
v_cruise_delta = 1. if metric else 1.6
# Don't adjust speed when pressing resume to exit standstill
cruise_standstill = self.button_change_states[button_type]["standstill"] or CS.cruiseState.standstill
if button_type == ButtonType.accelCruise and cruise_standstill:
return
for b in buttonEvents:
if b.type.raw in button_timers and not b.pressed:
if button_timers[b.type.raw] > CRUISE_LONG_PRESS:
return v_cruise_kph # end long press
button_type = b.type.raw
break
else:
for k in button_timers.keys():
if button_timers[k] and button_timers[k] % CRUISE_LONG_PRESS == 0:
button_type = k
long_press = True
break
# Don't adjust speed if we've enabled since the button was depressed (some ports enable on rising edge)
if not self.button_change_states[button_type]["enabled"]:
return
if button_type:
v_cruise_delta = v_cruise_delta * (5 if long_press else 1)
if long_press and v_cruise_kph % v_cruise_delta != 0: # partial interval
v_cruise_kph = CRUISE_NEAREST_FUNC[button_type](v_cruise_kph / v_cruise_delta) * v_cruise_delta
if long_press and self.v_cruise_kph % v_cruise_delta != 0: # partial interval
self.v_cruise_kph = CRUISE_NEAREST_FUNC[button_type](self.v_cruise_kph / v_cruise_delta) * v_cruise_delta
else:
v_cruise_kph += v_cruise_delta * CRUISE_INTERVAL_SIGN[button_type]
self.v_cruise_kph += v_cruise_delta * CRUISE_INTERVAL_SIGN[button_type]
# If set is pressed while overriding, clip cruise speed to minimum of vEgo
if gas_pressed and button_type in (ButtonType.decelCruise, ButtonType.setCruise):
v_cruise_kph = max(v_cruise_kph, v_ego * CV.MS_TO_KPH)
if CS.gasPressed and button_type in (ButtonType.decelCruise, ButtonType.setCruise):
self.v_cruise_kph = max(self.v_cruise_kph, CS.vEgo * CV.MS_TO_KPH)
self.v_cruise_kph = clip(round(self.v_cruise_kph, 1), V_CRUISE_MIN, V_CRUISE_MAX)
v_cruise_kph = clip(round(v_cruise_kph, 1), V_CRUISE_MIN, V_CRUISE_MAX)
def update_button_timers(self, CS, enabled):
# increment timer for buttons still pressed
for k in self.button_timers:
if self.button_timers[k] > 0:
self.button_timers[k] += 1
return v_cruise_kph
for b in CS.buttonEvents:
if b.type.raw in self.button_timers:
# Start/end timer and store current state on change of button pressed
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):
# initializing is handled by the PCM
if self.CP.pcmCruise:
return
def initialize_v_cruise(v_ego, buttonEvents, v_cruise_last):
for b in buttonEvents:
# 250kph or above probably means we never had a set speed
if b.type in (ButtonType.accelCruise, ButtonType.resumeCruise) and v_cruise_last < 250:
return v_cruise_last
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_cluster_kph = self.v_cruise_kph
return int(round(clip(v_ego * CV.MS_TO_KPH, V_CRUISE_ENABLE_MIN, V_CRUISE_MAX)))
def apply_deadzone(error, deadzone):
if error > deadzone:
error -= deadzone
elif error < - deadzone:
error += deadzone
else:
error = 0.
return error
def rate_limit(new_value, last_value, dw_step, up_step):
return clip(new_value, last_value + dw_step, last_value + up_step)
def get_lag_adjusted_curvature(CP, v_ego, psis, curvatures, curvature_rates):

@ -597,6 +597,7 @@ EVENTS: Dict[int, Dict[str, Union[Alert, AlertCallbackType]]] = {
EventName.buttonCancel: {
ET.USER_DISABLE: EngagementAlert(AudibleAlert.disengage),
ET.NO_ENTRY: NoEntryAlert("Cancel Pressed"),
},
EventName.brakeHold: {

@ -17,7 +17,8 @@ from selfdrive.controls.lib.vehicle_model import ACCELERATION_DUE_TO_GRAVITY
# friction in the steering wheel that needs to be overcome to
# move it at all, this is compensated for too.
LOW_SPEED_FACTOR = 200
LOW_SPEED_X = [0, 10, 20, 30]
LOW_SPEED_Y = [15, 13, 10, 5]
class LatControlTorque(LatControl):
@ -57,8 +58,9 @@ class LatControlTorque(LatControl):
actual_lateral_accel = actual_curvature * CS.vEgo ** 2
lateral_accel_deadzone = curvature_deadzone * CS.vEgo ** 2
setpoint = desired_lateral_accel + LOW_SPEED_FACTOR * desired_curvature
measurement = actual_lateral_accel + LOW_SPEED_FACTOR * actual_curvature
low_speed_factor = interp(CS.vEgo, LOW_SPEED_X, LOW_SPEED_Y)**2
setpoint = desired_lateral_accel + low_speed_factor * desired_curvature
measurement = actual_lateral_accel + low_speed_factor * actual_curvature
error = setpoint - measurement
gravity_adjusted_lateral_accel = desired_lateral_accel - params.roll * ACCELERATION_DUE_TO_GRAVITY
pid_log.error = self.torque_from_lateral_accel(error, self.torque_params, error,

@ -103,6 +103,7 @@ class LongControl:
elif self.long_control_state == LongCtrlState.stopping:
if output_accel > self.CP.stopAccel:
output_accel = min(output_accel, 0.0)
output_accel -= self.CP.stoppingDecelRate * DT_CTRL
self.reset(CS.vEgo)

@ -36,7 +36,7 @@ A_EGO_COST = 0.
J_EGO_COST = 5.0
A_CHANGE_COST = 200.
DANGER_ZONE_COST = 100.
CRASH_DISTANCE = .5
CRASH_DISTANCE = .25
LEAD_DANGER_FACTOR = 0.75
LIMIT_COST = 1e6
ACADOS_SOLVER_TYPE = 'SQP_RTI'
@ -49,6 +49,7 @@ MAX_T = 10.0
T_IDXS_LST = [index_function(idx, max_val=MAX_T, max_idx=N) for idx in range(N+1)]
T_IDXS = np.array(T_IDXS_LST)
FCW_IDXS = T_IDXS < 5.0
T_DIFFS = np.diff(T_IDXS, prepend=[0.])
MIN_ACCEL = -3.5
MAX_ACCEL = 2.0
@ -300,8 +301,10 @@ class LongitudinalMpc:
return lead_xv
def set_accel_limits(self, min_a, max_a):
# TODO this sets a max accel limit, but the minimum limit is only for cruise decel
# needs refactor
self.cruise_min_a = min_a
self.cruise_max_a = max_a
self.max_a = max_a
def update(self, carstate, radarstate, v_cruise, x, v, a, j):
v_ego = self.x0[1]
@ -316,16 +319,17 @@ class LongitudinalMpc:
lead_0_obstacle = lead_xv_0[:,0] + get_stopped_equivalence_factor(lead_xv_0[:,1])
lead_1_obstacle = lead_xv_1[:,0] + get_stopped_equivalence_factor(lead_xv_1[:,1])
self.params[:,0] = MIN_ACCEL
self.params[:,1] = self.max_a
# Update in ACC mode or ACC/e2e blend
if self.mode == 'acc':
self.params[:,0] = MIN_ACCEL
self.params[:,1] = self.cruise_max_a
self.params[:,5] = LEAD_DANGER_FACTOR
# Fake an obstacle for cruise, this ensures smooth acceleration to set speed
# when the leads are no factor.
v_lower = v_ego + (T_IDXS * self.cruise_min_a * 1.05)
v_upper = v_ego + (T_IDXS * self.cruise_max_a * 1.05)
v_upper = v_ego + (T_IDXS * self.max_a * 1.05)
v_cruise_clipped = np.clip(v_cruise * np.ones(N+1),
v_lower,
v_upper)
@ -337,9 +341,6 @@ class LongitudinalMpc:
x[:], v[:], a[:], j[:] = 0.0, 0.0, 0.0, 0.0
elif self.mode == 'blended':
self.params[:,0] = MIN_ACCEL
self.params[:,1] = MAX_ACCEL
self.params[:,5] = 1.0
x_obstacles = np.column_stack([lead_0_obstacle,
@ -351,7 +352,7 @@ class LongitudinalMpc:
x_and_cruise = np.column_stack([x, cruise_target])
x = np.min(x_and_cruise, axis=1)
self.source = 'e2e' if x_and_cruise[0,0] < x_and_cruise[0,1] else 'cruise'
self.source = 'e2e' if x_and_cruise[1,0] < x_and_cruise[1,1] else 'cruise'
else:
raise NotImplementedError(f'Planner mode {self.mode} not recognized in planner update')
@ -369,7 +370,7 @@ class LongitudinalMpc:
self.params[:,4] = T_FOLLOW
self.run()
if (np.any(lead_xv_0[:,0] - self.x_sol[:,0] < CRASH_DISTANCE) and
if (np.any(lead_xv_0[FCW_IDXS,0] - self.x_sol[FCW_IDXS,0] < CRASH_DISTANCE) and
radarstate.leadOne.modelProb > 0.9):
self.crash_cnt += 1
else:

@ -10,7 +10,7 @@ from common.params import Params
from common.realtime import DT_MDL
from selfdrive.modeld.constants import T_IDXS
from selfdrive.controls.lib.longcontrol import LongCtrlState
from selfdrive.controls.lib.longitudinal_mpc_lib.long_mpc import LongitudinalMpc
from selfdrive.controls.lib.longitudinal_mpc_lib.long_mpc import LongitudinalMpc, MIN_ACCEL, MAX_ACCEL
from selfdrive.controls.lib.longitudinal_mpc_lib.long_mpc import T_IDXS as T_IDXS_MPC
from selfdrive.controls.lib.drive_helpers import V_CRUISE_MAX, CONTROL_N
from system.swaglog import cloudlog
@ -58,6 +58,7 @@ class LongitudinalPlanner:
self.a_desired = init_a
self.v_desired_filter = FirstOrderFilter(init_v, 2.0, DT_MDL)
self.v_model_error = 0.0
self.v_desired_trajectory = np.zeros(CONTROL_N)
self.a_desired_trajectory = np.zeros(CONTROL_N)
@ -65,15 +66,16 @@ class LongitudinalPlanner:
self.solverExecutionTime = 0.0
def read_param(self):
e2e = self.params.get_bool('EndToEndLong') and self.CP.openpilotLongitudinalControl
e2e = self.params.get_bool('ExperimentalMode') and self.CP.openpilotLongitudinalControl
self.mpc.mode = 'blended' if e2e else 'acc'
def parse_model(self, model_msg):
@staticmethod
def parse_model(model_msg, model_error):
if (len(model_msg.position.x) == 33 and
len(model_msg.velocity.x) == 33 and
len(model_msg.acceleration.x) == 33):
x = np.interp(T_IDXS_MPC, T_IDXS, model_msg.position.x)
v = np.interp(T_IDXS_MPC, T_IDXS, model_msg.velocity.x)
x = np.interp(T_IDXS_MPC, T_IDXS, model_msg.position.x) - model_error * T_IDXS_MPC
v = np.interp(T_IDXS_MPC, T_IDXS, model_msg.velocity.x) - model_error
a = np.interp(T_IDXS_MPC, T_IDXS, model_msg.acceleration.x)
j = np.zeros(len(T_IDXS_MPC))
else:
@ -102,8 +104,12 @@ class LongitudinalPlanner:
# No change cost when user is controlling the speed, or when standstill
prev_accel_constraint = not (reset_state or sm['carState'].standstill)
accel_limits = [A_CRUISE_MIN, get_max_accel(v_ego)]
accel_limits_turns = limit_accel_in_turns(v_ego, sm['carState'].steeringAngleDeg, accel_limits, self.CP)
if self.mpc.mode == 'acc':
accel_limits = [A_CRUISE_MIN, get_max_accel(v_ego)]
accel_limits_turns = limit_accel_in_turns(v_ego, sm['carState'].steeringAngleDeg, accel_limits, self.CP)
else:
accel_limits = [MIN_ACCEL, MAX_ACCEL]
accel_limits_turns = [MIN_ACCEL, MAX_ACCEL]
if reset_state:
self.v_desired_filter.x = v_ego
@ -112,6 +118,9 @@ class LongitudinalPlanner:
# Prevent divergence, smooth in current v_ego
self.v_desired_filter.x = max(0.0, self.v_desired_filter.update(v_ego))
# Compute model v_ego error
if len(sm['modelV2'].temporalPose.trans):
self.v_model_error = sm['modelV2'].temporalPose.trans[0] - v_ego
if force_slow_decel:
# if required so, force a smooth deceleration
@ -124,7 +133,7 @@ class LongitudinalPlanner:
self.mpc.set_weights(prev_accel_constraint)
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'])
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.v_desired_trajectory = np.interp(T_IDXS[:CONTROL_N], T_IDXS_MPC, self.mpc.v_solution)
@ -132,8 +141,7 @@ class LongitudinalPlanner:
self.j_desired_trajectory = np.interp(T_IDXS[:CONTROL_N], T_IDXS_MPC[:-1], self.mpc.j_solution)
# TODO counter is only needed because radar is glitchy, remove once radar is gone
# TODO write fcw in e2e_long mode
self.fcw = self.mpc.mode == 'acc' and self.mpc.crash_cnt > 5 and not sm['carState'].standstill
self.fcw = self.mpc.crash_cnt > 2 and not sm['carState'].standstill
if self.fcw:
cloudlog.info("FCW triggered")

@ -1,10 +1,17 @@
#!/usr/bin/env python3
import unittest
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 cereal import car
from common.conversions import Conversions as CV
from common.params import Params
from selfdrive.test.longitudinal_maneuvers.maneuver import Maneuver
ButtonEvent = car.CarState.ButtonEvent
ButtonType = car.CarState.ButtonEvent.Type
from selfdrive.test.longitudinal_maneuvers.maneuver import Maneuver
def run_cruise_simulation(cruise, t_end=20.):
man = Maneuver(
@ -19,14 +26,14 @@ def run_cruise_simulation(cruise, t_end=20.):
)
valid, output = man.evaluate()
assert valid
return output[-1,3]
return output[-1, 3]
class TestCruiseSpeed(unittest.TestCase):
def test_cruise_speed(self):
params = Params()
for e2e in [False, True]:
params.put_bool("EndToEndLong", e2e)
params.put_bool("ExperimentalMode", e2e)
for speed in np.arange(5, 40, 5):
print(f'Testing {speed} m/s')
cruise_speed = float(speed)
@ -35,5 +42,111 @@ class TestCruiseSpeed(unittest.TestCase):
self.assertAlmostEqual(simulation_steady_state, cruise_speed, delta=.01, msg=f'Did not reach {speed} m/s')
# TODO: test pcmCruise
@parameterized_class(('pcm_cruise',), [(False,)])
class TestVCruiseHelper(unittest.TestCase):
def setUp(self):
self.CP = car.CarParams(pcmCruise=self.pcm_cruise) # pylint: disable=E1101
self.v_cruise_helper = VCruiseHelper(self.CP)
self.reset_cruise_speed_state()
def reset_cruise_speed_state(self):
# Two resets previous cruise speed
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):
# Simulates user pressing set with a current speed
self.v_cruise_helper.initialize_v_cruise(car.CarState(vEgo=v_ego))
def test_adjust_speed(self):
"""
Asserts speed changes on falling edges of buttons.
"""
self.enable(V_CRUISE_ENABLE_MIN * CV.KPH_TO_MS)
for btn in (ButtonType.accelCruise, ButtonType.decelCruise):
for pressed in (True, False):
CS = car.CarState(cruiseState={"available": True})
CS.buttonEvents = [ButtonEvent(type=btn, pressed=pressed)]
self.v_cruise_helper.update_v_cruise(CS, enabled=True, is_metric=False)
self.assertEqual(pressed, self.v_cruise_helper.v_cruise_kph == self.v_cruise_helper.v_cruise_kph_last)
def test_rising_edge_enable(self):
"""
Some car interfaces may enable on rising edge of a button,
ensure we don't adjust speed if enabled changes mid-press.
"""
# NOTE: enabled is always one frame behind the result from button press in controlsd
for enabled, pressed in ((False, False),
(False, True),
(True, False)):
CS = car.CarState(cruiseState={"available": True})
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)
# 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)
def test_resume_in_standstill(self):
"""
Asserts we don't increment set speed if user presses resume/accel to exit cruise standstill.
"""
self.enable(0)
for standstill in (True, False):
for pressed in (True, False):
CS = car.CarState(cruiseState={"available": True, "standstill": standstill})
CS.buttonEvents = [ButtonEvent(type=ButtonType.accelCruise, pressed=pressed)]
self.v_cruise_helper.update_v_cruise(CS, enabled=True, is_metric=False)
# speed should only update if not at standstill and button falling edge
should_equal = standstill or pressed
self.assertEqual(should_equal, self.v_cruise_helper.v_cruise_kph == self.v_cruise_helper.v_cruise_kph_last)
def test_set_gas_pressed(self):
"""
Asserts pressing set while enabled with gas pressed sets
the speed to the maximum of vEgo and current cruise speed.
"""
for v_ego in np.linspace(0, 100, 101):
self.reset_cruise_speed_state()
self.enable(V_CRUISE_ENABLE_MIN * CV.KPH_TO_MS)
# first decrement speed, then perform gas pressed logic
expected_v_cruise_kph = self.v_cruise_helper.v_cruise_kph - IMPERIAL_INCREMENT
expected_v_cruise_kph = max(expected_v_cruise_kph, v_ego * CV.MS_TO_KPH) # clip to min of vEgo
expected_v_cruise_kph = float(np.clip(round(expected_v_cruise_kph, 1), V_CRUISE_MIN, V_CRUISE_MAX))
CS = car.CarState(vEgo=float(v_ego), gasPressed=True, cruiseState={"available": True})
CS.buttonEvents = [ButtonEvent(type=ButtonType.decelCruise, pressed=False)]
self.v_cruise_helper.update_v_cruise(CS, enabled=True, is_metric=False)
# TODO: fix skipping first run due to enabled on rising edge exception
if v_ego == 0.0:
continue
self.assertEqual(expected_v_cruise_kph, self.v_cruise_helper.v_cruise_kph)
def test_initialize_v_cruise(self):
"""
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)
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)
if __name__ == "__main__":
unittest.main()

@ -27,7 +27,7 @@ class TestFollowingDistance(unittest.TestCase):
def test_following_distance(self):
params = Params()
for e2e in [False, True]:
params.put_bool("EndToEndLong", e2e)
params.put_bool("ExperimentalMode", e2e)
for speed in np.arange(0, 40, 5):
print(f'Testing {speed} m/s')
v_lead = float(speed)

@ -187,6 +187,7 @@ class Laikad:
"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,
"correctedMeasurements": meas_msgs

@ -26,4 +26,16 @@ extern "C" {
memcpy(std_buff, stdev.data(), sizeof(double) * stdev.size());
}
bool is_gps_ok(Localizer *localizer){
return localizer->is_gps_ok();
}
bool are_inputs_ok(Localizer *localizer){
return localizer->are_inputs_ok();
}
void observation_timings_invalid_reset(Localizer *localizer){
localizer->observation_timings_invalid_reset();
}
}

@ -19,6 +19,9 @@ const double VALID_TIME_SINCE_RESET = 1.0; // s
const double VALID_POS_STD = 50.0; // m
const double MAX_RESET_TRACKER = 5.0;
const double SANE_GPS_UNCERTAINTY = 1500.0; // m
const double INPUT_INVALID_THRESHOLD = 5.0; // same as reset tracker
const double DECAY = 0.99995; // same as reset tracker
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
@ -200,6 +203,14 @@ VectorXd Localizer::get_stdev() {
return this->kf->get_P().diagonal().array().sqrt();
}
bool Localizer::are_inputs_ok() {
return this->critical_services_valid(this->observation_values_invalid) && !this->observation_timings_invalid;
}
void Localizer::observation_timings_invalid_reset(){
this->observation_timings_invalid = false;
}
void Localizer::handle_sensor(double current_time, const cereal::SensorEventData::Reader& log) {
// TODO does not yet account for double sensor readings in the log
@ -209,10 +220,15 @@ 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");
this->observation_timings_invalid = true;
return;
}
else if (!this->is_timestamp_valid(sensor_time)) {
this->observation_timings_invalid = true;
return;
}
@ -227,6 +243,10 @@ void Localizer::handle_sensor(double current_time, const cereal::SensorEventData
auto meas = Vector3d(-v[2], -v[1], -v[0]);
if (meas.norm() < ROTATION_SANITY_CHECK) {
this->kf->predict_and_observe(sensor_time, OBSERVATION_PHONE_GYRO, { meas });
this->observation_values_invalid["gyroscope"] *= DECAY;
}
else{
this->observation_values_invalid["gyroscope"] += 1.0;
}
}
@ -242,6 +262,10 @@ void Localizer::handle_sensor(double current_time, const cereal::SensorEventData
auto meas = Vector3d(-v[2], -v[1], -v[0]);
if (meas.norm() < ACCEL_SANITY_CHECK) {
this->kf->predict_and_observe(sensor_time, OBSERVATION_PHONE_ACCEL, { meas });
this->observation_values_invalid["accelerometer"] *= DECAY;
}
else{
this->observation_values_invalid["accelerometer"] += 1.0;
}
}
}
@ -270,15 +294,22 @@ void Localizer::handle_gps(double current_time, const cereal::GpsLocationData::R
bool gps_lat_lng_alt_insane = ((std::abs(log.getLatitude()) > 90) || (std::abs(log.getLongitude()) > 180) || (std::abs(log.getAltitude()) > ALTITUDE_SANITY_CHECK));
bool gps_vel_insane = (floatlist2vector(log.getVNED()).norm() > TRANS_SANITY_CHECK);
if (gps_invalid_flag || gps_unreasonable || gps_accuracy_insane || gps_lat_lng_alt_insane || gps_vel_insane) {
// quectel gps verticalAccuracy is clipped to 500
bool gps_accuracy_insane_quectel = false;
if (!ublox_available) {
gps_accuracy_insane_quectel = log.getVerticalAccuracy() == 500;
}
if (gps_invalid_flag || gps_unreasonable || gps_accuracy_insane || gps_lat_lng_alt_insane || gps_vel_insane || gps_accuracy_insane_quectel) {
this->gps_valid = false;
this->determine_gps_mode(current_time);
return;
}
double sensor_time = current_time - sensor_time_offset;
// Process message
this->last_gps_fix = sensor_time;
this->gps_valid = true;
this->gps_mode = true;
Geodetic geodetic = { log.getLatitude(), log.getLongitude(), log.getAltitude() };
this->converter = std::make_unique<LocalCoord>(geodetic);
@ -328,8 +359,14 @@ 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;
}
if ((rot_device.norm() > ROTATION_SANITY_CHECK) || (trans_device.norm() > TRANS_SANITY_CHECK)) {
this->observation_values_invalid["cameraOdometry"] += 1.0;
return;
}
@ -337,10 +374,12 @@ void Localizer::handle_cam_odo(double current_time, const cereal::CameraOdometry
VectorXd trans_calib_std = floatlist2vector(log.getTransStd());
if ((rot_calib_std.minCoeff() <= MIN_STD_SANITY_CHECK) || (trans_calib_std.minCoeff() <= MIN_STD_SANITY_CHECK)) {
this->observation_values_invalid["cameraOdometry"] += 1.0;
return;
}
if ((rot_calib_std.norm() > 10 * ROTATION_SANITY_CHECK) || (trans_calib_std.norm() > 10 * TRANS_SANITY_CHECK)) {
this->observation_values_invalid["cameraOdometry"] += 1.0;
return;
}
@ -356,12 +395,19 @@ void Localizer::handle_cam_odo(double current_time, const cereal::CameraOdometry
{ rot_device }, { rot_device_cov });
this->kf->predict_and_observe(current_time, OBSERVATION_CAMERA_ODO_TRANSLATION,
{ trans_device }, { trans_device_cov });
this->observation_values_invalid["cameraOdometry"] *= DECAY;
}
void Localizer::handle_live_calib(double current_time, const cereal::LiveCalibrationData::Reader& log) {
if (!this->is_timestamp_valid(current_time)) {
this->observation_timings_invalid = true;
return;
}
if (log.getRpyCalib().size() > 0) {
auto live_calib = floatlist2vector(log.getRpyCalib());
if ((live_calib.minCoeff() < -CALIB_RPY_SANITY_CHECK) || (live_calib.maxCoeff() > CALIB_RPY_SANITY_CHECK)) {
this->observation_values_invalid["liveCalibration"] += 1.0;
return;
}
@ -369,6 +415,7 @@ void Localizer::handle_live_calib(double current_time, const cereal::LiveCalibra
this->device_from_calib = euler2rot(this->calib);
this->calib_from_device = this->device_from_calib.transpose();
this->calibrated = log.getCalStatus() == 1;
this->observation_values_invalid["liveCalibration"] *= DECAY;
}
}
@ -400,8 +447,8 @@ void Localizer::time_check(double current_time) {
void Localizer::update_reset_tracker() {
// reset tracker is tuned to trigger when over 1reset/10s over 2min period
if (this->isGpsOK()) {
this->reset_tracker *= .99995;
if (this->is_gps_ok()) {
this->reset_tracker *= DECAY;
} else {
this->reset_tracker = 0.0;
}
@ -476,9 +523,26 @@ kj::ArrayPtr<capnp::byte> Localizer::get_message_bytes(MessageBuilder& msg_build
return msg_builder.toBytes();
}
bool Localizer::is_gps_ok() {
return this->gps_valid;
}
bool Localizer::isGpsOK() {
return this->kf->get_filter_time() - this->last_gps_fix < 1.0;
bool Localizer::critical_services_valid(std::map<std::string, double> critical_services) {
for (auto &kv : critical_services){
if (kv.second >= INPUT_INVALID_THRESHOLD){
return false;
}
}
return true;
}
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");
return false;
}
return true;
}
void Localizer::determine_gps_mode(double current_time) {
@ -498,8 +562,10 @@ void Localizer::determine_gps_mode(double current_time) {
}
int Localizer::locationd_thread() {
ublox_available = Params().getBool("UbloxAvailable", true);
const char* gps_location_socket;
if (Params().getBool("UbloxAvailable", true)) {
if (ublox_available) {
gps_location_socket = "gpsLocationExternal";
} else {
gps_location_socket = "gpsLocation";
@ -513,10 +579,15 @@ int Localizer::locationd_thread() {
uint64_t cnt = 0;
bool filterInitialized = false;
const std::vector<std::string> critical_input_services = {"cameraOdometry", "liveCalibration", "accelerometer", "gyroscope"};
for (std::string service : critical_input_services) {
this->observation_values_invalid.insert({service, 0.0});
}
while (!do_exit) {
sm.update();
if (filterInitialized){
this->observation_timings_invalid_reset();
for (const char* service : service_list) {
if (sm.updated(service) && sm.valid(service)){
const cereal::Event::Reader log = sm[service];
@ -530,8 +601,8 @@ int Localizer::locationd_thread() {
// 100Hz publish for notcars, 20Hz for cars
const char* trigger_msg = sm["carParams"].getCarParams().getNotCar() ? "accelerometer" : "cameraOdometry";
if (sm.updated(trigger_msg)) {
bool inputsOK = sm.allAliveAndValid();
bool gpsOK = this->isGpsOK();
bool inputsOK = sm.allAliveAndValid() && this->are_inputs_ok();
bool gpsOK = this->is_gps_ok();
bool sensorsOK = sm.allAliveAndValid({"accelerometer", "gyroscope"});
MessageBuilder msg_builder;

@ -3,6 +3,7 @@
#include <eigen3/Eigen/Dense>
#include <fstream>
#include <memory>
#include <map>
#include <string>
#include "cereal/messaging/messaging.h"
@ -32,8 +33,12 @@ public:
void finite_check(double current_time = NAN);
void time_check(double current_time = NAN);
void update_reset_tracker();
bool isGpsOK();
bool is_gps_ok();
bool critical_services_valid(std::map<std::string, double> critical_services);
bool is_timestamp_valid(double current_time);
void determine_gps_mode(double current_time);
bool are_inputs_ok();
void observation_timings_invalid_reset();
kj::ArrayPtr<capnp::byte> get_message_bytes(MessageBuilder& msg_builder,
bool inputsOK, bool sensorsOK, bool gpsOK, bool msgValid);
@ -68,8 +73,11 @@ private:
std::unique_ptr<LocalCoord> converter;
int64_t unix_timestamp_millis = 0;
double last_gps_fix = 0;
double reset_tracker = 0.0;
bool device_fell = false;
bool gps_mode = false;
bool gps_valid = false;
bool ublox_available = true;
bool observation_timings_invalid = false;
std::map<std::string, double> observation_values_invalid;
};

@ -92,7 +92,7 @@ class ParamsLearner:
self.speed = msg.vEgo
in_linear_region = abs(self.steering_angle) < 45 or not self.steering_pressed
self.active = self.speed > 5 and in_linear_region
self.active = self.speed > 1 and in_linear_region
if self.active:
self.kf.predict_and_observe(t, ObservationKind.STEER_ANGLE, np.array([[math.radians(msg.steeringAngleDeg)]]))

@ -16,9 +16,9 @@ from selfdrive.controls.lib.vehicle_model import ACCELERATION_DUE_TO_GRAVITY
HISTORY = 5 # secs
POINTS_PER_BUCKET = 1500
MIN_POINTS_TOTAL = 4000
MIN_POINTS_TOTAL_QLOG = 800
MIN_POINTS_TOTAL_QLOG = 600
FIT_POINTS_TOTAL = 2000
FIT_POINTS_TOTAL_QLOG = 800
FIT_POINTS_TOTAL_QLOG = 600
MIN_VEL = 15 # m/s
FRICTION_FACTOR = 1.5 # ~85% of data coverage
FACTOR_SANITY = 0.3

@ -10,6 +10,7 @@
#include <string>
#include <thread>
#include <unordered_map>
#include <utility>
#include "cereal/messaging/messaging.h"
#include "cereal/services.h"

@ -4,6 +4,7 @@
#include <condition_variable>
#include <sstream>
#include <thread>
#include <utility>
#include "catch2/catch.hpp"
#include "cereal/messaging/messaging.h"

@ -4,6 +4,7 @@ import signal
import time
import unittest
from common.params import Params
import selfdrive.manager.manager as manager
from selfdrive.manager.process import DaemonProcess
from selfdrive.manager.process_config import managed_processes
@ -20,6 +21,10 @@ class TestManager(unittest.TestCase):
os.environ['PASSIVE'] = '0'
HARDWARE.set_power_save(False)
# ensure clean CarParams
params = Params()
params.clear_all()
def tearDown(self):
manager.manager_cleanup()
@ -40,6 +45,7 @@ class TestManager(unittest.TestCase):
Ensure all processes exit cleanly when stopped.
"""
HARDWARE.set_power_save(False)
manager.manager_init()
manager.manager_prepare()
for p in ALL_PROCESSES:
managed_processes[p].start()

@ -337,6 +337,17 @@ void fill_model(cereal::ModelDataV2::Builder &framed, const ModelOutput &net_out
for (int i=0; i<LEAD_MHP_SELECTION; i++) {
fill_lead(leads[i], net_outputs.leads, i, t_offsets[i]);
}
// temporal pose
const auto &v_mean = net_outputs.temporal_pose.velocity_mean;
const auto &r_mean = net_outputs.temporal_pose.rotation_mean;
const auto &v_std = net_outputs.temporal_pose.velocity_std;
const auto &r_std = net_outputs.temporal_pose.rotation_std;
auto temporal_pose = framed.initTemporalPose();
temporal_pose.setTrans({v_mean.x, v_mean.y, v_mean.z});
temporal_pose.setRot({r_mean.x, r_mean.y, r_mean.z});
temporal_pose.setTransStd({exp(v_std.x), exp(v_std.y), exp(v_std.z)});
temporal_pose.setRotStd({exp(r_std.x), exp(r_std.y), exp(r_std.z)});
}
void model_publish(PubMaster &pm, uint32_t vipc_frame_id, uint32_t vipc_frame_id_extra, uint32_t frame_id, float frame_drop,

@ -167,6 +167,14 @@ struct ModelOutputWideFromDeviceEuler {
};
static_assert(sizeof(ModelOutputWideFromDeviceEuler) == sizeof(ModelOutputXYZ)*2);
struct ModelOutputTemporalPose {
ModelOutputXYZ velocity_mean;
ModelOutputXYZ rotation_mean;
ModelOutputXYZ velocity_std;
ModelOutputXYZ rotation_std;
};
static_assert(sizeof(ModelOutputTemporalPose) == sizeof(ModelOutputXYZ)*4);
struct ModelOutputDisengageProb {
float gas_disengage;
float brake_disengage;
@ -225,6 +233,7 @@ struct ModelOutput {
const ModelOutputMeta meta;
const ModelOutputPose pose;
const ModelOutputWideFromDeviceEuler wide_from_device_euler;
const ModelOutputTemporalPose temporal_pose;
};
constexpr int OUTPUT_SIZE = sizeof(ModelOutput) / sizeof(float);

@ -1,3 +1,3 @@
version https://git-lfs.github.com/spec/v1
oid sha256:dcfad22cecf37275d01a339d96174800c109e9a70f853fdef3e4ef62ed3f4bbe
size 45922983
oid sha256:c73998c9f428380dd2282b451de6011469b717498ae83578cbf7aa95948910f7
size 45962473

@ -34,6 +34,7 @@ class DRIVER_MONITOR_SETTINGS():
self._EE_THRESH11 = 0.275
self._EE_THRESH12 = 5.5
self._EE_MAX_OFFSET1 = 0.06
self._EE_MIN_OFFSET1 = 0.025
self._EE_THRESH21 = 0.01
self._EE_THRESH22 = 0.35
@ -44,6 +45,7 @@ class DRIVER_MONITOR_SETTINGS():
self._POSE_YAW_THRESHOLD_SLACK = 0.5042
self._POSE_YAW_THRESHOLD_STRICT = self._POSE_YAW_THRESHOLD
self._PITCH_NATURAL_OFFSET = 0.029 # initial value before offset is learned
self._PITCH_NATURAL_THRESHOLD = 0.449
self._YAW_NATURAL_OFFSET = 0.097 # initial value before offset is learned
self._PITCH_MAX_OFFSET = 0.124
self._PITCH_MIN_OFFSET = -0.0881
@ -197,7 +199,7 @@ class DriverStatus():
self.settings._YAW_MIN_OFFSET), self.settings._YAW_MAX_OFFSET)
pitch_error = 0 if pitch_error > 0 else abs(pitch_error) # no positive pitch limit
yaw_error = abs(yaw_error)
if pitch_error > self.settings._POSE_PITCH_THRESHOLD*self.pose.cfactor_pitch or \
if pitch_error > (self.settings._POSE_PITCH_THRESHOLD*self.pose.cfactor_pitch if self.pose_calibrated else self.settings._PITCH_NATURAL_THRESHOLD) or \
yaw_error > self.settings._POSE_YAW_THRESHOLD*self.pose.cfactor_yaw:
distracted_types.append(DistractedType.DISTRACTED_POSE)
@ -205,7 +207,7 @@ class DriverStatus():
distracted_types.append(DistractedType.DISTRACTED_BLINK)
if self.ee1_calibrated:
ee1_dist = self.eev1 > min(self.ee1_offseter.filtered_stat.M, self.settings._EE_MAX_OFFSET1) * self.settings._EE_THRESH12
ee1_dist = self.eev1 > max(min(self.ee1_offseter.filtered_stat.M, self.settings._EE_MAX_OFFSET1), self.settings._EE_MIN_OFFSET1) * self.settings._EE_THRESH12
else:
ee1_dist = self.eev1 > self.settings._EE_THRESH11
# if self.ee2_calibrated:

@ -1,17 +1,132 @@
#include "lsm6ds3_accel.h"
#include <cassert>
#include <cmath>
#include <cstring>
#include "common/swaglog.h"
#include "common/timing.h"
#include "common/util.h"
LSM6DS3_Accel::LSM6DS3_Accel(I2CBus *bus, int gpio_nr, bool shared_gpio) :
I2CSensor(bus, gpio_nr, shared_gpio) {}
void LSM6DS3_Accel::wait_for_data_ready() {
uint8_t drdy = 0;
uint8_t buffer[6];
do {
read_register(LSM6DS3_ACCEL_I2C_REG_STAT_REG, &drdy, sizeof(drdy));
drdy &= LSM6DS3_ACCEL_DRDY_XLDA;
} while (drdy == 0);
read_register(LSM6DS3_ACCEL_I2C_REG_OUTX_L_XL, buffer, sizeof(buffer));
}
void LSM6DS3_Accel::read_and_avg_data(float* out_buf) {
uint8_t drdy = 0;
uint8_t buffer[6];
float scaling = 0.061f;
if (source == cereal::SensorEventData::SensorSource::LSM6DS3TRC) {
scaling = 0.122f;
}
for (int i = 0; i < 5; i++) {
do {
read_register(LSM6DS3_ACCEL_I2C_REG_STAT_REG, &drdy, sizeof(drdy));
drdy &= LSM6DS3_ACCEL_DRDY_XLDA;
} while (drdy == 0);
int len = read_register(LSM6DS3_ACCEL_I2C_REG_OUTX_L_XL, buffer, sizeof(buffer));
assert(len == sizeof(buffer));
for (int j = 0; j < 3; j++) {
out_buf[j] += (float)read_16_bit(buffer[j*2], buffer[j*2+1]) * scaling;
}
}
for (int i = 0; i < 3; i++) {
out_buf[i] /= 5.0f;
}
}
int LSM6DS3_Accel::self_test(int test_type) {
float val_st_off[3] = {0};
float val_st_on[3] = {0};
float test_val[3] = {0};
uint8_t ODR_FS_MO = LSM6DS3_ACCEL_ODR_52HZ; // full scale: +-2g, ODR: 52Hz
// prepare sensor for self-test
// enable block data update and automatic increment
int ret = set_register(LSM6DS3_ACCEL_I2C_REG_CTRL3_C, LSM6DS3_ACCEL_IF_INC_BDU);
if (ret < 0) {
return ret;
}
if (source == cereal::SensorEventData::SensorSource::LSM6DS3TRC) {
ODR_FS_MO = LSM6DS3_ACCEL_FS_4G | LSM6DS3_ACCEL_ODR_52HZ;
}
ret = set_register(LSM6DS3_ACCEL_I2C_REG_CTRL1_XL, ODR_FS_MO);
if (ret < 0) {
return ret;
}
// wait for stable output, and discard first values
util::sleep_for(100);
wait_for_data_ready();
read_and_avg_data(val_st_off);
// enable Self Test positive (or negative)
ret = set_register(LSM6DS3_ACCEL_I2C_REG_CTRL5_C, test_type);
if (ret < 0) {
return ret;
}
// wait for stable output, and discard first values
util::sleep_for(100);
wait_for_data_ready();
read_and_avg_data(val_st_on);
// disable sensor
ret = set_register(LSM6DS3_ACCEL_I2C_REG_CTRL1_XL, 0);
if (ret < 0) {
return ret;
}
// disable self test
ret = set_register(LSM6DS3_ACCEL_I2C_REG_CTRL5_C, 0);
if (ret < 0) {
return ret;
}
// calculate the mg values for self test
for (int i = 0; i < 3; i++) {
test_val[i] = fabs(val_st_on[i] - val_st_off[i]);
}
// verify test result
for (int i = 0; i < 3; i++) {
if ((LSM6DS3_ACCEL_MIN_ST_LIMIT_mg > test_val[i]) ||
(test_val[i] > LSM6DS3_ACCEL_MAX_ST_LIMIT_mg)) {
return -1;
}
}
return ret;
}
int LSM6DS3_Accel::init() {
int ret = 0;
uint8_t buffer[1];
uint8_t value = 0;
bool do_self_test = false;
const char* env_lsm_selftest =env_lsm_selftest = std::getenv("LSM_SELF_TEST");
if (env_lsm_selftest != nullptr && strncmp(env_lsm_selftest, "1", 1) == 0) {
do_self_test = true;
}
ret = read_register(LSM6DS3_ACCEL_I2C_REG_ID, buffer, 1);
if(ret < 0) {
@ -29,11 +144,29 @@ int LSM6DS3_Accel::init() {
source = cereal::SensorEventData::SensorSource::LSM6DS3TRC;
}
ret = self_test(LSM6DS3_ACCEL_POSITIVE_TEST);
if (ret < 0) {
LOGE("LSM6DS3 accel positive self-test failed!");
if (do_self_test) goto fail;
}
ret = self_test(LSM6DS3_ACCEL_NEGATIVE_TEST);
if (ret < 0) {
LOGE("LSM6DS3 accel negative self-test failed!");
if (do_self_test) goto fail;
}
ret = init_gpio();
if (ret < 0) {
goto fail;
}
// enable continuous update, and automatic increase
ret = set_register(LSM6DS3_ACCEL_I2C_REG_CTRL3_C, LSM6DS3_ACCEL_IF_INC);
if (ret < 0) {
goto fail;
}
// TODO: set scale and bandwidth. Default is +- 2G, 50 Hz
ret = set_register(LSM6DS3_ACCEL_I2C_REG_CTRL1_XL, LSM6DS3_ACCEL_ODR_104HZ);
if (ret < 0) {

@ -10,21 +10,37 @@
#define LSM6DS3_ACCEL_I2C_REG_ID 0x0F
#define LSM6DS3_ACCEL_I2C_REG_INT1_CTRL 0x0D
#define LSM6DS3_ACCEL_I2C_REG_CTRL1_XL 0x10
#define LSM6DS3_ACCEL_I2C_REG_CTRL3_C 0x12
#define LSM6DS3_ACCEL_I2C_REG_CTRL5_C 0x14
#define LSM6DS3_ACCEL_I2C_REG_CTR9_XL 0x18
#define LSM6DS3_ACCEL_I2C_REG_STAT_REG 0x1E
#define LSM6DS3_ACCEL_I2C_REG_OUTX_L_XL 0x28
// Constants
#define LSM6DS3_ACCEL_CHIP_ID 0x69
#define LSM6DS3TRC_ACCEL_CHIP_ID 0x6A
#define LSM6DS3_ACCEL_FS_4G (0b10 << 2)
#define LSM6DS3_ACCEL_ODR_52HZ (0b0011 << 4)
#define LSM6DS3_ACCEL_ODR_104HZ (0b0100 << 4)
#define LSM6DS3_ACCEL_INT1_DRDY_XL 0b1
#define LSM6DS3_ACCEL_DRDY_XLDA 0b1
#define LSM6DS3_ACCEL_DRDY_PULSE_MODE (1 << 7)
#define LSM6DS3_ACCEL_IF_INC 0b00000100
#define LSM6DS3_ACCEL_IF_INC_BDU 0b01000100
#define LSM6DS3_ACCEL_XYZ_DEN 0b11100000
#define LSM6DS3_ACCEL_POSITIVE_TEST 0b01
#define LSM6DS3_ACCEL_NEGATIVE_TEST 0b10
#define LSM6DS3_ACCEL_MIN_ST_LIMIT_mg 90.0f
#define LSM6DS3_ACCEL_MAX_ST_LIMIT_mg 1700.0f
class LSM6DS3_Accel : public I2CSensor {
uint8_t get_device_address() {return LSM6DS3_ACCEL_I2C_ADDR;}
cereal::SensorEventData::SensorSource source = cereal::SensorEventData::SensorSource::LSM6DS3;
// self test functions
int self_test(int test_type);
void wait_for_data_ready();
void read_and_avg_data(float* val_st_off);
public:
LSM6DS3_Accel(I2CBus *bus, int gpio_nr = 0, bool shared_gpio = false);
int init();

@ -2,19 +2,120 @@
#include <cassert>
#include <cmath>
#include <cstring>
#include "common/swaglog.h"
#include "common/timing.h"
#include "common/util.h"
#define DEG2RAD(x) ((x) * M_PI / 180.0)
LSM6DS3_Gyro::LSM6DS3_Gyro(I2CBus *bus, int gpio_nr, bool shared_gpio) :
I2CSensor(bus, gpio_nr, shared_gpio) {}
void LSM6DS3_Gyro::wait_for_data_ready() {
uint8_t drdy = 0;
uint8_t buffer[6];
do {
read_register(LSM6DS3_GYRO_I2C_REG_STAT_REG, &drdy, sizeof(drdy));
drdy &= LSM6DS3_GYRO_DRDY_GDA;
} while (drdy == 0);
read_register(LSM6DS3_GYRO_I2C_REG_OUTX_L_G, buffer, sizeof(buffer));
}
void LSM6DS3_Gyro::read_and_avg_data(float* out_buf) {
uint8_t drdy = 0;
uint8_t buffer[6];
for (int i = 0; i < 5; i++) {
do {
read_register(LSM6DS3_GYRO_I2C_REG_STAT_REG, &drdy, sizeof(drdy));
drdy &= LSM6DS3_GYRO_DRDY_GDA;
} while (drdy == 0);
int len = read_register(LSM6DS3_GYRO_I2C_REG_OUTX_L_G, buffer, sizeof(buffer));
assert(len == sizeof(buffer));
for (int j = 0; j < 3; j++) {
out_buf[j] += (float)read_16_bit(buffer[j*2], buffer[j*2+1]) * 70.0f;
}
}
// calculate the mg average values
for (int i = 0; i < 3; i++) {
out_buf[i] /= 5.0f;
}
}
int LSM6DS3_Gyro::self_test(int test_type) {
float val_st_off[3] = {0};
float val_st_on[3] = {0};
float test_val[3] = {0};
// prepare sensor for self-test
// full scale: 2000dps, ODR: 208Hz
int ret = set_register(LSM6DS3_GYRO_I2C_REG_CTRL2_G, LSM6DS3_GYRO_ODR_208HZ | LSM6DS3_GYRO_FS_2000dps);
if (ret < 0) {
return ret;
}
// wait for stable output, and discard first values
util::sleep_for(150);
wait_for_data_ready();
read_and_avg_data(val_st_off);
// enable Self Test positive (or negative)
ret = set_register(LSM6DS3_GYRO_I2C_REG_CTRL5_C, test_type);
if (ret < 0) {
return ret;
}
// wait for stable output, and discard first values
util::sleep_for(50);
wait_for_data_ready();
read_and_avg_data(val_st_on);
// disable sensor
ret = set_register(LSM6DS3_GYRO_I2C_REG_CTRL2_G, 0);
if (ret < 0) {
return ret;
}
// disable self test
ret = set_register(LSM6DS3_GYRO_I2C_REG_CTRL5_C, 0);
if (ret < 0) {
return ret;
}
// calculate the mg values for self test
for (int i = 0; i < 3; i++) {
test_val[i] = fabs(val_st_on[i] - val_st_off[i]);
}
// verify test result
for (int i = 0; i < 3; i++) {
if ((LSM6DS3_GYRO_MIN_ST_LIMIT_mdps > test_val[i]) ||
(test_val[i] > LSM6DS3_GYRO_MAX_ST_LIMIT_mdps)) {
return -1;
}
}
return ret;
}
int LSM6DS3_Gyro::init() {
int ret = 0;
uint8_t buffer[1];
uint8_t value = 0;
bool do_self_test = false;
const char* env_lsm_selftest =env_lsm_selftest = std::getenv("LSM_SELF_TEST");
if (env_lsm_selftest != nullptr && strncmp(env_lsm_selftest, "1", 1) == 0) {
do_self_test = true;
}
ret = read_register(LSM6DS3_GYRO_I2C_REG_ID, buffer, 1);
if(ret < 0) {
@ -37,6 +138,18 @@ int LSM6DS3_Gyro::init() {
goto fail;
}
ret = self_test(LSM6DS3_GYRO_POSITIVE_TEST);
if (ret < 0 ) {
LOGE("LSM6DS3 gyro positive self-test failed!");
if (do_self_test) goto fail;
}
ret = self_test(LSM6DS3_GYRO_NEGATIVE_TEST);
if (ret < 0) {
LOGE("LSM6DS3 gyro negative self-test failed!");
if (do_self_test) goto fail;
}
// TODO: set scale. Default is +- 250 deg/s
ret = set_register(LSM6DS3_GYRO_I2C_REG_CTRL2_G, LSM6DS3_GYRO_ODR_104HZ);
if (ret < 0) {
@ -65,7 +178,7 @@ fail:
int LSM6DS3_Gyro::shutdown() {
int ret = 0;
// disable data ready interrupt for accel on INT1
// disable data ready interrupt for gyro on INT1
uint8_t value = 0;
ret = read_register(LSM6DS3_GYRO_I2C_REG_INT1_CTRL, &value, 1);
if (ret < 0) {

@ -10,21 +10,33 @@
#define LSM6DS3_GYRO_I2C_REG_ID 0x0F
#define LSM6DS3_GYRO_I2C_REG_INT1_CTRL 0x0D
#define LSM6DS3_GYRO_I2C_REG_CTRL2_G 0x11
#define LSM6DS3_GYRO_I2C_REG_CTRL5_C 0x14
#define LSM6DS3_GYRO_I2C_REG_STAT_REG 0x1E
#define LSM6DS3_GYRO_I2C_REG_OUTX_L_G 0x22
#define LSM6DS3_GYRO_POSITIVE_TEST (0b01 << 2)
#define LSM6DS3_GYRO_NEGATIVE_TEST (0b11 << 2)
// Constants
#define LSM6DS3_GYRO_CHIP_ID 0x69
#define LSM6DS3TRC_GYRO_CHIP_ID 0x6A
#define LSM6DS3_GYRO_FS_2000dps (0b11 << 2)
#define LSM6DS3_GYRO_ODR_104HZ (0b0100 << 4)
#define LSM6DS3_GYRO_ODR_208HZ (0b0101 << 4)
#define LSM6DS3_GYRO_INT1_DRDY_G 0b10
#define LSM6DS3_GYRO_DRDY_GDA 0b10
#define LSM6DS3_GYRO_DRDY_PULSE_MODE (1 << 7)
#define LSM6DS3_GYRO_MIN_ST_LIMIT_mdps 150000.0f
#define LSM6DS3_GYRO_MAX_ST_LIMIT_mdps 700000.0f
class LSM6DS3_Gyro : public I2CSensor {
uint8_t get_device_address() {return LSM6DS3_GYRO_I2C_ADDR;}
cereal::SensorEventData::SensorSource source = cereal::SensorEventData::SensorSource::LSM6DS3;
// self test functions
int self_test(int test_type);
void wait_for_data_ready();
void read_and_avg_data(float* val_st_off);
public:
LSM6DS3_Gyro(I2CBus *bus, int gpio_nr = 0, bool shared_gpio = false);
int init();

@ -104,6 +104,9 @@ class TestSensord(unittest.TestCase):
# make sure gpiochip0 is readable
HARDWARE.initialize_hardware()
# enable LSM self test
os.environ["LSM_SELF_TEST"] = "1"
# read initial sensor values every test case can use
os.system("pkill -f ./_sensord")
try:
@ -118,6 +121,8 @@ class TestSensord(unittest.TestCase):
@classmethod
def tearDownClass(cls):
managed_processes["sensord"].stop()
if "LSM_SELF_TEST" in os.environ:
del os.environ['LSM_SELF_TEST']
def tearDown(self):
managed_processes["sensord"].stop()

@ -17,6 +17,7 @@ class Maneuver():
self.only_lead2 = kwargs.get("only_lead2", False)
self.only_radar = kwargs.get("only_radar", False)
self.ensure_start = kwargs.get("ensure_start", False)
self.enabled = kwargs.get("enabled", True)
self.duration = duration
self.title = title
@ -26,23 +27,24 @@ class Maneuver():
lead_relevancy=self.lead_relevancy,
speed=self.speed,
distance_lead=self.distance_lead,
enabled=self.enabled,
only_lead2=self.only_lead2,
only_radar=self.only_radar,
)
valid = True
logs = []
while plant.current_time() < self.duration:
speed_lead = np.interp(plant.current_time(), self.breakpoints, self.speed_lead_values)
prob = np.interp(plant.current_time(), self.breakpoints, self.prob_lead_values)
cruise = np.interp(plant.current_time(), self.breakpoints, self.cruise_values)
while plant.current_time < self.duration:
speed_lead = np.interp(plant.current_time, self.breakpoints, self.speed_lead_values)
prob = np.interp(plant.current_time, self.breakpoints, self.prob_lead_values)
cruise = np.interp(plant.current_time, self.breakpoints, self.cruise_values)
log = plant.step(speed_lead, prob, cruise)
d_rel = log['distance_lead'] - log['distance'] if self.lead_relevancy else 200.
v_rel = speed_lead - log['speed'] if self.lead_relevancy else 0.
log['d_rel'] = d_rel
log['v_rel'] = v_rel
logs.append(np.array([plant.current_time(),
logs.append(np.array([plant.current_time,
log['distance'],
log['distance_lead'],
log['speed'],

@ -10,11 +10,12 @@ from selfdrive.modeld.constants import T_IDXS
from selfdrive.controls.lib.longitudinal_planner import LongitudinalPlanner
from selfdrive.controls.lib.radar_helpers import _LEAD_ACCEL_TAU
class Plant():
class Plant:
messaging_initialized = False
def __init__(self, lead_relevancy=False, speed=0.0, distance_lead=2.0,
only_lead2=False, only_radar=False):
enabled=True, only_lead2=False, only_radar=False):
self.rate = 1. / DT_MDL
if not Plant.messaging_initialized:
@ -32,10 +33,11 @@ class Plant():
self.speeds = []
# lead car
self.distance_lead = distance_lead
self.lead_relevancy = lead_relevancy
self.only_lead2=only_lead2
self.only_radar=only_radar
self.distance_lead = distance_lead
self.enabled = enabled
self.only_lead2 = only_lead2
self.only_radar = only_radar
self.rk = Ratekeeper(self.rate, print_delay_threshold=100.0)
self.ts = 1. / self.rate
@ -47,6 +49,7 @@ class Plant():
self.planner = LongitudinalPlanner(CarInterface.get_params(CAR.CIVIC), init_v=self.speed)
@property
def current_time(self):
return float(self.rk.frame) / self.rate
@ -104,9 +107,7 @@ class Plant():
acceleration.x = [float(x) for x in np.zeros_like(T_IDXS)]
model.modelV2.acceleration = acceleration
control.controlsState.longControlState = LongCtrlState.pid
control.controlsState.longControlState = LongCtrlState.pid if self.enabled else LongCtrlState.off
control.controlsState.vCruise = float(v_cruise * 3.6)
car_state.carState.vEgo = float(self.speed)
car_state.carState.standstill = self.speed < 0.01
@ -141,7 +142,7 @@ class Plant():
# print at 5hz
if (self.rk.frame % (self.rate // 5)) == 0:
print("%2.2f sec %6.2f m %6.2f m/s %6.2f m/s2 lead_rel: %6.2f m %6.2f m/s"
% (self.current_time(), self.distance, self.speed, self.acceleration, d_rel, v_rel))
% (self.current_time, self.distance, self.speed, self.acceleration, d_rel, v_rel))
# ******** update prevs ********

@ -10,7 +10,7 @@ from selfdrive.test.longitudinal_maneuvers.maneuver import Maneuver
# TODO: make new FCW tests
maneuvers = [
Maneuver(
'approach stopped car at 20m/s, initial distance: 120m',
'approach stopped car at 25m/s, initial distance: 120m',
duration=20.,
initial_speed=25.,
lead_relevancy=True,
@ -118,6 +118,13 @@ maneuvers = [
breakpoints=[1., 10., 15.],
ensure_start=True,
),
Maneuver(
'cruising at 25 m/s while disabled',
duration=20.,
initial_speed=25.,
lead_relevancy=False,
enabled=False,
),
]
@ -143,11 +150,11 @@ def run_maneuver_worker(k):
params = Params()
man = maneuvers[k]
params.put_bool("EndToEndLong", True)
params.put_bool("ExperimentalMode", True)
print(man.title, ' in e2e mode')
valid, _ = man.evaluate()
self.assertTrue(valid, msg=man.title)
params.put_bool("EndToEndLong", False)
params.put_bool("ExperimentalMode", False)
print(man.title, ' in acc mode')
valid, _ = man.evaluate()
self.assertTrue(valid, msg=man.title)

@ -1 +1 @@
49ea844254883ac61caa2ac425f453799aeb28a6
ca02aa240e629920ad88a6510213cb0a153af92b

@ -1 +1 @@
01b24beff6855e8c4d2fb0efeeefafb46343e013
959e63af52d9efdb62156cab4b773f88b154fd75

@ -18,7 +18,7 @@ from tools.lib.logreader import LogReader
source_segments = [
("BODY", "937ccb7243511b65|2022-05-24--16-03-09--1"), # COMMA.BODY
("HYUNDAI", "02c45f73a2e5c6e9|2021-01-01--19-08-22--1"), # HYUNDAI.SONATA
("HYUNDAI2", "d545129f3ca90f28|2022-10-19--09-22-54--9"), # HYUNDAI.KIA_EV6
("HYUNDAI2", "d545129f3ca90f28|2022-11-07--20-43-08--3"), # HYUNDAI.KIA_EV6
("TOYOTA", "0982d79ebb0de295|2021-01-04--17-13-21--13"), # TOYOTA.PRIUS (INDI)
("TOYOTA2", "0982d79ebb0de295|2021-01-03--20-03-36--6"), # TOYOTA.RAV4 (LQR)
("TOYOTA3", "f7d7e3538cda1a2a|2021-08-16--08-55-34--6"), # TOYOTA.COROLLA_TSS2
@ -41,7 +41,7 @@ source_segments = [
segments = [
("BODY", "regenFA002A80700|2022-09-27--15-37-02--0"),
("HYUNDAI", "regenBE53A59065B|2022-09-27--16-52-03--0"),
("HYUNDAI2", "d545129f3ca90f28|2022-10-19--09-22-54--9"),
("HYUNDAI2", "d545129f3ca90f28|2022-11-07--20-43-08--3"),
("TOYOTA", "regen929C5790007|2022-09-27--16-27-47--0"),
("TOYOTA2", "regenEA3950D7F22|2022-09-27--15-43-24--0"),
("TOYOTA3", "regen89026F6BD8D|2022-09-27--15-45-37--0"),

@ -58,7 +58,7 @@ qt_env.Program("qt/spinner", ["qt/spinner.cc"], LIBS=qt_libs)
qt_src = ["main.cc", "qt/sidebar.cc", "qt/onroad.cc", "qt/body.cc",
"qt/window.cc", "qt/home.cc", "qt/offroad/settings.cc",
"qt/offroad/software_settings.cc", "qt/offroad/onboarding.cc",
"qt/offroad/driverview.cc"]
"qt/offroad/driverview.cc", "qt/offroad/experimental_mode.cc"]
qt_env.Program("_ui", qt_src + [asset_obj], LIBS=qt_libs)
if GetOption('test'):
qt_src.remove("main.cc") # replaced by test_runner

@ -4,6 +4,7 @@
#include <QMouseEvent>
#include <QVBoxLayout>
#include "selfdrive/ui/qt/offroad/experimental_mode.h"
#include "selfdrive/ui/qt/util.h"
#include "selfdrive/ui/qt/widgets/drive_stats.h"
#include "selfdrive/ui/qt/widgets/prime.h"
@ -22,7 +23,8 @@ HomeWindow::HomeWindow(QWidget* parent) : QWidget(parent) {
slayout = new QStackedLayout();
main_layout->addLayout(slayout);
home = new OffroadHome();
home = new OffroadHome(this);
QObject::connect(home, &OffroadHome::openSettings, this, &HomeWindow::openSettings);
slayout->addWidget(home);
onroad = new OnroadWindow(this);
@ -128,11 +130,24 @@ OffroadHome::OffroadHome(QWidget* parent) : QFrame(parent) {
main_layout->addSpacing(25);
center_layout = new QStackedLayout();
// Vertical experimental button and drive stats layout
QWidget* statsAndExperimentalModeButtonWidget = new QWidget(this);
QVBoxLayout* statsAndExperimentalModeButton = new QVBoxLayout(statsAndExperimentalModeButtonWidget);
statsAndExperimentalModeButton->setSpacing(30);
statsAndExperimentalModeButton->setMargin(0);
ExperimentalModeButton *experimental_mode = new ExperimentalModeButton(this);
QObject::connect(experimental_mode, &ExperimentalModeButton::openSettings, this, &OffroadHome::openSettings);
statsAndExperimentalModeButton->addWidget(experimental_mode, 1);
statsAndExperimentalModeButton->addWidget(new DriveStats, 1);
// Horizontal experimental + drive stats and setup widget
QWidget* statsAndSetupWidget = new QWidget(this);
QHBoxLayout* statsAndSetup = new QHBoxLayout(statsAndSetupWidget);
statsAndSetup->setMargin(0);
statsAndSetup->setSpacing(30);
statsAndSetup->addWidget(new DriveStats, 1);
statsAndSetup->addWidget(statsAndExperimentalModeButtonWidget, 1);
statsAndSetup->addWidget(new SetupWidget);
center_layout->addWidget(statsAndSetupWidget);

@ -22,6 +22,9 @@ class OffroadHome : public QFrame {
public:
explicit OffroadHome(QWidget* parent = 0);
signals:
void openSettings(int index = 0, const QString &param = "");
private:
void showEvent(QShowEvent *event) override;
void hideEvent(QHideEvent *event) override;
@ -45,7 +48,7 @@ public:
explicit HomeWindow(QWidget* parent = 0);
signals:
void openSettings();
void openSettings(int index = 0, const QString &param = "");
void closeSettings();
public slots:

@ -35,6 +35,7 @@ void DriverViewScene::showEvent(QShowEvent* event) {
}
void DriverViewScene::hideEvent(QHideEvent* event) {
// TODO: stop vipc thread ?
params.putBool("IsDriverViewEnabled", false);
}

@ -0,0 +1,76 @@
#include "selfdrive/ui/qt/offroad/experimental_mode.h"
#include <QDebug>
#include <QHBoxLayout>
#include <QPainter>
#include <QPainterPath>
#include <QStyle>
#include "selfdrive/ui/ui.h"
ExperimentalModeButton::ExperimentalModeButton(QWidget *parent) : QPushButton(parent) {
chill_pixmap = QPixmap("../assets/img_couch.svg").scaledToWidth(img_width, Qt::SmoothTransformation);
experimental_pixmap = QPixmap("../assets/img_experimental_grey.svg").scaledToWidth(img_width, Qt::SmoothTransformation);
// go to toggles and expand experimental mode description
connect(this, &QPushButton::clicked, [=]() { emit openSettings(2, "ExperimentalMode"); });
setFixedHeight(125);
QHBoxLayout *main_layout = new QHBoxLayout;
main_layout->setContentsMargins(horizontal_padding, 0, horizontal_padding, 0);
mode_label = new QLabel;
mode_icon = new QLabel;
mode_icon->setSizePolicy(QSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed));
main_layout->addWidget(mode_label, 1, Qt::AlignLeft);
main_layout->addWidget(mode_icon, 0, Qt::AlignRight);
setLayout(main_layout);
setStyleSheet(R"(
QPushButton {
border: none;
}
QLabel {
font-size: 45px;
font-weight: 300;
text-align: left;
font-family: JetBrainsMono;
color: #000000;
}
)");
}
void ExperimentalModeButton::paintEvent(QPaintEvent *event) {
QPainter p(this);
p.setPen(Qt::NoPen);
p.setRenderHint(QPainter::Antialiasing);
QPainterPath path;
path.addRoundedRect(rect(), 10, 10);
// gradient
bool pressed = isDown();
QLinearGradient gradient(rect().left(), 0, rect().right(), 0);
if (experimental_mode) {
gradient.setColorAt(0, QColor(255, 155, 63, pressed ? 0xcc : 0xff));
gradient.setColorAt(1, QColor(219, 56, 34, pressed ? 0xcc : 0xff));
} else {
gradient.setColorAt(0, QColor(20, 255, 171, pressed ? 0xcc : 0xff));
gradient.setColorAt(1, QColor(35, 149, 255, pressed ? 0xcc : 0xff));
}
p.fillPath(path, gradient);
// vertical line
p.setPen(QPen(QColor(0, 0, 0, 0x4d), 3, Qt::SolidLine));
int line_x = rect().right() - img_width - (2 * horizontal_padding);
p.drawLine(line_x, rect().bottom(), line_x, rect().top());
}
void ExperimentalModeButton::showEvent(QShowEvent *event) {
experimental_mode = params.getBool("ExperimentalMode");
mode_icon->setPixmap(experimental_mode ? experimental_pixmap : chill_pixmap);
mode_label->setText(experimental_mode ? tr("EXPERIMENTAL MODE ON") : tr("CHILL MODE ON"));
}

@ -0,0 +1,31 @@
#pragma once
#include <QLabel>
#include <QPushButton>
#include "common/params.h"
class ExperimentalModeButton : public QPushButton {
Q_OBJECT
public:
explicit ExperimentalModeButton(QWidget* parent = 0);
signals:
void openSettings(int index = 0, const QString &toggle = "");
private:
void showEvent(QShowEvent *event) override;
Params params;
bool experimental_mode;
int img_width = 100;
int horizontal_padding = 30;
QPixmap experimental_pixmap;
QPixmap chill_pixmap;
QLabel *mode_label;
QLabel *mode_icon;
protected:
void paintEvent(QPaintEvent *event) override;
};

@ -314,7 +314,7 @@ void WifiUI::refresh() {
QPushButton *forgetBtn = new QPushButton(tr("FORGET"));
forgetBtn->setObjectName("forgetBtn");
QObject::connect(forgetBtn, &QPushButton::clicked, [=]() {
if (ConfirmationDialog::confirm(tr("Forget Wi-Fi Network \"%1\"?").arg(QString::fromUtf8(network.ssid)), this)) {
if (ConfirmationDialog::confirm(tr("Forget Wi-Fi Network \"%1\"?").arg(QString::fromUtf8(network.ssid)), tr("Forget"), this)) {
wifi->forgetConnection(network.ssid);
}
});

@ -27,7 +27,7 @@
#include "selfdrive/ui/qt/widgets/input.h"
TogglesPanel::TogglesPanel(SettingsWindow *parent) : ListWidget(parent) {
// param, title, desc, icon
// param, title, desc, icon, confirm
std::vector<std::tuple<QString, QString, QString, QString>> toggle_defs{
{
"OpenpilotEnabledToggle",
@ -35,6 +35,20 @@ TogglesPanel::TogglesPanel(SettingsWindow *parent) : ListWidget(parent) {
tr("Use the openpilot system for adaptive cruise control and lane keep driver assistance. Your attention is required at all times to use this feature. Changing this setting takes effect when the car is powered off."),
"../assets/offroad/icon_openpilot.png",
},
{
"ExperimentalMode",
tr("Experimental Mode"),
"",
"../assets/img_experimental_white.svg",
},
{
"ExperimentalLongitudinalEnabled",
tr("Experimental openpilot Longitudinal Control"),
QString("<b>%1</b><br>%2")
.arg(tr("WARNING: openpilot longitudinal control is experimental for this car and will disable Automatic Emergency Braking (AEB)."))
.arg(tr("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.")),
"../assets/offroad/icon_speed_limit.png",
},
{
"IsLdwEnabled",
tr("Enable Lane Departure Warnings"),
@ -55,22 +69,10 @@ TogglesPanel::TogglesPanel(SettingsWindow *parent) : ListWidget(parent) {
},
{
"DisengageOnAccelerator",
tr("Disengage On Accelerator Pedal"),
tr("Disengage on Accelerator Pedal"),
tr("When enabled, pressing the accelerator pedal will disengage openpilot."),
"../assets/offroad/icon_disengage_on_accelerator.svg",
},
{
"EndToEndLong",
tr("🌮 End-to-end longitudinal (extremely alpha) 🌮"),
"",
"../assets/offroad/icon_road.png",
},
{
"ExperimentalLongitudinalEnabled",
tr("Experimental openpilot longitudinal control"),
tr("<b>WARNING: openpilot longitudinal control is experimental for this car and will disable AEB.</b>"),
"../assets/offroad/icon_speed_limit.png",
},
#ifdef ENABLE_MAPS
{
"NavSettingTime24h",
@ -85,7 +87,6 @@ TogglesPanel::TogglesPanel(SettingsWindow *parent) : ListWidget(parent) {
"../assets/offroad/icon_road.png",
},
#endif
};
for (auto &[param, title, desc, icon] : toggle_defs) {
@ -98,19 +99,38 @@ TogglesPanel::TogglesPanel(SettingsWindow *parent) : ListWidget(parent) {
toggles[param.toStdString()] = toggle;
}
// Toggles with confirmation dialogs
toggles["ExperimentalMode"]->setActiveIcon("../assets/img_experimental.svg");
toggles["ExperimentalMode"]->setConfirmation(true, true);
toggles["ExperimentalLongitudinalEnabled"]->setConfirmation(true, false);
connect(toggles["ExperimentalLongitudinalEnabled"], &ToggleControl::toggleFlipped, [=]() {
updateToggles();
});
}
void TogglesPanel::expandToggleDescription(const QString &param) {
toggles[param.toStdString()]->showDescription();
}
void TogglesPanel::showEvent(QShowEvent *event) {
updateToggles();
}
void TogglesPanel::updateToggles() {
auto e2e_toggle = toggles["EndToEndLong"];
auto e2e_toggle = toggles["ExperimentalMode"];
auto op_long_toggle = toggles["ExperimentalLongitudinalEnabled"];
const QString e2e_description = tr("Let the driving model control the gas and brakes. openpilot will drive as it thinks a human would. Super experimental.");
const QString e2e_description = QString("%1<br>"
"<h4>%2</h4><br>"
"%3<br>"
"<h4>%4</h4><br>"
"%5")
.arg(tr("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:"))
.arg(tr("🌮 End-to-End Longitudinal Control 🌮"))
.arg(tr("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."))
.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."));
auto cp_bytes = params.get("CarParamsPersistent");
if (!cp_bytes.empty()) {
@ -132,10 +152,10 @@ void TogglesPanel::updateToggles() {
} else {
// no long for now
e2e_toggle->setEnabled(false);
params.remove("EndToEndLong");
params.remove("ExperimentalMode");
const QString no_long = tr("openpilot longitudinal control is not currently available for this car.");
const QString exp_long = tr("Enable experimental longitudinal control to enable this.");
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("<b>" + (CP.getExperimentalLongitudinalAvailable() ? exp_long : no_long) + "</b><br><br>" + e2e_description);
}
@ -161,7 +181,7 @@ DevicePanel::DevicePanel(SettingsWindow *parent) : ListWidget(parent) {
auto resetCalibBtn = new ButtonControl(tr("Reset Calibration"), tr("RESET"), "");
connect(resetCalibBtn, &ButtonControl::showDescriptionEvent, this, &DevicePanel::updateCalibDescription);
connect(resetCalibBtn, &ButtonControl::clicked, [&]() {
if (ConfirmationDialog::confirm(tr("Are you sure you want to reset calibration?"), this)) {
if (ConfirmationDialog::confirm(tr("Are you sure you want to reset calibration?"), tr("Reset"), this)) {
params.remove("CalibrationParams");
}
});
@ -170,7 +190,7 @@ DevicePanel::DevicePanel(SettingsWindow *parent) : ListWidget(parent) {
if (!params.getBool("Passive")) {
auto retrainingBtn = new ButtonControl(tr("Review Training Guide"), tr("REVIEW"), tr("Review the rules, features, and limitations of openpilot"));
connect(retrainingBtn, &ButtonControl::clicked, [=]() {
if (ConfirmationDialog::confirm(tr("Are you sure you want to review the training guide?"), this)) {
if (ConfirmationDialog::confirm(tr("Are you sure you want to review the training guide?"), tr("Review"), this)) {
emit reviewTrainingGuide();
}
});
@ -181,7 +201,7 @@ DevicePanel::DevicePanel(SettingsWindow *parent) : ListWidget(parent) {
auto regulatoryBtn = new ButtonControl(tr("Regulatory"), tr("VIEW"), "");
connect(regulatoryBtn, &ButtonControl::clicked, [=]() {
const std::string txt = util::read_file("../assets/offroad/fcc.html");
RichTextDialog::alert(QString::fromStdString(txt), this);
ConfirmationDialog::rich(QString::fromStdString(txt), this);
});
addItem(regulatoryBtn);
}
@ -258,7 +278,7 @@ void DevicePanel::updateCalibDescription() {
void DevicePanel::reboot() {
if (!uiState()->engaged()) {
if (ConfirmationDialog::confirm(tr("Are you sure you want to reboot?"), this)) {
if (ConfirmationDialog::confirm(tr("Are you sure you want to reboot?"), tr("Reboot"), this)) {
// Check engaged again in case it changed while the dialog was open
if (!uiState()->engaged()) {
Params().putBool("DoReboot", true);
@ -271,7 +291,7 @@ void DevicePanel::reboot() {
void DevicePanel::poweroff() {
if (!uiState()->engaged()) {
if (ConfirmationDialog::confirm(tr("Are you sure you want to power off?"), this)) {
if (ConfirmationDialog::confirm(tr("Are you sure you want to power off?"), tr("Power Off"), this)) {
// Check engaged again in case it changed while the dialog was open
if (!uiState()->engaged()) {
Params().putBool("DoShutdown", true);
@ -283,8 +303,15 @@ void DevicePanel::poweroff() {
}
void SettingsWindow::showEvent(QShowEvent *event) {
panel_widget->setCurrentIndex(0);
nav_btns->buttons()[0]->setChecked(true);
setCurrentPanel(0);
}
void SettingsWindow::setCurrentPanel(int index, const QString &param) {
panel_widget->setCurrentIndex(index);
nav_btns->buttons()[index]->setChecked(true);
if (!param.isEmpty()) {
emit expandToggleDescription(param);
}
}
SettingsWindow::SettingsWindow(QWidget *parent) : QFrame(parent) {
@ -325,10 +352,13 @@ SettingsWindow::SettingsWindow(QWidget *parent) : QFrame(parent) {
QObject::connect(device, &DevicePanel::reviewTrainingGuide, this, &SettingsWindow::reviewTrainingGuide);
QObject::connect(device, &DevicePanel::showDriverView, this, &SettingsWindow::showDriverView);
TogglesPanel *toggles = new TogglesPanel(this);
QObject::connect(this, &SettingsWindow::expandToggleDescription, toggles, &TogglesPanel::expandToggleDescription);
QList<QPair<QString, QWidget *>> panels = {
{tr("Device"), device},
{tr("Network"), new Networking(this)},
{tr("Toggles"), new TogglesPanel(this)},
{tr("Toggles"), toggles},
{tr("Software"), new SoftwarePanel(this)},
};

@ -17,6 +17,7 @@ class SettingsWindow : public QFrame {
public:
explicit SettingsWindow(QWidget *parent = 0);
void setCurrentPanel(int index, const QString &param = "");
protected:
void showEvent(QShowEvent *event) override;
@ -25,6 +26,7 @@ signals:
void closeSettings();
void reviewTrainingGuide();
void showDriverView();
void expandToggleDescription(const QString &param);
private:
QPushButton *sidebar_alert_widget;
@ -56,6 +58,9 @@ public:
explicit TogglesPanel(SettingsWindow *parent);
void showEvent(QShowEvent *event) override;
public slots:
void expandToggleDescription(const QString &param);
private:
Params params;
std::map<std::string, ParamControl*> toggles;

@ -77,7 +77,7 @@ SoftwarePanel::SoftwarePanel(QWidget* parent) : ListWidget(parent) {
// uninstall button
auto uninstallBtn = new ButtonControl(tr("Uninstall %1").arg(getBrand()), tr("UNINSTALL"));
connect(uninstallBtn, &ButtonControl::clicked, [&]() {
if (ConfirmationDialog::confirm(tr("Are you sure you want to uninstall?"), this)) {
if (ConfirmationDialog::confirm(tr("Are you sure you want to uninstall?"), tr("Uninstall"), this)) {
params.putBool("DoUninstall", true);
}
});

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

Loading…
Cancel
Save