From ae87665e92cb17952abf2b7f182a0302264dc642 Mon Sep 17 00:00:00 2001
From: Lee Jong Mun <43285072+crwusiz@users.noreply.github.com>
Date: Fri, 16 Sep 2022 09:04:29 +0900
Subject: [PATCH 01/75] Multilang: add missing Korean translations (#25799)
kor translation update
---
selfdrive/ui/translations/main_ko.ts | 16 ++++++++--------
1 file changed, 8 insertions(+), 8 deletions(-)
diff --git a/selfdrive/ui/translations/main_ko.ts b/selfdrive/ui/translations/main_ko.ts
index b517c8320..2a827ca4a 100644
--- a/selfdrive/ui/translations/main_ko.ts
+++ b/selfdrive/ui/translations/main_ko.ts
@@ -985,42 +985,42 @@ location set
Updates are only downloaded while the car is off.
-
+ 업데이트는 차량 연결이 해제되어 있는 동안에만 다운로드됩니다.
Current Version
-
+ 현재 버전
Download
-
+ 다운로드
Install Update
-
+ 업데이트 설치
INSTALL
-
+ 설치
Target Branch
-
+ 대상 브랜치
SELECT
-
+ 선택
Select a branch
-
+ 브랜치 선택
From 834f212903f5c06a9fe8d6caa6b6da52ac7a7d83 Mon Sep 17 00:00:00 2001
From: cydia2020 <12470297+cydia2020@users.noreply.github.com>
Date: Fri, 16 Sep 2022 10:48:17 +1000
Subject: [PATCH 02/75] Multilang: add missing Chinese e2e toggle translations
(#25656)
* japanese e2e toggle
* chinese (simp)
* chinese (trad)
* OOPS
* Mention experimental in details
* Also in traditional
* Exp.
* suggestions
* Apply suggestions from code review
Co-authored-by: ZwX1616
* add back removed translations from merge
* Update selfdrive/ui/translations/main_zh-CHS.ts
Co-authored-by: Shane Smiskol
Co-authored-by: ZwX1616
---
selfdrive/ui/translations/main_zh-CHS.ts | 4 ++--
selfdrive/ui/translations/main_zh-CHT.ts | 4 ++--
2 files changed, 4 insertions(+), 4 deletions(-)
diff --git a/selfdrive/ui/translations/main_zh-CHS.ts b/selfdrive/ui/translations/main_zh-CHS.ts
index 8fce4e01a..8a6f856be 100644
--- a/selfdrive/ui/translations/main_zh-CHS.ts
+++ b/selfdrive/ui/translations/main_zh-CHS.ts
@@ -1167,7 +1167,7 @@ location set
🌮 End-to-end longitudinal (extremely alpha) 🌮
-
+ 🌮 端对端纵向控制(实验性功能) 🌮
@@ -1182,7 +1182,7 @@ location set
Let the driving model control the gas and brakes. openpilot will drive as it thinks a human would. Super experimental.
-
+ 让驾驶模型直接控制油门和刹车,openpilot将会模仿人类司机的驾驶方式。该功能仍非常实验性。
diff --git a/selfdrive/ui/translations/main_zh-CHT.ts b/selfdrive/ui/translations/main_zh-CHT.ts
index 022d41be8..675830542 100644
--- a/selfdrive/ui/translations/main_zh-CHT.ts
+++ b/selfdrive/ui/translations/main_zh-CHT.ts
@@ -1169,7 +1169,7 @@ location set
🌮 End-to-end longitudinal (extremely alpha) 🌮
-
+ 🌮 端對端縱向控制(實驗性功能) 🌮
@@ -1184,7 +1184,7 @@ location set
Let the driving model control the gas and brakes. openpilot will drive as it thinks a human would. Super experimental.
-
+ 讓駕駛模型直接控製油門和剎車,openpilot將會模仿人類司機的駕駛方式。該功能仍非常實驗性。
From 1aa8c0525ea5339eecd82cb08572636ebbaa7034 Mon Sep 17 00:00:00 2001
From: Jason Shuler
Date: Thu, 15 Sep 2022 20:55:02 -0400
Subject: [PATCH 03/75] GM: Chevy Equinox 2019-22 (#25431)
* Chevy Equinox Port
* LKAS is not standard on 2019, but it's the same package as ACC. (LKAS standard 2020+)
* 2019 here too
* clean up
* add to untested
* not in docs
Co-authored-by: Shane Smiskol
---
selfdrive/car/gm/interface.py | 10 +++++++++-
selfdrive/car/gm/values.py | 8 +++++++-
selfdrive/car/tests/routes.py | 1 +
selfdrive/car/torque_data/override.yaml | 1 +
4 files changed, 18 insertions(+), 2 deletions(-)
diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py
index be2889048..49d56cf09 100755
--- a/selfdrive/car/gm/interface.py
+++ b/selfdrive/car/gm/interface.py
@@ -71,7 +71,7 @@ class CarInterface(CarInterfaceBase):
# These cars have been put into dashcam only due to both a lack of users and test coverage.
# These cars likely still work fine. Once a user confirms each car works and a test route is
# added to selfdrive/car/tests/routes.py, we can remove it from this list.
- ret.dashcamOnly = candidate in {CAR.CADILLAC_ATS, CAR.HOLDEN_ASTRA, CAR.MALIBU, CAR.BUICK_REGAL}
+ ret.dashcamOnly = candidate in {CAR.CADILLAC_ATS, CAR.HOLDEN_ASTRA, CAR.MALIBU, CAR.BUICK_REGAL, CAR.EQUINOX}
# Start with a baseline tuning for all GM vehicles. Override tuning as needed in each model section below.
ret.minSteerSpeed = 10 * CV.KPH_TO_MS
@@ -170,6 +170,14 @@ class CarInterface(CarInterfaceBase):
tire_stiffness_factor = 1.0
CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning)
+ elif candidate == CAR.EQUINOX:
+ ret.minEnableSpeed = -1
+ ret.mass = 3500. * CV.LB_TO_KG + STD_CARGO_KG
+ ret.wheelbase = 2.72
+ ret.steerRatio = 14.4
+ ret.centerToFront = ret.wheelbase * 0.4
+ CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning)
+
# TODO: get actual value, for now starting with reasonable value for
# civic and scaling by mass and wheelbase
ret.rotationalInertia = scale_rot_inertia(ret.mass, ret.wheelbase)
diff --git a/selfdrive/car/gm/values.py b/selfdrive/car/gm/values.py
index a84cbdc91..25e624da7 100644
--- a/selfdrive/car/gm/values.py
+++ b/selfdrive/car/gm/values.py
@@ -60,6 +60,7 @@ class CAR:
ESCALADE_ESV = "CADILLAC ESCALADE ESV 2016"
BOLT_EUV = "CHEVROLET BOLT EUV 2022"
SILVERADO = "CHEVROLET SILVERADO 1500 2020"
+ EQUINOX = "CHEVROLET EQUINOX 2019"
class Footnote(Enum):
@@ -89,6 +90,7 @@ CAR_INFO: Dict[str, Union[GMCarInfo, List[GMCarInfo]]] = {
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),
],
+ CAR.EQUINOX: GMCarInfo("Chevrolet Equinox 2019-22", "Adaptive Cruise Control (ACC)", footnotes=[], harness=Harness.gm),
}
@@ -166,6 +168,10 @@ FINGERPRINTS = {
{
190: 6, 193: 8, 197: 8, 201: 8, 208: 8, 209: 7, 211: 2, 241: 6, 249: 8, 257: 8, 288: 5, 289: 8, 298: 8, 304: 3, 309: 8, 311: 8, 313: 8, 320: 4, 322: 7, 328: 1, 352: 5, 381: 8, 384: 4, 386: 8, 388: 8, 413: 8, 451: 8, 452: 8, 453: 6, 455: 7, 460: 5, 463: 3, 479: 3, 481: 7, 485: 8, 489: 8, 497: 8, 500: 6, 501: 8, 528: 5, 532: 6, 534: 2, 560: 8, 562: 8, 563: 5, 565: 5, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 707: 8, 715: 8, 717: 5, 761: 7, 789: 5, 800: 6, 801: 8, 810: 8, 840: 5, 842: 5, 844: 8, 848: 4, 869: 4, 880: 6, 977: 8, 1001: 8, 1011: 6, 1017: 8, 1020: 8, 1033: 7, 1034: 7, 1217: 8, 1221: 5, 1233: 8, 1249: 8, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1271: 8, 1280: 4, 1296: 4, 1300: 8, 1930: 7
}],
+ CAR.EQUINOX: [
+ {
+ 190: 6, 193: 8, 197: 8, 201: 8, 209: 7, 211: 2, 241: 6, 249: 8, 257: 8, 288: 5, 289: 8, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 8, 384: 4, 386: 8, 388: 8, 413: 8, 451: 8, 452: 8, 453: 6, 455: 7, 463: 3, 479: 3, 481: 7, 485: 8, 489: 8, 497: 8, 500: 6, 501: 8, 510: 8, 528: 5, 532: 6, 560: 8, 562: 8, 563: 5, 565: 5, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 789: 5, 800: 6, 810: 8, 840: 5, 842: 5, 844: 8, 869: 4, 880: 6, 977: 8, 1001: 8, 1011: 6, 1017: 8, 1020: 8, 1033: 7, 1034: 7, 1217: 8, 1221: 5, 1233: 8, 1249: 8, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1271: 8, 1280: 4, 1296: 4, 1300: 8, 1930: 7
+ }],
}
DBC: Dict[str, Dict[str, str]] = defaultdict(lambda: dbc_dict('gm_global_a_powertrain_generated', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis'))
@@ -173,6 +179,6 @@ DBC: Dict[str, Dict[str, str]] = defaultdict(lambda: dbc_dict('gm_global_a_power
EV_CAR = {CAR.VOLT, CAR.BOLT_EUV}
# We're integrated at the camera with VOACC on these cars (instead of ASCM w/ OBD-II harness)
-CAMERA_ACC_CAR = {CAR.BOLT_EUV, CAR.SILVERADO}
+CAMERA_ACC_CAR = {CAR.BOLT_EUV, CAR.SILVERADO, CAR.EQUINOX}
STEER_THRESHOLD = 1.0
diff --git a/selfdrive/car/tests/routes.py b/selfdrive/car/tests/routes.py
index 1f5d3edaf..9f28bf854 100644
--- a/selfdrive/car/tests/routes.py
+++ b/selfdrive/car/tests/routes.py
@@ -21,6 +21,7 @@ non_tested_cars = [
GM.CADILLAC_ATS,
GM.HOLDEN_ASTRA,
GM.MALIBU,
+ GM.EQUINOX,
HYUNDAI.ELANTRA_GT_I30,
HYUNDAI.GENESIS_G90,
HYUNDAI.KIA_OPTIMA_H,
diff --git a/selfdrive/car/torque_data/override.yaml b/selfdrive/car/torque_data/override.yaml
index 20fb5f7a6..2e0f601e8 100644
--- a/selfdrive/car/torque_data/override.yaml
+++ b/selfdrive/car/torque_data/override.yaml
@@ -27,6 +27,7 @@ RAM HD 5TH GEN: [1.4, 1.4, 0.0]
SUBARU OUTBACK 6TH GEN: [2.3, 2.3, 0.11]
CHEVROLET BOLT EUV 2022: [2.0, 2.0, 0.05]
CHEVROLET SILVERADO 1500 2020: [1.9, 1.9, 0.112]
+CHEVROLET EQUINOX 2019: [2.0, 2.0, 0.05]
VOLKSWAGEN PASSAT NMS: [2.5, 2.5, 0.1]
HYUNDAI TUCSON HYBRID 4TH GEN: [2.5, 2.5, 0.0]
From 5a80fda819fda68cad1caf7c6db15d9a495aefac Mon Sep 17 00:00:00 2001
From: Shane Smiskol
Date: Thu, 15 Sep 2022 19:24:18 -0700
Subject: [PATCH 04/75] GM: adjust Bolt EUV centerToFront
---
selfdrive/car/gm/interface.py | 2 +-
1 file changed, 1 insertion(+), 1 deletion(-)
diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py
index 49d56cf09..f3ab1ee72 100755
--- a/selfdrive/car/gm/interface.py
+++ b/selfdrive/car/gm/interface.py
@@ -156,7 +156,7 @@ class CarInterface(CarInterfaceBase):
ret.mass = 1669. + STD_CARGO_KG
ret.wheelbase = 2.675
ret.steerRatio = 16.8
- ret.centerToFront = ret.wheelbase * 0.4
+ ret.centerToFront = 2.15 # measured
tire_stiffness_factor = 1.0
ret.steerActuatorDelay = 0.2
CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning)
From 7ddcde687e3ffaa0ec91002871b76f9ca82752b1 Mon Sep 17 00:00:00 2001
From: eFini
Date: Fri, 16 Sep 2022 10:31:57 +0800
Subject: [PATCH 05/75] Multilang: add missing Chinese (Traditional)
translations (#25802)
---
selfdrive/ui/translations/main_zh-CHT.ts | 20 ++++++++++----------
1 file changed, 10 insertions(+), 10 deletions(-)
diff --git a/selfdrive/ui/translations/main_zh-CHT.ts b/selfdrive/ui/translations/main_zh-CHT.ts
index 675830542..ef958e714 100644
--- a/selfdrive/ui/translations/main_zh-CHT.ts
+++ b/selfdrive/ui/translations/main_zh-CHT.ts
@@ -985,42 +985,42 @@ location set
Updates are only downloaded while the car is off.
-
+ 系統更新只會在熄火時下載。
Current Version
-
+ 當前版本
Download
-
+ 下載
Install Update
-
+ 安裝更新
INSTALL
-
+ 安裝
Target Branch
-
+ 目標分支
SELECT
-
+ 選取
Select a branch
-
+ 選取一個分支
@@ -1174,12 +1174,12 @@ location set
Experimental openpilot longitudinal control
-
+ 使用 openpilot 縱向控制(實驗)
<b>WARNING: openpilot longitudinal control is experimental for this car and will disable AEB.</b>
-
+ <b>注意:這台車的 openpilot 縱向控制仍然是實驗中的功能,開啟這功能將會關閉自動緊急煞車 (AEB)。</b>
From 64c2d4b30f7d4be1e1726a5668c548ecf8d6e32e Mon Sep 17 00:00:00 2001
From: Shane Smiskol
Date: Thu, 15 Sep 2022 19:37:12 -0700
Subject: [PATCH 06/75] Wrap new UI strings
---
selfdrive/ui/qt/offroad/settings.cc | 4 ++--
selfdrive/ui/translations/main_ja.ts | 12 +++++++++++-
selfdrive/ui/translations/main_ko.ts | 12 +++++++++++-
selfdrive/ui/translations/main_pt-BR.ts | 12 +++++++++++-
selfdrive/ui/translations/main_zh-CHS.ts | 12 +++++++++++-
selfdrive/ui/translations/main_zh-CHT.ts | 12 +++++++++++-
6 files changed, 57 insertions(+), 7 deletions(-)
diff --git a/selfdrive/ui/qt/offroad/settings.cc b/selfdrive/ui/qt/offroad/settings.cc
index 52df247a2..ae878c541 100644
--- a/selfdrive/ui/qt/offroad/settings.cc
+++ b/selfdrive/ui/qt/offroad/settings.cc
@@ -134,8 +134,8 @@ void TogglesPanel::updateToggles() {
e2e_toggle->setEnabled(false);
params.remove("EndToEndLong");
- const QString no_long = "openpilot longitudinal control is not currently available for this car.";
- const QString exp_long = "Enable experimental longitudinal control to enable this.";
+ 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.");
e2e_toggle->setDescription("" + (CP.getExperimentalLongitudinalAvailable() ? exp_long : no_long) + "
" + e2e_description);
}
diff --git a/selfdrive/ui/translations/main_ja.ts b/selfdrive/ui/translations/main_ja.ts
index 4262473fb..3cc914975 100644
--- a/selfdrive/ui/translations/main_ja.ts
+++ b/selfdrive/ui/translations/main_ja.ts
@@ -1187,7 +1187,17 @@ location set
アクセルとブレーキの制御をopenpilotに任せます。openpilotが人間と同じように運転します。最初期の実験段階です。
-
+
+ openpilot longitudinal control is not currently available for this car.
+
+
+
+
+ Enable experimental longitudinal control to enable this.
+
+
+
+
Disengage On Accelerator Pedal
アクセル踏むと openpilot をキャンセル
diff --git a/selfdrive/ui/translations/main_ko.ts b/selfdrive/ui/translations/main_ko.ts
index 2a827ca4a..17914f21d 100644
--- a/selfdrive/ui/translations/main_ko.ts
+++ b/selfdrive/ui/translations/main_ko.ts
@@ -1187,7 +1187,17 @@ location set
주행모델이 가속과 감속을 제어하도록 하면 openpilot은 운전자가 생각하는것처럼 운전합니다. (매우 실험적)
-
+
+ openpilot longitudinal control is not currently available for this car.
+
+
+
+
+ Enable experimental longitudinal control to enable this.
+
+
+
+
Disengage On Accelerator Pedal
가속페달 조작시 해제
diff --git a/selfdrive/ui/translations/main_pt-BR.ts b/selfdrive/ui/translations/main_pt-BR.ts
index 91ffabc62..fe028e18b 100644
--- a/selfdrive/ui/translations/main_pt-BR.ts
+++ b/selfdrive/ui/translations/main_pt-BR.ts
@@ -1191,7 +1191,17 @@ trabalho definido
-
+
+ openpilot longitudinal control is not currently available for this car.
+
+
+
+
+ Enable experimental longitudinal control to enable this.
+
+
+
+
Disengage On Accelerator Pedal
Desacionar Com Pedal Do Acelerador
diff --git a/selfdrive/ui/translations/main_zh-CHS.ts b/selfdrive/ui/translations/main_zh-CHS.ts
index 8a6f856be..28008ef06 100644
--- a/selfdrive/ui/translations/main_zh-CHS.ts
+++ b/selfdrive/ui/translations/main_zh-CHS.ts
@@ -1185,7 +1185,17 @@ location set
让驾驶模型直接控制油门和刹车,openpilot将会模仿人类司机的驾驶方式。该功能仍非常实验性。
-
+
+ openpilot longitudinal control is not currently available for this car.
+
+
+
+
+ Enable experimental longitudinal control to enable this.
+
+
+
+
Disengage On Accelerator Pedal
踩油门时取消控制
diff --git a/selfdrive/ui/translations/main_zh-CHT.ts b/selfdrive/ui/translations/main_zh-CHT.ts
index ef958e714..19f5bf739 100644
--- a/selfdrive/ui/translations/main_zh-CHT.ts
+++ b/selfdrive/ui/translations/main_zh-CHT.ts
@@ -1187,7 +1187,17 @@ location set
讓駕駛模型直接控製油門和剎車,openpilot將會模仿人類司機的駕駛方式。該功能仍非常實驗性。
-
+
+ openpilot longitudinal control is not currently available for this car.
+
+
+
+
+ Enable experimental longitudinal control to enable this.
+
+
+
+
Disengage On Accelerator Pedal
油門取消控車
From cfaa1b7d3eeeb8ae16b77e04a0416dbacf4bc6d2 Mon Sep 17 00:00:00 2001
From: Jason Shuler
Date: Thu, 15 Sep 2022 23:11:53 -0400
Subject: [PATCH 07/75] GM: Chevy Bolt EV 2022-23 (#25430)
* Chevy Bolt EV w ACC Port
* dashcam
* The website allows you to select the package without ACC
* fix Bolt E(U)V centerToFront
* Update selfdrive/car/gm/values.py
Co-authored-by: Shane Smiskol
---
selfdrive/car/gm/interface.py | 10 +++++-----
selfdrive/car/gm/values.py | 6 ++++--
selfdrive/car/tests/routes.py | 1 +
selfdrive/car/torque_data/override.yaml | 1 +
4 files changed, 11 insertions(+), 7 deletions(-)
diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py
index f3ab1ee72..93be57cf2 100755
--- a/selfdrive/car/gm/interface.py
+++ b/selfdrive/car/gm/interface.py
@@ -71,7 +71,7 @@ class CarInterface(CarInterfaceBase):
# These cars have been put into dashcam only due to both a lack of users and test coverage.
# These cars likely still work fine. Once a user confirms each car works and a test route is
# added to selfdrive/car/tests/routes.py, we can remove it from this list.
- ret.dashcamOnly = candidate in {CAR.CADILLAC_ATS, CAR.HOLDEN_ASTRA, CAR.MALIBU, CAR.BUICK_REGAL, CAR.EQUINOX}
+ ret.dashcamOnly = candidate in {CAR.CADILLAC_ATS, CAR.HOLDEN_ASTRA, CAR.MALIBU, CAR.BUICK_REGAL, CAR.EQUINOX, CAR.BOLT_EV}
# Start with a baseline tuning for all GM vehicles. Override tuning as needed in each model section below.
ret.minSteerSpeed = 10 * CV.KPH_TO_MS
@@ -138,23 +138,23 @@ class CarInterface(CarInterfaceBase):
ret.mass = 1601. + STD_CARGO_KG
ret.wheelbase = 2.78
ret.steerRatio = 15.3
- ret.centerToFront = ret.wheelbase * 0.49
+ ret.centerToFront = ret.wheelbase * 0.5
elif candidate == CAR.ESCALADE_ESV:
ret.minEnableSpeed = -1. # engage speed is decided by pcm
ret.mass = 2739. + STD_CARGO_KG
ret.wheelbase = 3.302
ret.steerRatio = 17.3
- ret.centerToFront = ret.wheelbase * 0.49
+ ret.centerToFront = ret.wheelbase * 0.5
ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[10., 41.0], [10., 41.0]]
ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.13, 0.24], [0.01, 0.02]]
ret.lateralTuning.pid.kf = 0.000045
tire_stiffness_factor = 1.0
- elif candidate == CAR.BOLT_EUV:
+ elif candidate in (CAR.BOLT_EV, CAR.BOLT_EUV):
ret.minEnableSpeed = -1
ret.mass = 1669. + STD_CARGO_KG
- ret.wheelbase = 2.675
+ ret.wheelbase = 2.63779
ret.steerRatio = 16.8
ret.centerToFront = 2.15 # measured
tire_stiffness_factor = 1.0
diff --git a/selfdrive/car/gm/values.py b/selfdrive/car/gm/values.py
index 25e624da7..943e8a658 100644
--- a/selfdrive/car/gm/values.py
+++ b/selfdrive/car/gm/values.py
@@ -58,6 +58,7 @@ class CAR:
ACADIA = "GMC ACADIA DENALI 2018"
BUICK_REGAL = "BUICK REGAL ESSENCE 2018"
ESCALADE_ESV = "CADILLAC ESCALADE ESV 2016"
+ BOLT_EV = "CHEVROLET BOLT EV 2022"
BOLT_EUV = "CHEVROLET BOLT EUV 2022"
SILVERADO = "CHEVROLET SILVERADO 1500 2020"
EQUINOX = "CHEVROLET EQUINOX 2019"
@@ -85,6 +86,7 @@ CAR_INFO: Dict[str, Union[GMCarInfo, List[GMCarInfo]]] = {
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", "Adaptive Cruise Control (ACC)", footnotes=[], harness=Harness.gm),
CAR.BOLT_EUV: GMCarInfo("Chevrolet Bolt EUV 2022-23", "Premier or Premier Redline Trim without Super Cruise Package", video_link="https://youtu.be/xvwzGMUA210", footnotes=[], harness=Harness.gm),
CAR.SILVERADO: [
GMCarInfo("Chevrolet Silverado 1500 2020-21", "Safety Package II", footnotes=[], harness=Harness.gm),
@@ -176,9 +178,9 @@ FINGERPRINTS = {
DBC: Dict[str, Dict[str, str]] = defaultdict(lambda: dbc_dict('gm_global_a_powertrain_generated', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis'))
-EV_CAR = {CAR.VOLT, CAR.BOLT_EUV}
+EV_CAR = {CAR.VOLT, CAR.BOLT_EV, CAR.BOLT_EUV}
# We're integrated at the camera with VOACC on these cars (instead of ASCM w/ OBD-II harness)
-CAMERA_ACC_CAR = {CAR.BOLT_EUV, CAR.SILVERADO, CAR.EQUINOX}
+CAMERA_ACC_CAR = {CAR.BOLT_EV, CAR.BOLT_EUV, CAR.SILVERADO, CAR.EQUINOX}
STEER_THRESHOLD = 1.0
diff --git a/selfdrive/car/tests/routes.py b/selfdrive/car/tests/routes.py
index 9f28bf854..e86525baa 100644
--- a/selfdrive/car/tests/routes.py
+++ b/selfdrive/car/tests/routes.py
@@ -22,6 +22,7 @@ non_tested_cars = [
GM.HOLDEN_ASTRA,
GM.MALIBU,
GM.EQUINOX,
+ GM.BOLT_EV,
HYUNDAI.ELANTRA_GT_I30,
HYUNDAI.GENESIS_G90,
HYUNDAI.KIA_OPTIMA_H,
diff --git a/selfdrive/car/torque_data/override.yaml b/selfdrive/car/torque_data/override.yaml
index 2e0f601e8..b5d1a3119 100644
--- a/selfdrive/car/torque_data/override.yaml
+++ b/selfdrive/car/torque_data/override.yaml
@@ -25,6 +25,7 @@ KIA EV6 2022: [3.5, 3.0, 0.0]
RAM 1500 5TH GEN: [2.0, 2.0, 0.0]
RAM HD 5TH GEN: [1.4, 1.4, 0.0]
SUBARU OUTBACK 6TH GEN: [2.3, 2.3, 0.11]
+CHEVROLET BOLT EV 2022: [2.0, 2.0, 0.05]
CHEVROLET BOLT EUV 2022: [2.0, 2.0, 0.05]
CHEVROLET SILVERADO 1500 2020: [1.9, 1.9, 0.112]
CHEVROLET EQUINOX 2019: [2.0, 2.0, 0.05]
From b133a4c9a8e8f3ab8211fe1e7a52bd0bb41c5c47 Mon Sep 17 00:00:00 2001
From: Vivek Aithal
Date: Thu, 15 Sep 2022 20:15:57 -0700
Subject: [PATCH 08/75] regenerate replay segments for torqued (#25805)
* update segments in test_processes
* bump cereal
* update refs
---
cereal | 2 +-
selfdrive/test/process_replay/ref_commit | 2 +-
.../test/process_replay/test_processes.py | 30 +++++++++----------
3 files changed, 17 insertions(+), 17 deletions(-)
diff --git a/cereal b/cereal
index 513dfc7ee..e4130c905 160000
--- a/cereal
+++ b/cereal
@@ -1 +1 @@
-Subproject commit 513dfc7ee001243cd68a57a9d92fe3170fc49c7d
+Subproject commit e4130c90558dfb491e132992dce36e0e620e070a
diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit
index 739061025..062611316 100644
--- a/selfdrive/test/process_replay/ref_commit
+++ b/selfdrive/test/process_replay/ref_commit
@@ -1 +1 @@
-ef5395e5f36550d2b485216eee5406bf6062e9c9
\ No newline at end of file
+147410f09f242f05b922c9cc7ac04c3c3366419c
\ No newline at end of file
diff --git a/selfdrive/test/process_replay/test_processes.py b/selfdrive/test/process_replay/test_processes.py
index e8c2e1dc9..0f118971c 100755
--- a/selfdrive/test/process_replay/test_processes.py
+++ b/selfdrive/test/process_replay/test_processes.py
@@ -38,21 +38,21 @@ original_segments = [
]
segments = [
- ("BODY", "regen660D86654BA|2022-07-06--14-27-15--0"),
- ("HYUNDAI", "regen114E5FF24D8|2022-07-14--17-08-47--0"),
- ("HYUNDAI", "d824e27e8c60172c|2022-08-19--17-58-07--2"),
- ("TOYOTA", "regenBA97410FBEC|2022-07-06--14-26-49--0"),
- ("TOYOTA2", "regenDEDB1D9C991|2022-07-06--14-54-08--0"),
- ("TOYOTA3", "regenDDC1FE60734|2022-07-06--14-32-06--0"),
- ("HONDA", "regenE62960EEC38|2022-07-14--19-33-24--0"),
- ("HONDA2", "regenC3EBD92F029|2022-07-14--19-29-47--0"),
- ("CHRYSLER", "regen38346FB33D0|2022-07-14--18-05-26--0"),
- ("RAM", "2f4452b03ccb98f0|2022-07-07--08-01-56--3"),
- ("SUBARU", "regen54A1E2BE5AA|2022-07-14--18-07-50--0"),
- ("GM", "regen76027B408B7|2022-08-16--19-56-58--0"),
- ("NISSAN", "regenCA0B0DC946E|2022-07-14--18-10-17--0"),
- ("VOLKSWAGEN", "regen007098CA0EF|2022-07-06--15-01-26--0"),
- ("MAZDA", "regen61BA413D53B|2022-07-06--14-39-42--0"),
+ ("BODY", "regen9D38397D30D|2022-09-09--13-12-48--0"),
+ ("HYUNDAI", "regenB3953B393C0|2022-09-09--14-49-37--0"),
+ ("HYUNDAI", "regen8DB830E5376|2022-09-13--17-24-37--0"),
+ ("TOYOTA", "regen8FCBB6F06F1|2022-09-09--13-14-07--0"),
+ ("TOYOTA2", "regen956BFA75300|2022-09-09--14-51-24--0"),
+ ("TOYOTA3", "regenE909BC2F430|2022-09-09--20-44-49--0"),
+ ("HONDA", "regenD1D10209015|2022-09-09--14-53-09--0"),
+ ("HONDA2", "regen3F7C2EFDC08|2022-09-09--19-41-19--0"),
+ ("CHRYSLER", "regen92783EAE66B|2022-09-09--13-15-44--0"),
+ ("RAM", "regenBE5DAAEF30F|2022-09-13--17-06-24--0"),
+ ("SUBARU", "regen8A363AF7E14|2022-09-13--17-20-39--0"),
+ ("GM", "regen31EA3F9A37C|2022-09-09--21-06-36--0"),
+ ("NISSAN", "regenAA21ADE5921|2022-09-09--19-44-37--0"),
+ ("VOLKSWAGEN", "regenA1BF4D17761|2022-09-09--19-46-24--0"),
+ ("MAZDA", "regen1994C97E977|2022-09-13--16-34-44--0"),
]
# dashcamOnly makes don't need to be tested until a full port is done
From b7d9f157faa33023ab07db561c155db0abb28c0b Mon Sep 17 00:00:00 2001
From: Jason Wen <47793918+sunnyhaibin@users.noreply.github.com>
Date: Thu, 15 Sep 2022 23:16:54 -0400
Subject: [PATCH 09/75] Updater: Reboot instead of shutdown to install new
branch (#25804)
Reboot instead of shutdown to install new branch
---
selfdrive/ui/qt/offroad/software_settings.cc | 2 +-
1 file changed, 1 insertion(+), 1 deletion(-)
diff --git a/selfdrive/ui/qt/offroad/software_settings.cc b/selfdrive/ui/qt/offroad/software_settings.cc
index c9deef2ec..4f048241c 100644
--- a/selfdrive/ui/qt/offroad/software_settings.cc
+++ b/selfdrive/ui/qt/offroad/software_settings.cc
@@ -45,7 +45,7 @@ SoftwarePanel::SoftwarePanel(QWidget* parent) : ListWidget(parent) {
installBtn = new ButtonControl(tr("Install Update"), tr("INSTALL"));
connect(installBtn, &ButtonControl::clicked, [=]() {
installBtn->setEnabled(false);
- params.putBool("DoShutdown", true);
+ params.putBool("DoReboot", true);
});
addItem(installBtn);
From f0665911b2aa5807348ee5bf209ee21b8be2ca89 Mon Sep 17 00:00:00 2001
From: Dean Lee
Date: Fri, 16 Sep 2022 11:36:13 +0800
Subject: [PATCH 10/75] map: fix repeated call to m_map->setZoom (#25784)
Fix repeated map api calls
---
selfdrive/ui/qt/maps/map.cc | 3 ++-
selfdrive/ui/qt/maps/map.h | 2 +-
2 files changed, 3 insertions(+), 2 deletions(-)
diff --git a/selfdrive/ui/qt/maps/map.cc b/selfdrive/ui/qt/maps/map.cc
index 71706fd35..b5519dacc 100644
--- a/selfdrive/ui/qt/maps/map.cc
+++ b/selfdrive/ui/qt/maps/map.cc
@@ -204,7 +204,8 @@ void MapWindow::updateState(const UIState &s) {
if (zoom_counter == 0) {
m_map->setZoom(util::map_val(velocity_filter.x(), 0, 30, MAX_ZOOM, MIN_ZOOM));
- } else {
+ zoom_counter = -1;
+ } else if (zoom_counter > 0) {
zoom_counter--;
}
diff --git a/selfdrive/ui/qt/maps/map.h b/selfdrive/ui/qt/maps/map.h
index ecba867ed..c3d5e9253 100644
--- a/selfdrive/ui/qt/maps/map.h
+++ b/selfdrive/ui/qt/maps/map.h
@@ -98,7 +98,7 @@ private:
// Panning
QPointF m_lastPos;
int pan_counter = 0;
- int zoom_counter = 0;
+ int zoom_counter = -1;
// Position
std::optional last_position;
From 8fcbcd800610f30ddf85b5a314dbf40afb0fa320 Mon Sep 17 00:00:00 2001
From: eFini
Date: Fri, 16 Sep 2022 11:38:53 +0800
Subject: [PATCH 11/75] Multilang: add missing Chinese (Traditional)
translations (#25807)
added missing cht translations
---
selfdrive/ui/translations/main_zh-CHT.ts | 4 ++--
1 file changed, 2 insertions(+), 2 deletions(-)
diff --git a/selfdrive/ui/translations/main_zh-CHT.ts b/selfdrive/ui/translations/main_zh-CHT.ts
index 19f5bf739..364508bd1 100644
--- a/selfdrive/ui/translations/main_zh-CHT.ts
+++ b/selfdrive/ui/translations/main_zh-CHT.ts
@@ -1189,12 +1189,12 @@ location set
openpilot longitudinal control is not currently available for this car.
-
+ openpilot 縱向控制目前不適用於這輛車。
Enable experimental longitudinal control to enable this.
-
+ 打開縱向控制(實驗)以啟用此功能。
From 5356216e92f7c46d5aaefa1c3e85c91fd17816e4 Mon Sep 17 00:00:00 2001
From: Shane Smiskol
Date: Thu, 15 Sep 2022 20:45:01 -0700
Subject: [PATCH 12/75] remove unused compute_gb (#25808)
---
selfdrive/car/mazda/interface.py | 4 ----
selfdrive/car/mock/interface.py | 4 ----
2 files changed, 8 deletions(-)
diff --git a/selfdrive/car/mazda/interface.py b/selfdrive/car/mazda/interface.py
index 89ed5638c..7c42431e3 100755
--- a/selfdrive/car/mazda/interface.py
+++ b/selfdrive/car/mazda/interface.py
@@ -10,10 +10,6 @@ EventName = car.CarEvent.EventName
class CarInterface(CarInterfaceBase):
- @staticmethod
- def compute_gb(accel, speed):
- return float(accel) / 4.0
-
@staticmethod
def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=None, experimental_long=False):
ret = CarInterfaceBase.get_std_params(candidate, fingerprint)
diff --git a/selfdrive/car/mock/interface.py b/selfdrive/car/mock/interface.py
index 2c7f4611e..77e3703c2 100755
--- a/selfdrive/car/mock/interface.py
+++ b/selfdrive/car/mock/interface.py
@@ -28,10 +28,6 @@ class CarInterface(CarInterfaceBase):
self.yaw_rate = 0.
self.yaw_rate_meas = 0.
- @staticmethod
- def compute_gb(accel, speed):
- return accel
-
@staticmethod
def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=None, experimental_long=False):
ret = CarInterfaceBase.get_std_params(candidate, fingerprint)
From b7dc1968cd4c61d33f96124b36d8d7a48957748f Mon Sep 17 00:00:00 2001
From: Shane Smiskol
Date: Thu, 15 Sep 2022 21:21:10 -0700
Subject: [PATCH 13/75] GM minSteerSpeed: add some tolerance for Volt (#25809)
* add some tolerance for volts
* add comment
* update refs
---
selfdrive/car/gm/interface.py | 3 ++-
selfdrive/test/process_replay/ref_commit | 2 +-
2 files changed, 3 insertions(+), 2 deletions(-)
diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py
index 93be57cf2..22ea83759 100755
--- a/selfdrive/car/gm/interface.py
+++ b/selfdrive/car/gm/interface.py
@@ -74,7 +74,8 @@ class CarInterface(CarInterfaceBase):
ret.dashcamOnly = candidate in {CAR.CADILLAC_ATS, CAR.HOLDEN_ASTRA, CAR.MALIBU, CAR.BUICK_REGAL, CAR.EQUINOX, CAR.BOLT_EV}
# Start with a baseline tuning for all GM vehicles. Override tuning as needed in each model section below.
- ret.minSteerSpeed = 10 * CV.KPH_TO_MS
+ # Some GMs need some tolerance above 10 kph to avoid a fault
+ ret.minSteerSpeed = 10.1 * CV.KPH_TO_MS
ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]]
ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2], [0.00]]
ret.lateralTuning.pid.kf = 0.00004 # full torque for 20 deg at 80mph means 0.00007818594
diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit
index 062611316..b1a2785ba 100644
--- a/selfdrive/test/process_replay/ref_commit
+++ b/selfdrive/test/process_replay/ref_commit
@@ -1 +1 @@
-147410f09f242f05b922c9cc7ac04c3c3366419c
\ No newline at end of file
+a4aa1f37c6d966151d3b43a0b51fffbcfa0187b1
\ No newline at end of file
From 40f89b183e5ab39d4a176e54268b0eb9de8e9ebc Mon Sep 17 00:00:00 2001
From: ambientocclusion <1399123+ambientocclusion@users.noreply.github.com>
Date: Thu, 15 Sep 2022 21:59:52 -0700
Subject: [PATCH 14/75] Multilang: add missing Japanese translations (#25803)
Add missing Japanese translations
---
selfdrive/ui/translations/main_ja.ts | 20 ++++++++++----------
1 file changed, 10 insertions(+), 10 deletions(-)
diff --git a/selfdrive/ui/translations/main_ja.ts b/selfdrive/ui/translations/main_ja.ts
index 3cc914975..b41e1bff7 100644
--- a/selfdrive/ui/translations/main_ja.ts
+++ b/selfdrive/ui/translations/main_ja.ts
@@ -985,42 +985,42 @@ location set
Updates are only downloaded while the car is off.
-
+ 車の電源がオフの間のみ、アップデートのダウンロードが行われます。
Current Version
-
+ 現在のバージョン
Download
-
+ ダウンロード
Install Update
-
+ アップデート
INSTALL
-
+ インストール
Target Branch
-
+ 対象のブランチ
SELECT
-
+ 選択
Select a branch
-
+ ブランチを選択
@@ -1189,12 +1189,12 @@ location set
openpilot longitudinal control is not currently available for this car.
-
+ openpilotによるアクセル制御は、この車では現在利用できません。
Enable experimental longitudinal control to enable this.
-
+ ここ機能を使う為には、「実験段階のopenpilotによるアクセル制御」を先に有効化してください。
From 453635394db56098f3473574150147eb977d61f4 Mon Sep 17 00:00:00 2001
From: AlexandreSato <66435071+AlexandreSato@users.noreply.github.com>
Date: Fri, 16 Sep 2022 15:43:22 -0300
Subject: [PATCH 15/75] Toyota: add missing Corolla Cross Hybrid engine FW
(#25814)
* Fingerprint: Add missing toyota corolla cross hybrid FW engine
From user lucasolivmed#1416 dongleId: 3eb4c34a2a663c37
* fix typo
---
selfdrive/car/toyota/values.py | 1 +
1 file changed, 1 insertion(+)
diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py
index b0fb14311..26c61f5b7 100644
--- a/selfdrive/car/toyota/values.py
+++ b/selfdrive/car/toyota/values.py
@@ -817,6 +817,7 @@ FW_VERSIONS = {
b'\x01896637626000\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',
b'\x02896630A21000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00',
b'\x02896630ZJ5000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00',
b'\x02896630ZN8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00',
From d460b2c62b9c652c73a1f4b34a3a83784c5eadb5 Mon Sep 17 00:00:00 2001
From: Jason Young <46612682+jyoung8607@users.noreply.github.com>
Date: Fri, 16 Sep 2022 16:21:33 -0500
Subject: [PATCH 16/75] VW MQB: Add FW for 2021 Volkswagen Atlas (#25820)
---
selfdrive/car/volkswagen/values.py | 1 +
1 file changed, 1 insertion(+)
diff --git a/selfdrive/car/volkswagen/values.py b/selfdrive/car/volkswagen/values.py
index 4d17b4e3a..bdd1b5089 100755
--- a/selfdrive/car/volkswagen/values.py
+++ b/selfdrive/car/volkswagen/values.py
@@ -300,6 +300,7 @@ FW_VERSIONS = {
(Ecu.engine, 0x7e0, None): [
b'\xf1\x8703H906026AA\xf1\x899970',
b'\xf1\x8703H906026AJ\xf1\x890638',
+ b'\xf1\x8703H906026AJ\xf1\x891017',
b'\xf1\x8703H906026AT\xf1\x891922',
b'\xf1\x8703H906026BC\xf1\x892664',
b'\xf1\x8703H906026F \xf1\x896696',
From e6ff301864b06d0b1dc14e007e1769d53234e38b Mon Sep 17 00:00:00 2001
From: Igor Biletskyy
Date: Fri, 16 Sep 2022 14:22:19 -0700
Subject: [PATCH 17/75] RPv2: fix data length check (#25819)
fix
---
selfdrive/boardd/panda.cc | 3 ++-
1 file changed, 2 insertions(+), 1 deletion(-)
diff --git a/selfdrive/boardd/panda.cc b/selfdrive/boardd/panda.cc
index 685dabd87..4d72bc904 100644
--- a/selfdrive/boardd/panda.cc
+++ b/selfdrive/boardd/panda.cc
@@ -389,7 +389,8 @@ void Panda::pack_can_buffer(const capnp::List::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) ? 64 : 8));
+ 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() == dlc_to_len[data_len_code]);
can_header header;
From ff63f26409256cc728b35098d135d19c7284c6f1 Mon Sep 17 00:00:00 2001
From: AlexandreSato <66435071+AlexandreSato@users.noreply.github.com>
Date: Fri, 16 Sep 2022 18:32:38 -0300
Subject: [PATCH 18/75] Multilang: update pt-BR translations (#25812)
* update pt-BR translations
* fix some cutoff texts
---
selfdrive/ui/translations/main_pt-BR.ts | 32 ++++++++++++-------------
1 file changed, 16 insertions(+), 16 deletions(-)
diff --git a/selfdrive/ui/translations/main_pt-BR.ts b/selfdrive/ui/translations/main_pt-BR.ts
index fe028e18b..a490b4088 100644
--- a/selfdrive/ui/translations/main_pt-BR.ts
+++ b/selfdrive/ui/translations/main_pt-BR.ts
@@ -888,13 +888,13 @@ trabalho definido
OFFLINE
- DESCONEC
+ OFFLINE
ONLINE
- CONECTADO
+ ONLINE
@@ -989,47 +989,47 @@ trabalho definido
Updates are only downloaded while the car is off.
-
+ Atualizações baixadas durante o motor desligado.
Current Version
-
+ Versao Atual
Download
-
+ Download
Install Update
-
+ Instalar Atualização
INSTALL
-
+ INSTALAR
Target Branch
-
+ Alterar Branch
SELECT
-
+ SELECIONE
Select a branch
-
+ Selecione uma branch
UNINSTALL
- DESINSTALAR
+ DESINSTAL
@@ -1178,27 +1178,27 @@ trabalho definido
Experimental openpilot longitudinal control
-
+ Controle longitudinal experimental openpilot
<b>WARNING: openpilot longitudinal control is experimental for this car and will disable AEB.</b>
-
+ <b>AVISO: o controle longitudinal openpilot é experimental para este carro e irá desabilitar AEB.</b>
Let the driving model control the gas and brakes. openpilot will drive as it thinks a human would. Super experimental.
-
+ Deixe o modelo controlar o acelerador e os freios. openpilot irá conduzir como pensa que um humano faria. Super experimental.
openpilot longitudinal control is not currently available for this car.
-
+ controle longitudinal openpilot não está disponível para este carro.
Enable experimental longitudinal control to enable this.
-
+ Habilite o controle longitudinal experimental para habilitar isso.
From 10f08a94dd1cb4ebc803b208697b4dc70795132a Mon Sep 17 00:00:00 2001
From: Adeeb Shihadeh
Date: Fri, 16 Sep 2022 15:35:38 -0700
Subject: [PATCH 19/75] sensor test fixups (#25818)
* sensor test fixups
* fix that
* little more
* seems reliable now
* kill old instances
* unused
* cleanup
Co-authored-by: Bruce Wayne
---
selfdrive/sensord/tests/test_sensord.py | 107 +++++++++++-------------
1 file changed, 48 insertions(+), 59 deletions(-)
diff --git a/selfdrive/sensord/tests/test_sensord.py b/selfdrive/sensord/tests/test_sensord.py
index 837fe8883..0b5f054d2 100755
--- a/selfdrive/sensord/tests/test_sensord.py
+++ b/selfdrive/sensord/tests/test_sensord.py
@@ -1,15 +1,13 @@
#!/usr/bin/env python3
-
+import os
import time
import unittest
import numpy as np
from collections import namedtuple
-from smbus2 import SMBus
import cereal.messaging as messaging
from cereal import log
from system.hardware import TICI, HARDWARE
-from selfdrive.test.helpers import with_processes
from selfdrive.manager.process_config import managed_processes
SENSOR_CONFIGURATIONS = (
@@ -50,33 +48,33 @@ SENSOR_CONFIGURATIONS = (
)
Sensor = log.SensorEventData.SensorSource
-SensorConfig = namedtuple('SensorConfig', ['type', 'min_samples', 'sanity_min', 'sanity_max'])
+SensorConfig = namedtuple('SensorConfig', ['type', 'sanity_min', 'sanity_max'])
ALL_SENSORS = {
Sensor.rpr0521: {
- SensorConfig("light", 100, 0, 150),
+ SensorConfig("light", 0, 150),
},
Sensor.lsm6ds3: {
- SensorConfig("acceleration", 100, 5, 15),
- SensorConfig("gyroUncalibrated", 100, 0, .2),
- SensorConfig("temperature", 100, 0, 60),
+ SensorConfig("acceleration", 5, 15),
+ SensorConfig("gyroUncalibrated", 0, .2),
+ SensorConfig("temperature", 0, 60),
},
Sensor.lsm6ds3trc: {
- SensorConfig("acceleration", 100, 5, 15),
- SensorConfig("gyroUncalibrated", 100, 0, .2),
- SensorConfig("temperature", 100, 0, 60),
+ SensorConfig("acceleration", 5, 15),
+ SensorConfig("gyroUncalibrated", 0, .2),
+ SensorConfig("temperature", 0, 60),
},
Sensor.bmx055: {
- SensorConfig("acceleration", 100, 5, 15),
- SensorConfig("gyroUncalibrated", 100, 0, .2),
- SensorConfig("magneticUncalibrated", 100, 0, 300),
- SensorConfig("temperature", 100, 0, 60),
+ SensorConfig("acceleration", 5, 15),
+ SensorConfig("gyroUncalibrated", 0, .2),
+ SensorConfig("magneticUncalibrated", 0, 300),
+ SensorConfig("temperature", 0, 60),
},
Sensor.mmc5603nj: {
- SensorConfig("magneticUncalibrated", 100, 0, 300),
+ SensorConfig("magneticUncalibrated", 0, 300),
}
}
@@ -96,7 +94,6 @@ def read_sensor_events(duration_sec):
return events
def get_proc_interrupts(int_pin):
-
with open("/proc/interrupts") as f:
lines = f.read().split("\n")
@@ -117,12 +114,18 @@ class TestSensord(unittest.TestCase):
HARDWARE.initialize_hardware()
# read initial sensor values every test case can use
+ os.system("pkill -f ./_sensord")
+ cls.sample_secs = 5
managed_processes["sensord"].start()
- cls.events = read_sensor_events(5)
+ time.sleep(2)
+ cls.events = read_sensor_events(cls.sample_secs)
+ managed_processes["sensord"].stop()
+
+ @classmethod
+ def tearDownClass(cls):
managed_processes["sensord"].stop()
def tearDown(self):
- # interrupt check might leave sensord running
managed_processes["sensord"].stop()
def test_sensors_present(self):
@@ -138,34 +141,32 @@ class TestSensord(unittest.TestCase):
self.assertIn(seen, SENSOR_CONFIGURATIONS)
- def test_lsm6ds3_100Hz(self):
- # verify measurements are sampled and published at a 100Hz rate
+ def test_lsm6ds3_timing(self):
+ # verify measurements are sampled and published at 104Hz
- data_points = set()
+ sensor_t = {
+ 1: [], # accel
+ 5: [], # gyro
+ }
for event in self.events:
for measurement in event.sensorEvents:
+ if str(measurement.source).startswith("lsm6ds3") and measurement.sensor in sensor_t:
+ sensor_t[measurement.sensor].append(measurement.timestamp)
- # skip lsm6ds3 temperature measurements
- if measurement.which() == 'temperature':
- continue
-
- if str(measurement.source).startswith("lsm6ds3"):
- data_points.add(measurement.timestamp)
-
- assert len(data_points) != 0, "No lsm6ds3 sensor events"
+ for s, vals in sensor_t.items():
+ with self.subTest(sensor=s):
+ assert len(vals) > 0
+ tdiffs = np.diff(vals) / 1e6 # millis
- data_list = list(data_points)
- data_list.sort()
- tdiffs = np.diff(data_list)
+ high_delay_diffs = list(filter(lambda d: d >= 20., tdiffs))
+ assert len(high_delay_diffs) < 15, f"Too many large diffs: {high_delay_diffs}"
- high_delay_diffs = set(filter(lambda d: d >= 10.1*10**6, tdiffs))
- assert len(high_delay_diffs) < 10, f"Too many high delay packages: {high_delay_diffs}"
+ # 100-108Hz, expected 104Hz
+ avg_diff = sum(tdiffs)/len(tdiffs)
+ assert 9.3 < avg_diff < 10., f"avg difference {avg_diff}, below threshold"
- avg_diff = sum(tdiffs)/len(tdiffs)
- assert avg_diff > 9.6*10**6, f"avg difference {avg_diff}, below threshold"
-
- stddev = np.std(tdiffs)
- assert stddev < 1.5*10**6, f"Standard-dev to big {stddev}"
+ stddev = np.std(tdiffs)
+ assert stddev < 2.0, f"Standard-dev to big {stddev}"
def test_events_check(self):
# verify if all sensors produce events
@@ -217,13 +218,9 @@ class TestSensord(unittest.TestCase):
stddev = np.std(tdiffs)
assert stddev < 2*10**6, f"Timing diffs have to high stddev: {stddev}"
- @with_processes(['sensord'])
def test_sensor_values_sanity_check(self):
-
- events = read_sensor_events(2)
-
sensor_values = dict()
- for event in events:
+ for event in self.events:
for m in event.sensorEvents:
# filter unset events (bmx magn)
@@ -250,8 +247,9 @@ class TestSensord(unittest.TestCase):
key = (sensor, s.type)
val_cnt = len(sensor_values[key])
- err_msg = f"Sensor {sensor} {s.type} got {val_cnt} measurements, expected {s.min_samples}"
- assert val_cnt > s.min_samples, err_msg
+ min_samples = self.sample_secs * 100 # Hz
+ err_msg = f"Sensor {sensor} {s.type} got {val_cnt} measurements, expected {min_samples}"
+ assert min_samples*0.9 < val_cnt < min_samples*1.1, err_msg
mean_norm = np.mean(np.linalg.norm(sensor_values[key], axis=1))
err_msg = f"Sensor '{sensor} {s.type}' failed sanity checks {mean_norm} is not between {s.sanity_min} and {s.sanity_max}"
@@ -260,26 +258,17 @@ class TestSensord(unittest.TestCase):
def test_sensor_verify_no_interrupts_after_stop(self):
managed_processes["sensord"].start()
- time.sleep(1)
-
- # check if the interrupts are enableds
- with SMBus(SENSOR_BUS, force=True) as bus:
- int1_ctrl_reg = bus.read_byte_data(I2C_ADDR_LSM, 0x0D)
- assert int1_ctrl_reg == 3, "Interrupts not enabled!"
+ time.sleep(3)
# read /proc/interrupts to verify interrupts are received
state_one = get_proc_interrupts(LSM_INT_GPIO)
time.sleep(1)
state_two = get_proc_interrupts(LSM_INT_GPIO)
- assert state_one != state_two, "no Interrupts received after sensord start!"
+ assert state_one != state_two, f"no interrupts received after sensord start!\n{state_one} {state_two}"
managed_processes["sensord"].stop()
-
- # check if the interrupts got disabled
- with SMBus(SENSOR_BUS, force=True) as bus:
- int1_ctrl_reg = bus.read_byte_data(I2C_ADDR_LSM, 0x0D)
- assert int1_ctrl_reg == 0, "Interrupts not disabled!"
+ time.sleep(1)
# read /proc/interrupts to verify no more interrupts are received
state_one = get_proc_interrupts(LSM_INT_GPIO)
From f73b041d43a1ece437df38e26b1dd30759a79c9f Mon Sep 17 00:00:00 2001
From: Willem Melching
Date: Sat, 17 Sep 2022 02:33:38 +0200
Subject: [PATCH 20/75] Hyundai: match ego speed on dash (#25235)
* hyundai: match speed on dash
* still needs conversion to m/s
* always use CF_Clu_VehicleSpeed2
* clean up, like honda
* experiment
* to the source
* works pretty well on optima (matches exactly on Sonata)
* could be 0.5
* clean up test
* revert test_moedls
revert test_moedls
* woops
* woops.
* .
* fix hyst
* only CF_Clu_VehicleSpeed
* omgomgomg
* add all this mess because it always takes a while
* set vEgoCluster
* fix all rounding errors
* stash
* clean up
* clean up
* fix metric conversion
* only calculate when updated
* try to filter (didn't look great from plots)
* Revert "try to filter (didn't look great from plots)"
This reverts commit 7e9876c237341d07163985b0718fd9c553372e72.
* clean up
* update refs
Co-authored-by: Shane Smiskol
---
selfdrive/car/hyundai/carstate.py | 26 ++++++++++++++++++++----
selfdrive/test/process_replay/ref_commit | 2 +-
2 files changed, 23 insertions(+), 5 deletions(-)
diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py
index eab6e73f1..61da04d04 100644
--- a/selfdrive/car/hyundai/carstate.py
+++ b/selfdrive/car/hyundai/carstate.py
@@ -1,5 +1,6 @@
from collections import deque
import copy
+import math
from cereal import car
from common.conversions import Conversions as CV
@@ -9,6 +10,7 @@ from selfdrive.car.hyundai.values import HyundaiFlags, DBC, FEATURES, CAMERA_SCC
from selfdrive.car.interfaces import CarStateBase
PREV_BUTTON_SAMPLES = 8
+CLUSTER_SAMPLE_RATE = 20 # frames
class CarState(CarStateBase):
@@ -32,6 +34,10 @@ class CarState(CarStateBase):
self.park_brake = False
self.buttons_counter = 0
+ # On some cars, CLU15->CF_Clu_VehicleSpeed can oscillate faster than the dash updates. Sample at 5 Hz
+ self.cluster_speed = 0
+ self.cluster_speed_counter = CLUSTER_SAMPLE_RATE
+
self.params = CarControllerParams(CP)
def update(self, cp, cp_cam):
@@ -39,8 +45,9 @@ class CarState(CarStateBase):
return self.update_canfd(cp, cp_cam)
ret = car.CarState.new_message()
-
cp_cruise = cp_cam if self.CP.carFingerprint in CAMERA_SCC_CAR else cp
+ is_metric = cp.vl["CLU11"]["CF_Clu_SPEED_UNIT"] == 0
+ speed_conv = CV.KPH_TO_MS if is_metric else CV.MPH_TO_MS
ret.doorOpen = any([cp.vl["CGW1"]["CF_Gway_DrvDrSw"], cp.vl["CGW1"]["CF_Gway_AstDrSw"],
cp.vl["CGW2"]["CF_Gway_RLDrSw"], cp.vl["CGW2"]["CF_Gway_RRDrSw"]])
@@ -55,9 +62,19 @@ class CarState(CarStateBase):
)
ret.vEgoRaw = (ret.wheelSpeeds.fl + ret.wheelSpeeds.fr + ret.wheelSpeeds.rl + ret.wheelSpeeds.rr) / 4.
ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw)
-
ret.standstill = ret.vEgoRaw < 0.1
+ self.cluster_speed_counter += 1
+ if self.cluster_speed_counter > CLUSTER_SAMPLE_RATE:
+ self.cluster_speed = cp.vl["CLU15"]["CF_Clu_VehicleSpeed"]
+ self.cluster_speed_counter = 0
+
+ # mimic how dash converts to imperial
+ if not is_metric:
+ self.cluster_speed = math.floor(self.cluster_speed * CV.KPH_TO_MPH + CV.KPH_TO_MPH)
+
+ ret.vEgoCluster = self.cluster_speed * speed_conv
+
ret.steeringAngleDeg = cp.vl["SAS11"]["SAS_Angle"]
ret.steeringRateDeg = cp.vl["SAS11"]["SAS_Speed"]
ret.yawRate = cp.vl["ESP12"]["YAW_RATE"]
@@ -78,7 +95,6 @@ class CarState(CarStateBase):
ret.cruiseState.available = cp_cruise.vl["SCC11"]["MainMode_ACC"] == 1
ret.cruiseState.enabled = cp_cruise.vl["SCC12"]["ACCMode"] != 0
ret.cruiseState.standstill = cp_cruise.vl["SCC11"]["SCCInfoDisplay"] == 4.
- speed_conv = CV.MPH_TO_MS if cp.vl["CLU11"]["CF_Clu_SPEED_UNIT"] else CV.KPH_TO_MS
ret.cruiseState.speed = cp_cruise.vl["SCC11"]["VSetDis"] * speed_conv
# TODO: Find brake pressure
@@ -227,6 +243,8 @@ class CarState(CarStateBase):
("CF_Clu_AmpInfo", "CLU11"),
("CF_Clu_AliveCnt1", "CLU11"),
+ ("CF_Clu_VehicleSpeed", "CLU15"),
+
("ACCEnable", "TCS13"),
("ACC_REQ", "TCS13"),
("DriverBraking", "TCS13"),
@@ -251,6 +269,7 @@ class CarState(CarStateBase):
("TCS13", 50),
("TCS15", 10),
("CLU11", 50),
+ ("CLU15", 5),
("ESP12", 100),
("CGW1", 10),
("CGW2", 5),
@@ -309,7 +328,6 @@ class CarState(CarStateBase):
if CP.carFingerprint in FEATURES["use_cluster_gears"]:
signals.append(("CF_Clu_Gear", "CLU15"))
- checks.append(("CLU15", 5))
elif CP.carFingerprint in FEATURES["use_tcu_gears"]:
signals.append(("CUR_GR", "TCU12"))
checks.append(("TCU12", 100))
diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit
index b1a2785ba..bca5d0c3e 100644
--- a/selfdrive/test/process_replay/ref_commit
+++ b/selfdrive/test/process_replay/ref_commit
@@ -1 +1 @@
-a4aa1f37c6d966151d3b43a0b51fffbcfa0187b1
\ No newline at end of file
+a9a25795f5d8202f7f4c137f80ae030e790ff974
\ No newline at end of file
From 1a7d6665deafc1e35e5f8d56106a81a4686a6e44 Mon Sep 17 00:00:00 2001
From: Dean Lee
Date: Sat, 17 Sep 2022 10:45:51 +0800
Subject: [PATCH 21/75] sensord: remove unnecessary brace pair (#25816)
Remove unnecessary brace pair
---
selfdrive/sensord/sensors_qcom2.cc | 6 ++----
1 file changed, 2 insertions(+), 4 deletions(-)
diff --git a/selfdrive/sensord/sensors_qcom2.cc b/selfdrive/sensord/sensors_qcom2.cc
index a9d6e31d3..aaf79592c 100644
--- a/selfdrive/sensord/sensors_qcom2.cc
+++ b/selfdrive/sensord/sensors_qcom2.cc
@@ -88,10 +88,8 @@ void interrupt_loop(int fd, std::vector& sensors, PubMaster& pm) {
events.adoptWithCaveats(i, kj::mv(collected_events[i]));
}
- {
- std::lock_guard lock(pm_mutex);
- pm.send("sensorEvents", msg);
- }
+ std::lock_guard lock(pm_mutex);
+ pm.send("sensorEvents", msg);
}
// poweroff sensors, disable interrupts
From 467c4f7fb3bd954d7e0d9120ccd1c687532e6cdc Mon Sep 17 00:00:00 2001
From: Dean Lee
Date: Sat, 17 Sep 2022 11:10:08 +0800
Subject: [PATCH 22/75] camera_qcom2: remove unneeded static keywords (#25780)
---
system/camerad/cameras/camera_qcom2.cc | 10 +++++-----
1 file changed, 5 insertions(+), 5 deletions(-)
diff --git a/system/camerad/cameras/camera_qcom2.cc b/system/camerad/cameras/camera_qcom2.cc
index 544d65367..532b25d6d 100644
--- a/system/camerad/cameras/camera_qcom2.cc
+++ b/system/camerad/cameras/camera_qcom2.cc
@@ -821,8 +821,8 @@ void cameras_open(MultiCameraState *s) {
// query icp for MMU handles
LOG("-- Query ICP for MMU handles");
- static struct cam_isp_query_cap_cmd isp_query_cap_cmd = {0};
- static struct cam_query_cap_cmd query_cap_cmd = {0};
+ struct cam_isp_query_cap_cmd isp_query_cap_cmd = {0};
+ struct cam_query_cap_cmd query_cap_cmd = {0};
query_cap_cmd.handle_type = 1;
query_cap_cmd.caps_handle = (uint64_t)&isp_query_cap_cmd;
query_cap_cmd.size = sizeof(isp_query_cap_cmd);
@@ -835,7 +835,7 @@ void cameras_open(MultiCameraState *s) {
// subscribe
LOG("-- Subscribing");
- static struct v4l2_event_subscription sub = {0};
+ struct v4l2_event_subscription sub = {0};
sub.type = V4L_EVENT_CAM_REQ_MGR_EVENT;
sub.id = V4L_EVENT_CAM_REQ_MGR_SOF_BOOT_TS;
ret = HANDLE_EINTR(ioctl(s->video0_fd, VIDIOC_SUBSCRIBE_EVENT, &sub));
@@ -864,7 +864,7 @@ void CameraState::camera_close() {
LOGD("stop csiphy: %d", ret);
// link control stop
LOG("-- Stop link control");
- static struct cam_req_mgr_link_control req_mgr_link_control = {0};
+ struct cam_req_mgr_link_control req_mgr_link_control = {0};
req_mgr_link_control.ops = CAM_REQ_MGR_LINK_DEACTIVATE;
req_mgr_link_control.session_hdl = session_handle;
req_mgr_link_control.num_links = 1;
@@ -874,7 +874,7 @@ void CameraState::camera_close() {
// unlink
LOG("-- Unlink");
- static struct cam_req_mgr_unlink_info req_mgr_unlink_info = {0};
+ struct cam_req_mgr_unlink_info req_mgr_unlink_info = {0};
req_mgr_unlink_info.session_hdl = session_handle;
req_mgr_unlink_info.link_hdl = link_handle;
ret = do_cam_control(multi_cam_state->video0_fd, CAM_REQ_MGR_UNLINK, &req_mgr_unlink_info, sizeof(req_mgr_unlink_info));
From 25ce997f3768913915e83b72f4b3c2649a83d720 Mon Sep 17 00:00:00 2001
From: Dean Lee
Date: Sat, 17 Sep 2022 11:11:46 +0800
Subject: [PATCH 23/75] CameraBuf: remove unused member 'camera_state' (#25736)
---
system/camerad/cameras/camera_common.cc | 4 +---
system/camerad/cameras/camera_common.h | 5 -----
2 files changed, 1 insertion(+), 8 deletions(-)
diff --git a/system/camerad/cameras/camera_common.cc b/system/camerad/cameras/camera_common.cc
index 3dbe97596..b1b4dc7b4 100644
--- a/system/camerad/cameras/camera_common.cc
+++ b/system/camerad/cameras/camera_common.cc
@@ -65,11 +65,9 @@ private:
void CameraBuf::init(cl_device_id device_id, cl_context context, CameraState *s, VisionIpcServer * v, int frame_cnt, VisionStreamType init_yuv_type) {
vipc_server = v;
this->yuv_type = init_yuv_type;
-
- const CameraInfo *ci = &s->ci;
- camera_state = s;
frame_buf_count = frame_cnt;
+ const CameraInfo *ci = &s->ci;
// RAW frame
const int frame_size = (ci->frame_height + ci->extra_height) * ci->frame_stride;
camera_bufs = std::make_unique(frame_buf_count);
diff --git a/system/camerad/cameras/camera_common.h b/system/camerad/cameras/camera_common.h
index bb6de9c8f..8b4f5a933 100644
--- a/system/camerad/cameras/camera_common.h
+++ b/system/camerad/cameras/camera_common.h
@@ -81,15 +81,10 @@ class Debayer;
class CameraBuf {
private:
VisionIpcServer *vipc_server;
- CameraState *camera_state;
Debayer *debayer = nullptr;
-
VisionStreamType yuv_type;
-
int cur_buf_idx;
-
SafeQueue safe_queue;
-
int frame_buf_count;
public:
From 5bb230cde4dd61ff7b180a29a0951a44068161c1 Mon Sep 17 00:00:00 2001
From: Dean Lee
Date: Sat, 17 Sep 2022 11:18:54 +0800
Subject: [PATCH 24/75] camerad: remove function camera_autoexposure (#25733)
---
system/camerad/cameras/camera_common.h | 1 -
system/camerad/cameras/camera_qcom2.cc | 15 ++-------------
2 files changed, 2 insertions(+), 14 deletions(-)
diff --git a/system/camerad/cameras/camera_common.h b/system/camerad/cameras/camera_common.h
index 8b4f5a933..eaefd3c90 100644
--- a/system/camerad/cameras/camera_common.h
+++ b/system/camerad/cameras/camera_common.h
@@ -117,7 +117,6 @@ void cameras_init(VisionIpcServer *v, MultiCameraState *s, cl_device_id device_i
void cameras_open(MultiCameraState *s);
void cameras_run(MultiCameraState *s);
void cameras_close(MultiCameraState *s);
-void camera_autoexposure(CameraState *s, float grey_frac);
void camerad_thread();
int open_v4l_by_name_and_index(const char name[], int index = 0, int flags = O_RDWR | O_NONBLOCK);
diff --git a/system/camerad/cameras/camera_qcom2.cc b/system/camerad/cameras/camera_qcom2.cc
index 532b25d6d..ce1d0d6f2 100644
--- a/system/camerad/cameras/camera_qcom2.cc
+++ b/system/camerad/cameras/camera_qcom2.cc
@@ -1180,10 +1180,6 @@ void CameraState::set_camera_exposure(float grey_frac) {
}
}
-void camera_autoexposure(CameraState *s, float grey_frac) {
- s->set_camera_exposure(grey_frac);
-}
-
static float ar0231_parse_temp_sensor(uint16_t calib1, uint16_t calib2, uint16_t data_reg) {
// See AR0231 Developer Guide - page 36
float slope = (125.0 - 55.0) / ((float)calib1 - (float)calib2);
@@ -1210,15 +1206,8 @@ static void ar0231_process_registers(MultiCameraState *s, CameraState *c, cereal
framed.setTemperaturesC({temp_0, temp_1});
}
-static void driver_cam_auto_exposure(CameraState *c) {
- struct ExpRect {int x1, x2, x_skip, y1, y2, y_skip;};
- const CameraBuf *b = &c->buf;
- static ExpRect rect = {96, 1832, 2, 242, 1148, 4};
- camera_autoexposure(c, set_exposure_target(b, rect.x1, rect.x2, rect.x_skip, rect.y1, rect.y2, rect.y_skip));
-}
-
static void process_driver_camera(MultiCameraState *s, CameraState *c, int cnt) {
- driver_cam_auto_exposure(c);
+ c->set_camera_exposure(set_exposure_target(&c->buf, 96, 1832, 2, 242, 1148, 4));
MessageBuilder msg;
auto framed = msg.initEvent().initDriverCameraState();
@@ -1254,7 +1243,7 @@ void process_road_camera(MultiCameraState *s, CameraState *c, int cnt) {
const auto [x, y, w, h] = (c == &s->wide_road_cam) ? std::tuple(96, 250, 1734, 524) : std::tuple(96, 160, 1734, 986);
const int skip = 2;
- camera_autoexposure(c, set_exposure_target(b, x, x + w, skip, y, y + h, skip));
+ c->set_camera_exposure(set_exposure_target(b, x, x + w, skip, y, y + h, skip));
}
void cameras_run(MultiCameraState *s) {
From 78fd303d50b78dbb99992bb3ee4938eec8913575 Mon Sep 17 00:00:00 2001
From: Dean Lee
Date: Sat, 17 Sep 2022 11:50:10 +0800
Subject: [PATCH 25/75] camerad: cleanup CameraBuf::acquire (#25737)
* cleanup
* add that back
* less indent
Co-authored-by: Comma Device
---
system/camerad/cameras/camera_common.cc | 23 ++++++-----------------
system/camerad/cameras/camera_common.h | 1 -
2 files changed, 6 insertions(+), 18 deletions(-)
diff --git a/system/camerad/cameras/camera_common.cc b/system/camerad/cameras/camera_common.cc
index b1b4dc7b4..787fd9930 100644
--- a/system/camerad/cameras/camera_common.cc
+++ b/system/camerad/cameras/camera_common.cc
@@ -116,30 +116,24 @@ bool CameraBuf::acquire() {
if (camera_bufs_metadata[cur_buf_idx].frame_id == -1) {
LOGE("no frame data? wtf");
- release();
return false;
}
cur_frame_data = camera_bufs_metadata[cur_buf_idx];
cur_yuv_buf = vipc_server->get_buffer(yuv_type);
- cl_mem camrabuf_cl = camera_bufs[cur_buf_idx].buf_cl;
- cl_event event;
-
- double start_time = millis_since_boot();
-
cur_camera_buf = &camera_bufs[cur_buf_idx];
- debayer->queue(q, camrabuf_cl, cur_yuv_buf->buf_cl, rgb_width, rgb_height, &event);
-
+ double start_time = millis_since_boot();
+ cl_event event;
+ debayer->queue(q, camera_bufs[cur_buf_idx].buf_cl, cur_yuv_buf->buf_cl, rgb_width, rgb_height, &event);
clWaitForEvents(1, &event);
CL_CHECK(clReleaseEvent(event));
-
cur_frame_data.processing_time = (millis_since_boot() - start_time) / 1000.0;
VisionIpcBufExtra extra = {
- cur_frame_data.frame_id,
- cur_frame_data.timestamp_sof,
- cur_frame_data.timestamp_eof,
+ cur_frame_data.frame_id,
+ cur_frame_data.timestamp_sof,
+ cur_frame_data.timestamp_eof,
};
cur_yuv_buf->set_frame_id(cur_frame_data.frame_id);
vipc_server->send(cur_yuv_buf, &extra);
@@ -147,10 +141,6 @@ bool CameraBuf::acquire() {
return true;
}
-void CameraBuf::release() {
- // Empty
-}
-
void CameraBuf::queue(size_t buf_idx) {
safe_queue.push(buf_idx);
}
@@ -328,7 +318,6 @@ void *processing_thread(MultiCameraState *cameras, CameraState *cs, process_thre
// this takes 10ms???
publish_thumbnail(cameras->pm, &(cs->buf));
}
- cs->buf.release();
++cnt;
}
return NULL;
diff --git a/system/camerad/cameras/camera_common.h b/system/camerad/cameras/camera_common.h
index eaefd3c90..e5580a7a9 100644
--- a/system/camerad/cameras/camera_common.h
+++ b/system/camerad/cameras/camera_common.h
@@ -102,7 +102,6 @@ public:
~CameraBuf();
void init(cl_device_id device_id, cl_context context, CameraState *s, VisionIpcServer * v, int frame_cnt, VisionStreamType yuv_type);
bool acquire();
- void release();
void queue(size_t buf_idx);
};
From 8ae3199578b3f771396cd35315ce51b7cce27e49 Mon Sep 17 00:00:00 2001
From: Dean Lee
Date: Sat, 17 Sep 2022 12:10:26 +0800
Subject: [PATCH 26/75] camerad: make sure cl_context is valid for lifetime of
camerad (#25735)
---
system/camerad/cameras/camera_common.cc | 14 ++++++++------
1 file changed, 8 insertions(+), 6 deletions(-)
diff --git a/system/camerad/cameras/camera_common.cc b/system/camerad/cameras/camera_common.cc
index 787fd9930..580c4bc5e 100644
--- a/system/camerad/cameras/camera_common.cc
+++ b/system/camerad/cameras/camera_common.cc
@@ -336,15 +336,17 @@ void camerad_thread() {
cl_context context = CL_CHECK_ERR(clCreateContext(NULL, 1, &device_id, NULL, NULL, &err));
#endif
- MultiCameraState cameras = {};
- VisionIpcServer vipc_server("camerad", device_id, context);
+ {
+ MultiCameraState cameras = {};
+ VisionIpcServer vipc_server("camerad", device_id, context);
- cameras_open(&cameras);
- cameras_init(&vipc_server, &cameras, device_id, context);
+ cameras_open(&cameras);
+ cameras_init(&vipc_server, &cameras, device_id, context);
- vipc_server.start_listener();
+ vipc_server.start_listener();
- cameras_run(&cameras);
+ cameras_run(&cameras);
+ }
CL_CHECK(clReleaseContext(context));
}
From aa0d12842202ddf63d9a5998ccd04f865b6e9d6a Mon Sep 17 00:00:00 2001
From: Dean Lee
Date: Sat, 17 Sep 2022 13:17:30 +0800
Subject: [PATCH 27/75] ui: always show SetupWidget (#25742)
* always show SetupWidget
update translations
* delete hide
---
selfdrive/ui/qt/widgets/prime.cc | 4 +---
1 file changed, 1 insertion(+), 3 deletions(-)
diff --git a/selfdrive/ui/qt/widgets/prime.cc b/selfdrive/ui/qt/widgets/prime.cc
index 1d765d094..04684fc76 100644
--- a/selfdrive/ui/qt/widgets/prime.cc
+++ b/selfdrive/ui/qt/widgets/prime.cc
@@ -277,7 +277,7 @@ SetupWidget::SetupWidget(QWidget* parent) : QFrame(parent) {
primeUser = new PrimeUserWidget;
mainLayout->addWidget(primeUser);
- mainLayout->setCurrentWidget(primeAd);
+ mainLayout->setCurrentWidget(uiState()->prime_type ? (QWidget*)primeUser : (QWidget*)primeAd);
setFixedWidth(750);
setStyleSheet(R"(
@@ -299,11 +299,9 @@ SetupWidget::SetupWidget(QWidget* parent) : QFrame(parent) {
QObject::connect(repeater, &RequestRepeater::requestDone, this, &SetupWidget::replyFinished);
}
- hide(); // Only show when first request comes back
}
void SetupWidget::replyFinished(const QString &response, bool success) {
- show();
if (!success) return;
QJsonDocument doc = QJsonDocument::fromJson(response.toUtf8());
From 407448bbfb79ad9d9d235bc3d098887ea0d045fb Mon Sep 17 00:00:00 2001
From: cydia2020 <12470297+cydia2020@users.noreply.github.com>
Date: Sat, 17 Sep 2022 16:28:05 +1000
Subject: [PATCH 28/75] Toyota: go into standstill if interceptor detected
(#25024)
* Toyota: go into standstill if interceptor detected
* or
---
selfdrive/car/toyota/carcontroller.py | 2 +-
1 file changed, 1 insertion(+), 1 deletion(-)
diff --git a/selfdrive/car/toyota/carcontroller.py b/selfdrive/car/toyota/carcontroller.py
index b34a31a01..faea08ed3 100644
--- a/selfdrive/car/toyota/carcontroller.py
+++ b/selfdrive/car/toyota/carcontroller.py
@@ -81,7 +81,7 @@ class CarController:
pcm_cancel_cmd = 1
# on entering standstill, send standstill request
- if CS.out.standstill and not self.last_standstill and self.CP.carFingerprint not in NO_STOP_TIMER_CAR:
+ if CS.out.standstill and not self.last_standstill and (self.CP.carFingerprint not in NO_STOP_TIMER_CAR or self.CP.enableGasInterceptor):
self.standstill_req = True
if CS.pcm_acc_status != 8:
# pcm entered standstill or it's disabled
From 85ed5c4cb5d9b0132ab0e3eb5bcb096026f70b22 Mon Sep 17 00:00:00 2001
From: Vivek Aithal
Date: Sat, 17 Sep 2022 00:07:54 -0700
Subject: [PATCH 29/75] Torque Refactor (#25822)
* add torque gains refactor
* update refs
* avoid dict, use cereal struct
* bugfix
* no as_builder
* address final comments
---
selfdrive/car/interfaces.py | 30 ++++++++++++++----
selfdrive/controls/lib/latcontrol_torque.py | 35 ++++++++++-----------
selfdrive/test/process_replay/ref_commit | 2 +-
3 files changed, 41 insertions(+), 26 deletions(-)
diff --git a/selfdrive/car/interfaces.py b/selfdrive/car/interfaces.py
index bc6c31e12..87720f875 100644
--- a/selfdrive/car/interfaces.py
+++ b/selfdrive/car/interfaces.py
@@ -2,24 +2,27 @@ import yaml
import os
import time
from abc import abstractmethod, ABC
-from typing import Any, Dict, Optional, Tuple, List
+from typing import Any, Dict, Optional, Tuple, List, Callable
from cereal import car
from common.basedir import BASEDIR
from common.conversions import Conversions as CV
from common.kalman.simple_kalman import KF1D
+from common.numpy_fast import interp
from common.realtime import DT_CTRL
from selfdrive.car import apply_hysteresis, create_button_enable_events, gen_empty_fingerprint
-from selfdrive.controls.lib.drive_helpers import V_CRUISE_MAX
+from selfdrive.controls.lib.drive_helpers import V_CRUISE_MAX, apply_deadzone
from selfdrive.controls.lib.events import Events
from selfdrive.controls.lib.vehicle_model import VehicleModel
GearShifter = car.CarState.GearShifter
EventName = car.CarEvent.EventName
+TorqueFromLateralAccelCallbackType = Callable[[float, car.CarParams.LateralTorqueTuning, float, float, bool], float]
MAX_CTRL_SPEED = (V_CRUISE_MAX + 4) * CV.KPH_TO_MS
ACCEL_MAX = 2.0
ACCEL_MIN = -3.5
+FRICTION_THRESHOLD = 0.2
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')
@@ -101,6 +104,20 @@ class CarInterfaceBase(ABC):
def get_steer_feedforward_function(self):
return self.get_steer_feedforward_default
+ @staticmethod
+ def torque_from_lateral_accel_linear(lateral_accel_value, torque_params, lateral_accel_error, lateral_accel_deadzone, friction_compensation):
+ # The default is a linear relationship between torque and lateral acceleration (accounting for road roll and steering friction)
+ friction_interp = interp(
+ apply_deadzone(lateral_accel_error, lateral_accel_deadzone),
+ [-FRICTION_THRESHOLD, FRICTION_THRESHOLD],
+ [-torque_params.friction, torque_params.friction]
+ )
+ friction = friction_interp if friction_compensation else 0.0
+ return (lateral_accel_value / torque_params.latAccelFactor) + friction
+
+ def torque_from_lateral_accel(self) -> TorqueFromLateralAccelCallbackType:
+ return self.torque_from_lateral_accel_linear
+
# returns a set of default params to avoid repetition in car specific params
@staticmethod
def get_std_params(candidate, fingerprint):
@@ -144,11 +161,12 @@ class CarInterfaceBase(ABC):
tune.init('torque')
tune.torque.useSteeringAngle = use_steering_angle
- tune.torque.kp = 1.0 / params['LAT_ACCEL_FACTOR']
- tune.torque.kf = 1.0 / params['LAT_ACCEL_FACTOR']
- tune.torque.ki = 0.1 / params['LAT_ACCEL_FACTOR']
+ tune.torque.kp = 1.0
+ tune.torque.kf = 1.0
+ tune.torque.ki = 0.1
tune.torque.friction = params['FRICTION']
- tune.torque.steeringAngleDeadzoneDeg = steering_angle_deadzone_deg
+ tune.torque.latAccelFactor = params['LAT_ACCEL_FACTOR']
+ tune.torque.latAccelOffset = 0.0
@abstractmethod
def _update(self, c: car.CarControl) -> car.CarState:
diff --git a/selfdrive/controls/lib/latcontrol_torque.py b/selfdrive/controls/lib/latcontrol_torque.py
index c4604d90e..f65a58275 100644
--- a/selfdrive/controls/lib/latcontrol_torque.py
+++ b/selfdrive/controls/lib/latcontrol_torque.py
@@ -4,7 +4,6 @@ from cereal import log
from common.numpy_fast import interp
from selfdrive.controls.lib.latcontrol import LatControl, MIN_STEER_SPEED
from selfdrive.controls.lib.pid import PIDController
-from selfdrive.controls.lib.drive_helpers import apply_deadzone
from selfdrive.controls.lib.vehicle_model import ACCELERATION_DUE_TO_GRAVITY
# At higher speeds (25+mph) we can assume:
@@ -19,19 +18,20 @@ from selfdrive.controls.lib.vehicle_model import ACCELERATION_DUE_TO_GRAVITY
# move it at all, this is compensated for too.
-FRICTION_THRESHOLD = 0.2
-
-
class LatControlTorque(LatControl):
def __init__(self, CP, CI):
super().__init__(CP, CI)
- self.pid = PIDController(CP.lateralTuning.torque.kp, CP.lateralTuning.torque.ki,
- k_f=CP.lateralTuning.torque.kf, pos_limit=self.steer_max, neg_limit=-self.steer_max)
- self.get_steer_feedforward = CI.get_steer_feedforward_function()
- self.use_steering_angle = CP.lateralTuning.torque.useSteeringAngle
- self.friction = CP.lateralTuning.torque.friction
- self.kf = CP.lateralTuning.torque.kf
- self.steering_angle_deadzone_deg = CP.lateralTuning.torque.steeringAngleDeadzoneDeg
+ self.torque_params = CP.lateralTuning.torque
+ self.pid = PIDController(self.torque_params.kp, self.torque_params.ki,
+ k_f=self.torque_params.kf, pos_limit=self.steer_max, neg_limit=-self.steer_max)
+ self.torque_from_lateral_accel = CI.torque_from_lateral_accel()
+ self.use_steering_angle = self.torque_params.useSteeringAngle
+ self.steering_angle_deadzone_deg = self.torque_params.steeringAngleDeadzoneDeg
+
+ def update_live_torque_params(self, latAccelFactor, latAccelOffset, friction):
+ self.torque_params.latAccelFactor = latAccelFactor
+ self.torque_params.latAccelOffset = latAccelOffset
+ self.torque_params.friction = friction
def update(self, active, CS, VM, params, last_actuators, steer_limited, desired_curvature, desired_curvature_rate, llk):
pid_log = log.ControlsState.LateralTorqueState.new_message()
@@ -55,19 +55,16 @@ class LatControlTorque(LatControl):
actual_lateral_accel = actual_curvature * CS.vEgo ** 2
lateral_accel_deadzone = curvature_deadzone * CS.vEgo ** 2
-
low_speed_factor = interp(CS.vEgo, [0, 10, 20], [500, 500, 200])
setpoint = desired_lateral_accel + low_speed_factor * desired_curvature
measurement = actual_lateral_accel + low_speed_factor * actual_curvature
error = setpoint - measurement
- pid_log.error = error
+ 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, lateral_accel_deadzone, friction_compensation=False)
+ ff = self.torque_from_lateral_accel(gravity_adjusted_lateral_accel, self.torque_params, error, lateral_accel_deadzone, friction_compensation=True)
- ff = desired_lateral_accel - params.roll * ACCELERATION_DUE_TO_GRAVITY
- # convert friction into lateral accel units for feedforward
- friction_compensation = interp(apply_deadzone(error, lateral_accel_deadzone), [-FRICTION_THRESHOLD, FRICTION_THRESHOLD], [-self.friction, self.friction])
- ff += friction_compensation / self.kf
freeze_integrator = steer_limited or CS.steeringPressed or CS.vEgo < 5
- output_torque = self.pid.update(error,
+ output_torque = self.pid.update(pid_log.error,
feedforward=ff,
speed=CS.vEgo,
freeze_integrator=freeze_integrator)
@@ -78,9 +75,9 @@ class LatControlTorque(LatControl):
pid_log.d = self.pid.d
pid_log.f = self.pid.f
pid_log.output = -output_torque
- pid_log.saturated = self._check_saturation(self.steer_max - abs(output_torque) < 1e-3, CS, steer_limited)
pid_log.actualLateralAccel = actual_lateral_accel
pid_log.desiredLateralAccel = desired_lateral_accel
+ pid_log.saturated = self._check_saturation(self.steer_max - abs(output_torque) < 1e-3, CS, steer_limited)
# TODO left is positive in this convention
return -output_torque, 0.0, pid_log
diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit
index bca5d0c3e..afde6ec42 100644
--- a/selfdrive/test/process_replay/ref_commit
+++ b/selfdrive/test/process_replay/ref_commit
@@ -1 +1 @@
-a9a25795f5d8202f7f4c137f80ae030e790ff974
\ No newline at end of file
+d14f1a61a4bfde810128a6bb703aa543268fa4a9
\ No newline at end of file
From 06fb52c146aa9e00126127ac28fbbd22e9914e6f Mon Sep 17 00:00:00 2001
From: Cameron Clough
Date: Sat, 17 Sep 2022 00:24:57 -0700
Subject: [PATCH 30/75] Kia: update required packages (#25824)
* Kia: LKAS is standard on Ceed 2019
https://www.downeys.co.uk/newmodels/Ceed_V3_24_09_2019.pdf
* Kia: delete Forte 2018
It doesn't appear that this vehicle has Adaptive/Smart Cruise Control in
any form, which was later added in 2019.
https://cdn.dealereprocess.org/cdn/brochures/kia/2018-forte.pdf
https://cdn.dealereprocess.org/cdn/brochures/kia/2019-forte.pdf
* Kia: LKAS is standard on Forte 2019+
https://cdn.dealereprocess.org/cdn/brochures/kia/2019-forte.pdf
https://cdn.dealereprocess.org/cdn/brochures/kia/2020-forte.pdf
* Kia: rename Niro Electric to EV
https://www.kia.com/us/en/niro
Co-authored-by: Shane Smiskol
* Kia: LKAS is standard on Niro PHEV 2018+
https://cdn.dealereprocess.org/cdn/brochures/kia/2018-niro.pdf
https://cdn.dealereprocess.org/cdn/brochures/kia/2019-niro.pdf
* Kia: update required package on Optima 2017
The ACC package on the Optima 2017 is named "Advanced Smart Cruise
Control". It also doesn't have an LKAS package, only LDWS is available.
https://cdn.dealereprocess.org/cdn/brochures/kia/2017-optima.pdf
Co-authored-by: Shane Smiskol
* Kia: LKAS is standard on Optima 2019
https://cdn.dealereprocess.org/cdn/brochures/kia/2019-optima.pdf
* Kia: revert package change to Seltos 2021
LKAS is NOT a standard package on the Seltos 2021
https://cdn.dealereprocess.org/cdn/brochures/kia/2021-seltos.pdf
* Kia: update required package on Sorento 2018
Similar to the Optima 2017, the ACC package on the Sorento 2018 is named
"Advanced Smart Cruise Control". It also doesn't have an LKAS package,
only LDWS.
SCC and LKAS were introduced in MY2019.
https://cdn.dealereprocess.org/cdn/brochures/kia/2018-sorento.pdf
Co-authored-by: Shane Smiskol
* Kia: SCC is standard on Kia Niro PHEV 2018-19
https://cdn.dealereprocess.org/cdn/brochures/kia/2018-niro.pdf
Co-authored-by: Shane Smiskol
* Kia: update required package on Optima Hybrid 2017
Similar to the Optima 2017, the ACC package on he Optima Hybrid 2017 is
named "Advanced Smart Cruise Control". It also doesn't have an LKAS
pacakge, only LDWS.
https://cdn.dealereprocess.org/cdn/brochures/kia/2017-optimahybrid.pdf
* update docs
Co-authored-by: Shane Smiskol
---
docs/CARS.md | 25 ++++++++++++-------------
selfdrive/car/hyundai/values.py | 30 +++++++++++++++---------------
selfdrive/car/tests/test_docs.py | 3 ++-
3 files changed, 29 insertions(+), 29 deletions(-)
diff --git a/docs/CARS.md b/docs/CARS.md
index 510500dab..9df3b803d 100644
--- a/docs/CARS.md
+++ b/docs/CARS.md
@@ -4,7 +4,7 @@
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.
-# 205 Supported Cars
+# 204 Supported Cars
|Make|Model|Supported Package|ACC|No ACC accel below|No ALC below|Steering Torque|Resume from stop|Harness|
|---|---|---|:---:|:---:|:---:|:---:|:---:|:---:|
@@ -82,22 +82,21 @@ A supported vehicle is one that just works when you install a comma three. All s
|Hyundai|Veloster 2019-20|Smart Cruise Control (SCC)|Stock|5 mph|0 mph|[](##)|[](##)|Hyundai E|
|Jeep|Grand Cherokee 2016-18|Adaptive Cruise Control (ACC)|Stock|0 mph|9 mph|[](##)|[](##)|FCA|
|Jeep|Grand Cherokee 2019-21|Adaptive Cruise Control (ACC)|Stock|0 mph|39 mph|[](##)|[](##)|FCA|
-|Kia|Ceed 2019|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai E|
+|Kia|Ceed 2019|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai E|
|Kia|EV6 2022|Highway Driving Assist II|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai P|
-|Kia|Forte 2018|Smart Cruise Control (SCC) & LKAS|openpilot|0 mph|0 mph|[](##)|[](##)|Hyundai B|
-|Kia|Forte 2019-21|Smart Cruise Control (SCC) & LKAS|openpilot|0 mph|0 mph|[](##)|[](##)|Hyundai G|
+|Kia|Forte 2019-21|Smart Cruise Control (SCC)|openpilot|0 mph|0 mph|[](##)|[](##)|Hyundai G|
|Kia|K5 2021-22|Smart Cruise Control (SCC)|openpilot|0 mph|0 mph|[](##)|[](##)|Hyundai A|
-|Kia|Niro Electric 2019|All|openpilot|0 mph|0 mph|[](##)|[](##)|Hyundai H|
-|Kia|Niro Electric 2020|All|openpilot|0 mph|0 mph|[](##)|[](##)|Hyundai F|
-|Kia|Niro Electric 2021|All|openpilot|0 mph|0 mph|[](##)|[](##)|Hyundai C|
-|Kia|Niro Electric 2022|All|openpilot|0 mph|0 mph|[](##)|[](##)|Hyundai H|
+|Kia|Niro EV 2019|All|openpilot|0 mph|0 mph|[](##)|[](##)|Hyundai H|
+|Kia|Niro EV 2020|All|openpilot|0 mph|0 mph|[](##)|[](##)|Hyundai F|
+|Kia|Niro EV 2021|All|openpilot|0 mph|0 mph|[](##)|[](##)|Hyundai C|
+|Kia|Niro EV 2022|All|openpilot|0 mph|0 mph|[](##)|[](##)|Hyundai H|
|Kia|Niro Hybrid 2021|Smart Cruise Control (SCC) & LKAS|openpilot|0 mph|0 mph|[](##)|[](##)|Hyundai F|
|Kia|Niro Hybrid 2022|Smart Cruise Control (SCC) & LKAS|openpilot|0 mph|0 mph|[](##)|[](##)|Hyundai H|
-|Kia|Niro Plug-in Hybrid 2018-19|Smart Cruise Control (SCC) & LKAS|openpilot|10 mph|32 mph|[](##)|[](##)|Hyundai C|
-|Kia|Optima 2017|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|32 mph|[](##)|[](##)|Hyundai B|
-|Kia|Optima 2019|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai G|
-|Kia|Seltos 2021|Smart Cruise Control (SCC)|openpilot|0 mph|0 mph|[](##)|[](##)|Hyundai A|
-|Kia|Sorento 2018|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai C|
+|Kia|Niro Plug-in Hybrid 2018-19|All|openpilot|10 mph|32 mph|[](##)|[](##)|Hyundai C|
+|Kia|Optima 2017|Advanced Smart Cruise Control & LDWS|Stock|0 mph|32 mph|[](##)|[](##)|Hyundai B|
+|Kia|Optima 2019|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai G|
+|Kia|Seltos 2021|Smart Cruise Control (SCC) & LKAS|openpilot|0 mph|0 mph|[](##)|[](##)|Hyundai A|
+|Kia|Sorento 2018|Advanced Smart Cruise Control & LDWS|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai C|
|Kia|Sorento 2019|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai E|
|Kia|Stinger 2018-20|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai C|
|Kia|Telluride 2020|All|openpilot|0 mph|0 mph|[](##)|[](##)|Hyundai H|
diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py
index b81661487..3bc206297 100644
--- a/selfdrive/car/hyundai/values.py
+++ b/selfdrive/car/hyundai/values.py
@@ -143,34 +143,34 @@ CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = {
CAR.TUCSON_HYBRID_4TH_GEN: HyundaiCarInfo("Hyundai Tucson Hybrid 2022", "All", harness=Harness.hyundai_n),
# Kia
- CAR.KIA_FORTE: [
- HyundaiCarInfo("Kia Forte 2018", harness=Harness.hyundai_b),
- HyundaiCarInfo("Kia Forte 2019-21", harness=Harness.hyundai_g),
- ],
+ CAR.KIA_FORTE: HyundaiCarInfo("Kia Forte 2019-21", "Smart Cruise Control (SCC)", harness=Harness.hyundai_g),
CAR.KIA_K5_2021: HyundaiCarInfo("Kia K5 2021-22", "Smart Cruise Control (SCC)", harness=Harness.hyundai_a),
CAR.KIA_NIRO_EV: [
- HyundaiCarInfo("Kia Niro Electric 2019", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", harness=Harness.hyundai_h),
- HyundaiCarInfo("Kia Niro Electric 2020", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", harness=Harness.hyundai_f),
- HyundaiCarInfo("Kia Niro Electric 2021", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", harness=Harness.hyundai_c),
- HyundaiCarInfo("Kia Niro Electric 2022", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", harness=Harness.hyundai_h),
+ HyundaiCarInfo("Kia Niro EV 2019", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", harness=Harness.hyundai_h),
+ HyundaiCarInfo("Kia Niro EV 2020", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", harness=Harness.hyundai_f),
+ HyundaiCarInfo("Kia Niro EV 2021", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", harness=Harness.hyundai_c),
+ HyundaiCarInfo("Kia Niro EV 2022", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", harness=Harness.hyundai_h),
],
- CAR.KIA_NIRO_PHEV: HyundaiCarInfo("Kia Niro Plug-in Hybrid 2018-19", min_enable_speed=10. * CV.MPH_TO_MS, harness=Harness.hyundai_c),
+ CAR.KIA_NIRO_PHEV: HyundaiCarInfo("Kia Niro Plug-in Hybrid 2018-19", "All", min_enable_speed=10. * CV.MPH_TO_MS, harness=Harness.hyundai_c),
CAR.KIA_NIRO_HEV_2021: [
HyundaiCarInfo("Kia Niro Hybrid 2021", harness=Harness.hyundai_f), # TODO: could be hyundai_d, verify
HyundaiCarInfo("Kia Niro Hybrid 2022", harness=Harness.hyundai_h),
],
CAR.KIA_OPTIMA: [
- HyundaiCarInfo("Kia Optima 2017", min_steer_speed=32. * CV.MPH_TO_MS, harness=Harness.hyundai_b),
- HyundaiCarInfo("Kia Optima 2019", harness=Harness.hyundai_g),
+ HyundaiCarInfo("Kia Optima 2017", "Advanced Smart Cruise Control & LDWS", min_steer_speed=32. * CV.MPH_TO_MS, harness=Harness.hyundai_b),
+ HyundaiCarInfo("Kia Optima 2019", "Smart Cruise Control (SCC)", harness=Harness.hyundai_g),
+ ],
+ CAR.KIA_OPTIMA_H: [
+ HyundaiCarInfo("Kia Optima Hybrid 2017", "Advanced Smart Cruise Control & LDWS"), # TODO: info may be incorrect
+ HyundaiCarInfo("Kia Optima Hybrid 2019"),
],
- CAR.KIA_OPTIMA_H: HyundaiCarInfo("Kia Optima Hybrid 2017, 2019"), # TODO: info may be incorrect
- CAR.KIA_SELTOS: HyundaiCarInfo("Kia Seltos 2021", "Smart Cruise Control (SCC)", harness=Harness.hyundai_a),
+ CAR.KIA_SELTOS: HyundaiCarInfo("Kia Seltos 2021", harness=Harness.hyundai_a),
CAR.KIA_SORENTO: [
- HyundaiCarInfo("Kia Sorento 2018", video_link="https://www.youtube.com/watch?v=Fkh3s6WHJz8", harness=Harness.hyundai_c),
+ HyundaiCarInfo("Kia Sorento 2018", "Advanced Smart Cruise Control & LDWS", video_link="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_STINGER: HyundaiCarInfo("Kia Stinger 2018-20", video_link="https://www.youtube.com/watch?v=MJ94qoofYw0", harness=Harness.hyundai_c),
- CAR.KIA_CEED: HyundaiCarInfo("Kia Ceed 2019", harness=Harness.hyundai_e),
+ CAR.KIA_CEED: HyundaiCarInfo("Kia Ceed 2019", "Smart Cruise Control (SCC)", harness=Harness.hyundai_e),
CAR.KIA_EV6: HyundaiCarInfo("Kia EV6 2022", "Highway Driving Assist II", harness=Harness.hyundai_p),
# Genesis
diff --git a/selfdrive/car/tests/test_docs.py b/selfdrive/car/tests/test_docs.py
index af58bb5e5..191b36b8f 100755
--- a/selfdrive/car/tests/test_docs.py
+++ b/selfdrive/car/tests/test_docs.py
@@ -34,9 +34,10 @@ class TestCarDocs(unittest.TestCase):
if car.car_name == "hyundai":
self.assertNotIn("phev", tokens, "Use `Plug-in Hybrid`")
self.assertNotIn("hev", tokens, "Use `Hybrid`")
- self.assertNotIn("ev", tokens, "Use `Electric`")
if "plug-in hybrid" in car.model.lower():
self.assertIn("Plug-in Hybrid", car.model, "Use correct capitalization")
+ if car.make != "Kia":
+ self.assertNotIn("ev", tokens, "Use `Electric`")
elif car.car_name == "toyota":
if "rav4" in tokens:
self.assertIn("RAV4", car.model, "Use correct capitalization")
From 35f624c628c0e8f2e936ba945bdc516a8d17517e Mon Sep 17 00:00:00 2001
From: Shane Smiskol
Date: Sat, 17 Sep 2022 15:51:49 -0700
Subject: [PATCH 31/75] translations: remove locations (#25826)
* Remove locations
* no line nos
---
selfdrive/ui/tests/test_translations.py | 12 +-
selfdrive/ui/translations/main_en.ts | 4 -
selfdrive/ui/translations/main_ja.ts | 248 -----------------------
selfdrive/ui/translations/main_ko.ts | 248 -----------------------
selfdrive/ui/translations/main_pt-BR.ts | 248 -----------------------
selfdrive/ui/translations/main_zh-CHS.ts | 248 -----------------------
selfdrive/ui/translations/main_zh-CHT.ts | 248 -----------------------
selfdrive/ui/update_translations.py | 2 +-
8 files changed, 9 insertions(+), 1249 deletions(-)
diff --git a/selfdrive/ui/tests/test_translations.py b/selfdrive/ui/tests/test_translations.py
index d8609f110..11ecd30ae 100755
--- a/selfdrive/ui/tests/test_translations.py
+++ b/selfdrive/ui/tests/test_translations.py
@@ -29,10 +29,7 @@ class TestTranslations(unittest.TestCase):
def _read_translation_file(path, file):
tr_file = os.path.join(path, f"{file}.ts")
with open(tr_file, "r") as f:
- # ignore locations when checking if translations are updated
- lines = [line for line in f.read().splitlines() if
- not line.strip().startswith(LOCATION_TAG)]
- return "\n".join(lines)
+ return f.read()
def test_missing_translation_files(self):
for name, file in self.translation_files.items():
@@ -93,6 +90,13 @@ class TestTranslations(unittest.TestCase):
self.assertTrue(all([re.search("%[0-9]+", t) is None for t in numerusform]),
"Plural translations must use %n, not %1, %2, etc.: {}".format(numerusform))
+ def test_no_locations(self):
+ for name, file in self.translation_files.items():
+ with self.subTest(name=name, file=file):
+ for line in self._read_translation_file(TRANSLATIONS_DIR, file).splitlines():
+ self.assertFalse(line.strip().startswith(LOCATION_TAG),
+ f"Line contains location tag: {line.strip()}, remove all line numbers.")
+
if __name__ == "__main__":
unittest.main()
diff --git a/selfdrive/ui/translations/main_en.ts b/selfdrive/ui/translations/main_en.ts
index 42e30a59a..3f9692e5f 100644
--- a/selfdrive/ui/translations/main_en.ts
+++ b/selfdrive/ui/translations/main_en.ts
@@ -4,7 +4,6 @@
InputDialog
-
Need at least %n character(s)!
Need at least %n character!
@@ -15,7 +14,6 @@
QObject
-
%n minute(s) ago
%n minute ago
@@ -23,7 +21,6 @@
-
%n hour(s) ago
%n hour ago
@@ -31,7 +28,6 @@
-
%n day(s) ago
%n day ago
diff --git a/selfdrive/ui/translations/main_ja.ts b/selfdrive/ui/translations/main_ja.ts
index b41e1bff7..543893d44 100644
--- a/selfdrive/ui/translations/main_ja.ts
+++ b/selfdrive/ui/translations/main_ja.ts
@@ -4,17 +4,14 @@
AbstractAlert
-
Close
閉じる
-
Snooze Update
更新の一時停止
-
Reboot and Update
再起動してアップデート
@@ -22,53 +19,42 @@
AdvancedNetworking
-
Back
戻る
-
Enable Tethering
テザリングを有効化
-
Tethering Password
テザリングパスワード
-
-
EDIT
編集
-
Enter new tethering password
新しいテザリングパスワードを入力
-
IP Address
IP アドレス
-
Enable Roaming
ローミングを有効化
-
APN Setting
APN 設定
-
Enter APN
APN を入力
-
leave blank for automatic configuration
空白のままにして、自動設定にします
@@ -76,13 +62,10 @@
ConfirmationDialog
-
-
Ok
OK
-
Cancel
キャンセル
@@ -90,17 +73,14 @@
DeclinePage
-
You must accept the Terms and Conditions in order to use openpilot.
openpilot をご利用される前に、利用規約に同意する必要があります。
-
Back
戻る
-
Decline, uninstall %1
拒否して %1 をアンインストール
@@ -108,152 +88,122 @@
DevicePanel
-
Dongle ID
ドングル番号 (Dongle ID)
-
N/A
N/A
-
Serial
シリアル番号
-
Driver Camera
車内カメラ
-
PREVIEW
見る
-
Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off)
車内カメラをプレビューして、ドライバー監視システムの視界を確認ができます。(車両の電源を切る必要があります)
-
Reset Calibration
キャリブレーションをリセット
-
RESET
リセット
-
Are you sure you want to reset calibration?
キャリブレーションをリセットしてもよろしいですか?
-
Review Training Guide
入門書を見る
-
REVIEW
見る
-
Review the rules, features, and limitations of openpilot
openpilot の特徴を見る
-
Are you sure you want to review the training guide?
入門書を見てもよろしいですか?
-
Regulatory
認証情報
-
VIEW
見る
-
Change Language
言語を変更
-
CHANGE
変更
-
Select a language
言語を選択
-
Reboot
再起動
-
Power Off
電源を切る
-
openpilot requires the device to be mounted within 4° left or right and within 5° up or 8° down. openpilot is continuously calibrating, resetting is rarely required.
openpilot は、左または右の4°以内、上の5°または下の8°以内にデバイスを取付ける必要があります。キャリブレーションを引き続きます、リセットはほとんど必要ありません。
-
Your device is pointed %1° %2 and %3° %4.
このデバイスは%2の%1°、%4の%3°に向けます。
-
down
下
-
up
上
-
left
左
-
right
右
-
Are you sure you want to reboot?
再起動してもよろしいですか?
-
Disengage to Reboot
openpilot をキャンセルして再起動ができます
-
Are you sure you want to power off?
シャットダウンしてもよろしいですか?
-
Disengage to Power Off
openpilot をキャンセルしてシャットダウンができます
@@ -261,32 +211,26 @@
DriveStats
-
Drives
運転履歴
-
Hours
時間
-
ALL TIME
累計
-
PAST WEEK
先週
-
KM
km
-
Miles
マイル
@@ -294,7 +238,6 @@
DriverViewScene
-
camera starting
カメラを起動しています
@@ -302,12 +245,10 @@
InputDialog
-
Cancel
キャンセル
-
Need at least %n character(s)!
%n文字以上でお願いします!
@@ -317,22 +258,18 @@
Installer
-
Installing...
インストールしています...
-
Receiving objects:
オブジェクトをダウンロードしています:
-
Resolving deltas:
デルタを解決しています:
-
Updating files:
ファイルを更新しています:
@@ -340,27 +277,22 @@
MapETA
-
eta
予定到着時間
-
min
分
-
hr
時間
-
km
キロメートル
-
mi
マイル
@@ -368,22 +300,18 @@
MapInstructions
-
km
キロメートル
-
m
メートル
-
mi
マイル
-
ft
フィート
@@ -391,48 +319,40 @@
MapPanel
-
Current Destination
現在の目的地
-
CLEAR
削除
-
Recent Destinations
最近の目的地
-
Try the Navigation Beta
β版ナビゲーションを試す
-
Get turn-by-turn directions displayed and more with a comma
prime subscription. Sign up now: https://connect.comma.ai
より詳細な案内情報を得ることができます。
詳しくはこちら:https://connect.comma.ai
-
No home
location set
自宅の住所はまだ
設定されていません
-
No work
location set
職場の住所はまだ
設定されていません
-
no recent destinations
最近の目的地履歴がありません
@@ -440,12 +360,10 @@ location set
MapWindow
-
Map Loading
マップを読み込んでいます
-
Waiting for GPS
GPS信号を探しています
@@ -453,12 +371,10 @@ location set
MultiOptionDialog
-
Select
選択
-
Cancel
キャンセル
@@ -466,23 +382,18 @@ location set
Networking
-
Advanced
詳細
-
Enter password
パスワードを入力
-
-
for "%1"
ネットワーク名:%1
-
Wrong password
パスワードが間違っています
@@ -490,30 +401,22 @@ location set
NvgWindow
-
km/h
km/h
-
mph
mph
-
-
MAX
最高速度
-
-
SPEED
速度
-
-
LIMIT
制限速度
@@ -521,17 +424,14 @@ location set
OffroadHome
-
UPDATE
更新
-
ALERTS
警告
-
ALERT
警告
@@ -539,22 +439,18 @@ location set
PairingPopup
-
Pair your device to your comma account
デバイスと comma アカウントを連携する
-
Go to https://connect.comma.ai on your phone
モバイルデバイスで「connect.comma.ai」にアクセスして
-
Click "add new device" and scan the QR code on the right
「新しいデバイスを追加」を押すと、右側のQRコードをスキャンしてください
-
Bookmark connect.comma.ai to your home screen to use it like an app
「connect.comma.ai」をホーム画面に追加して、アプリのように使うことができます
@@ -562,32 +458,26 @@ location set
PrimeAdWidget
-
Upgrade Now
今すぐアップグレート
-
Become a comma prime member at connect.comma.ai
connect.comma.ai でプライム会員に登録できます
-
PRIME FEATURES:
特典:
-
Remote access
リモートアクセス
-
1 year of storage
一年間の保存期間
-
Developer perks
開発者向け特典
@@ -595,22 +485,18 @@ location set
PrimeUserWidget
-
✓ SUBSCRIBED
✓ 入会しました
-
comma prime
comma prime
-
CONNECT.COMMA.AI
CONNECT.COMMA.AI
-
COMMA POINTS
COMMA POINTS
@@ -618,41 +504,34 @@ location set
QObject
-
Reboot
再起動
-
Exit
閉じる
-
dashcam
ドライブレコーダー
-
openpilot
openpilot
-
%n minute(s) ago
%n 分前
-
%n hour(s) ago
%n 時間前
-
%n day(s) ago
%n 日前
@@ -662,47 +541,38 @@ location set
Reset
-
Reset failed. Reboot to try again.
初期化に失敗しました。再起動後に再試行してください。
-
Are you sure you want to reset your device?
初期化してもよろしいですか?
-
Resetting device...
デバイスが初期化されます...
-
System Reset
システムを初期化
-
System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot.
システムの初期化をリクエストしました。「確認」ボタンを押すとデバイスが初期化されます。「キャンセル」ボタンを押すと起動を続行します。
-
Cancel
キャンセル
-
Reboot
再起動
-
Confirm
確認
-
Unable to mount data partition. Press confirm to reset your device.
「data」パーティションをマウントできません。「確認」ボタンを押すとデバイスが初期化されます。
@@ -710,7 +580,6 @@ location set
RichTextDialog
-
Ok
OK
@@ -718,33 +587,26 @@ location set
SettingsWindow
-
×
×
-
Device
デバイス
-
-
Network
ネットワーク
-
Toggles
切り替え
-
Software
ソフトウェア
-
Navigation
ナビゲーション
@@ -752,105 +614,82 @@ location set
Setup
-
WARNING: Low Voltage
警告:低電圧
-
Power your device in a car with a harness or proceed at your own risk.
自己責任でハーネスから電源を供給してください。
-
Power off
電源を切る
-
-
-
Continue
続ける
-
Getting Started
はじめに
-
Before we get on the road, let’s finish installation and cover some details.
その前に、インストールを完了し、いくつかの詳細を説明します。
-
Connect to Wi-Fi
Wi-Fi に接続
-
-
Back
戻る
-
Continue without Wi-Fi
Wi-Fi に未接続で続行
-
Waiting for internet
インターネット接続を待機中
-
Choose Software to Install
インストールするソフトウェアを選びます
-
Dashcam
ドライブレコーダー
-
Custom Software
カスタムソフトウェア
-
Enter URL
URL を入力
-
for Custom Software
カスタムソフトウェア
-
Downloading...
ダウンロード中...
-
Download Failed
ダウンロード失敗
-
Ensure the entered URL is valid, and the device’s internet connection is good.
入力された URL を確認し、デバイスがインターネットに接続されていることを確認してください。
-
Reboot device
デバイスを再起動
-
Start over
最初からやり直す
@@ -858,17 +697,14 @@ location set
SetupWidget
-
Finish Setup
セットアップ完了
-
Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer.
デバイスを comma connect (connect.comma.ai)でペアリングし comma prime 特典を申請してください。
-
Pair device
デバイスをペアリング
@@ -876,106 +712,82 @@ location set
Sidebar
-
-
CONNECT
接続
-
OFFLINE
オフライン
-
-
ONLINE
オンライン
-
ERROR
エラー
-
-
-
TEMP
温度
-
HIGH
高温
-
GOOD
最適
-
OK
OK
-
VEHICLE
車両
-
NO
NO
-
PANDA
PANDA
-
GPS
GPS
-
SEARCH
検索
-
--
--
-
Wi-Fi
Wi-Fi
-
ETH
ETH
-
2G
2G
-
3G
3G
-
LTE
LTE
-
5G
5G
@@ -983,63 +795,50 @@ location set
SoftwarePanel
-
Updates are only downloaded while the car is off.
車の電源がオフの間のみ、アップデートのダウンロードが行われます。
-
Current Version
現在のバージョン
-
Download
ダウンロード
-
Install Update
アップデート
-
INSTALL
インストール
-
Target Branch
対象のブランチ
-
SELECT
選択
-
Select a branch
ブランチを選択
-
UNINSTALL
アンインストール
-
Uninstall %1
%1をアンインストール
-
Are you sure you want to uninstall?
アンインストールしてもよろしいですか?
-
-
CHECK
確認
@@ -1047,48 +846,38 @@ location set
SshControl
-
SSH Keys
SSH 鍵
-
Warning: This grants SSH access to all public keys in your GitHub settings. Never enter a GitHub username other than your own. A comma employee will NEVER ask you to add their GitHub username.
警告: これは、GitHub の設定にあるすべての公開鍵への SSH アクセスを許可するものです。自分以外の GitHub のユーザー名を入力しないでください。コンマのスタッフが GitHub のユーザー名を追加するようお願いすることはありません。
-
-
ADD
追加
-
Enter your GitHub username
GitHub のユーザー名を入力してください
-
LOADING
ローディング
-
REMOVE
削除
-
Username '%1' has no keys on GitHub
ユーザー名 “%1” は GitHub に鍵がありません
-
Request timed out
リクエストタイムアウト
-
Username '%1' doesn't exist on GitHub
ユーザー名 '%1' は GitHub に存在しません
@@ -1096,7 +885,6 @@ location set
SshToggle
-
Enable SSH
SSH を有効化
@@ -1104,22 +892,18 @@ location set
TermsPage
-
Terms & Conditions
利用規約
-
Decline
拒否
-
Scroll to accept
スクロールして同意
-
Agree
同意
@@ -1127,102 +911,82 @@ location set
TogglesPanel
-
Enable openpilot
openpilot を有効化
-
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.
アダプティブクルーズコントロールとレーンキーピングドライバーアシスト(openpilotシステム)。この機能を使用するには、常に注意が必要です。この設定を変更すると、車の電源が切れたときに有効になります。
-
Enable Lane Departure Warnings
車線逸脱警報機能を有効化
-
Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31 mph (50 km/h).
時速31マイル(50km)を超えるスピードで走行中、ウインカーを作動させずに検出された車線ライン上に車両が触れた場合、車線に戻るアラートを受信します。
-
Use Metric System
メートル法を有効化
-
Display speed in km/h instead of mph.
速度は mph ではなく km/h で表示されます。
-
Record and Upload Driver Camera
車内カメラの録画とアップロード
-
Upload data from the driver facing camera and help improve the driver monitoring algorithm.
車内カメラの映像をアップロードし、ドライバー監視システムのアルゴリズムの向上に役立てます。
-
🌮 End-to-end longitudinal (extremely alpha) 🌮
🌮 エンドツーエンドのアクセル制御 (超アルファ版) 🌮
-
Experimental openpilot longitudinal control
実験段階のopenpilotによるアクセル制御
-
<b>WARNING: openpilot longitudinal control is experimental for this car and will disable AEB.</b>
<b>警告: openpilotによるアクセル制御は実験段階であり、AEBを無効化します。</b>
-
Let the driving model control the gas and brakes. openpilot will drive as it thinks a human would. Super experimental.
アクセルとブレーキの制御をopenpilotに任せます。openpilotが人間と同じように運転します。最初期の実験段階です。
-
openpilot longitudinal control is not currently available for this car.
openpilotによるアクセル制御は、この車では現在利用できません。
-
Enable experimental longitudinal control to enable this.
ここ機能を使う為には、「実験段階のopenpilotによるアクセル制御」を先に有効化してください。
-
Disengage On Accelerator Pedal
アクセル踏むと openpilot をキャンセル
-
When enabled, pressing the accelerator pedal will disengage openpilot.
有効な場合は、アクセルを踏むと openpilot をキャンセルします。
-
Show ETA in 24h Format
24時間表示
-
Use 24h format instead of am/pm
AM/PM の代わりに24時間形式を使用します
-
Show Map on Left Side of UI
ディスプレイの左側にマップを表示
-
Show map on left side when in split screen view.
分割画面表示の場合、ディスプレイの左側にマップを表示します。
@@ -1230,42 +994,34 @@ location set
Updater
-
Update Required
更新が必要です
-
An operating system update is required. Connect your device to Wi-Fi for the fastest update experience. The download size is approximately 1GB.
オペレーティングシステムのアップデートが必要です。Wi-Fi に接続することで、最速のアップデートを体験できます。ダウンロードサイズは約 1GB です。
-
Connect to Wi-Fi
Wi-Fi に接続
-
Install
インストール
-
Back
戻る
-
Loading...
読み込み中...
-
Reboot
再起動
-
Update failed
更新失敗
@@ -1273,22 +1029,18 @@ location set
WifiUI
-
Scanning for networks...
ネットワークをスキャン中...
-
CONNECTING...
接続中...
-
FORGET
削除
-
Forget Wi-Fi Network "%1"?
Wi-Fiネットワーク%1を削除してもよろしいですか?
diff --git a/selfdrive/ui/translations/main_ko.ts b/selfdrive/ui/translations/main_ko.ts
index 17914f21d..2a806aaed 100644
--- a/selfdrive/ui/translations/main_ko.ts
+++ b/selfdrive/ui/translations/main_ko.ts
@@ -4,17 +4,14 @@
AbstractAlert
-
Close
닫기
-
Snooze Update
업데이트 일시중지
-
Reboot and Update
업데이트 및 재부팅
@@ -22,53 +19,42 @@
AdvancedNetworking
-
Back
뒤로
-
Enable Tethering
테더링 사용
-
Tethering Password
테더링 비밀번호
-
-
EDIT
편집
-
Enter new tethering password
새 테더링 비밀번호를 입력하세요
-
IP Address
IP 주소
-
Enable Roaming
로밍 사용
-
APN Setting
APN 설정
-
Enter APN
APN 입력
-
leave blank for automatic configuration
자동설정하려면 공백으로 두세요
@@ -76,13 +62,10 @@
ConfirmationDialog
-
-
Ok
확인
-
Cancel
취소
@@ -90,17 +73,14 @@
DeclinePage
-
You must accept the Terms and Conditions in order to use openpilot.
openpilot을 사용하려면 이용약관에 동의해야 합니다.
-
Back
뒤로
-
Decline, uninstall %1
거절, %1 제거
@@ -108,152 +88,122 @@
DevicePanel
-
Dongle ID
Dongle ID
-
N/A
N/A
-
Serial
Serial
-
Driver Camera
운전자 카메라
-
PREVIEW
미리보기
-
Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off)
운전자 모니터링이 좋은 가시성을 갖도록 운전자를 향한 카메라를 미리 봅니다. (차량연결은 해제되어있어야 합니다)
-
Reset Calibration
캘리브레이션
-
RESET
재설정
-
Are you sure you want to reset calibration?
캘리브레이션을 재설정하시겠습니까?
-
Review Training Guide
트레이닝 가이드
-
REVIEW
다시보기
-
Review the rules, features, and limitations of openpilot
openpilot의 규칙, 기능 및 제한 다시보기
-
Are you sure you want to review the training guide?
트레이닝 가이드를 다시보시겠습니까?
-
Regulatory
규제
-
VIEW
보기
-
Change Language
언어 변경
-
CHANGE
변경
-
Select a language
언어를 선택하세요
-
Reboot
재부팅
-
Power Off
전원 종료
-
openpilot requires the device to be mounted within 4° left or right and within 5° up or 8° down. openpilot is continuously calibrating, resetting is rarely required.
openpilot은 좌우측은 4° 이내, 위쪽은 5° 아래쪽은 8° 이내로 장치를 설치해야 합니다. openpilot은 지속적으로 보정되므로 리셋은 거의 필요하지 않습니다.
-
Your device is pointed %1° %2 and %3° %4.
사용자의 장치가 %1° %2 및 %3° %4 위치에 설치되어있습니다.
-
down
아래로
-
up
위로
-
left
좌측으로
-
right
우측으로
-
Are you sure you want to reboot?
재부팅 하시겠습니까?
-
Disengage to Reboot
재부팅 하려면 해제하세요
-
Are you sure you want to power off?
전원을 종료하시겠습니까?
-
Disengage to Power Off
전원을 종료하려면 해제하세요
@@ -261,32 +211,26 @@
DriveStats
-
Drives
주행
-
Hours
시간
-
ALL TIME
전체
-
PAST WEEK
지난주
-
KM
Km
-
Miles
Miles
@@ -294,7 +238,6 @@
DriverViewScene
-
camera starting
카메라 시작중
@@ -302,12 +245,10 @@
InputDialog
-
Cancel
취소
-
Need at least %n character(s)!
최소 %n 자가 필요합니다!
@@ -317,22 +258,18 @@
Installer
-
Installing...
설치중...
-
Receiving objects:
수신중:
-
Resolving deltas:
델타병합:
-
Updating files:
파일갱신:
@@ -340,27 +277,22 @@
MapETA
-
eta
도착
-
min
분
-
hr
시간
-
km
km
-
mi
mi
@@ -368,22 +300,18 @@
MapInstructions
-
km
km
-
m
m
-
mi
mi
-
ft
ft
@@ -391,48 +319,40 @@
MapPanel
-
Current Destination
현재 목적지
-
CLEAR
삭제
-
Recent Destinations
최근 목적지
-
Try the Navigation Beta
네비게이션(베타)를 사용해보세요
-
Get turn-by-turn directions displayed and more with a comma
prime subscription. Sign up now: https://connect.comma.ai
자세한 경로안내를 원하시면 comma prime을 구독하세요.
등록:https://connect.comma.ai
-
No home
location set
집
설정되지않음
-
No work
location set
회사
설정되지않음
-
no recent destinations
최근 목적지 없음
@@ -440,12 +360,10 @@ location set
MapWindow
-
Map Loading
지도 로딩
-
Waiting for GPS
GPS를 기다리는 중
@@ -453,12 +371,10 @@ location set
MultiOptionDialog
-
Select
선택
-
Cancel
취소
@@ -466,23 +382,18 @@ location set
Networking
-
Advanced
고급 설정
-
Enter password
비밀번호를 입력하세요
-
-
for "%1"
"%1"에 접속하려면 인증이 필요합니다
-
Wrong password
비밀번호가 틀렸습니다
@@ -490,30 +401,22 @@ location set
NvgWindow
-
km/h
km/h
-
mph
mph
-
-
MAX
MAX
-
-
SPEED
SPEED
-
-
LIMIT
LIMIT
@@ -521,17 +424,14 @@ location set
OffroadHome
-
UPDATE
업데이트
-
ALERTS
알림
-
ALERT
알림
@@ -539,22 +439,18 @@ location set
PairingPopup
-
Pair your device to your comma account
장치를 콤마 계정과 페어링합니다
-
Go to https://connect.comma.ai on your phone
https://connect.comma.ai에 접속하세요
-
Click "add new device" and scan the QR code on the right
"새 장치 추가"를 클릭하고 오른쪽 QR 코드를 검색합니다
-
Bookmark connect.comma.ai to your home screen to use it like an app
connect.comma.ai을 앱처럼 사용하려면 홈 화면에 바로가기를 만드십시오
@@ -562,32 +458,26 @@ location set
PrimeAdWidget
-
Upgrade Now
지금 업그레이드
-
Become a comma prime member at connect.comma.ai
connect.comma.ai에서 comma prime에 가입합니다
-
PRIME FEATURES:
PRIME 기능:
-
Remote access
원격 접속
-
1 year of storage
1년간 저장
-
Developer perks
개발자 혜택
@@ -595,22 +485,18 @@ location set
PrimeUserWidget
-
✓ SUBSCRIBED
✓ 구독함
-
comma prime
comma prime
-
CONNECT.COMMA.AI
CONNECT.COMMA.AI
-
COMMA POINTS
COMMA POINTS
@@ -618,41 +504,34 @@ location set
QObject
-
Reboot
재부팅
-
Exit
종료
-
dashcam
dashcam
-
openpilot
openpilot
-
%n minute(s) ago
%n 분전
-
%n hour(s) ago
%n 시간전
-
%n day(s) ago
%n 일전
@@ -662,47 +541,38 @@ location set
Reset
-
Reset failed. Reboot to try again.
초기화 실패. 재부팅후 다시 시도하세요.
-
Are you sure you want to reset your device?
장치를 초기화 하시겠습니까?
-
Resetting device...
장치 초기화중...
-
System Reset
장치 초기화
-
System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot.
장치를 초기화 합니다. 확인버튼을 누르면 모든 내용과 설정이 초기화됩니다. 부팅을 재개하려면 취소를 누르세요.
-
Cancel
취소
-
Reboot
재부팅
-
Confirm
확인
-
Unable to mount data partition. Press confirm to reset your device.
데이터 파티션을 마운트할 수 없습니다. 확인 버튼을 눌러 장치를 리셋합니다.
@@ -710,7 +580,6 @@ location set
RichTextDialog
-
Ok
확인
@@ -718,33 +587,26 @@ location set
SettingsWindow
-
×
×
-
Device
장치
-
-
Network
네트워크
-
Toggles
토글
-
Software
소프트웨어
-
Navigation
네비게이션
@@ -752,105 +614,82 @@ location set
Setup
-
WARNING: Low Voltage
경고: 전압이 낮습니다
-
Power your device in a car with a harness or proceed at your own risk.
하네스 보드에 차량의 전원을 연결하세요.
-
Power off
전원 종료
-
-
-
Continue
계속
-
Getting Started
설정 시작
-
Before we get on the road, let’s finish installation and cover some details.
출발하기 전에 설정을 완료하고 몇 가지 세부 사항을 살펴보겠습니다.
-
Connect to Wi-Fi
wifi 연결
-
-
Back
뒤로
-
Continue without Wi-Fi
wifi 연결없이 계속하기
-
Waiting for internet
네트워크 접속을 기다립니다
-
Choose Software to Install
설치할 소프트웨어를 선택하세요
-
Dashcam
Dashcam
-
Custom Software
Custom Software
-
Enter URL
URL 입력
-
for Custom Software
for Custom Software
-
Downloading...
다운로드중...
-
Download Failed
다운로드 실패
-
Ensure the entered URL is valid, and the device’s internet connection is good.
입력된 URL이 유효하고 장치의 네트워크 연결이 잘 되어 있는지 확인하세요.
-
Reboot device
재부팅
-
Start over
다시 시작
@@ -858,17 +697,14 @@ location set
SetupWidget
-
Finish Setup
설정 완료
-
Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer.
장치를 (connect.comma.ai)에서 페어링하고 comma prime 오퍼를 청구합니다.
-
Pair device
장치 페어링
@@ -876,106 +712,82 @@ location set
Sidebar
-
-
CONNECT
연결
-
OFFLINE
오프라인
-
-
ONLINE
온라인
-
ERROR
오류
-
-
-
TEMP
온도
-
HIGH
높음
-
GOOD
좋음
-
OK
경고
-
VEHICLE
차량
-
NO
NO
-
PANDA
PANDA
-
GPS
GPS
-
SEARCH
검색중
-
--
--
-
Wi-Fi
Wi-Fi
-
ETH
이더넷
-
2G
2G
-
3G
3G
-
LTE
LTE
-
5G
5G
@@ -983,63 +795,50 @@ location set
SoftwarePanel
-
Updates are only downloaded while the car is off.
업데이트는 차량 연결이 해제되어 있는 동안에만 다운로드됩니다.
-
Current Version
현재 버전
-
Download
다운로드
-
Install Update
업데이트 설치
-
INSTALL
설치
-
Target Branch
대상 브랜치
-
SELECT
선택
-
Select a branch
브랜치 선택
-
UNINSTALL
제거
-
Uninstall %1
%1 제거
-
Are you sure you want to uninstall?
제거하시겠습니까?
-
-
CHECK
확인
@@ -1047,48 +846,38 @@ location set
SshControl
-
SSH Keys
SSH 키
-
Warning: This grants SSH access to all public keys in your GitHub settings. Never enter a GitHub username other than your own. A comma employee will NEVER ask you to add their GitHub username.
경고: 허용으로 설정하면 GitHub 설정의 모든 공용 키에 대한 SSH 액세스 권한이 부여됩니다. GitHub 사용자 ID 이외에는 입력하지 마십시오. comma에서는 GitHub ID를 추가하라는 요청을 하지 않습니다.
-
-
ADD
추가
-
Enter your GitHub username
GitHub 사용자 ID
-
LOADING
로딩
-
REMOVE
제거
-
Username '%1' has no keys on GitHub
'%1'의 키가 GitHub에 없습니다
-
Request timed out
요청 시간 초과
-
Username '%1' doesn't exist on GitHub
'%1'은 GitHub에 없습니다
@@ -1096,7 +885,6 @@ location set
SshToggle
-
Enable SSH
SSH 사용
@@ -1104,22 +892,18 @@ location set
TermsPage
-
Terms & Conditions
약관
-
Decline
거절
-
Scroll to accept
허용하려면 아래로 스크롤하세요
-
Agree
동의
@@ -1127,102 +911,82 @@ location set
TogglesPanel
-
Enable openpilot
openpilot 사용
-
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.
어댑티브 크루즈 컨트롤 및 차선 유지 운전자 보조를 위해 openpilot 시스템을 사용하십시오. 이 기능을 사용하려면 항상 주의를 기울여야 합니다. 설정변경은 장치 재부팅후 적용됩니다.
-
Enable Lane Departure Warnings
차선 이탈 경고 사용
-
Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31 mph (50 km/h).
차량이 50km/h(31mph) 이상의 속도로 주행하는 동안 방향지시등 없이 감지된 차선 위를 주행할 경우 차선이탈 경고를 표시합니다.
-
Use Metric System
미터법 사용
-
Display speed in km/h instead of mph.
mph 대신 km/h로 속도를 표시합니다.
-
Record and Upload Driver Camera
운전자 카메라 녹화 및 업로드
-
Upload data from the driver facing camera and help improve the driver monitoring algorithm.
운전자 카메라에서 데이터를 업로드하고 운전자 모니터링 알고리즘을 개선합니다.
-
🌮 End-to-end longitudinal (extremely alpha) 🌮
🌮 e2e 롱컨트롤 사용 (매우 실험적) 🌮
-
Experimental openpilot longitudinal control
openpilot 롱컨트롤 (실험적)
-
<b>WARNING: openpilot longitudinal control is experimental for this car and will disable AEB.</b>
<b>경고: openpilot 롱컨트롤은 실험적인 기능으로 차량의 AEB를 비활성화합니다.</b>
-
Let the driving model control the gas and brakes. openpilot will drive as it thinks a human would. Super experimental.
주행모델이 가속과 감속을 제어하도록 하면 openpilot은 운전자가 생각하는것처럼 운전합니다. (매우 실험적)
-
openpilot longitudinal control is not currently available for this car.
-
Enable experimental longitudinal control to enable this.
-
Disengage On Accelerator Pedal
가속페달 조작시 해제
-
When enabled, pressing the accelerator pedal will disengage openpilot.
활성화된 경우 가속 페달을 누르면 openpilot이 해제됩니다.
-
Show ETA in 24h Format
24시간 형식으로 도착예정시간 표시
-
Use 24h format instead of am/pm
오전/오후 대신 24시간 형식 사용
-
Show Map on Left Side of UI
UI 왼쪽에 지도 표시
-
Show map on left side when in split screen view.
분할 화면 보기에서 지도를 왼쪽에 표시합니다.
@@ -1230,42 +994,34 @@ location set
Updater
-
Update Required
업데이트 필요
-
An operating system update is required. Connect your device to Wi-Fi for the fastest update experience. The download size is approximately 1GB.
OS 업데이트가 필요합니다. 장치를 wifi에 연결하면 가장 빠른 업데이트 경험을 제공합니다. 다운로드 크기는 약 1GB입니다.
-
Connect to Wi-Fi
wifi 연결
-
Install
설치
-
Back
뒤로
-
Loading...
로딩중...
-
Reboot
재부팅
-
Update failed
업데이트 실패
@@ -1273,22 +1029,18 @@ location set
WifiUI
-
Scanning for networks...
네트워크 검색 중...
-
CONNECTING...
연결중...
-
FORGET
저장안함
-
Forget Wi-Fi Network "%1"?
wifi 네트워크 저장안함 "%1"?
diff --git a/selfdrive/ui/translations/main_pt-BR.ts b/selfdrive/ui/translations/main_pt-BR.ts
index a490b4088..ff6f27dd4 100644
--- a/selfdrive/ui/translations/main_pt-BR.ts
+++ b/selfdrive/ui/translations/main_pt-BR.ts
@@ -4,17 +4,14 @@
AbstractAlert
-
Close
Fechar
-
Snooze Update
Adiar Atualização
-
Reboot and Update
Reiniciar e Atualizar
@@ -22,53 +19,42 @@
AdvancedNetworking
-
Back
Voltar
-
Enable Tethering
Ativar Tether
-
Tethering Password
Senha Tethering
-
-
EDIT
EDITAR
-
Enter new tethering password
Insira nova senha tethering
-
IP Address
Endereço IP
-
Enable Roaming
Ativar Roaming
-
APN Setting
APN Config
-
Enter APN
Insira APN
-
leave blank for automatic configuration
deixe em branco para configuração automática
@@ -76,13 +62,10 @@
ConfirmationDialog
-
-
Ok
OK
-
Cancel
Cancelar
@@ -90,17 +73,14 @@
DeclinePage
-
You must accept the Terms and Conditions in order to use openpilot.
Você precisa aceitar os Termos e Condições para utilizar openpilot.
-
Back
Voltar
-
Decline, uninstall %1
Rejeitar, desintalar %1
@@ -108,152 +88,122 @@
DevicePanel
-
Dongle ID
Dongle ID
-
N/A
N/A
-
Serial
Serial
-
Driver Camera
Câmera voltada para o Motorista
-
PREVIEW
PREVISUAL
-
Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off)
Pré-visualizar a câmera voltada para o motorista para garantir que monitor tem uma boa visibilidade (veículo precisa estar desligado)
-
Reset Calibration
Resetar Calibragem
-
RESET
RESET
-
Are you sure you want to reset calibration?
Tem certeza que quer resetar a calibragem?
-
Review Training Guide
Revisar Guia de Treinamento
-
REVIEW
REVISAR
-
Review the rules, features, and limitations of openpilot
Revisar regras, aprimoramentos e limitações do openpilot
-
Are you sure you want to review the training guide?
Tem certeza que quer rever o treinamento?
-
Regulatory
Regulatório
-
VIEW
VER
-
Change Language
Alterar Idioma
-
CHANGE
ALTERAR
-
Select a language
Selecione o Idioma
-
Reboot
Reiniciar
-
Power Off
Desligar
-
openpilot requires the device to be mounted within 4° left or right and within 5° up or 8° down. openpilot is continuously calibrating, resetting is rarely required.
o openpilot requer que o dispositivo seja montado dentro de 4° esquerda ou direita e dentro de 5° para cima ou 8° para baixo. o openpilot está continuamente calibrando, resetar raramente é necessário.
-
Your device is pointed %1° %2 and %3° %4.
Seu dispositivo está montado %1° %2 e %3° %4.
-
down
baixo
-
up
cima
-
left
esquerda
-
right
direita
-
Are you sure you want to reboot?
Tem certeza que quer reiniciar?
-
Disengage to Reboot
Desacione para Reiniciar
-
Are you sure you want to power off?
Tem certeza que quer desligar?
-
Disengage to Power Off
Desacione para Desligar
@@ -261,32 +211,26 @@
DriveStats
-
Drives
Dirigidas
-
Hours
Horas
-
ALL TIME
TOTAL
-
PAST WEEK
SEMANA PASSADA
-
KM
KM
-
Miles
Milhas
@@ -294,7 +238,6 @@
DriverViewScene
-
camera starting
câmera iniciando
@@ -302,12 +245,10 @@
InputDialog
-
Cancel
Cancelar
-
Need at least %n character(s)!
Necessita no mínimo %n caractere!
@@ -318,22 +259,18 @@
Installer
-
Installing...
Instalando...
-
Receiving objects:
Recebendo objetos:
-
Resolving deltas:
Resolvendo deltas:
-
Updating files:
Atualizando arquivos:
@@ -341,27 +278,22 @@
MapETA
-
eta
eta
-
min
min
-
hr
hr
-
km
km
-
mi
mi
@@ -369,22 +301,18 @@
MapInstructions
-
km
km
-
m
m
-
mi
milha
-
ft
pés
@@ -392,48 +320,40 @@
MapPanel
-
Current Destination
Destino Atual
-
CLEAR
LIMPAR
-
Recent Destinations
Destinos Recentes
-
Try the Navigation Beta
Experimente a Navegação Beta
-
Get turn-by-turn directions displayed and more with a comma
prime subscription. Sign up now: https://connect.comma.ai
Obtenha instruções passo a passo exibidas e muito mais com
uma assinatura prime Inscreva-se agora: https://connect.comma.ai
-
No home
location set
Sem local
residência definido
-
No work
location set
Sem local de
trabalho definido
-
no recent destinations
sem destinos recentes
@@ -441,12 +361,10 @@ trabalho definido
MapWindow
-
Map Loading
Carregando Mapa
-
Waiting for GPS
Esperando por GPS
@@ -454,12 +372,10 @@ trabalho definido
MultiOptionDialog
-
Select
Selecione
-
Cancel
Cancelar
@@ -467,23 +383,18 @@ trabalho definido
Networking
-
Advanced
Avançado
-
Enter password
Insira a senha
-
-
for "%1"
para "%1"
-
Wrong password
Senha incorreta
@@ -491,30 +402,22 @@ trabalho definido
NvgWindow
-
km/h
km/h
-
mph
mph
-
-
MAX
LIMITE
-
-
SPEED
MAX
-
-
LIMIT
VELO
@@ -522,17 +425,14 @@ trabalho definido
OffroadHome
-
UPDATE
ATUALIZAÇÃO
-
ALERTS
ALERTAS
-
ALERT
ALERTA
@@ -540,22 +440,18 @@ trabalho definido
PairingPopup
-
Pair your device to your comma account
Pareie seu dispositivo à sua conta comma
-
Go to https://connect.comma.ai on your phone
navegue até https://connect.comma.ai no seu telefone
-
Click "add new device" and scan the QR code on the right
Clique "add new device" e escaneie o QR code a seguir
-
Bookmark connect.comma.ai to your home screen to use it like an app
Salve connect.comma.ai como sua página inicial para utilizar como um app
@@ -563,32 +459,26 @@ trabalho definido
PrimeAdWidget
-
Upgrade Now
Atualizar Agora
-
Become a comma prime member at connect.comma.ai
Torne-se um membro comma prime em connect.comma.ai
-
PRIME FEATURES:
APRIMORAMENTOS PRIME:
-
Remote access
Acesso remoto
-
1 year of storage
1 ano de armazenamento
-
Developer perks
Benefícios para desenvolvedor
@@ -596,22 +486,18 @@ trabalho definido
PrimeUserWidget
-
✓ SUBSCRIBED
✓ INSCRITO
-
comma prime
comma prime
-
CONNECT.COMMA.AI
CONNECT.COMMA.AI
-
COMMA POINTS
PONTOS COMMA
@@ -619,27 +505,22 @@ trabalho definido
QObject
-
Reboot
Reiniciar
-
Exit
Sair
-
dashcam
dashcam
-
openpilot
openpilot
-
%n minute(s) ago
há %n minuto
@@ -647,7 +528,6 @@ trabalho definido
-
%n hour(s) ago
há %n hora
@@ -655,7 +535,6 @@ trabalho definido
-
%n day(s) ago
há %n dia
@@ -666,47 +545,38 @@ trabalho definido
Reset
-
Reset failed. Reboot to try again.
Reset falhou. Reinicie para tentar novamente.
-
Are you sure you want to reset your device?
Tem certeza que quer resetar seu dispositivo?
-
Resetting device...
Resetando dispositivo...
-
System Reset
Resetar Sistema
-
System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot.
Solicitado reset do sistema. Confirme para apagar todo conteúdo e configurações. Aperte cancelar para continuar boot.
-
Cancel
Cancelar
-
Reboot
Reiniciar
-
Confirm
Confirmar
-
Unable to mount data partition. Press confirm to reset your device.
Não foi possível montar a partição de dados. Pressione confirmar para resetar seu dispositivo.
@@ -714,7 +584,6 @@ trabalho definido
RichTextDialog
-
Ok
Ok
@@ -722,33 +591,26 @@ trabalho definido
SettingsWindow
-
×
×
-
Device
Dispositivo
-
-
Network
Rede
-
Toggles
Ajustes
-
Software
Software
-
Navigation
Navegação
@@ -756,105 +618,82 @@ trabalho definido
Setup
-
WARNING: Low Voltage
ALERTA: Baixa Voltagem
-
Power your device in a car with a harness or proceed at your own risk.
Ligue seu dispositivo em um carro com um chicote ou prossiga por sua conta e risco.
-
Power off
Desligar
-
-
-
Continue
Continuar
-
Getting Started
Começando
-
Before we get on the road, let’s finish installation and cover some details.
Antes de pegarmos a estrada, vamos terminar a instalação e cobrir alguns detalhes.
-
Connect to Wi-Fi
Conectar ao Wi-Fi
-
-
Back
Voltar
-
Continue without Wi-Fi
Continuar sem Wi-Fi
-
Waiting for internet
Esperando pela internet
-
Choose Software to Install
Escolher Software para Instalar
-
Dashcam
Dashcam
-
Custom Software
Sofware Customizado
-
Enter URL
Preencher URL
-
for Custom Software
para o Software Customizado
-
Downloading...
Baixando...
-
Download Failed
Download Falhou
-
Ensure the entered URL is valid, and the device’s internet connection is good.
Garanta que a URL inserida é valida, e uma boa conexão à internet.
-
Reboot device
Reiniciar Dispositivo
-
Start over
Inicializar
@@ -862,17 +701,14 @@ trabalho definido
SetupWidget
-
Finish Setup
Concluir
-
Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer.
Pareie seu dispositivo com comma connect (connect.comma.ai) e reivindique sua oferta de comma prime.
-
Pair device
Parear dispositivo
@@ -880,106 +716,82 @@ trabalho definido
Sidebar
-
-
CONNECT
CONEXÃO
-
OFFLINE
OFFLINE
-
-
ONLINE
ONLINE
-
ERROR
ERRO
-
-
-
TEMP
TEMP
-
HIGH
ALTA
-
GOOD
BOA
-
OK
OK
-
VEHICLE
VEÍCULO
-
NO
SEM
-
PANDA
PANDA
-
GPS
GPS
-
SEARCH
PROCURA
-
--
--
-
Wi-Fi
Wi-Fi
-
ETH
ETH
-
2G
2G
-
3G
3G
-
LTE
LTE
-
5G
5G
@@ -987,63 +799,50 @@ trabalho definido
SoftwarePanel
-
Updates are only downloaded while the car is off.
Atualizações baixadas durante o motor desligado.
-
Current Version
Versao Atual
-
Download
Download
-
Install Update
Instalar Atualização
-
INSTALL
INSTALAR
-
Target Branch
Alterar Branch
-
SELECT
SELECIONE
-
Select a branch
Selecione uma branch
-
UNINSTALL
DESINSTAL
-
Uninstall %1
Desintalar o %1
-
Are you sure you want to uninstall?
Tem certeza que quer desinstalar?
-
-
CHECK
VERIFICAR
@@ -1051,48 +850,38 @@ trabalho definido
SshControl
-
SSH Keys
Chave SSH
-
Warning: This grants SSH access to all public keys in your GitHub settings. Never enter a GitHub username other than your own. A comma employee will NEVER ask you to add their GitHub username.
Aviso: isso concede acesso SSH a todas as chaves públicas nas configurações do GitHub. Nunca insira um nome de usuário do GitHub que não seja o seu. Um funcionário da comma NUNCA pedirá que você adicione seu nome de usuário do GitHub.
-
-
ADD
ADICIONAR
-
Enter your GitHub username
Insira seu nome de usuário do GitHub
-
LOADING
CARREGANDO
-
REMOVE
REMOVER
-
Username '%1' has no keys on GitHub
Usuário "%1” não possui chaves no GitHub
-
Request timed out
A solicitação expirou
-
Username '%1' doesn't exist on GitHub
Usuário '%1' não existe no GitHub
@@ -1100,7 +889,6 @@ trabalho definido
SshToggle
-
Enable SSH
Habilitar SSH
@@ -1108,22 +896,18 @@ trabalho definido
TermsPage
-
Terms & Conditions
Termos & Condições
-
Decline
Declinar
-
Scroll to accept
Role a tela para aceitar
-
Agree
Concordo
@@ -1131,102 +915,82 @@ trabalho definido
TogglesPanel
-
Enable openpilot
Ativar openpilot
-
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.
Use o sistema openpilot para controle de cruzeiro adaptativo e assistência ao motorista de manutenção de faixa. Sua atenção é necessária o tempo todo para usar esse recurso. A alteração desta configuração tem efeito quando o carro é desligado.
-
Enable Lane Departure Warnings
Ativar Avisos de Saída de Faixa
-
Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31 mph (50 km/h).
Receba alertas para voltar para a pista se o seu veículo sair da faixa e a seta não tiver sido acionada previamente quando em velocidades superiores a 50 km/h.
-
Use Metric System
Usar Sistema Métrico
-
Display speed in km/h instead of mph.
Exibir velocidade em km/h invés de mph.
-
Record and Upload Driver Camera
Gravar e Upload Câmera Motorista
-
Upload data from the driver facing camera and help improve the driver monitoring algorithm.
Upload dados da câmera voltada para o motorista e ajude a melhorar o algoritmo de monitoramentor.
-
🌮 End-to-end longitudinal (extremely alpha) 🌮
🌮 End-to-end longitudinal (experimental) 🌮
-
Experimental openpilot longitudinal control
Controle longitudinal experimental openpilot
-
<b>WARNING: openpilot longitudinal control is experimental for this car and will disable AEB.</b>
<b>AVISO: o controle longitudinal openpilot é experimental para este carro e irá desabilitar AEB.</b>
-
Let the driving model control the gas and brakes. openpilot will drive as it thinks a human would. Super experimental.
Deixe o modelo controlar o acelerador e os freios. openpilot irá conduzir como pensa que um humano faria. Super experimental.
-
openpilot longitudinal control is not currently available for this car.
controle longitudinal openpilot não está disponível para este carro.
-
Enable experimental longitudinal control to enable this.
Habilite o controle longitudinal experimental para habilitar isso.
-
Disengage On Accelerator Pedal
Desacionar Com Pedal Do Acelerador
-
When enabled, pressing the accelerator pedal will disengage openpilot.
Quando ativado, pressionar o pedal do acelerador desacionará o openpilot.
-
Show ETA in 24h Format
Mostrar ETA em formato 24h
-
Use 24h format instead of am/pm
Use o formato 24h em vez de am/pm
-
Show Map on Left Side of UI
Exibir Mapa no Lado Esquerdo
-
Show map on left side when in split screen view.
Exibir mapa do lado esquerdo quando a tela for dividida.
@@ -1234,42 +998,34 @@ trabalho definido
Updater
-
Update Required
Atualização Necessária
-
An operating system update is required. Connect your device to Wi-Fi for the fastest update experience. The download size is approximately 1GB.
Uma atualização do sistema operacional é necessária. Conecte seu dispositivo ao Wi-Fi para a experiência de atualização mais rápida. O tamanho do download é de aproximadamente 1GB.
-
Connect to Wi-Fi
Conecte-se ao Wi-Fi
-
Install
Instalar
-
Back
Voltar
-
Loading...
Carregando...
-
Reboot
Reiniciar
-
Update failed
Falha na atualização
@@ -1277,22 +1033,18 @@ trabalho definido
WifiUI
-
Scanning for networks...
Procurando redes...
-
CONNECTING...
CONECTANDO...
-
FORGET
ESQUECER
-
Forget Wi-Fi Network "%1"?
Esquecer Rede Wi-Fi "%1"?
diff --git a/selfdrive/ui/translations/main_zh-CHS.ts b/selfdrive/ui/translations/main_zh-CHS.ts
index 28008ef06..6300875ee 100644
--- a/selfdrive/ui/translations/main_zh-CHS.ts
+++ b/selfdrive/ui/translations/main_zh-CHS.ts
@@ -4,17 +4,14 @@
AbstractAlert
-
Close
关闭
-
Snooze Update
暂停更新
-
Reboot and Update
重启并更新
@@ -22,53 +19,42 @@
AdvancedNetworking
-
Back
返回
-
Enable Tethering
启用WiFi热点
-
Tethering Password
WiFi热点密码
-
-
EDIT
编辑
-
Enter new tethering password
输入新的WiFi热点密码
-
IP Address
IP地址
-
Enable Roaming
启用数据漫游
-
APN Setting
APN设置
-
Enter APN
输入APN
-
leave blank for automatic configuration
留空以自动配置
@@ -76,13 +62,10 @@
ConfirmationDialog
-
-
Ok
好的
-
Cancel
取消
@@ -90,17 +73,14 @@
DeclinePage
-
You must accept the Terms and Conditions in order to use openpilot.
您必须接受条款和条件以使用openpilot。
-
Back
返回
-
Decline, uninstall %1
拒绝并卸载%1
@@ -108,152 +88,122 @@
DevicePanel
-
Dongle ID
设备ID(Dongle ID)
-
N/A
N/A
-
Serial
序列号
-
Driver Camera
驾驶员摄像头
-
PREVIEW
预览
-
Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off)
打开并预览驾驶员摄像头,以确保驾驶员监控具有良好视野。仅熄火时可用。
-
Reset Calibration
重置设备校准
-
RESET
重置
-
Are you sure you want to reset calibration?
您确定要重置设备校准吗?
-
Review Training Guide
新手指南
-
REVIEW
查看
-
Review the rules, features, and limitations of openpilot
查看openpilot的使用规则,以及其功能和限制。
-
Are you sure you want to review the training guide?
您确定要查看新手指南吗?
-
Regulatory
监管信息
-
VIEW
查看
-
Change Language
切换语言
-
CHANGE
切换
-
Select a language
选择语言
-
Reboot
重启
-
Power Off
关机
-
openpilot requires the device to be mounted within 4° left or right and within 5° up or 8° down. openpilot is continuously calibrating, resetting is rarely required.
openpilot要求设备安装的偏航角在左4°和右4°之间,俯仰角在上5°和下8°之间。一般来说,openpilot会持续更新校准,很少需要重置。
-
Your device is pointed %1° %2 and %3° %4.
您的设备校准为%1° %2、%3° %4。
-
down
朝下
-
up
朝上
-
left
朝左
-
right
朝右
-
Are you sure you want to reboot?
您确定要重新启动吗?
-
Disengage to Reboot
取消openpilot以重新启动
-
Are you sure you want to power off?
您确定要关机吗?
-
Disengage to Power Off
取消openpilot以关机
@@ -261,32 +211,26 @@
DriveStats
-
Drives
旅程数
-
Hours
小时
-
ALL TIME
全部
-
PAST WEEK
过去一周
-
KM
公里
-
Miles
英里
@@ -294,7 +238,6 @@
DriverViewScene
-
camera starting
正在启动相机
@@ -302,12 +245,10 @@
InputDialog
-
Cancel
取消
-
Need at least %n character(s)!
至少需要 %n 个字符!
@@ -317,22 +258,18 @@
Installer
-
Installing...
正在安装……
-
Receiving objects:
正在接收:
-
Resolving deltas:
正在处理:
-
Updating files:
正在更新文件:
@@ -340,27 +277,22 @@
MapETA
-
eta
埃塔
-
min
分钟
-
hr
小时
-
km
km
-
mi
mi
@@ -368,22 +300,18 @@
MapInstructions
-
km
km
-
m
m
-
mi
mi
-
ft
ft
@@ -391,46 +319,38 @@
MapPanel
-
Current Destination
当前目的地
-
CLEAR
清空
-
Recent Destinations
最近目的地
-
Try the Navigation Beta
试用导航测试版
-
Get turn-by-turn directions displayed and more with a comma
prime subscription. Sign up now: https://connect.comma.ai
订阅comma prime以获取导航。
立即注册:https://connect.comma.ai
-
No home
location set
家:未设定
-
No work
location set
工作:未设定
-
no recent destinations
无最近目的地
@@ -438,12 +358,10 @@ location set
MapWindow
-
Map Loading
地图加载中
-
Waiting for GPS
等待 GPS
@@ -451,12 +369,10 @@ location set
MultiOptionDialog
-
Select
选择
-
Cancel
取消
@@ -464,23 +380,18 @@ location set
Networking
-
Advanced
高级
-
Enter password
输入密码
-
-
for "%1"
网络名称:"%1"
-
Wrong password
密码错误
@@ -488,30 +399,22 @@ location set
NvgWindow
-
km/h
km/h
-
mph
mph
-
-
MAX
最高定速
-
-
SPEED
SPEED
-
-
LIMIT
LIMIT
@@ -519,17 +422,14 @@ location set
OffroadHome
-
UPDATE
更新
-
ALERTS
警报
-
ALERT
警报
@@ -537,22 +437,18 @@ location set
PairingPopup
-
Pair your device to your comma account
将您的设备与comma账号配对
-
Go to https://connect.comma.ai on your phone
在手机上访问 https://connect.comma.ai
-
Click "add new device" and scan the QR code on the right
点击“添加新设备”,扫描右侧二维码
-
Bookmark connect.comma.ai to your home screen to use it like an app
将 connect.comma.ai 收藏到您的主屏幕,以便像应用程序一样使用它
@@ -560,32 +456,26 @@ location set
PrimeAdWidget
-
Upgrade Now
现在升级
-
Become a comma prime member at connect.comma.ai
打开connect.comma.ai以注册comma prime会员
-
PRIME FEATURES:
comma prime特权:
-
Remote access
远程访问
-
1 year of storage
1年数据存储
-
Developer perks
开发者福利
@@ -593,22 +483,18 @@ location set
PrimeUserWidget
-
✓ SUBSCRIBED
✓ 已订阅
-
comma prime
comma prime
-
CONNECT.COMMA.AI
CONNECT.COMMA.AI
-
COMMA POINTS
COMMA POINTS点数
@@ -616,41 +502,34 @@ location set
QObject
-
Reboot
重启
-
Exit
退出
-
dashcam
行车记录仪
-
openpilot
openpilot
-
%n minute(s) ago
%n 分钟前
-
%n hour(s) ago
%n 小时前
-
%n day(s) ago
%n 天前
@@ -660,47 +539,38 @@ location set
Reset
-
Reset failed. Reboot to try again.
重置失败。 重新启动以重试。
-
Are you sure you want to reset your device?
您确定要重置您的设备吗?
-
Resetting device...
正在重置设备……
-
System Reset
恢复出厂设置
-
System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot.
已触发系统重置:确认以删除所有内容和设置。取消以正常启动设备。
-
Cancel
取消
-
Reboot
重启
-
Confirm
确认
-
Unable to mount data partition. Press confirm to reset your device.
无法挂载数据分区。 确认以重置您的设备。
@@ -708,7 +578,6 @@ location set
RichTextDialog
-
Ok
好的
@@ -716,33 +585,26 @@ location set
SettingsWindow
-
×
×
-
Device
设备
-
-
Network
网络
-
Toggles
设定
-
Software
软件
-
Navigation
导航
@@ -750,105 +612,82 @@ location set
Setup
-
WARNING: Low Voltage
警告:低电压
-
Power your device in a car with a harness or proceed at your own risk.
请使用car harness线束为您的设备供电,或自行承担风险。
-
Power off
关机
-
-
-
Continue
继续
-
Getting Started
开始设置
-
Before we get on the road, let’s finish installation and cover some details.
开始旅程之前,让我们完成安装并介绍一些细节。
-
Connect to Wi-Fi
连接到WiFi
-
-
Back
返回
-
Continue without Wi-Fi
不连接WiFi并继续
-
Waiting for internet
等待网络连接
-
Choose Software to Install
选择要安装的软件
-
Dashcam
Dashcam(行车记录仪)
-
Custom Software
自定义软件
-
Enter URL
输入网址
-
for Custom Software
以下载自定义软件
-
Downloading...
正在下载……
-
Download Failed
下载失败
-
Ensure the entered URL is valid, and the device’s internet connection is good.
请确保互联网连接良好且输入的URL有效。
-
Reboot device
重启设备
-
Start over
重来
@@ -856,17 +695,14 @@ location set
SetupWidget
-
Finish Setup
完成设置
-
Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer.
将您的设备与comma connect (connect.comma.ai)配对并领取您的comma prime优惠。
-
Pair device
配对设备
@@ -874,106 +710,82 @@ location set
Sidebar
-
-
CONNECT
CONNECT
-
OFFLINE
离线
-
-
ONLINE
在线
-
ERROR
连接出错
-
-
-
TEMP
设备温度
-
HIGH
过热
-
GOOD
良好
-
OK
一般
-
VEHICLE
车辆连接
-
NO
无
-
PANDA
PANDA
-
GPS
GPS
-
SEARCH
搜索中
-
--
--
-
Wi-Fi
Wi-Fi
-
ETH
以太网
-
2G
2G
-
3G
3G
-
LTE
LTE
-
5G
5G
@@ -981,63 +793,50 @@ location set
SoftwarePanel
-
Updates are only downloaded while the car is off.
-
Current Version
-
Download
-
Install Update
-
INSTALL
-
Target Branch
-
SELECT
-
Select a branch
-
UNINSTALL
卸载
-
Uninstall %1
卸载 %1
-
Are you sure you want to uninstall?
您确定要卸载吗?
-
-
CHECK
查看
@@ -1045,48 +844,38 @@ location set
SshControl
-
SSH Keys
SSH密钥
-
Warning: This grants SSH access to all public keys in your GitHub settings. Never enter a GitHub username other than your own. A comma employee will NEVER ask you to add their GitHub username.
警告:这将授予SSH访问权限给您GitHub设置中的所有公钥。切勿输入您自己以外的GitHub用户名。comma员工永远不会要求您添加他们的GitHub用户名。
-
-
ADD
添加
-
Enter your GitHub username
输入您的GitHub用户名
-
LOADING
正在加载
-
REMOVE
删除
-
Username '%1' has no keys on GitHub
用户名“%1”在GitHub上没有密钥
-
Request timed out
请求超时
-
Username '%1' doesn't exist on GitHub
GitHub上不存在用户名“%1”
@@ -1094,7 +883,6 @@ location set
SshToggle
-
Enable SSH
启用SSH
@@ -1102,22 +890,18 @@ location set
TermsPage
-
Terms & Conditions
条款和条件
-
Decline
拒绝
-
Scroll to accept
滑动以接受
-
Agree
同意
@@ -1125,102 +909,82 @@ location set
TogglesPanel
-
Enable openpilot
启用openpilot
-
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.
使用openpilot进行自适应巡航和车道保持辅助。使用此功能时您必须时刻保持注意力。该设置的更改在熄火时生效。
-
Enable Lane Departure Warnings
启用车道偏离警告
-
Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31 mph (50 km/h).
车速超过31mph(50km/h)时,若检测到车辆越过车道线且未打转向灯,系统将发出警告以提醒您返回车道。
-
Use Metric System
使用公制单位
-
Display speed in km/h instead of mph.
显示车速时,以km/h代替mph。
-
Record and Upload Driver Camera
录制并上传驾驶员摄像头
-
Upload data from the driver facing camera and help improve the driver monitoring algorithm.
上传驾驶员摄像头的数据,帮助改进驾驶员监控算法。
-
🌮 End-to-end longitudinal (extremely alpha) 🌮
🌮 端对端纵向控制(实验性功能) 🌮
-
Experimental openpilot longitudinal control
-
<b>WARNING: openpilot longitudinal control is experimental for this car and will disable AEB.</b>
-
Let the driving model control the gas and brakes. openpilot will drive as it thinks a human would. Super experimental.
让驾驶模型直接控制油门和刹车,openpilot将会模仿人类司机的驾驶方式。该功能仍非常实验性。
-
openpilot longitudinal control is not currently available for this car.
-
Enable experimental longitudinal control to enable this.
-
Disengage On Accelerator Pedal
踩油门时取消控制
-
When enabled, pressing the accelerator pedal will disengage openpilot.
启用后,踩下油门踏板将取消openpilot。
-
Show ETA in 24h Format
以24小时格式显示预计到达时间
-
Use 24h format instead of am/pm
使用24小时制代替am/pm
-
Show Map on Left Side of UI
在介面左侧显示地图
-
Show map on left side when in split screen view.
在分屏模式中,将地图置于屏幕左侧。
@@ -1228,42 +992,34 @@ location set
Updater
-
Update Required
需要更新
-
An operating system update is required. Connect your device to Wi-Fi for the fastest update experience. The download size is approximately 1GB.
操作系统需要更新。请将您的设备连接到WiFi以获取更快的更新体验。下载大小约为1GB。
-
Connect to Wi-Fi
连接到WiFi
-
Install
安装
-
Back
返回
-
Loading...
正在加载……
-
Reboot
重启
-
Update failed
更新失败
@@ -1271,22 +1027,18 @@ location set
WifiUI
-
Scanning for networks...
正在扫描网络……
-
CONNECTING...
正在连接……
-
FORGET
忘记
-
Forget Wi-Fi Network "%1"?
忘记WiFi网络 "%1"?
diff --git a/selfdrive/ui/translations/main_zh-CHT.ts b/selfdrive/ui/translations/main_zh-CHT.ts
index 364508bd1..73faf11f6 100644
--- a/selfdrive/ui/translations/main_zh-CHT.ts
+++ b/selfdrive/ui/translations/main_zh-CHT.ts
@@ -4,17 +4,14 @@
AbstractAlert
-
Close
關閉
-
Snooze Update
暫停更新
-
Reboot and Update
重啟並更新
@@ -22,53 +19,42 @@
AdvancedNetworking
-
Back
回上頁
-
Enable Tethering
啟用網路分享
-
Tethering Password
網路分享密碼
-
-
EDIT
編輯
-
Enter new tethering password
輸入新的網路分享密碼
-
IP Address
IP 地址
-
Enable Roaming
啟用漫遊
-
APN Setting
APN 設置
-
Enter APN
輸入 APN
-
leave blank for automatic configuration
留空白將自動配置
@@ -76,13 +62,10 @@
ConfirmationDialog
-
-
Ok
確定
-
Cancel
取消
@@ -90,17 +73,14 @@
DeclinePage
-
You must accept the Terms and Conditions in order to use openpilot.
您必須先接受條款和條件才能使用 openpilot。
-
Back
回上頁
-
Decline, uninstall %1
拒絕並卸載 %1
@@ -108,152 +88,122 @@
DevicePanel
-
Dongle ID
Dongle ID
-
N/A
無法使用
-
Serial
序號
-
Driver Camera
駕駛員攝像頭
-
PREVIEW
預覽
-
Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off)
預覽駕駛員監控鏡頭畫面,以確保其具有良好視野。(僅在熄火時可用)
-
Reset Calibration
重置校準
-
RESET
重置
-
Are you sure you want to reset calibration?
您確定要重置校準嗎?
-
Review Training Guide
觀看使用教學
-
REVIEW
觀看
-
Review the rules, features, and limitations of openpilot
觀看 openpilot 的使用規則、功能和限制
-
Are you sure you want to review the training guide?
您確定要觀看使用教學嗎?
-
Regulatory
法規/監管
-
VIEW
觀看
-
Change Language
更改語言
-
CHANGE
更改
-
Select a language
選擇語言
-
Reboot
重新啟動
-
Power Off
關機
-
openpilot requires the device to be mounted within 4° left or right and within 5° up or 8° down. openpilot is continuously calibrating, resetting is rarely required.
openpilot 需要將裝置固定在左右偏差 4° 以內,朝上偏差 5° 以内或朝下偏差 8° 以内。鏡頭在後台會持續自動校準,很少有需要重置的情况。
-
Your device is pointed %1° %2 and %3° %4.
你的設備目前朝%2 %1° 以及朝%4 %3° 。
-
down
下
-
up
上
-
left
左
-
right
右
-
Are you sure you want to reboot?
您確定要重新啟動嗎?
-
Disengage to Reboot
請先取消控車才能重新啟動
-
Are you sure you want to power off?
您確定您要關機嗎?
-
Disengage to Power Off
請先取消控車才能關機
@@ -261,32 +211,26 @@
DriveStats
-
Drives
旅程
-
Hours
小時
-
ALL TIME
總共
-
PAST WEEK
上周
-
KM
公里
-
Miles
英里
@@ -294,7 +238,6 @@
DriverViewScene
-
camera starting
開啟相機中
@@ -302,12 +245,10 @@
InputDialog
-
Cancel
取消
-
Need at least %n character(s)!
需要至少 %n 個字元!
@@ -317,22 +258,18 @@
Installer
-
Installing...
安裝中…
-
Receiving objects:
接收對象:
-
Resolving deltas:
分析差異:
-
Updating files:
更新檔案:
@@ -340,27 +277,22 @@
MapETA
-
eta
抵達
-
min
分鐘
-
hr
小時
-
km
km
-
mi
mi
@@ -368,22 +300,18 @@
MapInstructions
-
km
km
-
m
m
-
mi
mi
-
ft
ft
@@ -391,48 +319,40 @@
MapPanel
-
Current Destination
當前目的地
-
CLEAR
清除
-
Recent Destinations
最近目的地
-
Try the Navigation Beta
試用導航功能
-
Get turn-by-turn directions displayed and more with a comma
prime subscription. Sign up now: https://connect.comma.ai
成為 comma 高級會員來使用導航功能
立即註冊:https://connect.comma.ai
-
No home
location set
未設定
住家位置
-
No work
location set
未設定
工作位置
-
no recent destinations
沒有最近的導航記錄
@@ -440,12 +360,10 @@ location set
MapWindow
-
Map Loading
地圖加載中
-
Waiting for GPS
等待 GPS
@@ -453,12 +371,10 @@ location set
MultiOptionDialog
-
Select
選擇
-
Cancel
取消
@@ -466,23 +382,18 @@ location set
Networking
-
Advanced
進階
-
Enter password
輸入密碼
-
-
for "%1"
給 "%1"
-
Wrong password
密碼錯誤
@@ -490,30 +401,22 @@ location set
NvgWindow
-
km/h
km/h
-
mph
mph
-
-
MAX
最高
-
-
SPEED
速度
-
-
LIMIT
速限
@@ -521,17 +424,14 @@ location set
OffroadHome
-
UPDATE
更新
-
ALERTS
提醒
-
ALERT
提醒
@@ -539,22 +439,18 @@ location set
PairingPopup
-
Pair your device to your comma account
將設備與您的 comma 帳號配對
-
Go to https://connect.comma.ai on your phone
用手機連至 https://connect.comma.ai
-
Click "add new device" and scan the QR code on the right
點選 "add new device" 後掃描右邊的二維碼
-
Bookmark connect.comma.ai to your home screen to use it like an app
將 connect.comma.ai 加入您的主屏幕,以便像手機 App 一樣使用它
@@ -562,32 +458,26 @@ location set
PrimeAdWidget
-
Upgrade Now
馬上升級
-
Become a comma prime member at connect.comma.ai
成為 connect.comma.ai 的高級會員
-
PRIME FEATURES:
高級會員特點:
-
Remote access
遠程訪問
-
1 year of storage
一年的雲端行車記錄
-
Developer perks
開發者福利
@@ -595,22 +485,18 @@ location set
PrimeUserWidget
-
✓ SUBSCRIBED
✓ 已訂閱
-
comma prime
comma 高級會員
-
CONNECT.COMMA.AI
CONNECT.COMMA.AI
-
COMMA POINTS
COMMA 積分
@@ -618,41 +504,34 @@ location set
QObject
-
Reboot
重新啟動
-
Exit
離開
-
dashcam
行車記錄器
-
openpilot
openpilot
-
%n minute(s) ago
%n 分鐘前
-
%n hour(s) ago
%n 小時前
-
%n day(s) ago
%n 天前
@@ -662,47 +541,38 @@ location set
Reset
-
Reset failed. Reboot to try again.
重置失敗。請重新啟動後再試。
-
Are you sure you want to reset your device?
您確定要重置你的設備嗎?
-
Resetting device...
重置設備中…
-
System Reset
系統重置
-
System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot.
系統重置已觸發。請按確認刪除所有內容和設置。按取消恢復啟動。
-
Cancel
取消
-
Reboot
重新啟動
-
Confirm
確認
-
Unable to mount data partition. Press confirm to reset your device.
無法掛載數據分區。請按確認重置您的設備。
@@ -710,7 +580,6 @@ location set
RichTextDialog
-
Ok
確定
@@ -718,33 +587,26 @@ location set
SettingsWindow
-
×
×
-
Device
設備
-
-
Network
網路
-
Toggles
設定
-
Software
軟體
-
Navigation
導航
@@ -752,105 +614,82 @@ location set
Setup
-
WARNING: Low Voltage
警告:電壓過低
-
Power your device in a car with a harness or proceed at your own risk.
請使用車上 harness 提供的電源,若繼續的話您需要自擔風險。
-
Power off
關機
-
-
-
Continue
繼續
-
Getting Started
入門
-
Before we get on the road, let’s finish installation and cover some details.
在我們上路之前,讓我們完成安裝並介紹一些細節。
-
Connect to Wi-Fi
連接到無線網絡
-
-
Back
回上頁
-
Continue without Wi-Fi
在沒有 Wi-Fi 的情況下繼續
-
Waiting for internet
連接至網路中
-
Choose Software to Install
選擇要安裝的軟體
-
Dashcam
行車記錄器
-
Custom Software
定制的軟體
-
Enter URL
輸入網址
-
for Custom Software
定制的軟體
-
Downloading...
下載中…
-
Download Failed
下載失敗
-
Ensure the entered URL is valid, and the device’s internet connection is good.
請確定您輸入的是有效的安裝網址,並且確定設備的網路連線狀態良好。
-
Reboot device
重新啟動
-
Start over
重新開始
@@ -858,17 +697,14 @@ location set
SetupWidget
-
Finish Setup
完成設置
-
Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer.
將您的設備與 comma connect (connect.comma.ai) 配對並領取您的 comma 高級會員優惠。
-
Pair device
配對設備
@@ -876,106 +712,82 @@ location set
Sidebar
-
-
CONNECT
雲端服務
-
OFFLINE
已離線
-
-
ONLINE
已連線
-
ERROR
錯誤
-
-
-
TEMP
溫度
-
HIGH
偏高
-
GOOD
正常
-
OK
一般
-
VEHICLE
車輛通訊
-
NO
未連線
-
PANDA
車輛通訊
-
GPS
GPS
-
SEARCH
車輛通訊
-
--
--
-
Wi-Fi
-
ETH
-
2G
-
3G
-
LTE
-
5G
@@ -983,63 +795,50 @@ location set
SoftwarePanel
-
Updates are only downloaded while the car is off.
系統更新只會在熄火時下載。
-
Current Version
當前版本
-
Download
下載
-
Install Update
安裝更新
-
INSTALL
安裝
-
Target Branch
目標分支
-
SELECT
選取
-
Select a branch
選取一個分支
-
UNINSTALL
卸載
-
Uninstall %1
卸載 %1
-
Are you sure you want to uninstall?
您確定您要卸載嗎?
-
-
CHECK
檢查
@@ -1047,48 +846,38 @@ location set
SshControl
-
SSH Keys
SSH 密鑰
-
Warning: This grants SSH access to all public keys in your GitHub settings. Never enter a GitHub username other than your own. A comma employee will NEVER ask you to add their GitHub username.
警告:這將授權給 GitHub 帳號中所有公鑰 SSH 訪問權限。切勿輸入非您自己的 GitHub 用戶名。comma 員工「永遠不會」要求您添加他們的 GitHub 用戶名。
-
-
ADD
新增
-
Enter your GitHub username
請輸入您 GitHub 的用戶名
-
LOADING
載入中
-
REMOVE
移除
-
Username '%1' has no keys on GitHub
GitHub 用戶 '%1' 沒有設定任何密鑰
-
Request timed out
請求超時
-
Username '%1' doesn't exist on GitHub
GitHub 用戶 '%1' 不存在
@@ -1096,7 +885,6 @@ location set
SshToggle
-
Enable SSH
啟用 SSH 服務
@@ -1104,22 +892,18 @@ location set
TermsPage
-
Terms & Conditions
條款和條件
-
Decline
拒絕
-
Scroll to accept
滑動至頁尾接受條款
-
Agree
接受
@@ -1127,102 +911,82 @@ location set
TogglesPanel
-
Enable openpilot
啟用 openpilot
-
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.
使用 openpilot 的主動式巡航和車道保持功能,開啟後您需要持續集中注意力,設定變更在重新啟動車輛後生效。
-
Enable Lane Departure Warnings
啟用車道偏離警告
-
Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31 mph (50 km/h).
車速在時速 50 公里 (31 英里) 以上且未打方向燈的情況下,如果偵測到車輛駛出目前車道線時,發出車道偏離警告。
-
Use Metric System
使用公制單位
-
Display speed in km/h instead of mph.
啟用後,速度單位顯示將從 mp/h 改為 km/h。
-
Record and Upload Driver Camera
記錄並上傳駕駛監控影像
-
Upload data from the driver facing camera and help improve the driver monitoring algorithm.
上傳駕駛監控的錄像來協助我們提升駕駛監控的準確率。
-
🌮 End-to-end longitudinal (extremely alpha) 🌮
🌮 端對端縱向控制(實驗性功能) 🌮
-
Experimental openpilot longitudinal control
使用 openpilot 縱向控制(實驗)
-
<b>WARNING: openpilot longitudinal control is experimental for this car and will disable AEB.</b>
<b>注意:這台車的 openpilot 縱向控制仍然是實驗中的功能,開啟這功能將會關閉自動緊急煞車 (AEB)。</b>
-
Let the driving model control the gas and brakes. openpilot will drive as it thinks a human would. Super experimental.
讓駕駛模型直接控製油門和剎車,openpilot將會模仿人類司機的駕駛方式。該功能仍非常實驗性。
-
openpilot longitudinal control is not currently available for this car.
openpilot 縱向控制目前不適用於這輛車。
-
Enable experimental longitudinal control to enable this.
打開縱向控制(實驗)以啟用此功能。
-
Disengage On Accelerator Pedal
油門取消控車
-
When enabled, pressing the accelerator pedal will disengage openpilot.
啟用後,踩踏油門將會取消 openpilot 控制。
-
Show ETA in 24h Format
預計到達時間單位改用 24 小時制
-
Use 24h format instead of am/pm
使用 24 小時制。(預設值為 12 小時制)
-
Show Map on Left Side of UI
將地圖顯示在畫面的左側
-
Show map on left side when in split screen view.
進入分割畫面後,地圖將會顯示在畫面的左側。
@@ -1230,42 +994,34 @@ location set
Updater
-
Update Required
系統更新
-
An operating system update is required. Connect your device to Wi-Fi for the fastest update experience. The download size is approximately 1GB.
設備的操作系統需要更新。請將您的設備連接到 Wi-Fi 以獲得最快的更新體驗。下載大小約為 1GB。
-
Connect to Wi-Fi
連接到無線網絡
-
Install
安裝
-
Back
回上頁
-
Loading...
載入中…
-
Reboot
重新啟動
-
Update failed
更新失敗
@@ -1273,22 +1029,18 @@ location set
WifiUI
-
Scanning for networks...
掃描無線網路中...
-
CONNECTING...
連線中...
-
FORGET
清除
-
Forget Wi-Fi Network "%1"?
清除 Wi-Fi 網路 "%1"?
diff --git a/selfdrive/ui/update_translations.py b/selfdrive/ui/update_translations.py
index afd42c3b3..e15d4c343 100755
--- a/selfdrive/ui/update_translations.py
+++ b/selfdrive/ui/update_translations.py
@@ -19,7 +19,7 @@ def update_translations(vanish=False, plural_only=None, translations_dir=TRANSLA
for file in translation_files.values():
tr_file = os.path.join(translations_dir, f"{file}.ts")
- args = f"lupdate -locations relative -recursive {UI_DIR} -ts {tr_file}"
+ args = f"lupdate -locations none -recursive {UI_DIR} -ts {tr_file}"
if vanish:
args += " -no-obsolete"
if file in plural_only:
From e4612ac4c48597864dabef6f25b4db0d846426e0 Mon Sep 17 00:00:00 2001
From: royjr
Date: Sat, 17 Sep 2022 18:55:12 -0400
Subject: [PATCH 32/75] ui: fix toggle spacing issue (#25831)
---
selfdrive/ui/qt/widgets/controls.cc | 2 --
1 file changed, 2 deletions(-)
diff --git a/selfdrive/ui/qt/widgets/controls.cc b/selfdrive/ui/qt/widgets/controls.cc
index b5f646c37..a1ebf57b0 100644
--- a/selfdrive/ui/qt/widgets/controls.cc
+++ b/selfdrive/ui/qt/widgets/controls.cc
@@ -18,8 +18,6 @@ QFrame *horizontal_line(QWidget *parent) {
}
AbstractControl::AbstractControl(const QString &title, const QString &desc, const QString &icon, QWidget *parent) : QFrame(parent) {
- setSizePolicy(QSizePolicy::Preferred, QSizePolicy::Minimum);
-
QVBoxLayout *main_layout = new QVBoxLayout(this);
main_layout->setMargin(0);
From 583304fc7b5970ec5f079720bf6c6aa7ff91ce5a Mon Sep 17 00:00:00 2001
From: Dean Lee
Date: Mon, 19 Sep 2022 05:01:33 +0800
Subject: [PATCH 33/75] params: cleanup constructor (#25834)
---
common/params.cc | 6 ++----
1 file changed, 2 insertions(+), 4 deletions(-)
diff --git a/common/params.cc b/common/params.cc
index 7b2d4490e..a64c2f133 100644
--- a/common/params.cc
+++ b/common/params.cc
@@ -198,10 +198,8 @@ std::unordered_map keys = {
Params::Params(const std::string &path) {
- const char* env = std::getenv("OPENPILOT_PREFIX");
- prefix = env ? "/" + std::string(env) : "/d";
- std::string default_param_path = ensure_params_path(prefix);
- params_path = path.empty() ? default_param_path : ensure_params_path(prefix, path);
+ prefix = "/" + util::getenv("OPENPILOT_PREFIX", "d");
+ params_path = ensure_params_path(prefix, path);
}
std::vector Params::allKeys() const {
From 8870b439dd5f9b0ae1a53d75bab3a1470ea7d372 Mon Sep 17 00:00:00 2001
From: Dean Lee
Date: Tue, 20 Sep 2022 04:24:20 +0800
Subject: [PATCH 34/75] camerad: fix class/struct forward declaration mistake
(#25842)
---
system/camerad/cameras/camera_common.h | 2 +-
1 file changed, 1 insertion(+), 1 deletion(-)
diff --git a/system/camerad/cameras/camera_common.h b/system/camerad/cameras/camera_common.h
index e5580a7a9..088b9f793 100644
--- a/system/camerad/cameras/camera_common.h
+++ b/system/camerad/cameras/camera_common.h
@@ -75,7 +75,7 @@ typedef struct FrameMetadata {
} FrameMetadata;
struct MultiCameraState;
-struct CameraState;
+class CameraState;
class Debayer;
class CameraBuf {
From 8b741261cf4538ab88f42f18837ba13d71bcc0de Mon Sep 17 00:00:00 2001
From: Adeeb Shihadeh
Date: Mon, 19 Sep 2022 14:06:03 -0700
Subject: [PATCH 35/75] loggerd: add params test cases (#25843)
---
selfdrive/loggerd/tests/test_loggerd.py | 12 ++++++++++--
1 file changed, 10 insertions(+), 2 deletions(-)
diff --git a/selfdrive/loggerd/tests/test_loggerd.py b/selfdrive/loggerd/tests/test_loggerd.py
index b0907c54a..a2138b0aa 100755
--- a/selfdrive/loggerd/tests/test_loggerd.py
+++ b/selfdrive/loggerd/tests/test_loggerd.py
@@ -83,8 +83,10 @@ class TestLoggerd(unittest.TestCase):
("GitRemote", "gitRemote", "remote"),
]
params = Params()
+ params.clear_all()
for k, _, v in fake_params:
params.put(k, v)
+ params.put("LaikadEphemeris", "abc")
lr = list(LogReader(str(self._gen_bootlog())))
initData = lr[0].initData
@@ -99,8 +101,14 @@ class TestLoggerd(unittest.TestCase):
with open("/proc/version") as f:
self.assertEqual(initData.kernelVersion, f.read())
- for _, k, v in fake_params:
- self.assertEqual(getattr(initData, k), v)
+ # check params
+ logged_params = {entry.key: entry.value for entry in initData.params.entries}
+ expected_params = set(k for k, _, __ in fake_params) | {'LaikadEphemeris'}
+ assert set(logged_params.keys()) == expected_params, set(logged_params.keys()) ^ expected_params
+ assert logged_params['LaikadEphemeris'] == b'', f"DONT_LOG param value was logged: {repr(logged_params['LaikadEphemeris'])}"
+ for param_key, initData_key, v in fake_params:
+ self.assertEqual(getattr(initData, initData_key), v)
+ self.assertEqual(logged_params[param_key].decode(), v)
def test_rotation(self):
os.environ["LOGGERD_TEST"] = "1"
From 7b5d8adfb1819799ec635347712a2f9a40278fa3 Mon Sep 17 00:00:00 2001
From: Shane Smiskol
Date: Mon, 19 Sep 2022 14:14:19 -0700
Subject: [PATCH 36/75] Hyundai Elantra 2021: replace VW engine FW
5a4405495d2750ef|2022-09-11--12-37-48
---
selfdrive/car/hyundai/values.py | 2 +-
1 file changed, 1 insertion(+), 1 deletion(-)
diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py
index 3bc206297..ea6fca592 100644
--- a/selfdrive/car/hyundai/values.py
+++ b/selfdrive/car/hyundai/values.py
@@ -1200,7 +1200,7 @@ FW_VERSIONS = {
],
(Ecu.engine, 0x7e0, None): [
b'\xf1\x82CNCWD0AMFCXCSFFA',
- b'\xf1\x82CNCWD0AMFCXCSFFB',
+ b'\xf1\x81HM6M2_0a0_FF0',
b'\xf1\x82CNCVD0AMFCXCSFFB',
b'\xf1\x870\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\xf1\x81HM6M2_0a0_G80',
],
From 4fa62f146426f76c9c1c2867d9729b33ec612b59 Mon Sep 17 00:00:00 2001
From: Vivek Aithal
Date: Mon, 19 Sep 2022 15:19:26 -0700
Subject: [PATCH 37/75] Live torque (#25456)
* wip torqued
* add basic logic
* setup in manager
* check sanity and publish msg
* add first order filter to outputs
* wire up controlsd, and update gains
* rename intercept to offset
* add cloudlog, live values are not updated
* fix bugs, do not reset points for now
* fix crashes
* rename to main
* fix bugs, works offline
* fix float in cereal bug
* add latacc filter
* randomly choose points, approx for iid
* add variable decay
* local param to capnp instead of dict
* verify works in replay
* use torqued output in controlsd
* use in controlsd; use points from past routes
* controlsd bugfix
* filter before updating gains, needs to be replaced
* save all points to ensure smooth transition across routes, revert friction factor to 1.5
* add filters to prevent noisy low-speed data points; improve fit sanity
* add engaged buffer
* revert lat_acc thresh
* use paramsd realtime process config
* make latacc-to-torque generic, and overrideable
* move freq to 4Hz, avoid storing in np.array, don't publish points in the message
* float instead of np
* remove constant while storing pts
* rename slope, offset to lat_accet_factor, offset
* resolve issues
* use camelcase in all capnp params
* use camelcase everywhere
* reduce latacc threshold or sanity, add car_sane todo, save points properly
* add and check tag
* write param to disk at end of route
* remove args
* rebase op, cereal
* save on exit
* restore default handler
* cpu usage check
* add to process replay
* handle reset better, reduce unnecessary computation
* always publish raw values - useful for debug
* regen routes
* update refs
* checks on cache restore
* check tuning vals too
* clean that up
* reduce cpu usage
* reduce cpu usage by 75%
* cleanup
* optimize further
* handle reset condition better, don't put points in init, use only in corolla
* bump cereal after rebasing
* update refs
* Update common/params.cc
Co-authored-by: Adeeb Shihadeh
* remove unnecessary checks
* Update RELEASES.md
Co-authored-by: Adeeb Shihadeh
---
RELEASES.md | 2 +
common/params.cc | 2 +
release/files_common | 1 +
selfdrive/car/interfaces.py | 1 +
selfdrive/controls/controlsd.py | 8 +-
selfdrive/controls/lib/latcontrol_torque.py | 2 +-
selfdrive/locationd/torqued.py | 290 ++++++++++++++++++
selfdrive/manager/process_config.py | 1 +
.../test/process_replay/process_replay.py | 27 +-
selfdrive/test/process_replay/ref_commit | 2 +-
selfdrive/test/process_replay/regen.py | 8 +-
selfdrive/test/process_replay/regen_all.py | 11 +-
.../test/process_replay/test_processes.py | 10 +-
selfdrive/test/test_onroad.py | 1 +
selfdrive/test/update_ci_routes.py | 2 +-
15 files changed, 350 insertions(+), 18 deletions(-)
create mode 100755 selfdrive/locationd/torqued.py
diff --git a/RELEASES.md b/RELEASES.md
index 56cffeebe..a749158cb 100644
--- a/RELEASES.md
+++ b/RELEASES.md
@@ -2,6 +2,8 @@ Version 0.8.17 (2022-XX-XX)
========================
* New driving model
* Internal feature space accuracy increased tenfold during training, this makes the model dramatically more accurate.
+* torqued
+ * Learn torque parameters live for each car as opposed to using platform average values, which improves lateral control
Version 0.8.16 (2022-08-26)
========================
diff --git a/common/params.cc b/common/params.cc
index a64c2f133..63208879b 100644
--- a/common/params.cc
+++ b/common/params.cc
@@ -144,6 +144,8 @@ std::unordered_map keys = {
{"LastUpdateException", CLEAR_ON_MANAGER_START},
{"LastUpdateTime", PERSISTENT},
{"LiveParameters", PERSISTENT},
+ {"LiveTorqueCarParams", PERSISTENT},
+ {"LiveTorqueParameters", PERSISTENT | DONT_LOG},
{"NavDestination", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_OFF},
{"NavSettingTime24h", PERSISTENT},
{"NavSettingLeftSide", PERSISTENT},
diff --git a/release/files_common b/release/files_common
index be0a4f0f0..fa4fa997c 100644
--- a/release/files_common
+++ b/release/files_common
@@ -240,6 +240,7 @@ selfdrive/locationd/models/live_kf.cc
selfdrive/locationd/models/constants.py
selfdrive/locationd/models/gnss_helpers.py
+selfdrive/locationd/torqued.py
selfdrive/locationd/calibrationd.py
system/logcatd/.gitignore
diff --git a/selfdrive/car/interfaces.py b/selfdrive/car/interfaces.py
index 87720f875..a789fc6ca 100644
--- a/selfdrive/car/interfaces.py
+++ b/selfdrive/car/interfaces.py
@@ -167,6 +167,7 @@ class CarInterfaceBase(ABC):
tune.torque.friction = params['FRICTION']
tune.torque.latAccelFactor = params['LAT_ACCEL_FACTOR']
tune.torque.latAccelOffset = 0.0
+ tune.torque.steeringAngleDeadzoneDeg = steering_angle_deadzone_deg
@abstractmethod
def _update(self, c: car.CarControl) -> car.CarState:
diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py
index 308753529..8b41e305f 100755
--- a/selfdrive/controls/controlsd.py
+++ b/selfdrive/controls/controlsd.py
@@ -104,7 +104,7 @@ class Controls:
ignore += ['roadCameraState']
self.sm = messaging.SubMaster(['deviceState', 'pandaStates', 'peripheralState', 'modelV2', 'liveCalibration',
'driverMonitoringState', 'longitudinalPlan', 'lateralPlan', 'liveLocationKalman',
- 'managerState', 'liveParameters', 'radarState'] + self.camera_packets + joystick_packet,
+ 'managerState', 'liveParameters', 'radarState', 'liveTorqueParameters'] + self.camera_packets + joystick_packet,
ignore_alive=ignore, ignore_avg_freq=['radarState', 'longitudinalPlan'])
# set alternative experiences from parameters
@@ -578,6 +578,12 @@ class Controls:
sr = max(params.steerRatio, 0.1)
self.VM.update_params(x, sr)
+ # Update Torque Params
+ if self.CP.lateralTuning.which() == 'torque':
+ torque_params = self.sm['liveTorqueParameters']
+ if self.sm.all_checks(['liveTorqueParameters']) and torque_params.useParams:
+ self.LaC.update_live_torque_params(torque_params.latAccelFactorFiltered, torque_params.latAccelOffsetFiltered, torque_params.frictionCoefficientFiltered)
+
lat_plan = self.sm['lateralPlan']
long_plan = self.sm['longitudinalPlan']
diff --git a/selfdrive/controls/lib/latcontrol_torque.py b/selfdrive/controls/lib/latcontrol_torque.py
index f65a58275..fa1bb480f 100644
--- a/selfdrive/controls/lib/latcontrol_torque.py
+++ b/selfdrive/controls/lib/latcontrol_torque.py
@@ -51,7 +51,7 @@ class LatControlTorque(LatControl):
desired_lateral_accel = desired_curvature * CS.vEgo ** 2
# desired rate is the desired rate of change in the setpoint, not the absolute desired curvature
- #desired_lateral_jerk = desired_curvature_rate * CS.vEgo ** 2
+ # desired_lateral_jerk = desired_curvature_rate * CS.vEgo ** 2
actual_lateral_accel = actual_curvature * CS.vEgo ** 2
lateral_accel_deadzone = curvature_deadzone * CS.vEgo ** 2
diff --git a/selfdrive/locationd/torqued.py b/selfdrive/locationd/torqued.py
new file mode 100755
index 000000000..9f0700821
--- /dev/null
+++ b/selfdrive/locationd/torqued.py
@@ -0,0 +1,290 @@
+#!/usr/bin/env python3
+import os
+import sys
+import signal
+import numpy as np
+from collections import deque, defaultdict
+
+import cereal.messaging as messaging
+from cereal import car, log
+from common.params import Params
+from common.realtime import config_realtime_process, DT_MDL
+from common.filter_simple import FirstOrderFilter
+from system.swaglog import cloudlog
+from selfdrive.controls.lib.vehicle_model import ACCELERATION_DUE_TO_GRAVITY
+from selfdrive.car.toyota.values import CAR as TOYOTA
+
+HISTORY = 5 # secs
+POINTS_PER_BUCKET = 1500
+MIN_POINTS_TOTAL = 4000
+FIT_POINTS_TOTAL = 2000
+MIN_VEL = 15 # m/s
+FRICTION_FACTOR = 1.5 # ~85% of data coverage
+FACTOR_SANITY = 0.3
+FRICTION_SANITY = 0.5
+STEER_MIN_THRESHOLD = 0.02
+MIN_FILTER_DECAY = 50
+MAX_FILTER_DECAY = 250
+LAT_ACC_THRESHOLD = 1
+STEER_BUCKET_BOUNDS = [(-0.5, -0.3), (-0.3, -0.2), (-0.2, -0.1), (-0.1, 0), (0, 0.1), (0.1, 0.2), (0.2, 0.3), (0.3, 0.5)]
+MIN_BUCKET_POINTS = [100, 300, 500, 500, 500, 500, 300, 100]
+MAX_RESETS = 5.0
+MAX_INVALID_THRESHOLD = 10
+MIN_ENGAGE_BUFFER = 2 # secs
+
+VERSION = 1 # bump this to invalidate old parameter caches
+ALLOWED_FINGERPRINTS = [TOYOTA.COROLLA_TSS2, TOYOTA.COROLLA, TOYOTA.COROLLAH_TSS2]
+
+
+def slope2rot(slope):
+ sin = np.sqrt(slope**2 / (slope**2 + 1))
+ cos = np.sqrt(1 / (slope**2 + 1))
+ return np.array([[cos, -sin], [sin, cos]])
+
+
+class npqueue:
+ def __init__(self, maxlen, rowsize):
+ self.maxlen = maxlen
+ self.arr = np.empty((0, rowsize))
+
+ def __len__(self):
+ return len(self.arr)
+
+ def append(self, pt):
+ if len(self.arr) < self.maxlen:
+ self.arr = np.append(self.arr, [pt], axis=0)
+ else:
+ self.arr[:-1] = self.arr[1:]
+ self.arr[-1] = pt
+
+
+class PointBuckets:
+ def __init__(self, x_bounds, min_points):
+ self.x_bounds = x_bounds
+ self.buckets = {bounds: npqueue(maxlen=POINTS_PER_BUCKET, rowsize=3) for bounds in x_bounds}
+ self.buckets_min_points = {bounds: min_point for bounds, min_point in zip(x_bounds, min_points)}
+
+ def bucket_lengths(self):
+ return [len(v) for v in self.buckets.values()]
+
+ def __len__(self):
+ return sum(self.bucket_lengths())
+
+ def is_valid(self):
+ return all(len(v) >= min_pts for v, min_pts in zip(self.buckets.values(), self.buckets_min_points.values())) and (self.__len__() >= MIN_POINTS_TOTAL)
+
+ def add_point(self, x, y):
+ for bound_min, bound_max in self.x_bounds:
+ if (x >= bound_min) and (x < bound_max):
+ self.buckets[(bound_min, bound_max)].append([x, 1.0, y])
+ break
+
+ def get_points(self, num_points=None):
+ points = np.concatenate([x.arr for x in self.buckets.values() if len(x) > 0])
+ if num_points is None:
+ return points
+ return points[np.random.choice(np.arange(len(points)), min(len(points), num_points), replace=False)]
+
+ def load_points(self, points):
+ for x, y in points:
+ self.add_point(x, y)
+
+
+class TorqueEstimator:
+ def __init__(self, CP):
+ self.hist_len = int(HISTORY / DT_MDL)
+ self.lag = CP.steerActuatorDelay + .2 # from controlsd
+
+ self.offline_friction = 0.0
+ self.offline_latAccelFactor = 0.0
+ self.resets = 0.0
+ self.use_params = CP.carFingerprint in ALLOWED_FINGERPRINTS
+
+ if CP.lateralTuning.which() == 'torque':
+ self.offline_friction = CP.lateralTuning.torque.friction
+ self.offline_latAccelFactor = CP.lateralTuning.torque.latAccelFactor
+
+ self.reset()
+
+ initial_params = {
+ 'latAccelFactor': self.offline_latAccelFactor,
+ 'latAccelOffset': 0.0,
+ 'frictionCoefficient': self.offline_friction,
+ 'points': []
+ }
+ self.decay = MIN_FILTER_DECAY
+ self.min_lataccel_factor = (1.0 - FACTOR_SANITY) * self.offline_latAccelFactor
+ self.max_lataccel_factor = (1.0 + FACTOR_SANITY) * self.offline_latAccelFactor
+ self.min_friction = (1.0 - FRICTION_SANITY) * self.offline_friction
+ self.max_friction = (1.0 + FRICTION_SANITY) * self.offline_friction
+
+ # try to restore cached params
+ params = Params()
+ params_cache = params.get("LiveTorqueCarParams")
+ torque_cache = params.get("LiveTorqueParameters")
+ if params_cache is not None and torque_cache is not None:
+ try:
+ cache_ltp = log.Event.from_bytes(torque_cache).liveTorqueParameters
+ cache_CP = car.CarParams.from_bytes(params_cache)
+ if self.get_restore_key(cache_CP, cache_ltp.version) == self.get_restore_key(CP, VERSION):
+ initial_params = {
+ 'latAccelFactor': cache_ltp.latAccelFactorFiltered,
+ 'latAccelOffset': cache_ltp.latAccelOffsetFiltered,
+ 'frictionCoefficient': cache_ltp.frictionCoefficientFiltered,
+ 'points': cache_ltp.points
+ }
+ self.decay = cache_ltp.decay
+ self.filtered_points.load_points(initial_params['points'])
+ cloudlog.info("restored torque params from cache")
+ except Exception:
+ cloudlog.exception("failed to restore cached torque params")
+ params.remove("LiveTorqueCarParams")
+ params.remove("LiveTorqueParameters")
+
+ self.filtered_params = {}
+ for param in initial_params:
+ self.filtered_params[param] = FirstOrderFilter(initial_params[param], self.decay, DT_MDL)
+
+ def get_restore_key(self, CP, version):
+ a, b = None, None
+ if CP.lateralTuning.which() == 'torque':
+ a = CP.lateralTuning.torque.friction
+ b = CP.lateralTuning.torque.latAccelFactor
+ return (CP.carFingerprint, CP.lateralTuning.which(), a, b, version)
+
+ def reset(self):
+ self.resets += 1.0
+ self.invalid_values_tracker = 0.0
+ self.decay = MIN_FILTER_DECAY
+ self.raw_points = defaultdict(lambda: deque(maxlen=self.hist_len))
+ self.filtered_points = PointBuckets(x_bounds=STEER_BUCKET_BOUNDS, min_points=MIN_BUCKET_POINTS)
+
+ def estimate_params(self):
+ points = self.filtered_points.get_points(FIT_POINTS_TOTAL)
+ # total least square solution as both x and y are noisy observations
+ # this is empirically the slope of the hysteresis parallelogram as opposed to the line through the diagonals
+ try:
+ _, _, v = np.linalg.svd(points, full_matrices=False)
+ slope, offset = -v.T[0:2, 2] / v.T[2, 2]
+ _, spread = np.matmul(points[:, [0, 2]], slope2rot(slope)).T
+ friction_coeff = np.std(spread) * FRICTION_FACTOR
+ except np.linalg.LinAlgError as e:
+ cloudlog.exception(f"Error computing live torque params: {e}")
+ slope = offset = friction_coeff = np.nan
+ return slope, offset, friction_coeff
+
+ def update_params(self, params):
+ self.decay = min(self.decay + DT_MDL, MAX_FILTER_DECAY)
+ for param, value in params.items():
+ self.filtered_params[param].update(value)
+ self.filtered_params[param].update_alpha(self.decay)
+
+ def is_sane(self, latAccelFactor, latAccelOffset, friction):
+ if any([val is None or np.isnan(val) for val in [latAccelFactor, latAccelOffset, friction]]):
+ return False
+ return (self.max_friction >= friction >= self.min_friction) and\
+ (self.max_lataccel_factor >= latAccelFactor >= self.min_lataccel_factor)
+
+ def handle_log(self, t, which, msg):
+ if which == "carControl":
+ self.raw_points["carControl_t"].append(t + self.lag)
+ self.raw_points["steer_torque"].append(-msg.actuatorsOutput.steer)
+ self.raw_points["active"].append(msg.latActive)
+ elif which == "carState":
+ self.raw_points["carState_t"].append(t + self.lag)
+ self.raw_points["vego"].append(msg.vEgo)
+ self.raw_points["steer_override"].append(msg.steeringPressed)
+ elif which == "liveLocationKalman":
+ if len(self.raw_points['steer_torque']) == self.hist_len:
+ yaw_rate = msg.angularVelocityCalibrated.value[2]
+ roll = msg.orientationNED.value[0]
+ active = np.interp(np.arange(t - MIN_ENGAGE_BUFFER, t, DT_MDL), self.raw_points['carControl_t'], self.raw_points['active']).astype(bool)
+ steer_override = np.interp(np.arange(t - MIN_ENGAGE_BUFFER, t, DT_MDL), self.raw_points['carState_t'], self.raw_points['steer_override']).astype(bool)
+ vego = np.interp(t, self.raw_points['carState_t'], self.raw_points['vego'])
+ steer = np.interp(t, self.raw_points['carControl_t'], self.raw_points['steer_torque'])
+ lateral_acc = (vego * yaw_rate) - (np.sin(roll) * ACCELERATION_DUE_TO_GRAVITY)
+ if all(active) and (not any(steer_override)) and (vego > MIN_VEL) and (abs(steer) > STEER_MIN_THRESHOLD) and (abs(lateral_acc) <= LAT_ACC_THRESHOLD):
+ self.filtered_points.add_point(float(steer), float(lateral_acc))
+
+ def get_msg(self, valid=True, with_points=False):
+ msg = messaging.new_message('liveTorqueParameters')
+ msg.valid = valid
+ liveTorqueParameters = msg.liveTorqueParameters
+ liveTorqueParameters.version = VERSION
+ liveTorqueParameters.useParams = self.use_params
+
+ if self.filtered_points.is_valid():
+ latAccelFactor, latAccelOffset, friction_coeff = self.estimate_params()
+ liveTorqueParameters.latAccelFactorRaw = float(latAccelFactor)
+ liveTorqueParameters.latAccelOffsetRaw = float(latAccelOffset)
+ liveTorqueParameters.frictionCoefficientRaw = float(friction_coeff)
+
+ if self.is_sane(latAccelFactor, latAccelOffset, friction_coeff):
+ liveTorqueParameters.liveValid = True
+ self.update_params({'latAccelFactor': latAccelFactor, 'latAccelOffset': latAccelOffset, 'frictionCoefficient': friction_coeff})
+ self.invalid_values_tracker = max(0.0, self.invalid_values_tracker - 0.5)
+ else:
+ cloudlog.exception("live torque params are numerically unstable")
+ liveTorqueParameters.liveValid = False
+ self.invalid_values_tracker += 1.0
+ # Reset when ~10 invalid over 5 secs
+ if self.invalid_values_tracker > MAX_INVALID_THRESHOLD:
+ # Do not reset the filter as it may cause a drastic jump, just reset points
+ self.reset()
+ else:
+ liveTorqueParameters.liveValid = False
+
+ if with_points:
+ liveTorqueParameters.points = self.filtered_points.get_points()[:, [0, 2]].tolist()
+
+ liveTorqueParameters.latAccelFactorFiltered = float(self.filtered_params['latAccelFactor'].x)
+ liveTorqueParameters.latAccelOffsetFiltered = float(self.filtered_params['latAccelOffset'].x)
+ liveTorqueParameters.frictionCoefficientFiltered = float(self.filtered_params['frictionCoefficient'].x)
+ liveTorqueParameters.totalBucketPoints = len(self.filtered_points)
+ liveTorqueParameters.decay = self.decay
+ liveTorqueParameters.maxResets = self.resets
+ return msg
+
+
+def main(sm=None, pm=None):
+ config_realtime_process([0, 1, 2, 3], 5)
+
+ if sm is None:
+ sm = messaging.SubMaster(['carControl', 'carState', 'liveLocationKalman'], poll=['liveLocationKalman'])
+
+ if pm is None:
+ pm = messaging.PubMaster(['liveTorqueParameters'])
+
+ params = Params()
+ CP = car.CarParams.from_bytes(params.get("CarParams", block=True))
+ estimator = TorqueEstimator(CP)
+
+ def cache_params(sig, frame):
+ signal.signal(sig, signal.SIG_DFL)
+ cloudlog.warning("caching torque params")
+
+ params = Params()
+ params.put("LiveTorqueCarParams", CP.as_builder().to_bytes())
+
+ msg = estimator.get_msg(with_points=True)
+ params.put("LiveTorqueParameters", msg.to_bytes())
+
+ sys.exit(0)
+ if "REPLAY" not in os.environ:
+ signal.signal(signal.SIGINT, cache_params)
+
+ while True:
+ sm.update()
+ if sm.all_checks():
+ for which in sm.updated.keys():
+ if sm.updated[which]:
+ t = sm.logMonoTime[which] * 1e-9
+ estimator.handle_log(t, which, sm[which])
+
+ # 4Hz driven by liveLocationKalman
+ if sm.frame % 5 == 0:
+ pm.send('liveTorqueParameters', estimator.get_msg(valid=sm.all_checks()))
+
+
+if __name__ == "__main__":
+ main()
diff --git a/selfdrive/manager/process_config.py b/selfdrive/manager/process_config.py
index 7702b96ea..06efdbb96 100644
--- a/selfdrive/manager/process_config.py
+++ b/selfdrive/manager/process_config.py
@@ -38,6 +38,7 @@ procs = [
NativeProcess("locationd", "selfdrive/locationd", ["./locationd"]),
NativeProcess("boardd", "selfdrive/boardd", ["./boardd"], enabled=False),
PythonProcess("calibrationd", "selfdrive.locationd.calibrationd"),
+ PythonProcess("torqued", "selfdrive.locationd.torqued"),
PythonProcess("controlsd", "selfdrive.controls.controlsd"),
PythonProcess("deleter", "selfdrive.loggerd.deleter", offroad=True),
PythonProcess("dmonitoringd", "selfdrive.monitoring.dmonitoringd", enabled=(not PC or WEBCAM), callback=driverview),
diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py
index b4e3f6265..038b0cf46 100755
--- a/selfdrive/test/process_replay/process_replay.py
+++ b/selfdrive/test/process_replay/process_replay.py
@@ -229,6 +229,15 @@ def calibration_rcv_callback(msg, CP, cfg, fsm):
return recv_socks, fsm.frame == 0 or msg.which() == 'cameraOdometry'
+def torqued_rcv_callback(msg, CP, cfg, fsm):
+ # should_recv always true to increment frame
+ recv_socks = []
+ frame = fsm.frame + 1 # incrementing hasn't happened yet in SubMaster
+ if msg.which() == 'liveLocationKalman' and (frame % 5) == 0:
+ recv_socks = ["liveTorqueParameters"]
+ return recv_socks, fsm.frame == 0 or msg.which() == 'liveLocationKalman'
+
+
def ublox_rcv_callback(msg):
msg_class, msg_id = msg.ubloxRaw[2:4]
if (msg_class, msg_id) in {(1, 7 * 16)}:
@@ -251,8 +260,10 @@ CONFIGS = [
proc_name="controlsd",
pub_sub={
"can": ["controlsState", "carState", "carControl", "sendcan", "carEvents", "carParams"],
- "deviceState": [], "pandaStates": [], "peripheralState": [], "liveCalibration": [], "driverMonitoringState": [], "longitudinalPlan": [], "lateralPlan": [], "liveLocationKalman": [], "liveParameters": [], "radarState": [],
- "modelV2": [], "driverCameraState": [], "roadCameraState": [], "wideRoadCameraState": [], "managerState": [], "testJoystick": [],
+ "deviceState": [], "pandaStates": [], "peripheralState": [], "liveCalibration": [], "driverMonitoringState": [],
+ "longitudinalPlan": [], "lateralPlan": [], "liveLocationKalman": [], "liveParameters": [], "radarState": [],
+ "modelV2": [], "driverCameraState": [], "roadCameraState": [], "wideRoadCameraState": [], "managerState": [],
+ "testJoystick": [], "liveTorqueParameters": [],
},
ignore=["logMonoTime", "valid", "controlsState.startMonoTime", "controlsState.cumLagMs"],
init_callback=fingerprint,
@@ -374,6 +385,18 @@ CONFIGS = [
tolerance=NUMPY_TOLERANCE,
fake_pubsubmaster=True,
),
+ ProcessConfig(
+ proc_name="torqued",
+ pub_sub={
+ "liveLocationKalman": ["liveTorqueParameters"],
+ "carState": [], "controlsState": [],
+ },
+ ignore=["logMonoTime"],
+ init_callback=get_car_params,
+ should_recv_callback=torqued_rcv_callback,
+ tolerance=NUMPY_TOLERANCE,
+ fake_pubsubmaster=True,
+ ),
]
diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit
index afde6ec42..7b24c04c9 100644
--- a/selfdrive/test/process_replay/ref_commit
+++ b/selfdrive/test/process_replay/ref_commit
@@ -1 +1 @@
-d14f1a61a4bfde810128a6bb703aa543268fa4a9
\ No newline at end of file
+deb07ca8c5dc021e57e81307764a84aa3d7aef32
\ No newline at end of file
diff --git a/selfdrive/test/process_replay/regen.py b/selfdrive/test/process_replay/regen.py
index 4e1cbfd30..d565e3639 100755
--- a/selfdrive/test/process_replay/regen.py
+++ b/selfdrive/test/process_replay/regen.py
@@ -269,11 +269,11 @@ def regen_segment(lr, frs=None, outdir=FAKEDATA, disable_tqdm=False):
return seg_path
-def regen_and_save(route, sidx, upload=False, use_route_meta=False, outdir=FAKEDATA, disable_tqdm=False):
+def regen_and_save(route, sidx, upload=False, use_route_meta=True, outdir=FAKEDATA, disable_tqdm=False):
if use_route_meta:
- r = Route(args.route)
- lr = LogReader(r.log_paths()[args.seg])
- fr = FrameReader(r.camera_paths()[args.seg])
+ r = Route(route)
+ lr = LogReader(r.log_paths()[sidx])
+ fr = FrameReader(r.camera_paths()[sidx])
else:
lr = LogReader(f"cd:/{route.replace('|', '/')}/{sidx}/rlog.bz2")
fr = FrameReader(f"cd:/{route.replace('|', '/')}/{sidx}/fcamera.hevc")
diff --git a/selfdrive/test/process_replay/regen_all.py b/selfdrive/test/process_replay/regen_all.py
index f10d7ea03..f69d07eb6 100755
--- a/selfdrive/test/process_replay/regen_all.py
+++ b/selfdrive/test/process_replay/regen_all.py
@@ -3,11 +3,12 @@ import argparse
import concurrent.futures
import os
import random
+import traceback
from tqdm import tqdm
from selfdrive.test.process_replay.helpers import OpenpilotPrefix
from selfdrive.test.process_replay.regen import regen_and_save
-from selfdrive.test.process_replay.test_processes import FAKEDATA, original_segments as segments
+from selfdrive.test.process_replay.test_processes import FAKEDATA, source_segments as segments
from tools.lib.route import SegmentName
@@ -16,11 +17,15 @@ def regen_job(segment, upload, disable_tqdm):
sn = SegmentName(segment[1])
fake_dongle_id = 'regen' + ''.join(random.choice('0123456789ABCDEF') for _ in range(11))
try:
- relr = regen_and_save(sn.route_name.canonical_name, sn.segment_num, upload=upload, use_route_meta=False, outdir=os.path.join(FAKEDATA, fake_dongle_id), disable_tqdm=disable_tqdm)
+ relr = regen_and_save(sn.route_name.canonical_name, sn.segment_num, upload=upload, use_route_meta=False,
+ outdir=os.path.join(FAKEDATA, fake_dongle_id), disable_tqdm=disable_tqdm)
relr = '|'.join(relr.split('/')[-2:])
return f' ("{segment[0]}", "{relr}"), '
except Exception as e:
- return f" {segment} failed: {str(e)}"
+ err = f" {segment} failed: {str(e)}"
+ err += traceback.format_exc()
+ err += "\n\n"
+ return err
if __name__ == "__main__":
diff --git a/selfdrive/test/process_replay/test_processes.py b/selfdrive/test/process_replay/test_processes.py
index 0f118971c..ee892a2fd 100755
--- a/selfdrive/test/process_replay/test_processes.py
+++ b/selfdrive/test/process_replay/test_processes.py
@@ -15,22 +15,22 @@ from system.version import get_commit
from tools.lib.filereader import FileReader
from tools.lib.logreader import LogReader
-original_segments = [
+source_segments = [
("BODY", "937ccb7243511b65|2022-05-24--16-03-09--1"), # COMMA.BODY
("HYUNDAI", "02c45f73a2e5c6e9|2021-01-01--19-08-22--1"), # HYUNDAI.SONATA
- ("HYUNDAI", "d824e27e8c60172c|2022-08-19--17-58-07--2"), # HYUNDAI.KIA_EV6
+ ("HYUNDAI", "d824e27e8c60172c|2022-09-13--11-26-50--2"), # 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
("HONDA", "eb140f119469d9ab|2021-06-12--10-46-24--27"), # HONDA.CIVIC (NIDEC)
("HONDA2", "7d2244f34d1bbcda|2021-06-25--12-25-37--26"), # HONDA.ACCORD (BOSCH)
("CHRYSLER", "4deb27de11bee626|2021-02-20--11-28-55--8"), # CHRYSLER.PACIFICA
- ("RAM", "2f4452b03ccb98f0|2022-07-07--08-01-56--3"), # CHRYSLER.RAM_1500
- ("SUBARU", "4d70bc5e608678be|2021-01-15--17-02-04--5"), # SUBARU.IMPREZA
+ ("RAM", "2f4452b03ccb98f0|2022-09-07--13-55-08--10"), # CHRYSLER.RAM_1500
+ ("SUBARU", "341dccd5359e3c97|2022-09-12--10-35-33--3"), # SUBARU.OUTBACK
("GM", "0c58b6a25109da2b|2021-02-23--16-35-50--11"), # GM.VOLT
("NISSAN", "35336926920f3571|2021-02-12--18-38-48--46"), # NISSAN.XTRAIL
("VOLKSWAGEN", "de9592456ad7d144|2021-06-29--11-00-15--6"), # VOLKSWAGEN.GOLF
- ("MAZDA", "bd6a637565e91581|2021-10-30--15-14-53--2"), # MAZDA.CX9_2021
+ ("MAZDA", "bd6a637565e91581|2021-10-30--15-14-53--4"), # MAZDA.CX9_2021
# Enable when port is tested and dashcamOnly is no longer set
#("TESLA", "bb50caf5f0945ab1|2021-06-19--17-20-18--3"), # TESLA.AP2_MODELS
diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py
index 55e1ef161..b29ca5d35 100755
--- a/selfdrive/test/test_onroad.py
+++ b/selfdrive/test/test_onroad.py
@@ -36,6 +36,7 @@ PROCS = {
"./_dmonitoringmodeld": 5.0,
"selfdrive.thermald.thermald": 3.87,
"selfdrive.locationd.calibrationd": 2.0,
+ "selfdrive.locationd.torqued": 5.0,
"./_soundd": 1.0,
"selfdrive.monitoring.dmonitoringd": 4.0,
"./proclogd": 1.54,
diff --git a/selfdrive/test/update_ci_routes.py b/selfdrive/test/update_ci_routes.py
index 99a63b8df..a1e8c35f6 100755
--- a/selfdrive/test/update_ci_routes.py
+++ b/selfdrive/test/update_ci_routes.py
@@ -4,7 +4,7 @@ import subprocess
from azure.storage.blob import BlockBlobService # pylint: disable=import-error
from selfdrive.car.tests.routes import routes as test_car_models_routes
-from selfdrive.test.process_replay.test_processes import original_segments as replay_segments
+from selfdrive.test.process_replay.test_processes import source_segments as replay_segments
from xx.chffr.lib import azureutil # pylint: disable=import-error
from xx.chffr.lib.storage import _DATA_ACCOUNT_PRODUCTION, _DATA_ACCOUNT_CI, _DATA_BUCKET_PRODUCTION # pylint: disable=import-error
From 805a54ad0f24b64bb1253f5aeed6e5b99c3f842e Mon Sep 17 00:00:00 2001
From: Adeeb Shihadeh
Date: Mon, 19 Sep 2022 17:41:37 -0700
Subject: [PATCH 38/75] updated: commits are always strings
---
selfdrive/updated.py | 2 +-
1 file changed, 1 insertion(+), 1 deletion(-)
diff --git a/selfdrive/updated.py b/selfdrive/updated.py
index 79b759a90..fc51ae799 100755
--- a/selfdrive/updated.py
+++ b/selfdrive/updated.py
@@ -240,7 +240,7 @@ def handle_agnos_update() -> None:
class Updater:
def __init__(self):
self.params = Params()
- self.branches = defaultdict(lambda: None)
+ self.branches = defaultdict(lambda: '')
@property
def target_branch(self) -> str:
From de1882429a20e4d7fd37cdcaf67e54b3649a7fde Mon Sep 17 00:00:00 2001
From: Adeeb Shihadeh
Date: Mon, 19 Sep 2022 20:40:03 -0700
Subject: [PATCH 39/75] update release notes
---
RELEASES.md | 8 ++++++--
1 file changed, 6 insertions(+), 2 deletions(-)
diff --git a/RELEASES.md b/RELEASES.md
index a749158cb..5ef2acdd4 100644
--- a/RELEASES.md
+++ b/RELEASES.md
@@ -2,8 +2,12 @@ Version 0.8.17 (2022-XX-XX)
========================
* New driving model
* Internal feature space accuracy increased tenfold during training, this makes the model dramatically more accurate.
-* torqued
- * Learn torque parameters live for each car as opposed to using platform average values, which improves lateral control
+* Self-tuning torque lateral controller parameters
+ * Parameters are learned live for each car
+ * Enabled only on Toyota Corolla for now
+* UI updates
+ * Matched speeds shown on car's dash
+ * Improved update experience
Version 0.8.16 (2022-08-26)
========================
From d1c95fb0d4e87c35f5eb8b425de0c054da93a3a0 Mon Sep 17 00:00:00 2001
From: Adeeb Shihadeh
Date: Mon, 19 Sep 2022 20:43:12 -0700
Subject: [PATCH 40/75] add event flagging too
---
RELEASES.md | 1 +
1 file changed, 1 insertion(+)
diff --git a/RELEASES.md b/RELEASES.md
index 5ef2acdd4..6edd900cb 100644
--- a/RELEASES.md
+++ b/RELEASES.md
@@ -8,6 +8,7 @@ Version 0.8.17 (2022-XX-XX)
* UI updates
* Matched speeds shown on car's dash
* Improved update experience
+ * Added button to flag events that are shown in comma connect
Version 0.8.16 (2022-08-26)
========================
From bcf31aea07c26099aa861ab93c5586e645a25928 Mon Sep 17 00:00:00 2001
From: Kurt Nistelberger
Date: Mon, 19 Sep 2022 21:01:32 -0700
Subject: [PATCH 41/75] sensord: move sensors in lowest power mode on exit/kill
(#25787)
* add low power modes
* add sleep to lsm gyro init
* bmx055 gyro has a 30ms wakeup time from deep suspend
* Sensord skip init values, first 500ms (#25775)
* remove lsm gyro sleep, handled by general cut
Co-authored-by: Kurt Nistelberger
---
selfdrive/sensord/sensors/bmx055_accel.cc | 18 +++++++++++++
selfdrive/sensord/sensors/bmx055_accel.h | 5 +++-
selfdrive/sensord/sensors/bmx055_gyro.cc | 18 +++++++++++++
selfdrive/sensord/sensors/bmx055_gyro.h | 5 +++-
selfdrive/sensord/sensors/bmx055_magn.cc | 10 ++++++++
selfdrive/sensord/sensors/bmx055_magn.h | 2 +-
selfdrive/sensord/sensors/lsm6ds3_accel.cc | 17 +++++++++++--
selfdrive/sensord/sensors/lsm6ds3_gyro.cc | 17 +++++++++++--
selfdrive/sensord/sensors/mmc5603nj_magn.cc | 28 +++++++++++++++++++++
selfdrive/sensord/sensors/mmc5603nj_magn.h | 2 +-
selfdrive/sensord/sensors_qcom2.cc | 17 +++++++++++++
11 files changed, 131 insertions(+), 8 deletions(-)
diff --git a/selfdrive/sensord/sensors/bmx055_accel.cc b/selfdrive/sensord/sensors/bmx055_accel.cc
index e191d0d72..c6dcdbd7a 100644
--- a/selfdrive/sensord/sensors/bmx055_accel.cc
+++ b/selfdrive/sensord/sensors/bmx055_accel.cc
@@ -4,6 +4,7 @@
#include "common/swaglog.h"
#include "common/timing.h"
+#include "common/util.h"
BMX055_Accel::BMX055_Accel(I2CBus *bus) : I2CSensor(bus) {}
@@ -23,6 +24,13 @@ int BMX055_Accel::init() {
goto fail;
}
+ ret = set_register(BMX055_ACCEL_I2C_REG_PMU, BMX055_ACCEL_NORMAL_MODE);
+ if (ret < 0) {
+ goto fail;
+ }
+ // bmx055 accel has a 1.3ms wakeup time from deep suspend mode
+ util::sleep_for(10);
+
// High bandwidth
// ret = set_register(BMX055_ACCEL_I2C_REG_HBW, BMX055_ACCEL_HBW_ENABLE);
// if (ret < 0) {
@@ -43,6 +51,16 @@ fail:
return ret;
}
+int BMX055_Accel::shutdown() {
+ // enter deep suspend mode (lowest power mode)
+ int ret = set_register(BMX055_ACCEL_I2C_REG_PMU, BMX055_ACCEL_DEEP_SUSPEND);
+ if (ret < 0) {
+ LOGE("Could not move BMX055 ACCEL in deep suspend mode!")
+ }
+
+ return ret;
+}
+
bool BMX055_Accel::get_event(cereal::SensorEventData::Builder &event) {
uint64_t start_time = nanos_since_boot();
uint8_t buffer[6];
diff --git a/selfdrive/sensord/sensors/bmx055_accel.h b/selfdrive/sensord/sensors/bmx055_accel.h
index 3b6dd536a..6a0f9f1ad 100644
--- a/selfdrive/sensord/sensors/bmx055_accel.h
+++ b/selfdrive/sensord/sensors/bmx055_accel.h
@@ -10,6 +10,7 @@
#define BMX055_ACCEL_I2C_REG_X_LSB 0x02
#define BMX055_ACCEL_I2C_REG_TEMP 0x08
#define BMX055_ACCEL_I2C_REG_BW 0x10
+#define BMX055_ACCEL_I2C_REG_PMU 0x11
#define BMX055_ACCEL_I2C_REG_HBW 0x13
#define BMX055_ACCEL_I2C_REG_FIFO 0x3F
@@ -18,6 +19,8 @@
#define BMX055_ACCEL_HBW_ENABLE 0b10000000
#define BMX055_ACCEL_HBW_DISABLE 0b00000000
+#define BMX055_ACCEL_DEEP_SUSPEND 0b00100000
+#define BMX055_ACCEL_NORMAL_MODE 0b00000000
#define BMX055_ACCEL_BW_7_81HZ 0b01000
#define BMX055_ACCEL_BW_15_63HZ 0b01001
@@ -34,5 +37,5 @@ public:
BMX055_Accel(I2CBus *bus);
int init();
bool get_event(cereal::SensorEventData::Builder &event);
- int shutdown() { return 0; }
+ int shutdown();
};
diff --git a/selfdrive/sensord/sensors/bmx055_gyro.cc b/selfdrive/sensord/sensors/bmx055_gyro.cc
index a7ed8deba..4deb15ec6 100644
--- a/selfdrive/sensord/sensors/bmx055_gyro.cc
+++ b/selfdrive/sensord/sensors/bmx055_gyro.cc
@@ -4,6 +4,7 @@
#include
#include "common/swaglog.h"
+#include "common/util.h"
#define DEG2RAD(x) ((x) * M_PI / 180.0)
@@ -26,6 +27,13 @@ int BMX055_Gyro::init() {
goto fail;
}
+ ret = set_register(BMX055_GYRO_I2C_REG_LPM1, BMX055_GYRO_NORMAL_MODE);
+ if (ret < 0) {
+ goto fail;
+ }
+ // bmx055 gyro has a 30ms wakeup time from deep suspend mode
+ util::sleep_for(50);
+
// High bandwidth
// ret = set_register(BMX055_GYRO_I2C_REG_HBW, BMX055_GYRO_HBW_ENABLE);
// if (ret < 0) {
@@ -54,6 +62,16 @@ fail:
return ret;
}
+int BMX055_Gyro::shutdown() {
+ // enter deep suspend mode (lowest power mode)
+ int ret = set_register(BMX055_GYRO_I2C_REG_LPM1, BMX055_GYRO_DEEP_SUSPEND);
+ if (ret < 0) {
+ LOGE("Could not move BMX055 GYRO in deep suspend mode!")
+ }
+
+ return ret;
+}
+
bool BMX055_Gyro::get_event(cereal::SensorEventData::Builder &event) {
uint64_t start_time = nanos_since_boot();
uint8_t buffer[6];
diff --git a/selfdrive/sensord/sensors/bmx055_gyro.h b/selfdrive/sensord/sensors/bmx055_gyro.h
index fea6c3e19..ac5dacc4a 100644
--- a/selfdrive/sensord/sensors/bmx055_gyro.h
+++ b/selfdrive/sensord/sensors/bmx055_gyro.h
@@ -10,6 +10,7 @@
#define BMX055_GYRO_I2C_REG_RATE_X_LSB 0x02
#define BMX055_GYRO_I2C_REG_RANGE 0x0F
#define BMX055_GYRO_I2C_REG_BW 0x10
+#define BMX055_GYRO_I2C_REG_LPM1 0x11
#define BMX055_GYRO_I2C_REG_HBW 0x13
#define BMX055_GYRO_I2C_REG_FIFO 0x3F
@@ -18,6 +19,8 @@
#define BMX055_GYRO_HBW_ENABLE 0b10000000
#define BMX055_GYRO_HBW_DISABLE 0b00000000
+#define BMX055_GYRO_DEEP_SUSPEND 0b00100000
+#define BMX055_GYRO_NORMAL_MODE 0b00000000
#define BMX055_GYRO_RANGE_2000 0b000
#define BMX055_GYRO_RANGE_1000 0b001
@@ -34,5 +37,5 @@ public:
BMX055_Gyro(I2CBus *bus);
int init();
bool get_event(cereal::SensorEventData::Builder &event);
- int shutdown() { return 0; }
+ int shutdown();
};
diff --git a/selfdrive/sensord/sensors/bmx055_magn.cc b/selfdrive/sensord/sensors/bmx055_magn.cc
index 9ba6cebd5..74e18b7c8 100644
--- a/selfdrive/sensord/sensors/bmx055_magn.cc
+++ b/selfdrive/sensord/sensors/bmx055_magn.cc
@@ -155,6 +155,16 @@ int BMX055_Magn::init() {
return ret;
}
+int BMX055_Magn::shutdown() {
+ // move to suspend mode
+ int ret = set_register(BMX055_MAGN_I2C_REG_PWR_0, 0);
+ if (ret < 0) {
+ LOGE("Could not move BMX055 MAGN in suspend mode!")
+ }
+
+ return ret;
+}
+
bool BMX055_Magn::perform_self_test() {
uint8_t buffer[8];
int16_t x, y;
diff --git a/selfdrive/sensord/sensors/bmx055_magn.h b/selfdrive/sensord/sensors/bmx055_magn.h
index c762f2c3b..0549e163f 100644
--- a/selfdrive/sensord/sensors/bmx055_magn.h
+++ b/selfdrive/sensord/sensors/bmx055_magn.h
@@ -60,5 +60,5 @@ public:
BMX055_Magn(I2CBus *bus);
int init();
bool get_event(cereal::SensorEventData::Builder &event);
- int shutdown() { return 0; }
+ int shutdown();
};
diff --git a/selfdrive/sensord/sensors/lsm6ds3_accel.cc b/selfdrive/sensord/sensors/lsm6ds3_accel.cc
index 8cc89e457..513125fd5 100644
--- a/selfdrive/sensord/sensors/lsm6ds3_accel.cc
+++ b/selfdrive/sensord/sensors/lsm6ds3_accel.cc
@@ -71,12 +71,25 @@ int LSM6DS3_Accel::shutdown() {
value &= ~(LSM6DS3_ACCEL_INT1_DRDY_XL);
ret = set_register(LSM6DS3_ACCEL_I2C_REG_INT1_CTRL, value);
if (ret < 0) {
+ LOGE("Could not disable lsm6ds3 acceleration interrupt!")
+ goto fail;
+ }
+
+ // enable power-down mode
+ value = 0;
+ ret = read_register(LSM6DS3_ACCEL_I2C_REG_CTRL1_XL, &value, 1);
+ if (ret < 0) {
+ goto fail;
+ }
+
+ value &= 0x0F;
+ ret = set_register(LSM6DS3_ACCEL_I2C_REG_CTRL1_XL, value);
+ if (ret < 0) {
+ LOGE("Could not power-down lsm6ds3 accelerometer!")
goto fail;
}
- return ret;
fail:
- LOGE("Could not disable lsm6ds3 acceleration interrupt!")
return ret;
}
diff --git a/selfdrive/sensord/sensors/lsm6ds3_gyro.cc b/selfdrive/sensord/sensors/lsm6ds3_gyro.cc
index a7321e8fa..fd0436a5f 100644
--- a/selfdrive/sensord/sensors/lsm6ds3_gyro.cc
+++ b/selfdrive/sensord/sensors/lsm6ds3_gyro.cc
@@ -74,12 +74,25 @@ int LSM6DS3_Gyro::shutdown() {
value &= ~(LSM6DS3_GYRO_INT1_DRDY_G);
ret = set_register(LSM6DS3_GYRO_I2C_REG_INT1_CTRL, value);
if (ret < 0) {
+ LOGE("Could not disable lsm6ds3 gyroscope interrupt!")
+ goto fail;
+ }
+
+ // enable power-down mode
+ value = 0;
+ ret = read_register(LSM6DS3_GYRO_I2C_REG_CTRL2_G, &value, 1);
+ if (ret < 0) {
+ goto fail;
+ }
+
+ value &= 0x0F;
+ ret = set_register(LSM6DS3_GYRO_I2C_REG_CTRL2_G, value);
+ if (ret < 0) {
+ LOGE("Could not power-down lsm6ds3 gyroscope!")
goto fail;
}
- return ret;
fail:
- LOGE("Could not disable lsm6ds3 gyroscope interrupt!")
return ret;
}
diff --git a/selfdrive/sensord/sensors/mmc5603nj_magn.cc b/selfdrive/sensord/sensors/mmc5603nj_magn.cc
index 2bfd887a7..8af4956ed 100644
--- a/selfdrive/sensord/sensors/mmc5603nj_magn.cc
+++ b/selfdrive/sensord/sensors/mmc5603nj_magn.cc
@@ -51,6 +51,34 @@ fail:
return ret;
}
+int MMC5603NJ_Magn::shutdown() {
+ int ret = 0;
+
+ // disable auto reset of measurements
+ uint8_t value = 0;
+ ret = read_register(MMC5603NJ_I2C_REG_INTERNAL_0, &value, 1);
+ if (ret < 0) {
+ goto fail;
+ }
+
+ value &= ~(MMC5603NJ_CMM_FREQ_EN | MMC5603NJ_AUTO_SR_EN);
+ ret = set_register(MMC5603NJ_I2C_REG_INTERNAL_0, value);
+ if (ret < 0) {
+ goto fail;
+ }
+
+ // set ODR to 0 to leave continuous mode
+ ret = set_register(MMC5603NJ_I2C_REG_ODR, 0);
+ if (ret < 0) {
+ goto fail;
+ }
+ return ret;
+
+fail:
+ LOGE("Could not disable mmc5603nj auto set reset")
+ return ret;
+}
+
bool MMC5603NJ_Magn::get_event(cereal::SensorEventData::Builder &event) {
uint64_t start_time = nanos_since_boot();
diff --git a/selfdrive/sensord/sensors/mmc5603nj_magn.h b/selfdrive/sensord/sensors/mmc5603nj_magn.h
index 857bd10a5..2c06cab96 100644
--- a/selfdrive/sensord/sensors/mmc5603nj_magn.h
+++ b/selfdrive/sensord/sensors/mmc5603nj_magn.h
@@ -26,5 +26,5 @@ public:
MMC5603NJ_Magn(I2CBus *bus);
int init();
bool get_event(cereal::SensorEventData::Builder &event);
- int shutdown() { return 0; }
+ int shutdown();
};
diff --git a/selfdrive/sensord/sensors_qcom2.cc b/selfdrive/sensord/sensors_qcom2.cc
index aaf79592c..ded4b5c0b 100644
--- a/selfdrive/sensord/sensors_qcom2.cc
+++ b/selfdrive/sensord/sensors_qcom2.cc
@@ -28,6 +28,10 @@
ExitHandler do_exit;
std::mutex pm_mutex;
+// filter first values (0.5sec) as those may contain inaccuracies
+uint64_t init_ts = 0;
+constexpr uint64_t init_delay = 500*1e6;
+
void interrupt_loop(int fd, std::vector& sensors, PubMaster& pm) {
struct pollfd fd_list[1] = {0};
fd_list[0].fd = fd;
@@ -88,6 +92,10 @@ void interrupt_loop(int fd, std::vector& sensors, PubMaster& pm) {
events.adoptWithCaveats(i, kj::mv(collected_events[i]));
}
+ if (ts - init_ts < init_delay) {
+ continue;
+ }
+
std::lock_guard lock(pm_mutex);
pm.send("sensorEvents", msg);
}
@@ -167,6 +175,7 @@ int sensor_loop() {
}
PubMaster pm({"sensorEvents"});
+ init_ts = nanos_since_boot();
// thread for reading events via interrupts
std::vector lsm_interrupt_sensors = {&lsm6ds3_accel, &lsm6ds3_gyro};
@@ -185,6 +194,10 @@ int sensor_loop() {
sensors[i]->get_event(event);
}
+ if (nanos_since_boot() - init_ts < init_delay) {
+ continue;
+ }
+
{
std::lock_guard lock(pm_mutex);
pm.send("sensorEvents", msg);
@@ -194,6 +207,10 @@ int sensor_loop() {
std::this_thread::sleep_for(std::chrono::milliseconds(10) - (end - begin));
}
+ for (Sensor *sensor : sensors) {
+ sensor->shutdown();
+ }
+
lsm_interrupt_thread.join();
delete i2c_bus_imu;
return 0;
From fc29147d027e44bebc8c3e74e8798281795d2b84 Mon Sep 17 00:00:00 2001
From: Adeeb Shihadeh
Date: Mon, 19 Sep 2022 21:21:56 -0700
Subject: [PATCH 42/75] Update RELEASES.md
---
RELEASES.md | 1 +
1 file changed, 1 insertion(+)
diff --git a/RELEASES.md b/RELEASES.md
index 6edd900cb..9a43e642d 100644
--- a/RELEASES.md
+++ b/RELEASES.md
@@ -8,6 +8,7 @@ Version 0.8.17 (2022-XX-XX)
* UI updates
* Matched speeds shown on car's dash
* Improved update experience
+ * Border turns grey while overriding steering
* Added button to flag events that are shown in comma connect
Version 0.8.16 (2022-08-26)
From 6561c0ca7306a92c4a3b2e037b7e33dde3d8bbf2 Mon Sep 17 00:00:00 2001
From: Shane Smiskol
Date: Mon, 19 Sep 2022 22:05:02 -0700
Subject: [PATCH 43/75] Kia Optima: we support 2020, update packages
LDWS comes in the same trim/package as ASCC
---
docs/CARS.md | 6 +++---
selfdrive/car/hyundai/values.py | 10 +++++-----
2 files changed, 8 insertions(+), 8 deletions(-)
diff --git a/docs/CARS.md b/docs/CARS.md
index 9df3b803d..d65c27d5b 100644
--- a/docs/CARS.md
+++ b/docs/CARS.md
@@ -93,10 +93,10 @@ A supported vehicle is one that just works when you install a comma three. All s
|Kia|Niro Hybrid 2021|Smart Cruise Control (SCC) & LKAS|openpilot|0 mph|0 mph|[](##)|[](##)|Hyundai F|
|Kia|Niro Hybrid 2022|Smart Cruise Control (SCC) & LKAS|openpilot|0 mph|0 mph|[](##)|[](##)|Hyundai H|
|Kia|Niro Plug-in Hybrid 2018-19|All|openpilot|10 mph|32 mph|[](##)|[](##)|Hyundai C|
-|Kia|Optima 2017|Advanced Smart Cruise Control & LDWS|Stock|0 mph|32 mph|[](##)|[](##)|Hyundai B|
-|Kia|Optima 2019|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai G|
+|Kia|Optima 2017|Advanced Smart Cruise Control|Stock|0 mph|32 mph|[](##)|[](##)|Hyundai B|
+|Kia|Optima 2019-20|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai G|
|Kia|Seltos 2021|Smart Cruise Control (SCC) & LKAS|openpilot|0 mph|0 mph|[](##)|[](##)|Hyundai A|
-|Kia|Sorento 2018|Advanced Smart Cruise Control & LDWS|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai C|
+|Kia|Sorento 2018|Advanced Smart Cruise Control|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai C|
|Kia|Sorento 2019|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai E|
|Kia|Stinger 2018-20|Smart Cruise Control (SCC) & LKAS|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai C|
|Kia|Telluride 2020|All|openpilot|0 mph|0 mph|[](##)|[](##)|Hyundai H|
diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py
index ea6fca592..f3e45873a 100644
--- a/selfdrive/car/hyundai/values.py
+++ b/selfdrive/car/hyundai/values.py
@@ -157,16 +157,16 @@ CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = {
HyundaiCarInfo("Kia Niro Hybrid 2022", harness=Harness.hyundai_h),
],
CAR.KIA_OPTIMA: [
- HyundaiCarInfo("Kia Optima 2017", "Advanced Smart Cruise Control & LDWS", min_steer_speed=32. * CV.MPH_TO_MS, harness=Harness.hyundai_b),
- HyundaiCarInfo("Kia Optima 2019", "Smart Cruise Control (SCC)", harness=Harness.hyundai_g),
+ HyundaiCarInfo("Kia Optima 2017", "Advanced Smart Cruise Control", min_steer_speed=32. * CV.MPH_TO_MS, harness=Harness.hyundai_b),
+ HyundaiCarInfo("Kia Optima 2019-20", "Smart Cruise Control (SCC)", harness=Harness.hyundai_g),
],
CAR.KIA_OPTIMA_H: [
- HyundaiCarInfo("Kia Optima Hybrid 2017", "Advanced Smart Cruise Control & LDWS"), # TODO: info may be incorrect
- HyundaiCarInfo("Kia Optima Hybrid 2019"),
+ HyundaiCarInfo("Kia Optima Hybrid 2017", "Advanced Smart Cruise Control"), # TODO: may support adjacent years
+ HyundaiCarInfo("Kia Optima Hybrid 2019", "Smart Cruise Control (SCC)"),
],
CAR.KIA_SELTOS: HyundaiCarInfo("Kia Seltos 2021", harness=Harness.hyundai_a),
CAR.KIA_SORENTO: [
- HyundaiCarInfo("Kia Sorento 2018", "Advanced Smart Cruise Control & LDWS", video_link="https://www.youtube.com/watch?v=Fkh3s6WHJz8", harness=Harness.hyundai_c),
+ HyundaiCarInfo("Kia Sorento 2018", "Advanced Smart Cruise Control", video_link="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_STINGER: HyundaiCarInfo("Kia Stinger 2018-20", video_link="https://www.youtube.com/watch?v=MJ94qoofYw0", harness=Harness.hyundai_c),
From 2c9f751616d01a695968150c0edccc57cc2f6d4f Mon Sep 17 00:00:00 2001
From: Shane Smiskol
Date: Mon, 19 Sep 2022 23:33:59 -0700
Subject: [PATCH 44/75] Optima: split into two platforms (#24815)
* Add missing fw versions for 2019 Optima
* move versions to new platform
* add temp fw version notes
temp notes
* clean up
* Update docs
* add fw versions from the last 180 days
* add tests
* fix
* remove FPv1 for Optima
* seems like the 2016 is the same
* revert
* add versions from our 2019 Optima
* label/move some versions
* add some versions from a 2020! (3d96bd05b5513638)
* this is from the same 2017 as earlier
(4f930156368f7830)
* vin lookup isn't perfect
* Revert "vin lookup isn't perfect"
This reverts commit 62c563bc4549b37160254d45bb90fcbc1f6cd589.
* a 2020 (df71aec6e636d7e4)
* cleanup, this transmission is also a 2020 version
df71aec6e636d7e4|2021-10-07--17-59-28
* this comes with scc
* one line
* revert
* bump panda
* add our transmission FW
* Add test route
---
panda | 2 +-
selfdrive/car/hyundai/hyundaican.py | 2 +-
selfdrive/car/hyundai/interface.py | 4 +-
selfdrive/car/hyundai/values.py | 46 ++++++++++++++---------
selfdrive/car/tests/routes.py | 1 +
selfdrive/car/torque_data/substitute.yaml | 3 +-
6 files changed, 37 insertions(+), 21 deletions(-)
diff --git a/panda b/panda
index 046fd58e8..11ea11225 160000
--- a/panda
+++ b/panda
@@ -1 +1 @@
-Subproject commit 046fd58e8d64c58ed80769fcbec5ac2417a04c71
+Subproject commit 11ea112258b66a0969fa340cd5e2d870378e5c5d
diff --git a/selfdrive/car/hyundai/hyundaican.py b/selfdrive/car/hyundai/hyundaican.py
index df5cb6ae6..b3e1aa6b6 100644
--- a/selfdrive/car/hyundai/hyundaican.py
+++ b/selfdrive/car/hyundai/hyundaican.py
@@ -38,7 +38,7 @@ def create_lkas11(packer, frame, car_fingerprint, apply_steer, steer_req,
values["CF_Lkas_SysWarning"] = 4 if sys_warning else 0
# Likely cars lacking the ability to show individual lane lines in the dash
- elif car_fingerprint in (CAR.KIA_OPTIMA,):
+ elif car_fingerprint in (CAR.KIA_OPTIMA, CAR.KIA_OPTIMA_2019):
# SysWarning 4 = keep hands on wheel + beep
values["CF_Lkas_SysWarning"] = 4 if sys_warning else 0
diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py
index c32cfbeec..97c1f7a5d 100644
--- a/selfdrive/car/hyundai/interface.py
+++ b/selfdrive/car/hyundai/interface.py
@@ -202,11 +202,13 @@ class CarInterface(CarInterfaceBase):
ret.lateralTuning.indi.timeConstantV = [1.4]
ret.lateralTuning.indi.actuatorEffectivenessBP = [0.]
ret.lateralTuning.indi.actuatorEffectivenessV = [1.8]
- elif candidate in (CAR.KIA_OPTIMA, CAR.KIA_OPTIMA_H):
+ elif candidate in (CAR.KIA_OPTIMA, CAR.KIA_OPTIMA_2019, CAR.KIA_OPTIMA_H):
ret.mass = 3558. * CV.LB_TO_KG
ret.wheelbase = 2.80
ret.steerRatio = 13.75
tire_stiffness_factor = 0.5
+ if candidate == CAR.KIA_OPTIMA:
+ ret.minSteerSpeed = 32 * CV.MPH_TO_MS
CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning)
elif candidate == CAR.KIA_STINGER:
ret.lateralTuning.pid.kf = 0.00005
diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py
index f3e45873a..3afae91e7 100644
--- a/selfdrive/car/hyundai/values.py
+++ b/selfdrive/car/hyundai/values.py
@@ -85,7 +85,8 @@ class CAR:
KIA_NIRO_EV = "KIA NIRO EV 2020"
KIA_NIRO_PHEV = "KIA NIRO HYBRID 2019"
KIA_NIRO_HEV_2021 = "KIA NIRO HYBRID 2021"
- KIA_OPTIMA = "KIA OPTIMA SX 2019 & 2016"
+ KIA_OPTIMA = "KIA OPTIMA 2016"
+ KIA_OPTIMA_2019 = "KIA OPTIMA 2019"
KIA_OPTIMA_H = "KIA OPTIMA HYBRID 2017 & SPORTS 2019"
KIA_SELTOS = "KIA SELTOS 2021"
KIA_SORENTO = "KIA SORENTO GT LINE 2018"
@@ -156,10 +157,8 @@ CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = {
HyundaiCarInfo("Kia Niro Hybrid 2021", harness=Harness.hyundai_f), # TODO: could be hyundai_d, verify
HyundaiCarInfo("Kia Niro Hybrid 2022", harness=Harness.hyundai_h),
],
- CAR.KIA_OPTIMA: [
- HyundaiCarInfo("Kia Optima 2017", "Advanced Smart Cruise Control", min_steer_speed=32. * CV.MPH_TO_MS, harness=Harness.hyundai_b),
- HyundaiCarInfo("Kia Optima 2019-20", "Smart Cruise Control (SCC)", harness=Harness.hyundai_g),
- ],
+ CAR.KIA_OPTIMA: HyundaiCarInfo("Kia Optima 2017", "Advanced Smart Cruise Control", harness=Harness.hyundai_b), # TODO: may support 2016, 2018
+ CAR.KIA_OPTIMA_2019: HyundaiCarInfo("Kia Optima 2019-20", "Smart Cruise Control (SCC)", harness=Harness.hyundai_g),
CAR.KIA_OPTIMA_H: [
HyundaiCarInfo("Kia Optima Hybrid 2017", "Advanced Smart Cruise Control"), # TODO: may support adjacent years
HyundaiCarInfo("Kia Optima Hybrid 2019", "Smart Cruise Control (SCC)"),
@@ -230,9 +229,6 @@ FINGERPRINTS = {
CAR.SONATA_LF: [
{66: 8, 67: 8, 68: 8, 127: 8, 273: 8, 274: 8, 275: 8, 339: 8, 356: 4, 399: 8, 447: 8, 512: 6, 544: 8, 593: 8, 608: 8, 688: 5, 790: 8, 809: 8, 832: 8, 884: 8, 897: 8, 899: 8, 902: 8, 903: 6, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1151: 6, 1168: 7, 1170: 8, 1253: 8, 1254: 8, 1255: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1314: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1342: 6, 1345: 8, 1348: 8, 1349: 8, 1351: 8, 1353: 8, 1363: 8, 1365: 8, 1366: 8, 1367: 8, 1369: 8, 1397: 8, 1407: 8, 1415: 8, 1419: 8, 1425: 2, 1427: 6, 1440: 8, 1456: 4, 1470: 8, 1472: 8, 1486: 8, 1487: 8, 1491: 8, 1530: 8, 1532: 5, 2000: 8, 2001: 8, 2004: 8, 2005: 8, 2008: 8, 2009: 8, 2012: 8, 2013: 8, 2014: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8},
],
- CAR.KIA_OPTIMA: [{
- 64: 8, 66: 8, 67: 8, 68: 8, 127: 8, 128: 8, 129: 8, 273: 8, 274: 8, 275: 8, 339: 8, 354: 3, 356: 4, 399: 8, 447: 8, 512: 6, 544: 8, 558: 8, 593: 8, 608: 8, 640: 8, 688: 5, 790: 8, 809: 8, 832: 8, 884: 8, 897: 8, 899: 8, 902: 8, 903: 6, 909: 8, 912: 7, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1151: 6, 1168: 7, 1170: 8, 1186: 2, 1191: 2, 1253: 8, 1254: 8, 1255: 8, 1265: 4, 1268: 8, 1280: 1, 1282: 4, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1342: 6, 1345: 8, 1348: 8, 1349: 8, 1351: 8, 1353: 8, 1356: 8, 1363: 8, 1365: 8, 1366: 8, 1367: 8, 1369: 8, 1407: 8, 1414: 3, 1415: 8, 1419: 8, 1425: 2, 1427: 6, 1440: 8, 1456: 4, 1470: 8, 1472: 8, 1486: 8, 1487: 8, 1491: 8, 1492: 8, 1530: 8, 1532: 5, 1792: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 1988: 8, 1996: 8, 2000: 8, 2001: 8, 2004: 8, 2008: 8, 2009: 8, 2012: 8, 2015: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8, 1371: 8, 1397: 8, 1961: 8
- }],
CAR.KIA_SORENTO: [{
67: 8, 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1064: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1168: 7, 1170: 8, 1173: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1370: 8, 1371: 8, 1384: 8, 1407: 8, 1411: 8, 1419: 8, 1425: 2, 1427: 6, 1444: 8, 1456: 4, 1470: 8, 1489: 1
}],
@@ -1144,25 +1140,40 @@ FW_VERSIONS = {
},
CAR.KIA_OPTIMA: {
(Ecu.fwdRadar, 0x7d0, None): [
- b'\xf1\x00JF__ SCC F-CUP 1.00 1.00 96400-D4110 ',
+ b'\xf1\x00JF__ SCC F-CUP 1.00 1.00 96400-D4100 ',
],
(Ecu.abs, 0x7d1, None): [
- b'\xf1\x00JF ESC \x0b 11 \x18\x030 58920-D5180',
+ b'\xf1\x00JF ESC \x0f 16 \x16\x06\x17 58920-D5080',
],
- (Ecu.engine, 0x7e0, None): [
- b'\xf1\x89F1JF600AISEIU702\xf1\x82F1JF600AISEIU702',
+ (Ecu.fwdCamera, 0x7c4, None): [
+ b'\xf1\x00JFWGN LDWS AT USA LHD 1.00 1.02 95895-D4100 G21',
],
- (Ecu.eps, 0x7d4, None): [
- b'\xf1\x00TM MDPS C 1.00 1.00 56340-S2000 8409',
+ (Ecu.transmission, 0x7e1, None): [
+ b'\xf1\x87\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xf1\x816T6J0051\x00\x00\xf1\x006T6J0_C2\x00\x006T6J0051\x00\x00TJF0T20NSB\x00\x00\x00\x00',
+ ],
+ },
+ CAR.KIA_OPTIMA_2019: {
+ (Ecu.fwdRadar, 0x7d0, None): [
+ b'\xf1\x00JF__ SCC F-CUP 1.00 1.00 96400-D4110 ',
+ ],
+ (Ecu.abs, 0x7d1, None): [
+ b'\xf1\x00JF ESC \x0b 11 \x18\x030 58920-D5180',
+ b"\xf1\x00JF ESC \t 11 \x18\x03' 58920-D5260",
],
(Ecu.fwdCamera, 0x7c4, None): [
b'\xf1\x00JFA LKAS AT USA LHD 1.00 1.00 95895-D5001 h32',
- b'\xf1\x00JFA LKAS AT USA LHD 1.00 1.02 95895-D5000 h31',
+ b'\xf1\x00JFA LKAS AT USA LHD 1.00 1.00 95895-D5100 h32',
],
(Ecu.transmission, 0x7e1, None): [
+ b'\xf1\x006U2V0_C2\x00\x006U2V8051\x00\x00DJF0T16NL0\t\xd2GW',
+ b'\xf1\x006U2V0_C2\x00\x006U2VA051\x00\x00DJF0T16NL1\xca3\xeb.',
+ b'\xf1\x006U2V0_C2\x00\x006U2VC051\x00\x00DJF0T16NL2\x9eA\x80\x01',
+ b'\xf1\x006U2V0_C2\x00\x006U2VA051\x00\x00DJF0T16NL1\x00\x00\x00\x00',
b'\xf1\x816U2V8051\x00\x00\xf1\x006U2V0_C2\x00\x006U2V8051\x00\x00DJF0T16NL0\t\xd2GW',
b'\xf1\x816U2VA051\x00\x00\xf1\x006U2V0_C2\x00\x006U2VA051\x00\x00DJF0T16NL1\xca3\xeb.',
+ b'\xf1\x816U2VC051\x00\x00\xf1\x006U2V0_C2\x00\x006U2VC051\x00\x00DJF0T16NL2\x9eA\x80\x01',
b'\xf1\x816U2VA051\x00\x00\xf1\x006U2V0_C2\x00\x006U2VA051\x00\x00DJF0T16NL1\x00\x00\x00\x00',
+ b'\xf1\x87\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xf1\x816T6B8051\x00\x00\xf1\x006T6H0_C2\x00\x006T6B8051\x00\x00TJFSG24NH27\xa7\xc2\xb4',
],
},
CAR.ELANTRA_2021: {
@@ -1358,7 +1369,7 @@ CHECKSUM = {
FEATURES = {
# which message has the gear
"use_cluster_gears": {CAR.ELANTRA, CAR.ELANTRA_GT_I30, CAR.KONA},
- "use_tcu_gears": {CAR.KIA_OPTIMA, CAR.SONATA_LF, CAR.VELOSTER, CAR.TUCSON},
+ "use_tcu_gears": {CAR.KIA_OPTIMA, CAR.KIA_OPTIMA_2019, CAR.SONATA_LF, CAR.VELOSTER, CAR.TUCSON},
"use_elect_gears": {CAR.KIA_NIRO_EV, CAR.KIA_NIRO_PHEV, CAR.KIA_NIRO_HEV_2021, CAR.KIA_OPTIMA_H, CAR.IONIQ_EV_LTD, CAR.KONA_EV, CAR.IONIQ, CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.ELANTRA_HEV_2021, CAR.SONATA_HYBRID, CAR.KONA_HEV, CAR.IONIQ_HEV_2022, CAR.SANTA_FE_HEV_2022, CAR.SANTA_FE_PHEV_2022, CAR.IONIQ_PHEV_2019, CAR.KONA_EV_2022},
# these cars use the FCA11 message for the AEB and FCW signals, all others use SCC12
@@ -1374,7 +1385,7 @@ HYBRID_CAR = {CAR.IONIQ_PHEV, CAR.ELANTRA_HEV_2021, CAR.KIA_NIRO_PHEV, CAR.KIA_N
EV_CAR = {CAR.IONIQ_EV_2020, CAR.IONIQ_EV_LTD, CAR.KONA_EV, CAR.KIA_NIRO_EV, CAR.KONA_EV_2022}
# these cars require a special panda safety mode due to missing counters and checksums in the messages
-LEGACY_SAFETY_MODE_CAR = {CAR.HYUNDAI_GENESIS, CAR.IONIQ_EV_2020, CAR.IONIQ_EV_LTD, CAR.IONIQ_PHEV, CAR.IONIQ, CAR.KONA_EV, CAR.KIA_SORENTO, CAR.SONATA_LF, CAR.KIA_OPTIMA, CAR.VELOSTER, CAR.KIA_STINGER, CAR.GENESIS_G70, CAR.GENESIS_G80, CAR.KIA_CEED, CAR.ELANTRA, CAR.IONIQ_HEV_2022}
+LEGACY_SAFETY_MODE_CAR = {CAR.HYUNDAI_GENESIS, CAR.IONIQ_EV_2020, CAR.IONIQ_EV_LTD, CAR.IONIQ_PHEV, CAR.IONIQ, CAR.KONA_EV, CAR.KIA_SORENTO, CAR.SONATA_LF, CAR.KIA_OPTIMA, CAR.KIA_OPTIMA_2019, CAR.VELOSTER, CAR.KIA_STINGER, CAR.GENESIS_G70, CAR.GENESIS_G80, CAR.KIA_CEED, CAR.ELANTRA, CAR.IONIQ_HEV_2022}
# If 0x500 is present on bus 1 it probably has a Mando radar outputting radar points.
# If no points are outputted by default it might be possible to turn it on using selfdrive/debug/hyundai_enable_radar_points.py
@@ -1400,6 +1411,7 @@ DBC = {
CAR.KIA_NIRO_PHEV: dbc_dict('hyundai_kia_generic', 'hyundai_kia_mando_front_radar'),
CAR.KIA_NIRO_HEV_2021: dbc_dict('hyundai_kia_generic', None),
CAR.KIA_OPTIMA: dbc_dict('hyundai_kia_generic', None),
+ CAR.KIA_OPTIMA_2019: dbc_dict('hyundai_kia_generic', None),
CAR.KIA_OPTIMA_H: dbc_dict('hyundai_kia_generic', None),
CAR.KIA_SELTOS: dbc_dict('hyundai_kia_generic', None),
CAR.KIA_SORENTO: dbc_dict('hyundai_kia_generic', None), # Has 0x5XX messages, but different format
diff --git a/selfdrive/car/tests/routes.py b/selfdrive/car/tests/routes.py
index e86525baa..3ae3a357c 100644
--- a/selfdrive/car/tests/routes.py
+++ b/selfdrive/car/tests/routes.py
@@ -89,6 +89,7 @@ routes = [
CarTestRoute("656ac0d830792fcc|2021-12-28--14-45-56", HYUNDAI.SANTA_FE_PHEV_2022, segment=1),
CarTestRoute("e0e98335f3ebc58f|2021-03-07--16-38-29", HYUNDAI.KIA_CEED),
CarTestRoute("7653b2bce7bcfdaa|2020-03-04--15-34-32", HYUNDAI.KIA_OPTIMA),
+ CarTestRoute("018654717bc93d7d|2022-09-19--23-11-10", HYUNDAI.KIA_OPTIMA_2019, segment=0),
CarTestRoute("c75a59efa0ecd502|2021-03-11--20-52-55", HYUNDAI.KIA_SELTOS),
CarTestRoute("5b7c365c50084530|2020-04-15--16-13-24", HYUNDAI.SONATA),
CarTestRoute("b2a38c712dcf90bd|2020-05-18--18-12-48", HYUNDAI.SONATA_LF),
diff --git a/selfdrive/car/torque_data/substitute.yaml b/selfdrive/car/torque_data/substitute.yaml
index de64a5544..92361d37f 100644
--- a/selfdrive/car/torque_data/substitute.yaml
+++ b/selfdrive/car/torque_data/substitute.yaml
@@ -17,7 +17,8 @@ LEXUS RC 2020: LEXUS NX 2020
TOYOTA AVALON HYBRID 2019: TOYOTA AVALON 2019
TOYOTA AVALON HYBRID 2022: TOYOTA AVALON 2022
-KIA OPTIMA SX 2019 & 2016: HYUNDAI SONATA 2020
+KIA OPTIMA 2016: HYUNDAI SONATA 2020
+KIA OPTIMA 2019: HYUNDAI SONATA 2020
KIA OPTIMA HYBRID 2017 & SPORTS 2019: HYUNDAI SONATA 2020
KIA FORTE E 2018 & GT 2021: HYUNDAI SONATA 2020
KIA CEED INTRO ED 2019: HYUNDAI SONATA 2020
From 1379989e0de7f2d5d163879befd32638dc1ebe1b Mon Sep 17 00:00:00 2001
From: Cameron Clough
Date: Tue, 20 Sep 2022 10:45:13 -0700
Subject: [PATCH 45/75] sidebar: add button pressed states (#25848)
* add flag img
* add image assets
* try darker button pressed
* remove pressed image, set opacity instead
* settings can be pressed too!
* cleanup
* make settings button white
* bookmark
---
selfdrive/assets/images/button_flag.png | Bin 0 -> 3305 bytes
selfdrive/ui/qt/home.cc | 1 +
selfdrive/ui/qt/sidebar.cc | 31 +++++++++++++++++++-----
selfdrive/ui/qt/sidebar.h | 5 +++-
4 files changed, 30 insertions(+), 7 deletions(-)
create mode 100644 selfdrive/assets/images/button_flag.png
diff --git a/selfdrive/assets/images/button_flag.png b/selfdrive/assets/images/button_flag.png
new file mode 100644
index 0000000000000000000000000000000000000000..b55620328a77a6672a4fb7e726ecd484bb2af97c
GIT binary patch
literal 3305
zcmVNc=P)EX>4Tx04R}tkv&MmKpe$iQ>7{u2Q!E`WT;LSL`5963Pq?8YK2xEOfLO`CWa)%
z#ZhoAIQX$xb#QUk)xlK|1V2C=otzY1q{ROvg%&X$9QWhhy~o`#EOhoQoa{JX5qX={aJNSSq%$+QzJ8>BN)7F-)CP&_~QAN=mtE=-L3Nznw*`Qo}C!$4#gXw+Qy``C3GCqVcaxH4M)jXE&>NqViN
z#g2f!ZQ$a%rKx+sGHG&+-hZ-r00006VoOIv0QUgi08@4%FGc_W010qNS#tmY
z3ljhU3ljkVnw%H_000McNliru<_Q!81vre}6oCK$02y>eSad^gZEa<4bO1wgWnpw>
zWFU8GbZ8()Nlj2!fese{01ClLL_t(|+U=cRh!y7u8q`2P9kn{N!!5a(P!unrgmRs$>i
ze_8=71D5*lm&d+-0NjgxeIK~%zrPFI07YV0}hll8+O`n9yPP`5;9v6cL4_joRCAB)Q_0iyArZ@5-tILC=tso
zrWHiS5#WSG>`Kf%Md&eWp-;`uxzoV=lCdiWfcKqqr~OKVgzP}Zy+rqYcgUyI*a2Mk
zu~o@VDB`d$&zhWjKauY-vngfB<}w}vK9r1^Fa&()W3CKY-zyT`65AqAa^VuNGlV-n
z7J!T+z*)+3zqzQ)0%Lhk;6$(TQVeiF~Mgj-G`szirB@O&qa5^g!jxE6R1
ztt*Dk4Dj8ox4BuyG7b~%hE|C#PG32i<i~h4KkC1+wm}D%rl-o)n
zq`ysdj_PfkEfb4@b6MPSv;?L>xDLjLLL5
zne)^4MDRjtX{R#uWJ$2`hfS++=Xr_3OR-L
zF;xCmmbph4BB8T>ekN62^6;>L*X&9Z|ASo#>7N|b89XA*EV-?l40%8?6e)9{
zBO(2|qizw3v>9r3R#2-9xnHppJz{@bLi&5wn-w?FBQ`gCQn6Wv97Cs0h~BZ-JC<0;
zam7sZnDInH`qL*g%!n+8o3%+YUJv(l1nMx)ym%+x?9)q_U&PJxj)g+@!dOoY>Sz$Wg^b
zLi!r6jkqE&2Il+7n)*i(QXe@lF%Ti43@L)k
zkjoSY5eUm_z*5CQgjBMH2!*9JV7cNT0%5sIwg@gm3K3Kf`9NV1f$*S4f!^C9O3yu&
zY@w1ZM5~g0UvUtDaK8rJRUAYh+*J=Lg6kobAw^Ib@|NNt0^wE-xUM*eK)7B5t|<;8
z5U$nC><%!iScsgNHM2YOQ}%7eL*&fu`6(MTtBObGIOo3P
zocq3W?sJMp$6SpIIjMMbEaTUJKLWo24msz(sHk+ru1;*wa#uL8dV
zzQvP|5`W%j%AYysOwmfjl}19Uk4z@xD&Qorf#%P(F9lu&_B!VlDQYd5i@WzIpuUDr
zD?Tk{{0i_6(JL$#5^Wi95WRnVA^tJnKhofDxUyt(83%x0`^=cM6t4u{aL&D=2)3TC
zn+bVA@o6aImw~r^&)9AWeg=5mIroyvcS9~T71GQm&_;_!1I!cJZ+BUyTlJK0054Zu#%b@`f*BIOv{6+VSH-63UOkn$68O1u?xz(V
zbQ(I=EZ}E-(^)kc2T8upm`3^j1+c541I^jQLi&Zu%N3Jx4e%@4TW3roQ&w@E@^XAJ
zJV}NGI94GU=Qm2EIl#0v=s4$oT%q#a)UBpM`t_md3dq=MqeNCb0~`fjs>m=i(YBDD
zqZJrn(pqOsqkJE6&b{oMEAtUIEuCul2RF0xlyu{6n;RvvVg>Me-Js)26!sbKRA)kZ
zj+7)A^Dl{7)Zs>nEHh<%&?(bP2^Mt85@wTs0s{pP#zUgRS^oum0eCh*8OzL!nLU>z
zYoua!K{Djiz}JB_k}wlC
zS}<*9!|nd2PH$0Zz!5!hq$45CY)YkDEKsVaI&!PipXk>n{{(DN{6&mQX7*yIzqzZs
z6`Hz5w^MamJ!E|99@FO_JY(I+*tL*e$_e$8!uO36UHg>Am8hSrJRL3Z^i0TDKlxX*
z0i$Zn055b~s#6!zOSu;KKtoQYhL{bF9{A6#hpg)-Zvdm{z^baqIGU!6sb|PorW_$U
zH+r!?w^B0aWt>R+f83L&+x&%Y*XLGRw)aBDo(butJWq7^yC@g?7J70pxRPC0zV`xe
z>T@iOjBoYw2W0Y~lXGqx(c7-nQx>;p+}_K~n5mGlLFX)55-Q>}J=Uw9F*hN-l*4}d
zmXyVjakSH|WI+uzO$MDQqSGSuUd8a4AzJjF%JPS1eyEXONPPjgq|ZE9ripF`-pKj~
z=W@!Hzwh}yv`Z*N4x8C31CnqJXbCe?ew0=`$B>^7}Lz|
z_~$TG!t*K7FXmOEgDcq$O878v0zLPg#o)3h>nXYr8L}>0PWj!(`_MMFUiFIm{NOSb
z+~*&1DilnQ5nS3@b!g%h%F5WFbP~JLrIp9Ps+K3=rDs#{@2hZ^%TqnY{1Z
z2&^Z1!`A??DuXgV3*7bs-UO~zQ9udVo~Y}Hw#Ka{dQ&U@*JXVAQq1MCuO9&SVqf0}
n?)vZV0=I|`c)eD2@tW~}SCLm|)u(RX00000NkvXXu0mjf5f&U4
literal 0
HcmV?d00001
diff --git a/selfdrive/ui/qt/home.cc b/selfdrive/ui/qt/home.cc
index 435ba9056..78bc6aab4 100644
--- a/selfdrive/ui/qt/home.cc
+++ b/selfdrive/ui/qt/home.cc
@@ -41,6 +41,7 @@ HomeWindow::HomeWindow(QWidget* parent) : QWidget(parent) {
setAttribute(Qt::WA_NoSystemBackground);
QObject::connect(uiState(), &UIState::uiUpdate, this, &HomeWindow::updateState);
QObject::connect(uiState(), &UIState::offroadTransition, this, &HomeWindow::offroadTransition);
+ QObject::connect(uiState(), &UIState::offroadTransition, sidebar, &Sidebar::offroadTransition);
}
void HomeWindow::showSidebar(bool show) {
diff --git a/selfdrive/ui/qt/sidebar.cc b/selfdrive/ui/qt/sidebar.cc
index a84542d29..eeb163aa1 100644
--- a/selfdrive/ui/qt/sidebar.cc
+++ b/selfdrive/ui/qt/sidebar.cc
@@ -32,8 +32,9 @@ void Sidebar::drawMetric(QPainter &p, const QPair &label, QCol
p.drawText(label_rect, Qt::AlignCenter, label.second);
}
-Sidebar::Sidebar(QWidget *parent) : QFrame(parent) {
+Sidebar::Sidebar(QWidget *parent) : QFrame(parent), onroad(false), flag_pressed(false), settings_pressed(false) {
home_img = loadPixmap("../assets/images/button_home.png", home_btn.size());
+ flag_img = loadPixmap("../assets/images/button_flag.png", home_btn.size());
settings_img = loadPixmap("../assets/images/button_settings.png", settings_btn.size(), Qt::IgnoreAspectRatio);
connect(this, &Sidebar::valueChanged, [=] { update(); });
@@ -47,17 +48,34 @@ Sidebar::Sidebar(QWidget *parent) : QFrame(parent) {
pm = std::make_unique>({"userFlag"});
}
+void Sidebar::mousePressEvent(QMouseEvent *event) {
+ if (onroad && home_btn.contains(event->pos())) {
+ flag_pressed = true;
+ update();
+ } else if (settings_btn.contains(event->pos())) {
+ settings_pressed = true;
+ update();
+ }
+}
+
void Sidebar::mouseReleaseEvent(QMouseEvent *event) {
+ if (flag_pressed || settings_pressed) {
+ flag_pressed = settings_pressed = false;
+ update();
+ }
if (home_btn.contains(event->pos())) {
MessageBuilder msg;
msg.initEvent().initUserFlag();
pm->send("userFlag", msg);
- }
- if (settings_btn.contains(event->pos())) {
+ } else if (settings_btn.contains(event->pos())) {
emit openSettings();
}
}
+void Sidebar::offroadTransition(bool offroad) {
+ onroad = !offroad;
+}
+
void Sidebar::updateState(const UIState &s) {
if (!isVisible()) return;
@@ -102,11 +120,12 @@ void Sidebar::paintEvent(QPaintEvent *event) {
p.fillRect(rect(), QColor(57, 57, 57));
- // static imgs
- p.setOpacity(0.65);
+ // buttons
+ p.setOpacity(settings_pressed ? 0.65 : 1.0);
p.drawPixmap(settings_btn.x(), settings_btn.y(), settings_img);
+ p.setOpacity(onroad && flag_pressed ? 0.65 : 1.0);
+ p.drawPixmap(home_btn.x(), home_btn.y(), onroad ? flag_img : home_img);
p.setOpacity(1.0);
- p.drawPixmap(home_btn.x(), home_btn.y(), home_img);
// network
int x = 58;
diff --git a/selfdrive/ui/qt/sidebar.h b/selfdrive/ui/qt/sidebar.h
index 621a21444..53ad7467a 100644
--- a/selfdrive/ui/qt/sidebar.h
+++ b/selfdrive/ui/qt/sidebar.h
@@ -24,14 +24,17 @@ signals:
void valueChanged();
public slots:
+ void offroadTransition(bool offroad);
void updateState(const UIState &s);
protected:
void paintEvent(QPaintEvent *event) override;
+ void mousePressEvent(QMouseEvent *event) override;
void mouseReleaseEvent(QMouseEvent *event) override;
void drawMetric(QPainter &p, const QPair &label, QColor c, int y);
- QPixmap home_img, settings_img;
+ QPixmap home_img, flag_img, settings_img;
+ bool onroad, flag_pressed, settings_pressed;
const QMap network_type = {
{cereal::DeviceState::NetworkType::NONE, tr("--")},
{cereal::DeviceState::NetworkType::WIFI, tr("Wi-Fi")},
From c5df17cd571cb2bd77bbd13539cd6c773f76d9ad Mon Sep 17 00:00:00 2001
From: Cameron Clough
Date: Tue, 20 Sep 2022 10:54:46 -0700
Subject: [PATCH 46/75] sidebar: updated bookmark image
---
selfdrive/assets/images/button_flag.png | Bin 3305 -> 1611 bytes
1 file changed, 0 insertions(+), 0 deletions(-)
diff --git a/selfdrive/assets/images/button_flag.png b/selfdrive/assets/images/button_flag.png
index b55620328a77a6672a4fb7e726ecd484bb2af97c..cac4db6d4cdb51c4ec2d93f3a68bdb89513ab2df 100644
GIT binary patch
delta 1605
zcmV-L2D@SBW+;iQ*zOg1hSr^v_nhiE-z;bM(WlO-)77UkNsv=eQGe6W&|o}f=7F`{;yi&46>9a&w(Q|;~ufcwQ^HfkFL^YtsyWHl3!G2$Gk3%6np+U3t
z1FkbC8wM`$8sG3(NcN^-IR4-Y*>G@)t2|&R8iW+#2mHu8WJAIg?g=Q)*~1Ph@(12d
zTBPO7M}L-4ktcD+Q@>ah8R3~^A5>(7XA-L-BRrFopdur@W5lS)2-`&pP>~VpNm>;d
zp+iYdry@6?Bj>n&kBW@Y3&N<#2nmM;sK||3kaV23C`P
zV5`W$;Px}NiacNDCWkdDGK3tz=Yxt2p~PPyQGbyk)cDO@RAdMie}zOvhLPi~kSa2a
z67TSyiVS0gcRWQ!hSA^^<0>)?gV(N5kzqKzoUI~5$@_gD6&Xs=e^a9(L#g`PLlqfH
z-7kJrWGIb_j3%<>2o)Jh+b_peWGJTJLQ|0{a?2uZe}kwZLva}$N2th9Iu#j*PD48m
zPJfe49IT3rgVlmO4o0_#acH$^q1_*8BDJv_gIZrT#G%rcUvVh(b!;4RJs=PRr$<)e
zVDu1G92z~=7l)M|G>t<^3P+!r^Coj7i_DRJ7@ryM@;Tq~DX(%7nIf(D&qJ8;5qJ29
zC;Z9Ryu~FXimZiyu*8gO{K5eMhdiR@4Sy~oPh^SYPv~A~d>YsZWeU-m*ojDRjb~vHKLDo;>U3`tc%HQ~y8A6AH2pCtxjH|t%KIy5v$$t!q
z<7&1#K*`V4oLQy30ZQ8*>BWqz{@QqIfPcaafg`=PIAo5?T
z8QfUqEoR6Xd$_GZoLt~NKT~fM;5V2dYY^vlM#J(t-|>V%)=%XP=13Y1JN~d@F7rO$
z2Ws?7bVzW$=rE?($_%V{Db5af|y5M}d&5svh&Or!lt5
zN8INLL(w4S^0bt3FJ&r3T`-v{2EFn$3QP17-mP9&&YoTi{el*~sDC_Cw$`ij
zqZZ+MU3s+CQCG_Fq9+pMSaualP8JOoJDPMH3$m!N+(DI&C0TSR=-4GX3bH|Qn<$dpq%(x*-?^>0>y+gxH~1qXfYH}@QeYA3GQ|*3$oE6pV%JUkdti%
z_9oOBI=RE6iAP|9nQVx+Xj!khG
z8df_k@EEBD6*UbFEe4Cl(b3_sSPbp@znY3dmb`xf0#!3U;F{w&00000NkvXXu0mjf
Dp)Tg`
literal 3305
zcmVNc=P)EX>4Tx04R}tkv&MmKpe$iQ>7{u2Q!E`WT;LSL`5963Pq?8YK2xEOfLO`CWa)%
z#ZhoAIQX$xb#QUk)xlK|1V2C=otzY1q{ROvg%&X$9QWhhy~o`#EOhoQoa{JX5qX={aJNSSq%$+QzJ8>BN)7F-)CP&_~QAN=mtE=-L3Nznw*`Qo}C!$4#gXw+Qy``C3GCqVcaxH4M)jXE&>NqViN
z#g2f!ZQ$a%rKx+sGHG&+-hZ-r00006VoOIv0QUgi08@4%FGc_W010qNS#tmY
z3ljhU3ljkVnw%H_000McNliru<_Q!81vre}6oCK$02y>eSad^gZEa<4bO1wgWnpw>
zWFU8GbZ8()Nlj2!fese{01ClLL_t(|+U=cRh!y7u8q`2P9kn{N!!5a(P!unrgmRs$>i
ze_8=71D5*lm&d+-0NjgxeIK~%zrPFI07YV0}hll8+O`n9yPP`5;9v6cL4_joRCAB)Q_0iyArZ@5-tILC=tso
zrWHiS5#WSG>`Kf%Md&eWp-;`uxzoV=lCdiWfcKqqr~OKVgzP}Zy+rqYcgUyI*a2Mk
zu~o@VDB`d$&zhWjKauY-vngfB<}w}vK9r1^Fa&()W3CKY-zyT`65AqAa^VuNGlV-n
z7J!T+z*)+3zqzQ)0%Lhk;6$(TQVeiF~Mgj-G`szirB@O&qa5^g!jxE6R1
ztt*Dk4Dj8ox4BuyG7b~%hE|C#PG32i<i~h4KkC1+wm}D%rl-o)n
zq`ysdj_PfkEfb4@b6MPSv;?L>xDLjLLL5
zne)^4MDRjtX{R#uWJ$2`hfS++=Xr_3OR-L
zF;xCmmbph4BB8T>ekN62^6;>L*X&9Z|ASo#>7N|b89XA*EV-?l40%8?6e)9{
zBO(2|qizw3v>9r3R#2-9xnHppJz{@bLi&5wn-w?FBQ`gCQn6Wv97Cs0h~BZ-JC<0;
zam7sZnDInH`qL*g%!n+8o3%+YUJv(l1nMx)ym%+x?9)q_U&PJxj)g+@!dOoY>Sz$Wg^b
zLi!r6jkqE&2Il+7n)*i(QXe@lF%Ti43@L)k
zkjoSY5eUm_z*5CQgjBMH2!*9JV7cNT0%5sIwg@gm3K3Kf`9NV1f$*S4f!^C9O3yu&
zY@w1ZM5~g0UvUtDaK8rJRUAYh+*J=Lg6kobAw^Ib@|NNt0^wE-xUM*eK)7B5t|<;8
z5U$nC><%!iScsgNHM2YOQ}%7eL*&fu`6(MTtBObGIOo3P
zocq3W?sJMp$6SpIIjMMbEaTUJKLWo24msz(sHk+ru1;*wa#uL8dV
zzQvP|5`W%j%AYysOwmfjl}19Uk4z@xD&Qorf#%P(F9lu&_B!VlDQYd5i@WzIpuUDr
zD?Tk{{0i_6(JL$#5^Wi95WRnVA^tJnKhofDxUyt(83%x0`^=cM6t4u{aL&D=2)3TC
zn+bVA@o6aImw~r^&)9AWeg=5mIroyvcS9~T71GQm&_;_!1I!cJZ+BUyTlJK0054Zu#%b@`f*BIOv{6+VSH-63UOkn$68O1u?xz(V
zbQ(I=EZ}E-(^)kc2T8upm`3^j1+c541I^jQLi&Zu%N3Jx4e%@4TW3roQ&w@E@^XAJ
zJV}NGI94GU=Qm2EIl#0v=s4$oT%q#a)UBpM`t_md3dq=MqeNCb0~`fjs>m=i(YBDD
zqZJrn(pqOsqkJE6&b{oMEAtUIEuCul2RF0xlyu{6n;RvvVg>Me-Js)26!sbKRA)kZ
zj+7)A^Dl{7)Zs>nEHh<%&?(bP2^Mt85@wTs0s{pP#zUgRS^oum0eCh*8OzL!nLU>z
zYoua!K{Djiz}JB_k}wlC
zS}<*9!|nd2PH$0Zz!5!hq$45CY)YkDEKsVaI&!PipXk>n{{(DN{6&mQX7*yIzqzZs
z6`Hz5w^MamJ!E|99@FO_JY(I+*tL*e$_e$8!uO36UHg>Am8hSrJRL3Z^i0TDKlxX*
z0i$Zn055b~s#6!zOSu;KKtoQYhL{bF9{A6#hpg)-Zvdm{z^baqIGU!6sb|PorW_$U
zH+r!?w^B0aWt>R+f83L&+x&%Y*XLGRw)aBDo(butJWq7^yC@g?7J70pxRPC0zV`xe
z>T@iOjBoYw2W0Y~lXGqx(c7-nQx>;p+}_K~n5mGlLFX)55-Q>}J=Uw9F*hN-l*4}d
zmXyVjakSH|WI+uzO$MDQqSGSuUd8a4AzJjF%JPS1eyEXONPPjgq|ZE9ripF`-pKj~
z=W@!Hzwh}yv`Z*N4x8C31CnqJXbCe?ew0=`$B>^7}Lz|
z_~$TG!t*K7FXmOEgDcq$O878v0zLPg#o)3h>nXYr8L}>0PWj!(`_MMFUiFIm{NOSb
z+~*&1DilnQ5nS3@b!g%h%F5WFbP~JLrIp9Ps+K3=rDs#{@2hZ^%TqnY{1Z
z2&^Z1!`A??DuXgV3*7bs-UO~zQ9udVo~Y}Hw#Ka{dQ&U@*JXVAQq1MCuO9&SVqf0}
n?)vZV0=I|`c)eD2@tW~}SCLm|)u(RX00000NkvXXu0mjf5f&U4
From 2cba29eabe58a120d51b398f7d13c1ac4130d52c Mon Sep 17 00:00:00 2001
From: Adeeb Shihadeh
Date: Tue, 20 Sep 2022 11:19:23 -0700
Subject: [PATCH 47/75] Hyundai: improve EV6 resume reliability (#25847)
* Hyundai: improve EV6 resume reliability
* this is pretty good
Co-authored-by: Comma Device
---
selfdrive/car/hyundai/carcontroller.py | 3 ++-
1 file changed, 2 insertions(+), 1 deletion(-)
diff --git a/selfdrive/car/hyundai/carcontroller.py b/selfdrive/car/hyundai/carcontroller.py
index db80bcdf4..6f7cc319e 100644
--- a/selfdrive/car/hyundai/carcontroller.py
+++ b/selfdrive/car/hyundai/carcontroller.py
@@ -97,7 +97,8 @@ class CarController:
# cruise standstill resume
elif CC.cruiseControl.resume:
if not (self.CP.flags & HyundaiFlags.CANFD_ALT_BUTTONS):
- can_sends.append(hyundaicanfd.create_buttons(self.packer, CS.buttons_counter+1, Buttons.RES_ACCEL))
+ for _ in range(20):
+ can_sends.append(hyundaicanfd.create_buttons(self.packer, CS.buttons_counter+1, Buttons.RES_ACCEL))
self.last_button_frame = self.frame
else:
From 53959082e7e3e200fb62e1c44219fa4e656eb8de Mon Sep 17 00:00:00 2001
From: Igor Biletskyy
Date: Tue, 20 Sep 2022 12:39:12 -0700
Subject: [PATCH 48/75] boardd: add CAN health to pandaStates (#25800)
* init
* try this
* mistake
* fix
* bump cereal
* make obvious
* fixes
* remove comment
* one helath header
* ..
* preallocate vectors
---
cereal | 2 +-
selfdrive/boardd/boardd.cc | 46 ++++++++++++++++++++++++++++++++++++--
selfdrive/boardd/panda.cc | 6 +++++
selfdrive/boardd/panda.h | 2 ++
4 files changed, 53 insertions(+), 3 deletions(-)
diff --git a/cereal b/cereal
index e4130c905..3baa20e1d 160000
--- a/cereal
+++ b/cereal
@@ -1 +1 @@
-Subproject commit e4130c90558dfb491e132992dce36e0e620e070a
+Subproject commit 3baa20e1da5d88dcb1d3ae9678471eb8013958f2
diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc
index 0872a9471..7009f28e1 100644
--- a/selfdrive/boardd/boardd.cc
+++ b/selfdrive/boardd/boardd.cc
@@ -295,13 +295,19 @@ void send_empty_panda_state(PubMaster *pm) {
std::optional send_panda_states(PubMaster *pm, const std::vector &pandas, bool spoofing_started) {
bool ignition_local = false;
+ const uint32_t pandas_cnt = pandas.size();
// build msg
MessageBuilder msg;
auto evt = msg.initEvent();
- auto pss = evt.initPandaStates(pandas.size());
+ auto pss = evt.initPandaStates(pandas_cnt);
std::vector pandaStates;
+ pandaStates.reserve(pandas_cnt);
+
+ std::vector> pandaCanStates;
+ pandaCanStates.reserve(pandas_cnt);
+
for (const auto& panda : pandas){
auto health_opt = panda->get_state();
if (!health_opt) {
@@ -310,6 +316,16 @@ std::optional send_panda_states(PubMaster *pm, const std::vector
health_t health = *health_opt;
+ std::array can_health{};
+ for (uint32_t i = 0; i < PANDA_CAN_CNT; i++) {
+ auto can_health_opt = panda->get_can_state(i);
+ if (!can_health_opt) {
+ return std::nullopt;
+ }
+ can_health[i] = *can_health_opt;
+ }
+ pandaCanStates.push_back(can_health);
+
if (spoofing_started) {
health.ignition_line_pkt = 1;
}
@@ -319,7 +335,7 @@ std::optional send_panda_states(PubMaster *pm, const std::vector
pandaStates.push_back(health);
}
- for (uint32_t i = 0; i < pandas.size(); i++) {
+ for (uint32_t i = 0; i < pandas_cnt; i++) {
auto panda = pandas[i];
const auto &health = pandaStates[i];
@@ -366,6 +382,32 @@ std::optional send_panda_states(PubMaster *pm, const std::vector
ps.setInterruptLoad(health.interrupt_load);
ps.setFanPower(health.fan_power);
+ std::array cs = {ps.initCanState0(), ps.initCanState1(), ps.initCanState2()};
+
+ for (uint32_t j = 0; j < PANDA_CAN_CNT; j++) {
+ const auto &can_health = pandaCanStates[i][j];
+ cs[j].setBusOff((bool)can_health.bus_off);
+ cs[j].setBusOffCnt(can_health.bus_off_cnt);
+ cs[j].setErrorWarning((bool)can_health.error_warning);
+ cs[j].setErrorPassive((bool)can_health.error_passive);
+ cs[j].setLastError(cereal::PandaState::PandaCanState::LecErrorCode(can_health.last_error));
+ cs[j].setLastStoredError(cereal::PandaState::PandaCanState::LecErrorCode(can_health.last_stored_error));
+ cs[j].setLastDataError(cereal::PandaState::PandaCanState::LecErrorCode(can_health.last_data_error));
+ cs[j].setLastDataStoredError(cereal::PandaState::PandaCanState::LecErrorCode(can_health.last_data_stored_error));
+ cs[j].setReceiveErrorCnt(can_health.receive_error_cnt);
+ cs[j].setTransmitErrorCnt(can_health.transmit_error_cnt);
+ cs[j].setTotalErrorCnt(can_health.total_error_cnt);
+ cs[j].setTotalTxLostCnt(can_health.total_tx_lost_cnt);
+ cs[j].setTotalRxLostCnt(can_health.total_rx_lost_cnt);
+ cs[j].setTotalTxCnt(can_health.total_tx_cnt);
+ cs[j].setTotalRxCnt(can_health.total_rx_cnt);
+ cs[j].setTotalFwdCnt(can_health.total_fwd_cnt);
+ cs[j].setCanSpeed(can_health.can_speed);
+ cs[j].setCanDataSpeed(can_health.can_data_speed);
+ cs[j].setCanfdEnabled(can_health.canfd_enabled);
+ cs[j].setBrsEnabled(can_health.canfd_enabled);
+ }
+
// Convert faults bitset to capnp list
std::bitset fault_bits(health.faults_pkt);
auto faults = ps.initFaults(fault_bits.count());
diff --git a/selfdrive/boardd/panda.cc b/selfdrive/boardd/panda.cc
index 4d72bc904..7ddf15f9c 100644
--- a/selfdrive/boardd/panda.cc
+++ b/selfdrive/boardd/panda.cc
@@ -317,6 +317,12 @@ std::optional Panda::get_state() {
return err >= 0 ? std::make_optional(health) : std::nullopt;
}
+std::optional 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));
+ return err >= 0 ? std::make_optional(can_health) : std::nullopt;
+}
+
void Panda::set_loopback(bool loopback) {
usb_write(0xe5, loopback, 0);
}
diff --git a/selfdrive/boardd/panda.h b/selfdrive/boardd/panda.h
index 1cefc3cb4..a4afbdac1 100644
--- a/selfdrive/boardd/panda.h
+++ b/selfdrive/boardd/panda.h
@@ -16,6 +16,7 @@
#include "panda/board/health.h"
#define TIMEOUT 0
+#define PANDA_CAN_CNT 3
#define PANDA_BUS_CNT 4
#define RECV_SIZE (0x4000U)
#define USB_TX_SOFT_LIMIT (0x100U)
@@ -81,6 +82,7 @@ class Panda {
uint16_t get_fan_speed();
void set_ir_pwr(uint16_t ir_pwr);
std::optional get_state();
+ std::optional get_can_state(uint16_t can_number);
void set_loopback(bool loopback);
std::optional> get_firmware_version();
std::optional