From 6d8f1667228d74e8c9afca52bafb50c0730a0d83 Mon Sep 17 00:00:00 2001
From: Erich Moraga <33645296+ErichMoraga@users.noreply.github.com>
Date: Sun, 18 Dec 2022 22:09:40 -0600
Subject: [PATCH 001/484] Add several missing HIGHLANDER_TSS2 firmwares
(#26801)
* Add several missing HIGHLANDER_TSS2 firmwares
`@randywf#0891` 2023 Toyota Highlander (ICE) DongleID/route d9049fcd50225c9d|2022-12-14--12-16-16
* docs.py gen'd CARS.md w/ 2023 Highlander update
---
docs/CARS.md | 2 +-
selfdrive/car/toyota/values.py | 6 +++++-
2 files changed, 6 insertions(+), 2 deletions(-)
diff --git a/docs/CARS.md b/docs/CARS.md
index 4f1a7cb652..ce067609aa 100644
--- a/docs/CARS.md
+++ b/docs/CARS.md
@@ -180,7 +180,7 @@ A supported vehicle is one that just works when you install a comma three. All s
|Toyota|Corolla Hatchback 2019-22|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota|
|Toyota|Corolla Hybrid 2020-22|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota|
|Toyota|Highlander 2017-19|All|openpilot available[2](#footnotes)|0 mph|0 mph|[](##)|[](##)|Toyota|
-|Toyota|Highlander 2020-22|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota|
+|Toyota|Highlander 2020-23|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota|
|Toyota|Highlander Hybrid 2017-19|All|openpilot available[2](#footnotes)|0 mph|0 mph|[](##)|[](##)|Toyota|
|Toyota|Highlander Hybrid 2020-22|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota|
|Toyota|Mirai 2021|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota|
diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py
index 8ff06a591a..80c0ccbb83 100644
--- a/selfdrive/car/toyota/values.py
+++ b/selfdrive/car/toyota/values.py
@@ -129,7 +129,7 @@ CAR_INFO: Dict[str, Union[ToyotaCarInfo, List[ToyotaCarInfo]]] = {
ToyotaCarInfo("Lexus UX Hybrid 2019-22"),
],
CAR.HIGHLANDER: ToyotaCarInfo("Toyota Highlander 2017-19", video_link="https://www.youtube.com/watch?v=0wS0wXSLzoo"),
- CAR.HIGHLANDER_TSS2: ToyotaCarInfo("Toyota Highlander 2020-22"),
+ CAR.HIGHLANDER_TSS2: ToyotaCarInfo("Toyota Highlander 2020-23"),
CAR.HIGHLANDERH: ToyotaCarInfo("Toyota Highlander Hybrid 2017-19"),
CAR.HIGHLANDERH_TSS2: ToyotaCarInfo("Toyota Highlander Hybrid 2020-22"),
CAR.PRIUS: [
@@ -980,12 +980,14 @@ FW_VERSIONS = {
b'8965B48241\x00\x00\x00\x00\x00\x00',
b'8965B48310\x00\x00\x00\x00\x00\x00',
b'8965B48320\x00\x00\x00\x00\x00\x00',
+ b'8965B48400\x00\x00\x00\x00\x00\x00',
],
(Ecu.abs, 0x7b0, None): [
b'\x01F15260E051\x00\x00\x00\x00\x00\x00',
b'\x01F15260E061\x00\x00\x00\x00\x00\x00',
b'\x01F15260E110\x00\x00\x00\x00\x00\x00',
b'\x01F15260E170\x00\x00\x00\x00\x00\x00',
+ b'\x01F15260E05300\x00\x00\x00\x00',
],
(Ecu.engine, 0x700, None): [
b'\x01896630E62100\x00\x00\x00\x00',
@@ -1003,6 +1005,7 @@ FW_VERSIONS = {
b'\x01896630ED9100\x00\x00\x00\x00',
b'\x01896630EE1000\x00\x00\x00\x00',
b'\x01896630EE1100\x00\x00\x00\x00',
+ b'\x01896630EG5000\x00\x00\x00\x00',
],
(Ecu.fwdRadar, 0x750, 0xf): [
b'\x018821F3301400\x00\x00\x00\x00',
@@ -1013,6 +1016,7 @@ FW_VERSIONS = {
b'\x028646F0E02100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00',
b'\x028646F4803000\x00\x00\x00\x008646G5301200\x00\x00\x00\x00',
b'\x028646F4803000\x00\x00\x00\x008646G3304000\x00\x00\x00\x00',
+ b'\x028646F4803200\x00\x00\x00\x008646G3304000\x00\x00\x00\x00',
],
},
CAR.HIGHLANDERH_TSS2: {
From 777dc9dcd2ef3c1011d487f7584f3da9c396e513 Mon Sep 17 00:00:00 2001
From: Samer Khatib <56684133+skhatib07@users.noreply.github.com>
Date: Tue, 20 Dec 2022 16:44:33 -0500
Subject: [PATCH 002/484] Added unofficial support for Ubuntu 22.10 in
ubuntu_setup.sh (#26828)
* Added unofficial support for Ubuntu 22.10 in ubuntu_setup.sh
Added a conditional to check if $UBUNTU_CODENAME is equal to "kinetic" in ubuntu_setup.sh. Installs the same packages as Ubuntu 22.04 LTS Jammy Jellyfish.
* Attempt #2 at adding unofficial support for Ubuntu 22.10 in ubuntu_setup.sh
Still checks to see if $UBUNTU_CODENAME is equal to "kinetic" I just fixed some errors that were appearing beforehand
* Update tools/ubuntu_setup.sh
* Update tools/ubuntu_setup.sh
* Update tools/ubuntu_setup.sh
* Update tools/ubuntu_setup.sh
Co-authored-by: Adeeb Shihadeh
---
tools/ubuntu_setup.sh | 11 +++++++----
1 file changed, 7 insertions(+), 4 deletions(-)
diff --git a/tools/ubuntu_setup.sh b/tools/ubuntu_setup.sh
index 89d33a6127..09296ef94d 100755
--- a/tools/ubuntu_setup.sh
+++ b/tools/ubuntu_setup.sh
@@ -82,7 +82,7 @@ function install_ubuntu_common_requirements() {
}
# Install Ubuntu 22.04 LTS packages
-function install_ubuntu_jammy_requirements() {
+function install_ubuntu_lts_latest_requirements() {
install_ubuntu_common_requirements
$SUDO apt-get install -y --no-install-recommends \
@@ -108,7 +108,10 @@ if [ -f "/etc/os-release" ]; then
source /etc/os-release
case "$VERSION_CODENAME" in
"jammy")
- install_ubuntu_jammy_requirements
+ install_ubuntu_lts_latest_requirements
+ ;;
+ "kinetic")
+ install_ubuntu_lts_latest_requirements
;;
"focal")
install_ubuntu_focal_requirements
@@ -120,8 +123,8 @@ if [ -f "/etc/os-release" ]; then
if [[ ! $REPLY =~ ^[Yy]$ ]]; then
exit 1
fi
- if [ "$UBUNTU_CODENAME" = "jammy" ]; then
- install_ubuntu_jammy_requirements
+ if [ "$UBUNTU_CODENAME" = "jammy" ] || [ "$UBUNTU_CODENAME" = "kinetic" ]; then
+ install_ubuntu_lts_latest_requirements
else
install_ubuntu_focal_requirements
fi
From 49ae806534a32858a327745698ca2f36e5210803 Mon Sep 17 00:00:00 2001
From: Hamid Ebadi
Date: Tue, 20 Dec 2022 22:45:06 +0100
Subject: [PATCH 003/484] carla sim: fix accelerometer sensor data (#26794)
---
tools/sim/bridge.py | 2 +-
1 file changed, 1 insertion(+), 1 deletion(-)
diff --git a/tools/sim/bridge.py b/tools/sim/bridge.py
index f72927ba9a..f0694078e2 100755
--- a/tools/sim/bridge.py
+++ b/tools/sim/bridge.py
@@ -128,7 +128,7 @@ def imu_callback(imu, vehicle_state):
vehicle_state.bearing_deg = math.degrees(imu.compass)
dat = messaging.new_message('accelerometer')
dat.accelerometer.sensor = 4
- dat.accelerometer.type = 0x1
+ dat.accelerometer.type = 0x10
dat.accelerometer.timestamp = dat.logMonoTime # TODO: use the IMU timestamp
dat.accelerometer.init('acceleration')
dat.accelerometer.acceleration.v = [imu.accelerometer.x, imu.accelerometer.y, imu.accelerometer.z]
From 5ab2fc16ab5b883f3fa151d0e7362bc73545ca32 Mon Sep 17 00:00:00 2001
From: Mitchell Goff
Date: Tue, 20 Dec 2022 14:19:21 -0800
Subject: [PATCH 004/484] model_replay: use last N frames of segment so
navRoute is valid (#26790)
* model_replay: use last N frames of segment so navRoute is valid
* Use llk logMonoTime for MapRenderState.locationMonoTime
* Record mapRenderState
* update refs
Co-authored-by: Comma Device
---
selfdrive/navd/map_renderer.cc | 4 ++--
selfdrive/test/process_replay/model_replay.py | 16 +++++++++++-----
.../test/process_replay/model_replay_ref_commit | 2 +-
3 files changed, 14 insertions(+), 8 deletions(-)
diff --git a/selfdrive/navd/map_renderer.cc b/selfdrive/navd/map_renderer.cc
index 91f31d06dc..51676bb3a3 100644
--- a/selfdrive/navd/map_renderer.cc
+++ b/selfdrive/navd/map_renderer.cc
@@ -169,7 +169,7 @@ void MapRenderer::publish(const double render_time) {
VisionBuf* buf = vipc_server->get_buffer(VisionStreamType::VISION_STREAM_MAP);
VisionIpcBufExtra extra = {
.frame_id = frame_id,
- .timestamp_sof = sm->rcv_time("liveLocationKalman"),
+ .timestamp_sof = (*sm)["liveLocationKalman"].getLogMonoTime(),
.timestamp_eof = ts,
};
@@ -206,7 +206,7 @@ void MapRenderer::publish(const double render_time) {
// Send state msg
MessageBuilder msg;
auto state = msg.initEvent().initMapRenderState();
- state.setLocationMonoTime(sm->rcv_time("liveLocationKalman"));
+ state.setLocationMonoTime((*sm)["liveLocationKalman"].getLogMonoTime());
state.setRenderTime(render_time);
state.setFrameId(frame_id);
pm->send("mapRenderState", msg);
diff --git a/selfdrive/test/process_replay/model_replay.py b/selfdrive/test/process_replay/model_replay.py
index ce861b37e6..324801fead 100755
--- a/selfdrive/test/process_replay/model_replay.py
+++ b/selfdrive/test/process_replay/model_replay.py
@@ -43,12 +43,12 @@ def replace_calib(msg, calib):
def nav_model_replay(lr):
- sm = messaging.SubMaster(['navModel', 'navThumbnail'])
+ sm = messaging.SubMaster(['navModel', 'navThumbnail', 'mapRenderState'])
pm = messaging.PubMaster(['liveLocationKalman', 'navRoute'])
nav = [m for m in lr if m.which() == 'navRoute']
llk = [m for m in lr if m.which() == 'liveLocationKalman']
- assert len(nav) > 0 and len(llk) >= NAV_FRAMES
+ assert len(nav) > 0 and len(llk) >= NAV_FRAMES and nav[0].logMonoTime < llk[-NAV_FRAMES].logMonoTime
log_msgs = []
try:
@@ -59,8 +59,8 @@ def nav_model_replay(lr):
# setup position and route
for _ in range(10):
- for s in (llk, nav):
- pm.send(s[0].which(), s[0].as_builder().to_bytes())
+ for s in (llk[-NAV_FRAMES], nav[0]):
+ pm.send(s.which(), s.as_builder().to_bytes())
sm.update(1000)
if sm.updated['navModel']:
break
@@ -74,12 +74,16 @@ def nav_model_replay(lr):
sm.update(0)
# run replay
- for n in range(NAV_FRAMES):
+ for n in range(len(llk) - NAV_FRAMES, len(llk)):
pm.send(llk[n].which(), llk[n].as_builder().to_bytes())
m = messaging.recv_one(sm.sock['navThumbnail'])
assert m is not None, f"no navThumbnail, frame={n}"
log_msgs.append(m)
+ m = messaging.recv_one(sm.sock['mapRenderState'])
+ assert m is not None, f"no mapRenderState, frame={n}"
+ log_msgs.append(m)
+
m = messaging.recv_one(sm.sock['navModel'])
assert m is not None, f"no navModel response, frame={n}"
log_msgs.append(m)
@@ -231,6 +235,8 @@ if __name__ == "__main__":
'navModel.dspExecutionTime',
'navModel.modelExecutionTime',
'navThumbnail.timestampEof',
+ 'mapRenderState.locationMonoTime',
+ 'mapRenderState.renderTime',
]
if PC:
ignore += [
diff --git a/selfdrive/test/process_replay/model_replay_ref_commit b/selfdrive/test/process_replay/model_replay_ref_commit
index aa204e0f8a..22e021dcaf 100644
--- a/selfdrive/test/process_replay/model_replay_ref_commit
+++ b/selfdrive/test/process_replay/model_replay_ref_commit
@@ -1 +1 @@
-4ff972367fdb9546be68ee0ba0d45cf4f839dae7
+db587bfef2317c5a3471632ac47381457e1be853
\ No newline at end of file
From f75b640cf57d8f1a54d2d421194178d3ea9d38f1 Mon Sep 17 00:00:00 2001
From: lucentheart <97204067+lucentheart@users.noreply.github.com>
Date: Tue, 20 Dec 2022 20:57:07 -0500
Subject: [PATCH 005/484] Add missing FW versions for 2019 Honda Passport
(#26815)
Update values.py
---
selfdrive/car/honda/values.py | 4 ++++
1 file changed, 4 insertions(+)
diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py
index 905c9f4b4f..2906b23bda 100644
--- a/selfdrive/car/honda/values.py
+++ b/selfdrive/car/honda/values.py
@@ -1167,6 +1167,7 @@ FW_VERSIONS = {
(Ecu.programmedFuelInjection, 0x18da10f1, None): [
b'37805-RLV-B220\x00\x00',
b'37805-RLV-B210\x00\x00',
+ b'37805-RLV-L160\x00\x00',
],
(Ecu.eps, 0x18da30f1, None): [
b'39990-TGS-A230\x00\x00',
@@ -1177,6 +1178,7 @@ FW_VERSIONS = {
],
(Ecu.gateway, 0x18daeff1, None): [
b'38897-TG7-A040\x00\x00',
+ b'38897-TG7-A030\x00\x00',
],
(Ecu.srs, 0x18da53f1, None): [
b'77959-TGS-A010\x00\x00',
@@ -1186,10 +1188,12 @@ FW_VERSIONS = {
],
(Ecu.transmission, 0x18da1ef1, None): [
b'28101-5EZ-A600\x00\x00',
+ b'28101-5EZ-A430\x00\x00',
],
(Ecu.combinationMeter, 0x18da60f1, None): [
b'78109-TGS-AT20\x00\x00',
b'78109-TGS-AX20\x00\x00',
+ b'78109-TGS-AJ20\x00\x00',
],
(Ecu.vsa, 0x18da28f1, None): [
b'57114-TGS-A530\x00\x00',
From c4d2e8bcf4ce7187c92a4321e0ab2d99fa0791a6 Mon Sep 17 00:00:00 2001
From: Adeeb Shihadeh
Date: Tue, 20 Dec 2022 20:03:24 -0800
Subject: [PATCH 006/484] bump panda
---
panda | 2 +-
1 file changed, 1 insertion(+), 1 deletion(-)
diff --git a/panda b/panda
index 9e5c28e568..345147fe2b 160000
--- a/panda
+++ b/panda
@@ -1 +1 @@
-Subproject commit 9e5c28e568a1efe4bac340b48b3c16aafc82e84c
+Subproject commit 345147fe2bc3a06c44709426f9fcd298588b9fe4
From af561393fe0d535315a52e35556697667886089d Mon Sep 17 00:00:00 2001
From: Robbe Derks
Date: Wed, 28 Dec 2022 15:38:10 +0100
Subject: [PATCH 007/484] Tesla non-zero stopAccel (#26840)
remove stopAccel override
---
selfdrive/car/tesla/interface.py | 1 -
1 file changed, 1 deletion(-)
diff --git a/selfdrive/car/tesla/interface.py b/selfdrive/car/tesla/interface.py
index 49e06d8923..6a73472108 100755
--- a/selfdrive/car/tesla/interface.py
+++ b/selfdrive/car/tesla/interface.py
@@ -23,7 +23,6 @@ class CarInterface(CarInterfaceBase):
ret.longitudinalTuning.kpV = [0]
ret.longitudinalTuning.kiBP = [0]
ret.longitudinalTuning.kiV = [0]
- ret.stopAccel = 0.0
ret.longitudinalActuatorDelayUpperBound = 0.5 # s
ret.radarTimeStep = (1.0 / 8) # 8Hz
From f15a5c9ad697e41eb273875577855ec5edede7f4 Mon Sep 17 00:00:00 2001
From: Dean Lee
Date: Thu, 29 Dec 2022 08:47:49 +0800
Subject: [PATCH 008/484] cabana: align y axis correctly (#26837)
---
tools/cabana/chartswidget.cc | 39 ++++++++++++++++++++++++------------
tools/cabana/chartswidget.h | 5 ++++-
2 files changed, 30 insertions(+), 14 deletions(-)
diff --git a/tools/cabana/chartswidget.cc b/tools/cabana/chartswidget.cc
index bc28666a34..da39fb1a66 100644
--- a/tools/cabana/chartswidget.cc
+++ b/tools/cabana/chartswidget.cc
@@ -156,6 +156,7 @@ void ChartsWidget::showChart(const QString &id, const Signal *sig, bool show, bo
QObject::connect(chart, &ChartView::zoomReset, this, &ChartsWidget::zoomReset);
QObject::connect(chart, &ChartView::seriesRemoved, this, &ChartsWidget::seriesChanged);
QObject::connect(chart, &ChartView::seriesAdded, this, &ChartsWidget::seriesChanged);
+ QObject::connect(chart, &ChartView::axisYUpdated, this, &ChartsWidget::alignCharts);
charts_layout->insertWidget(0, chart);
charts.push_back(chart);
}
@@ -171,6 +172,7 @@ void ChartsWidget::removeChart(ChartView *chart) {
charts.removeOne(chart);
chart->deleteLater();
updateToolBar();
+ alignCharts();
emit seriesChanged();
}
@@ -183,6 +185,16 @@ void ChartsWidget::removeAll() {
emit seriesChanged();
}
+void ChartsWidget::alignCharts() {
+ int plot_left = 0;
+ for (auto c : charts) {
+ plot_left = qMax((qreal)plot_left, c->getYAsixLabelWidth());
+ }
+ for (auto c : charts) {
+ c->setPlotAreaLeftPosition(plot_left);
+ }
+}
+
bool ChartsWidget::eventFilter(QObject *obj, QEvent *event) {
if (obj != this && event->type() == QEvent::Close) {
emit dock_btn->triggered();
@@ -202,7 +214,6 @@ ChartView::ChartView(QWidget *parent) : QChartView(nullptr, parent) {
chart->addAxis(axis_y, Qt::AlignLeft);
chart->legend()->setShowToolTips(true);
chart->layout()->setContentsMargins(0, 0, 0, 0);
- chart->setMargins(QMargins(20, 11, 11, 11));
QToolButton *remove_btn = new QToolButton();
remove_btn->setText("X");
@@ -234,6 +245,19 @@ ChartView::ChartView(QWidget *parent) : QChartView(nullptr, parent) {
QObject::connect(manage_btn, &QToolButton::clicked, this, &ChartView::manageSeries);
}
+qreal ChartView::getYAsixLabelWidth() const {
+ QFontMetrics fm(axis_y->labelsFont());
+ int n = qMax(int(-qFloor(std::log10((axis_y->max() - axis_y->min()) / (axis_y->tickCount() - 1)))), 0) + 1;
+ return qMax(fm.width(QString::number(axis_y->min(), 'f', n)), fm.width(QString::number(axis_y->max(), 'f', n))) + 20;
+}
+
+void ChartView::setPlotAreaLeftPosition(int pos) {
+ if (std::ceil(chart()->plotArea().left()) != pos) {
+ const float left_margin = chart()->margins().left() + pos - chart()->plotArea().left();
+ chart()->setMargins(QMargins(left_margin, 11, 11, 11));
+ }
+}
+
void ChartView::addSeries(const QString &msg_id, const Signal *sig) {
QLineSeries *series = new QLineSeries(this);
series->setUseOpenGL(true);
@@ -361,16 +385,6 @@ void ChartView::setDisplayRange(double min, double max) {
}
}
-void ChartView::adjustChartMargins() {
- // TODO: Remove hardcoded aligned_pos
- const int aligned_pos = 60;
- if ((int)chart()->plotArea().left() != aligned_pos) {
- const float left_margin = chart()->margins().left() + aligned_pos - chart()->plotArea().left();
- chart()->setMargins(QMargins(left_margin, 11, 11, 11));
- scene()->invalidate({}, QGraphicsScene::ForegroundLayer);
- }
-}
-
void ChartView::updateSeries(const Signal *sig) {
auto events = can->events();
if (!events || sigs.isEmpty()) return;
@@ -436,8 +450,7 @@ void ChartView::updateAxisY() {
double range = max_y - min_y;
applyNiceNumbers(min_y - range * 0.05, max_y + range * 0.05);
}
-
- adjustChartMargins();
+ QTimer::singleShot(0, this, &ChartView::axisYUpdated);
}
void ChartView::applyNiceNumbers(qreal min, qreal max) {
diff --git a/tools/cabana/chartswidget.h b/tools/cabana/chartswidget.h
index 1799a25488..7a8325382d 100644
--- a/tools/cabana/chartswidget.h
+++ b/tools/cabana/chartswidget.h
@@ -26,6 +26,8 @@ public:
void updateSeries(const Signal *sig = nullptr);
void setEventsRange(const std::pair &range);
void setDisplayRange(double min, double max);
+ void setPlotAreaLeftPosition(int pos);
+ qreal getYAsixLabelWidth() const;
struct SigItem {
QString msg_id;
@@ -44,6 +46,7 @@ signals:
void zoomIn(double min, double max);
void zoomReset();
void remove();
+ void axisYUpdated();
private slots:
void msgRemoved(uint32_t address);
@@ -58,7 +61,6 @@ private:
void mouseMoveEvent(QMouseEvent *ev) override;
void leaveEvent(QEvent *event) override;
void resizeEvent(QResizeEvent *event) override;
- void adjustChartMargins();
void updateAxisY();
void updateTitle();
void updateFromSettings();
@@ -89,6 +91,7 @@ signals:
void seriesChanged();
private:
+ void alignCharts();
void removeChart(ChartView *chart);
void eventsMerged();
void updateState();
From 65509669b676bad41d57443454dbea8ffbc1c8f7 Mon Sep 17 00:00:00 2001
From: Dean Lee
Date: Thu, 29 Dec 2022 08:51:02 +0800
Subject: [PATCH 009/484] Cabana: add tool to find similar bits (#26834)
* find similar bits
* set window title
---
tools/cabana/SConscript | 2 +-
tools/cabana/mainwin.cc | 8 ++
tools/cabana/mainwin.h | 2 +
tools/cabana/tools/findsimilarbits.cc | 115 ++++++++++++++++++++++++++
tools/cabana/tools/findsimilarbits.h | 23 ++++++
5 files changed, 149 insertions(+), 1 deletion(-)
create mode 100644 tools/cabana/tools/findsimilarbits.cc
create mode 100644 tools/cabana/tools/findsimilarbits.h
diff --git a/tools/cabana/SConscript b/tools/cabana/SConscript
index 52fe9e346d..718e2e50af 100644
--- a/tools/cabana/SConscript
+++ b/tools/cabana/SConscript
@@ -18,7 +18,7 @@ cabana_env = qt_env.Clone()
prev_moc_path = cabana_env['QT_MOCHPREFIX']
cabana_env['QT_MOCHPREFIX'] = os.path.dirname(prev_moc_path) + '/cabana/moc_'
cabana_lib = cabana_env.Library("cabana_lib", ['mainwin.cc', 'binaryview.cc', 'chartswidget.cc', 'historylog.cc', 'videowidget.cc', 'signaledit.cc', 'dbcmanager.cc',
- 'canmessages.cc', 'commands.cc', 'messageswidget.cc', 'settings.cc', 'detailwidget.cc'], LIBS=cabana_libs, FRAMEWORKS=base_frameworks)
+ 'canmessages.cc', 'commands.cc', 'messageswidget.cc', 'settings.cc', 'detailwidget.cc', 'tools/findsimilarbits.cc'], LIBS=cabana_libs, FRAMEWORKS=base_frameworks)
cabana_env.Program('_cabana', ['cabana.cc', cabana_lib], LIBS=cabana_libs, FRAMEWORKS=base_frameworks)
if GetOption('test'):
diff --git a/tools/cabana/mainwin.cc b/tools/cabana/mainwin.cc
index f14d522c20..4ae53223a8 100644
--- a/tools/cabana/mainwin.cc
+++ b/tools/cabana/mainwin.cc
@@ -133,6 +133,9 @@ void MainWindow::createActions() {
commands_act->setDefaultWidget(undo_view);
commands_menu->addAction(commands_act);
+ QMenu *tools_menu = menuBar()->addMenu(tr("&Tools"));
+ tools_menu->addAction(tr("Find &Similar Bits"), this, &MainWindow::findSimilarBits);
+
QMenu *help_menu = menuBar()->addMenu(tr("&Help"));
help_menu->addAction(tr("About &Qt"), qApp, &QApplication::aboutQt);
}
@@ -283,3 +286,8 @@ void MainWindow::setOption() {
SettingsDlg dlg(this);
dlg.exec();
}
+
+void MainWindow::findSimilarBits() {
+ FindSimilarBitsDlg dlg(this);
+ dlg.exec();
+}
diff --git a/tools/cabana/mainwin.h b/tools/cabana/mainwin.h
index 17c513d809..5d3ba470a1 100644
--- a/tools/cabana/mainwin.h
+++ b/tools/cabana/mainwin.h
@@ -11,6 +11,7 @@
#include "tools/cabana/detailwidget.h"
#include "tools/cabana/messageswidget.h"
#include "tools/cabana/videowidget.h"
+#include "tools/cabana/tools/findsimilarbits.h"
class MainWindow : public QMainWindow {
Q_OBJECT
@@ -41,6 +42,7 @@ protected:
void DBCFileChanged();
void updateDownloadProgress(uint64_t cur, uint64_t total, bool success);
void setOption();
+ void findSimilarBits();
VideoWidget *video_widget;
MessagesWidget *messages_widget;
diff --git a/tools/cabana/tools/findsimilarbits.cc b/tools/cabana/tools/findsimilarbits.cc
new file mode 100644
index 0000000000..5fa5bcf7b8
--- /dev/null
+++ b/tools/cabana/tools/findsimilarbits.cc
@@ -0,0 +1,115 @@
+#include "tools/cabana/tools/findsimilarbits.h"
+
+#include
+#include
+#include
+#include
+#include
+#include
+
+#include "tools/cabana/canmessages.h"
+#include "tools/cabana/dbcmanager.h"
+
+FindSimilarBitsDlg::FindSimilarBitsDlg(QWidget *parent) : QDialog(parent) {
+ setWindowTitle(tr("Find similar bits"));
+ QVBoxLayout *main_layout = new QVBoxLayout(this);
+
+ QHBoxLayout *form_layout = new QHBoxLayout();
+ bus_combo = new QComboBox(this);
+ QSet bus_set;
+ for (auto it = can->can_msgs.begin(); it != can->can_msgs.end(); ++it) {
+ bus_set << DBCManager::parseId(it.key()).first;
+ }
+ for (uint8_t bus : bus_set) {
+ bus_combo->addItem(QString::number(bus));
+ }
+ bus_combo->model()->sort(0);
+ bus_combo->setCurrentIndex(0);
+ form_layout->addWidget(new QLabel("Bus"));
+ form_layout->addWidget(bus_combo);
+
+ bit_combo = new QComboBox(this);
+ bit_combo->addItems({"0", "1"});
+ bit_combo->setCurrentIndex(1);
+ form_layout->addWidget(new QLabel("Bit"));
+ form_layout->addWidget(bit_combo);
+
+ min_msgs = new QLineEdit(this);
+ min_msgs->setValidator(new QIntValidator(this));
+ min_msgs->setText("100");
+ form_layout->addWidget(new QLabel("Min msg count"));
+ form_layout->addWidget(min_msgs);
+ search_btn = new QPushButton(tr("&Find"), this);
+ form_layout->addWidget(search_btn);
+ form_layout->addStretch(1);
+ main_layout->addLayout(form_layout);
+
+ table = new QTableWidget(this);
+ table->setEditTriggers(QAbstractItemView::NoEditTriggers);
+ table->horizontalHeader()->setStretchLastSection(true);
+ main_layout->addWidget(table);
+
+ setMinimumSize({700, 500});
+ QObject::connect(search_btn, &QPushButton::clicked, this, &FindSimilarBitsDlg::find);
+}
+
+void FindSimilarBitsDlg::find() {
+ search_btn->setEnabled(false);
+ table->clear();
+ auto msg_mismatched = calcBits(bus_combo->currentText().toUInt(), bit_combo->currentIndex(), min_msgs->text().toInt());
+ table->setRowCount(msg_mismatched.size());
+ table->setColumnCount(6);
+ table->setHorizontalHeaderLabels({"address", "byte idx", "bit idx", "mismatches", "total", "perc%"});
+ for (int i = 0; i < msg_mismatched.size(); ++i) {
+ auto &m = msg_mismatched[i];
+ table->setItem(i, 0, new QTableWidgetItem(QString("%1").arg(m.address, 1, 16)));
+ table->setItem(i, 1, new QTableWidgetItem(QString::number(m.byte_idx)));
+ table->setItem(i, 2, new QTableWidgetItem(QString::number(m.bit_idx)));
+ table->setItem(i, 3, new QTableWidgetItem(QString::number(m.mismatches)));
+ table->setItem(i, 4, new QTableWidgetItem(QString::number(m.total)));
+ table->setItem(i, 5, new QTableWidgetItem(QString::number(m.perc)));
+ }
+ search_btn->setEnabled(true);
+}
+
+QList FindSimilarBitsDlg::calcBits(uint8_t bus, int bit_to_find, int min_msgs_cnt) {
+ QHash> mismatches;
+ QHash msg_count;
+ auto events = can->events();
+ for (auto e : *events) {
+ if (e->which == cereal::Event::Which::CAN) {
+ for (const auto &c : e->event.getCan()) {
+ if (c.getSrc() == bus) {
+ uint32_t address = c.getAddress();
+ ++msg_count[address];
+ auto &mismatched = mismatches[address];
+ const auto dat = c.getDat();
+ if (mismatched.size() < dat.size() * 8) {
+ mismatched.resize(dat.size() * 8);
+ }
+ for (int i = 0; i < dat.size(); ++i) {
+ for (int j = 0; j < 8; ++j) {
+ int bit = ((dat[i] >> (7 - j)) & 1) != 0;
+ mismatched[i * 8 + j] += (bit != bit_to_find);
+ }
+ }
+ }
+ }
+ }
+ }
+
+ QList result;
+ result.reserve(mismatches.size());
+ for (auto it = mismatches.begin(); it != mismatches.end(); ++it) {
+ if (auto cnt = msg_count[it.key()]; cnt > min_msgs_cnt) {
+ auto &mismatched = it.value();
+ for (int i = 0; i < mismatched.size(); ++i) {
+ if (uint32_t perc = (mismatched[i] / (double)cnt) * 100; perc < 50) {
+ result.push_back({it.key(), (uint32_t)i / 8, (uint32_t)i % 8, mismatched[i], cnt, perc});
+ }
+ }
+ }
+ }
+ std::sort(result.begin(), result.end(), [](auto &l, auto &r) { return l.perc > r.perc; });
+ return result;
+}
diff --git a/tools/cabana/tools/findsimilarbits.h b/tools/cabana/tools/findsimilarbits.h
new file mode 100644
index 0000000000..79db4a1c69
--- /dev/null
+++ b/tools/cabana/tools/findsimilarbits.h
@@ -0,0 +1,23 @@
+#pragma once
+
+#include
+#include
+#include
+#include
+
+class FindSimilarBitsDlg : public QDialog {
+public:
+ FindSimilarBitsDlg(QWidget *parent);
+
+private:
+ struct mismatched_struct {
+ uint32_t address, byte_idx, bit_idx, mismatches, total, perc;
+ };
+ QList calcBits(uint8_t bus, int bit_to_find, int min_msgs_cnt);
+ void find();
+
+ QTableWidget *table;
+ QComboBox *bus_combo, *bit_combo;
+ QPushButton *search_btn;
+ QLineEdit *min_msgs;
+};
From 7ae87923864af4cd1378eeccc23c002fc66447e5 Mon Sep 17 00:00:00 2001
From: Dean Lee
Date: Thu, 29 Dec 2022 10:21:06 +0800
Subject: [PATCH 010/484] Cabana: make all panels dockable into each other
(#26838)
---
tools/cabana/cabana.cc | 4 +-
tools/cabana/chartswidget.cc | 4 +-
tools/cabana/mainwin.cc | 100 ++++++++++++++++-------------------
tools/cabana/mainwin.h | 6 +--
tools/cabana/settings.cc | 6 ++-
tools/cabana/settings.h | 2 +-
tools/cabana/videowidget.cc | 13 +++--
tools/cabana/videowidget.h | 2 +-
8 files changed, 70 insertions(+), 67 deletions(-)
diff --git a/tools/cabana/cabana.cc b/tools/cabana/cabana.cc
index 51418e293f..4f037ba595 100644
--- a/tools/cabana/cabana.cc
+++ b/tools/cabana/cabana.cc
@@ -6,6 +6,8 @@
#include "tools/cabana/mainwin.h"
int main(int argc, char *argv[]) {
+ QCoreApplication::setApplicationName("Cabana");
+ QCoreApplication::setAttribute(Qt::AA_ShareOpenGLContexts);
initApp(argc, argv);
QApplication app(argc, argv);
@@ -36,7 +38,7 @@ int main(int argc, char *argv[]) {
int ret = 0;
if (p.loadRoute(route, cmd_parser.value("data_dir"), replay_flags)) {
MainWindow w;
- w.showMaximized();
+ w.show();
ret = app.exec();
}
return ret;
diff --git a/tools/cabana/chartswidget.cc b/tools/cabana/chartswidget.cc
index da39fb1a66..71886a113f 100644
--- a/tools/cabana/chartswidget.cc
+++ b/tools/cabana/chartswidget.cc
@@ -1,5 +1,6 @@
#include "tools/cabana/chartswidget.h"
+#include
#include
#include
#include
@@ -42,7 +43,8 @@ ChartsWidget::ChartsWidget(QWidget *parent) : QWidget(parent) {
main_layout->addWidget(charts_scroll);
max_chart_range = settings.max_chart_x_range;
- use_dark_theme = palette().color(QPalette::WindowText).value() > palette().color(QPalette::Background).value();
+ use_dark_theme = QApplication::style()->standardPalette().color(QPalette::WindowText).value() >
+ QApplication::style()->standardPalette().color(QPalette::Background).value();
updateToolBar();
QObject::connect(dbc(), &DBCManager::DBCFileChanged, this, &ChartsWidget::removeAll);
diff --git a/tools/cabana/mainwin.cc b/tools/cabana/mainwin.cc
index 4ae53223a8..43aa330029 100644
--- a/tools/cabana/mainwin.cc
+++ b/tools/cabana/mainwin.cc
@@ -1,19 +1,16 @@
#include "tools/cabana/mainwin.h"
#include
-#include
#include
#include
+#include
#include
#include
#include
-#include
#include
#include
#include
#include
-#include
-#include
#include
#include
#include
@@ -25,58 +22,20 @@ void qLogMessageHandler(QtMsgType type, const QMessageLogContext &context, const
}
MainWindow::MainWindow() : QMainWindow() {
- setWindowTitle("Cabana");
- QWidget *central_widget = new QWidget(this);
- QHBoxLayout *main_layout = new QHBoxLayout(central_widget);
- main_layout->setContentsMargins(11, 11, 11, 0);
- main_layout->setSpacing(0);
-
- splitter = new QSplitter(Qt::Horizontal, this);
- splitter->setHandleWidth(11);
-
- QWidget *messages_container = new QWidget(this);
- QVBoxLayout *messages_layout = new QVBoxLayout(messages_container);
- messages_layout->setContentsMargins(0, 0, 0, 0);
-
- // left panel
- dbc_combo = createDBCSelector();
- messages_layout->addWidget(dbc_combo);
- messages_widget = new MessagesWidget(this);
- messages_layout->addWidget(messages_widget);
- splitter->addWidget(messages_container);
-
- charts_widget = new ChartsWidget(this);
+ createDockWindows();
detail_widget = new DetailWidget(charts_widget, this);
- splitter->addWidget(detail_widget);
- if (!settings.splitter_state.isEmpty()) {
- splitter->restoreState(settings.splitter_state);
- }
- main_layout->addWidget(splitter);
-
- // right widgets
- QWidget *right_container = new QWidget(this);
- right_container->setFixedWidth(640);
- r_layout = new QVBoxLayout(right_container);
- r_layout->setContentsMargins(11, 0, 0, 0);
- QHBoxLayout *right_hlayout = new QHBoxLayout();
- fingerprint_label = new QLabel(this);
- right_hlayout->addWidget(fingerprint_label, 0, Qt::AlignLeft);
-
- // TODO: click to select another route.
- right_hlayout->addWidget(new QLabel(can->routeName()), 0, Qt::AlignRight);
- r_layout->addLayout(right_hlayout);
-
- video_widget = new VideoWidget(this);
- r_layout->addWidget(video_widget, 0, Qt::AlignTop);
- r_layout->addWidget(charts_widget, 1);
- r_layout->addStretch(0);
- main_layout->addWidget(right_container);
-
- setCentralWidget(central_widget);
+ detail_widget->setSizePolicy(QSizePolicy::Minimum, QSizePolicy::Preferred);
+ setCentralWidget(detail_widget);
createActions();
createStatusBar();
createShortcuts();
+ restoreGeometry(settings.geometry);
+ if (isMaximized()) {
+ setGeometry(QApplication::desktop()->availableGeometry(this));
+ }
+ restoreState(settings.window_state);
+
qRegisterMetaType("uint64_t");
qRegisterMetaType("ReplyMsgType");
installMessageHandler([this](ReplyMsgType type, const std::string msg) {
@@ -140,6 +99,39 @@ void MainWindow::createActions() {
help_menu->addAction(tr("About &Qt"), qApp, &QApplication::aboutQt);
}
+void MainWindow::createDockWindows() {
+ // left panel
+ QWidget *messages_container = new QWidget(this);
+ QVBoxLayout *messages_layout = new QVBoxLayout(messages_container);
+ dbc_combo = createDBCSelector();
+ messages_layout->addWidget(dbc_combo);
+ messages_widget = new MessagesWidget(this);
+ messages_layout->addWidget(messages_widget);
+
+ QDockWidget *dock = new QDockWidget(tr("MESSAGES"), this);
+ dock->setObjectName("MessagesPanel");
+ dock->setAllowedAreas(Qt::LeftDockWidgetArea | Qt::RightDockWidgetArea | Qt::TopDockWidgetArea | Qt::BottomDockWidgetArea);
+ dock->setFeatures(QDockWidget::DockWidgetMovable | QDockWidget::DockWidgetFloatable);
+ dock->setWidget(messages_container);
+ addDockWidget(Qt::LeftDockWidgetArea, dock);
+
+ // right panel
+ QWidget *right_container = new QWidget(this);
+ r_layout = new QVBoxLayout(right_container);
+ charts_widget = new ChartsWidget(this);
+ video_widget = new VideoWidget(this);
+ r_layout->addWidget(video_widget, 0, Qt::AlignTop);
+ r_layout->addWidget(charts_widget, 1);
+ r_layout->addStretch(0);
+
+ video_dock = new QDockWidget(can->routeName(), this);
+ video_dock->setObjectName(tr("VideoPanel"));
+ video_dock->setAllowedAreas(Qt::LeftDockWidgetArea | Qt::RightDockWidgetArea);
+ video_dock->setFeatures(QDockWidget::DockWidgetMovable | QDockWidget::DockWidgetFloatable);
+ video_dock->setWidget(right_container);
+ addDockWidget(Qt::RightDockWidgetArea, video_dock);
+}
+
QComboBox *MainWindow::createDBCSelector() {
QComboBox *c = new QComboBox(this);
c->setEditable(true);
@@ -205,7 +197,7 @@ void MainWindow::loadDBCFromClipboard() {
void MainWindow::loadDBCFromFingerprint() {
auto fingerprint = can->carFingerprint();
- fingerprint_label->setText(fingerprint.isEmpty() ? tr("Unknown Car") : fingerprint);
+ video_dock->setWindowTitle(tr("ROUTE: %1 FINGERPINT: %2").arg(can->routeName()).arg(fingerprint.isEmpty() ? tr("Unknown Car") : fingerprint));
if (!fingerprint.isEmpty()) {
auto dbc_name = fingerprint_to_dbc[fingerprint];
if (dbc_name != QJsonValue::Undefined) {
@@ -257,7 +249,6 @@ void MainWindow::dockCharts(bool dock) {
floating_window->setLayout(new QVBoxLayout());
floating_window->layout()->addWidget(charts_widget);
floating_window->installEventFilter(charts_widget);
- floating_window->setMinimumSize(QGuiApplication::primaryScreen()->size() / 2);
floating_window->showMaximized();
}
}
@@ -277,7 +268,8 @@ void MainWindow::closeEvent(QCloseEvent *event) {
if (floating_window)
floating_window->deleteLater();
- settings.splitter_state = splitter->saveState();
+ settings.geometry = saveGeometry();
+ settings.window_state = saveState();
settings.save();
QWidget::closeEvent(event);
}
diff --git a/tools/cabana/mainwin.h b/tools/cabana/mainwin.h
index 5d3ba470a1..f8b5f92349 100644
--- a/tools/cabana/mainwin.h
+++ b/tools/cabana/mainwin.h
@@ -1,10 +1,10 @@
#pragma once
#include
+#include
#include
#include
#include
-#include
#include
#include "tools/cabana/chartswidget.h"
@@ -35,6 +35,7 @@ signals:
protected:
void createActions();
+ void createDockWindows();
QComboBox *createDBCSelector();
void createStatusBar();
void createShortcuts();
@@ -45,14 +46,13 @@ protected:
void findSimilarBits();
VideoWidget *video_widget;
+ QDockWidget *video_dock;
MessagesWidget *messages_widget;
DetailWidget *detail_widget;
ChartsWidget *charts_widget;
- QSplitter *splitter;
QWidget *floating_window = nullptr;
QVBoxLayout *r_layout;
QProgressBar *progress_bar;
- QLabel *fingerprint_label;
QJsonDocument fingerprint_to_dbc;
QComboBox *dbc_combo;
};
diff --git a/tools/cabana/settings.cc b/tools/cabana/settings.cc
index 63e26f3808..5e7f833317 100644
--- a/tools/cabana/settings.cc
+++ b/tools/cabana/settings.cc
@@ -19,7 +19,8 @@ void Settings::save() {
s.setValue("chart_height", chart_height);
s.setValue("max_chart_x_range", max_chart_x_range);
s.setValue("last_dir", last_dir);
- s.setValue("splitter_state", splitter_state);
+ s.setValue("window_state", window_state);
+ s.setValue("geometry", geometry);
}
void Settings::load() {
@@ -29,7 +30,8 @@ void Settings::load() {
chart_height = s.value("chart_height", 200).toInt();
max_chart_x_range = s.value("max_chart_x_range", 3 * 60).toInt();
last_dir = s.value("last_dir", QDir::homePath()).toString();
- splitter_state = s.value("splitter_state").toByteArray();
+ window_state = s.value("window_state").toByteArray();
+ geometry = s.value("geometry").toByteArray();
}
// SettingsDlg
diff --git a/tools/cabana/settings.h b/tools/cabana/settings.h
index 1db92fe231..d231a3a53a 100644
--- a/tools/cabana/settings.h
+++ b/tools/cabana/settings.h
@@ -18,7 +18,7 @@ public:
int chart_height = 200;
int max_chart_x_range = 3 * 60; // 3 minutes
QString last_dir;
- QByteArray splitter_state;
+ QByteArray window_state, geometry;
signals:
void changed();
diff --git a/tools/cabana/videowidget.cc b/tools/cabana/videowidget.cc
index 6cd173b514..7e40ba2adb 100644
--- a/tools/cabana/videowidget.cc
+++ b/tools/cabana/videowidget.cc
@@ -17,10 +17,17 @@ inline QString formatTime(int seconds) {
return QDateTime::fromTime_t(seconds).toString(seconds > 60 * 60 ? "hh:mm:ss" : "mm:ss");
}
-VideoWidget::VideoWidget(QWidget *parent) : QWidget(parent) {
- QVBoxLayout *main_layout = new QVBoxLayout(this);
+VideoWidget::VideoWidget(QWidget *parent) : QFrame(parent) {
+ setFrameShape(QFrame::StyledPanel);
+ setFrameShadow(QFrame::Sunken);
+ QHBoxLayout *containter_layout = new QHBoxLayout(this);
+ QVBoxLayout *main_layout = new QVBoxLayout();
main_layout->setContentsMargins(0, 0, 0, 0);
+ containter_layout->addStretch(1);
+ containter_layout->addLayout(main_layout);
+ containter_layout->addStretch(1);
+
cam_widget = new CameraWidget("camerad", can->visionStreamType(), false, this);
cam_widget->setFixedSize(parent->width(), parent->width() / 1.596);
main_layout->addWidget(cam_widget);
@@ -56,8 +63,6 @@ VideoWidget::VideoWidget(QWidget *parent) : QWidget(parent) {
}
main_layout->addLayout(control_layout);
- setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed);
-
QObject::connect(can, &CANMessages::updated, this, &VideoWidget::updateState);
QObject::connect(slider, &QSlider::sliderReleased, [this]() { can->seekTo(slider->value() / 1000.0); });
QObject::connect(slider, &QSlider::valueChanged, [=](int value) { time_label->setText(formatTime(value / 1000)); });
diff --git a/tools/cabana/videowidget.h b/tools/cabana/videowidget.h
index ea62081a91..86cdc6f114 100644
--- a/tools/cabana/videowidget.h
+++ b/tools/cabana/videowidget.h
@@ -35,7 +35,7 @@ private:
QSize thumbnail_size = {};
};
-class VideoWidget : public QWidget {
+class VideoWidget : public QFrame {
Q_OBJECT
public:
From ab797588f800c02c6ea181a86b3b1c7d760e8c72 Mon Sep 17 00:00:00 2001
From: Dean Lee
Date: Thu, 29 Dec 2022 10:22:04 +0800
Subject: [PATCH 011/484] Cabana: double click on logs cell to open the chart
(#26833)
---
tools/cabana/chartswidget.cc | 7 ++++---
tools/cabana/detailwidget.cc | 3 +++
tools/cabana/historylog.cc | 12 ++++++++++++
tools/cabana/historylog.h | 4 ++++
4 files changed, 23 insertions(+), 3 deletions(-)
diff --git a/tools/cabana/chartswidget.cc b/tools/cabana/chartswidget.cc
index 71886a113f..cf01533aaa 100644
--- a/tools/cabana/chartswidget.cc
+++ b/tools/cabana/chartswidget.cc
@@ -145,8 +145,9 @@ ChartView *ChartsWidget::findChart(const QString &id, const Signal *sig) {
void ChartsWidget::showChart(const QString &id, const Signal *sig, bool show, bool merge) {
setUpdatesEnabled(false);
- if (show) {
- ChartView *chart = merge && charts.size() > 0 ? charts.back() : nullptr;
+ ChartView *chart = findChart(id, sig);
+ if (show && !chart) {
+ chart = merge && charts.size() > 0 ? charts.back() : nullptr;
if (!chart) {
chart = new ChartView(this);
chart->chart()->setTheme(use_dark_theme ? QChart::QChart::ChartThemeDark : QChart::ChartThemeLight);
@@ -163,7 +164,7 @@ void ChartsWidget::showChart(const QString &id, const Signal *sig, bool show, bo
charts.push_back(chart);
}
chart->addSeries(id, sig);
- } else if (ChartView *chart = findChart(id, sig)) {
+ } else if (!show && chart) {
chart->removeSeries(id, sig);
}
updateToolBar();
diff --git a/tools/cabana/detailwidget.cc b/tools/cabana/detailwidget.cc
index 108aa8776e..06377616da 100644
--- a/tools/cabana/detailwidget.cc
+++ b/tools/cabana/detailwidget.cc
@@ -108,6 +108,9 @@ DetailWidget::DetailWidget(ChartsWidget *charts, QWidget *parent) : charts(chart
});
QObject::connect(tabbar, &QTabBar::tabCloseRequested, tabbar, &QTabBar::removeTab);
QObject::connect(charts, &ChartsWidget::seriesChanged, this, &DetailWidget::updateChartState);
+ QObject::connect(history_log, &LogsWidget::openChart, [this](const QString &id, const Signal *sig) {
+ this->charts->showChart(id, sig, true, false);
+ });
QObject::connect(undo_stack, &QUndoStack::indexChanged, [this]() {
if (undo_stack->count() > 0)
dbcMsgChanged();
diff --git a/tools/cabana/historylog.cc b/tools/cabana/historylog.cc
index 3e456e44e9..0fd939c6f7 100644
--- a/tools/cabana/historylog.cc
+++ b/tools/cabana/historylog.cc
@@ -22,6 +22,8 @@ QVariant HistoryLogModel::data(const QModelIndex &index, int role) const {
return !sigs.empty() ? QString::number(m.sig_values[index.column() - 1]) : m.data;
} else if (role == Qt::FontRole && index.column() == 1 && sigs.empty()) {
return QFontDatabase::systemFont(QFontDatabase::FixedFont);
+ } else if (role == Qt::ToolTipRole && index.column() > 0 && !sigs.empty()) {
+ return tr("double click to open the chart");
}
return {};
}
@@ -182,6 +184,7 @@ LogsWidget::LogsWidget(QWidget *parent) : QWidget(parent) {
logs->setModel(model);
main_layout->addWidget(logs);
+ QObject::connect(logs, &QTableView::doubleClicked, this, &LogsWidget::doubleClicked);
QObject::connect(signals_cb, SIGNAL(currentIndexChanged(int)), this, SLOT(setFilter()));
QObject::connect(comp_box, SIGNAL(currentIndexChanged(int)), this, SLOT(setFilter()));
QObject::connect(value_edit, &QLineEdit::textChanged, this, &LogsWidget::setFilter);
@@ -218,3 +221,12 @@ void LogsWidget::setFilter() {
}
model->setFilter(signals_cb->currentIndex(), value_edit->text(), cmp);
}
+
+void LogsWidget::doubleClicked(const QModelIndex &index) {
+ if (index.isValid()) {
+ if (model->sigs.size() > 0 && index.column() > 0) {
+ emit openChart(model->msg_id, model->sigs[index.column()-1]);
+ }
+ can->seekTo(model->messages[index.row()].mono_time / (double)1e9 - can->routeStartTime());
+ }
+}
diff --git a/tools/cabana/historylog.h b/tools/cabana/historylog.h
index d5ae47192e..c636f9b48f 100644
--- a/tools/cabana/historylog.h
+++ b/tools/cabana/historylog.h
@@ -60,10 +60,14 @@ public:
void setMessage(const QString &message_id);
void updateState() { model->updateState(); }
+signals:
+ void openChart(const QString &msg_id, const Signal *sig);
+
private slots:
void setFilter();
private:
+ void doubleClicked(const QModelIndex &index);
void showEvent(QShowEvent *event) override { model->setMessage(model->msg_id); };
HistoryLog *logs;
From 981532f0c32f58e0ba4675fe3b066d7c6d0d9a8e Mon Sep 17 00:00:00 2001
From: Kurt Nistelberger
Date: Thu, 29 Dec 2022 17:56:35 -0700
Subject: [PATCH 012/484] Laikad preperation (#26800)
* laikad update, renaming
* update locationd
* address PR comments
* draft to fix replay
* fix process relay to allow no response for messages
* bump cereal
* update process replay ref commit
* move laikad helpers to laika
* fix ublox test
* update refs
* add proper qcom replay support
* fix gnss support if both is available
* update refs
* move laika back to master
* move cereal back to master
Co-authored-by: Kurt Nistelberger
---
cereal | 2 +-
laika_repo | 2 +-
release/files_common | 1 -
selfdrive/locationd/laikad.py | 154 +++++++++++-------
selfdrive/locationd/laikad_helpers.py | 89 ----------
selfdrive/locationd/locationd.cc | 92 ++++++++++-
selfdrive/locationd/locationd.h | 2 +
.../locationd/test/test_ublox_processing.py | 7 +-
.../test/process_replay/process_replay.py | 25 ++-
selfdrive/test/process_replay/ref_commit | 2 +-
10 files changed, 197 insertions(+), 179 deletions(-)
delete mode 100644 selfdrive/locationd/laikad_helpers.py
diff --git a/cereal b/cereal
index 22b1431132..f200875ca3 160000
--- a/cereal
+++ b/cereal
@@ -1 +1 @@
-Subproject commit 22b1431132b038253a24ab3fbbe3af36ef93b95b
+Subproject commit f200875ca300d3a7b9293c4effcc9456e359e505
diff --git a/laika_repo b/laika_repo
index e1049cde0a..5eb0c3c259 160000
--- a/laika_repo
+++ b/laika_repo
@@ -1 +1 @@
-Subproject commit e1049cde0a68f7d4a70b1ebd76befdc0e163ad55
+Subproject commit 5eb0c3c2596dd12a232b83bdb057a716810e89cf
diff --git a/release/files_common b/release/files_common
index f438904118..a06543abbf 100644
--- a/release/files_common
+++ b/release/files_common
@@ -233,7 +233,6 @@ selfdrive/locationd/generated/gps.cpp
selfdrive/locationd/generated/gps.h
selfdrive/locationd/laikad.py
-selfdrive/locationd/laikad_helpers.py
selfdrive/locationd/locationd.h
selfdrive/locationd/locationd.cc
selfdrive/locationd/paramsd.py
diff --git a/selfdrive/locationd/laikad.py b/selfdrive/locationd/laikad.py
index 6936d88acc..1f13c2b69a 100755
--- a/selfdrive/locationd/laikad.py
+++ b/selfdrive/locationd/laikad.py
@@ -20,7 +20,7 @@ from laika.ephemeris import Ephemeris, EphemerisType, convert_ublox_ephem, parse
from laika.gps_time import GPSTime
from laika.helpers import ConstellationId
from laika.raw_gnss import GNSSMeasurement, correct_measurements, process_measurements, read_raw_ublox, read_raw_qcom
-from selfdrive.locationd.laikad_helpers import calc_pos_fix_gauss_newton, get_posfix_sympy_fun
+from laika.opt import calc_pos_fix, get_posfix_sympy_fun, calc_vel_fix, get_velfix_sympy_func
from selfdrive.locationd.models.constants import GENERATED_DIR, ObservationKind
from selfdrive.locationd.models.gnss_kf import GNSSKalman
from selfdrive.locationd.models.gnss_kf import States as GStates
@@ -58,9 +58,9 @@ class Laikad:
self.load_cache()
self.posfix_functions = {constellation: get_posfix_sympy_fun(constellation) for constellation in (ConstellationId.GPS, ConstellationId.GLONASS)}
- self.last_pos_fix = []
- self.last_pos_residual = []
- self.last_pos_fix_t = None
+ self.velfix_function = get_velfix_sympy_func()
+ self.last_fix_pos = None
+ self.last_fix_t = None
self.gps_week = None
self.use_qcom = use_qcom
@@ -92,20 +92,23 @@ class Laikad:
cloudlog.debug("Cache saved")
self.last_cached_t = t
- def get_est_pos(self, t, processed_measurements):
- if self.last_pos_fix_t is None or abs(self.last_pos_fix_t - t) >= 2:
- min_measurements = 6 if any(p.constellation_id == ConstellationId.GLONASS for p in processed_measurements) else 5
- pos_fix, pos_fix_residual = calc_pos_fix_gauss_newton(processed_measurements, self.posfix_functions, min_measurements=min_measurements)
- if len(pos_fix) > 0:
- self.last_pos_fix_t = t
- residual_median = np.median(np.abs(pos_fix_residual))
- if np.median(np.abs(pos_fix_residual)) < POS_FIX_RESIDUAL_THRESHOLD:
- cloudlog.debug(f"Pos fix is within threshold with median: {residual_median.round()}")
- self.last_pos_fix = pos_fix[:3]
- self.last_pos_residual = pos_fix_residual
- else:
- cloudlog.debug(f"Pos fix failed with median: {residual_median.round()}. All residuals: {np.round(pos_fix_residual)}")
- return self.last_pos_fix
+ def get_lsq_fix(self, t, measurements):
+ if self.last_fix_t is None or abs(self.last_fix_t - t) > 0:
+ min_measurements = 6 if any(p.constellation_id == ConstellationId.GLONASS for p in measurements) else 5
+ position_solution, pr_residuals = calc_pos_fix(measurements, self.posfix_functions, min_measurements=min_measurements)
+
+ if len(position_solution) < 3:
+ return None
+ position_estimate = position_solution[:3]
+ #TODO median abs residual is decent estimate of std, can be improved with measurements stds and/or DOP
+ position_std = np.median(np.abs(pr_residuals)) * np.ones(3)
+ velocity_solution, prr_residuals = calc_vel_fix(measurements, position_estimate, self.velfix_function, min_measurements=min_measurements)
+ if len(velocity_solution) < 3:
+ return None
+
+ velocity_estimate = velocity_solution[:3]
+ velocity_std = np.median(np.abs(prr_residuals)) * np.ones(3)
+ return position_estimate, position_std, velocity_estimate, velocity_std
def is_good_report(self, gnss_msg):
if gnss_msg.which() == 'drMeasurementReport' and self.use_qcom:
@@ -148,11 +151,36 @@ class Laikad:
self.astro_dog.add_navs({ephem.prn: [ephem]})
self.cache_ephemeris(t=ephem.epoch)
+ def process_report(self, new_meas, t):
+ # Filter measurements with unexpected pseudoranges for GPS and GLONASS satellites
+ new_meas = [m for m in new_meas if 1e7 < m.observables['C1C'] < 3e7]
+ processed_measurements = process_measurements(new_meas, self.astro_dog)
+
+ instant_fix = self.get_lsq_fix(t, processed_measurements)
+ if instant_fix is None:
+ return None
+ else:
+ position_estimate, position_std, velocity_estimate, velocity_std = instant_fix
+ self.last_fix_t = t
+ self.last_fix_pos = position_estimate
+ self.lat_fix_pos_std = position_std
+
+ corrected_measurements = correct_measurements(processed_measurements, position_estimate, self.astro_dog)
+ if (t*1e9) % 10 == 0:
+ cloudlog.debug(f"Measurements Incoming/Processed/Corrected: {len(new_meas), len(processed_measurements), len(corrected_measurements)}")
+ return position_estimate, position_std, velocity_estimate, velocity_std, corrected_measurements, processed_measurements
+
def process_gnss_msg(self, gnss_msg, gnss_mono_time: int, block=False):
- if self.is_good_report(gnss_msg):
+ if self.is_ephemeris(gnss_msg):
+ self.read_ephemeris(gnss_msg)
+ return None
+ elif self.is_good_report(gnss_msg):
+
week, tow, new_meas = self.read_report(gnss_msg)
- self.gps_week = week
+ if len(new_meas) == 0:
+ return None
+ self.gps_week = week
t = gnss_mono_time * 1e-9
if week > 0:
self.got_first_gnss_msg = True
@@ -160,44 +188,38 @@ class Laikad:
if self.auto_fetch_orbits:
self.fetch_orbits(latest_msg_t, block)
- # Filter measurements with unexpected pseudoranges for GPS and GLONASS satellites
- new_meas = [m for m in new_meas if 1e7 < m.observables['C1C'] < 3e7]
-
- processed_measurements = process_measurements(new_meas, self.astro_dog)
- est_pos = self.get_est_pos(t, processed_measurements)
-
- corrected_measurements = correct_measurements(processed_measurements, est_pos, self.astro_dog) if len(est_pos) > 0 else []
- if gnss_mono_time % 10 == 0:
- cloudlog.debug(f"Measurements Incoming/Processed/Corrected: {len(new_meas), len(processed_measurements), len(corrected_measurements)}")
-
- self.update_localizer(est_pos, t, corrected_measurements)
- kf_valid = all(self.kf_valid(t))
- ecef_pos = self.gnss_kf.x[GStates.ECEF_POS]
- ecef_vel = self.gnss_kf.x[GStates.ECEF_VELOCITY]
-
- p = self.gnss_kf.P.diagonal()
- pos_std = np.sqrt(p[GStates.ECEF_POS])
- vel_std = np.sqrt(p[GStates.ECEF_VELOCITY])
+ output = self.process_report(new_meas, t)
+ if output is None:
+ return None
+ position_estimate, position_std, velocity_estimate, velocity_std, corrected_measurements, _ = output
+ self.update_localizer(position_estimate, t, corrected_measurements)
meas_msgs = [create_measurement_msg(m) for m in corrected_measurements]
- dat = messaging.new_message("gnssMeasurements")
+ msg = messaging.new_message("gnssMeasurements")
measurement_msg = log.LiveLocationKalman.Measurement.new_message
- dat.gnssMeasurements = {
+
+ P_diag = self.gnss_kf.P.diagonal()
+ kf_valid = all(self.kf_valid(t))
+ msg.gnssMeasurements = {
"gpsWeek": week,
"gpsTimeOfWeek": tow,
- "positionECEF": measurement_msg(value=ecef_pos.tolist(), std=pos_std.tolist(), valid=kf_valid),
- "velocityECEF": measurement_msg(value=ecef_vel.tolist(), std=vel_std.tolist(), valid=kf_valid),
- # TODO std is incorrectly the dimension of the measurements and not 3D
- "positionFixECEF": measurement_msg(value=self.last_pos_fix, std=self.last_pos_residual, valid=self.last_pos_fix_t == t),
- "ubloxMonoTime": gnss_mono_time,
+ "kalmanPositionECEF": measurement_msg(value=self.gnss_kf.x[GStates.ECEF_POS].tolist(),
+ std=np.sqrt(P_diag[GStates.ECEF_POS]).tolist(),
+ valid=kf_valid),
+ "kalmanVelocityECEF": measurement_msg(value=self.gnss_kf.x[GStates.ECEF_VELOCITY].tolist(),
+ std=np.sqrt(P_diag[GStates.ECEF_VELOCITY]).tolist(),
+ valid=kf_valid),
+ "positionECEF": measurement_msg(value=position_estimate, std=position_std.tolist(), valid=bool(self.last_fix_t == t)),
+ "velocityECEF": measurement_msg(value=velocity_estimate, std=velocity_std.tolist(), valid=bool(self.last_fix_t == t)),
+
+ "measTime": gnss_mono_time,
"correctedMeasurements": meas_msgs
}
- return dat
- elif self.is_ephemeris(gnss_msg):
- self.read_ephemeris(gnss_msg)
+ return msg
#elif gnss_msg.which() == 'ionoData':
- # todo add this. Needed to better correct messages offline. First fix ublox_msg.cc to sent them.
+ # TODO: add this, Needed to better correct messages offline. First fix ublox_msg.cc to sent them.
+
def update_localizer(self, est_pos, t: float, measurements: List[GNSSMeasurement]):
# Check time and outputs are valid
@@ -349,9 +371,23 @@ class EphemerisSourceType(IntEnum):
qcom = 3
-def main(sm=None, pm=None):
+def process_msg(laikad, gnss_msg, mono_time, block=False):
+ # TODO: Understand and use remaining unknown constellations
+ if gnss_msg.which() == "drMeasurementReport":
+ if getattr(gnss_msg, gnss_msg.which()).source not in ['glonass', 'gps', 'beidou', 'sbas']:
+ return None
+
+ if getattr(gnss_msg, gnss_msg.which()).gpsWeek > np.iinfo(np.int16).max:
+ # gpsWeek 65535 is received rarely from quectel, this cannot be
+ # passed to GnssMeasurements's gpsWeek (Int16)
+ return None
+
+ return laikad.process_gnss_msg(gnss_msg, mono_time, block=block)
+
+
+def main(sm=None, pm=None, qc=None):
use_qcom = not Params().get_bool("UbloxAvailable", block=True)
- if use_qcom:
+ if use_qcom or (qc is not None and qc):
raw_gnss_socket = "qcomGnss"
else:
raw_gnss_socket = "ubloxGnss"
@@ -371,19 +407,13 @@ def main(sm=None, pm=None):
if sm.updated[raw_gnss_socket]:
gnss_msg = sm[raw_gnss_socket]
- # TODO: Understand and use remaining unknown constellations
- if gnss_msg.which() == "drMeasurementReport":
- if getattr(gnss_msg, gnss_msg.which()).source not in ['glonass', 'gps', 'beidou', 'sbas']:
- continue
+ msg = process_msg(laikad, gnss_msg, sm.logMonoTime[raw_gnss_socket], replay)
+ if msg is None:
+ msg = messaging.new_message("gnssMeasurements")
+ msg.valid = False
- if getattr(gnss_msg, gnss_msg.which()).gpsWeek > np.iinfo(np.int16).max:
- # gpsWeek 65535 is received rarely from quectel, this cannot be
- # passed to GnssMeasurements's gpsWeek (Int16)
- continue
+ pm.send('gnssMeasurements', msg)
- msg = laikad.process_gnss_msg(gnss_msg, sm.logMonoTime[raw_gnss_socket], block=replay)
- if msg is not None:
- pm.send('gnssMeasurements', msg)
if not laikad.got_first_gnss_msg and sm.updated['clocks']:
clocks_msg = sm['clocks']
t = GPSTime.from_datetime(datetime.utcfromtimestamp(clocks_msg.wallTimeNanos * 1E-9))
diff --git a/selfdrive/locationd/laikad_helpers.py b/selfdrive/locationd/laikad_helpers.py
deleted file mode 100644
index f13e8e73bb..0000000000
--- a/selfdrive/locationd/laikad_helpers.py
+++ /dev/null
@@ -1,89 +0,0 @@
-import numpy as np
-import sympy
-
-from laika.constants import EARTH_ROTATION_RATE, SPEED_OF_LIGHT
-from laika.helpers import ConstellationId
-
-
-def calc_pos_fix_gauss_newton(measurements, posfix_functions, x0=None, signal='C1C', min_measurements=6):
- '''
- Calculates gps fix using gauss newton method
- To solve the problem a minimal of 4 measurements are required.
- If Glonass is included 5 are required to solve for the additional free variable.
- returns:
- 0 -> list with positions
- '''
- if x0 is None:
- x0 = [0, 0, 0, 0, 0]
- n = len(measurements)
- if n < min_measurements:
- return [], []
-
- Fx_pos = pr_residual(measurements, posfix_functions, signal=signal)
- x = gauss_newton(Fx_pos, x0)
- residual, _ = Fx_pos(x, weight=1.0)
- return x.tolist(), residual.tolist()
-
-
-def pr_residual(measurements, posfix_functions, signal='C1C'):
- def Fx_pos(inp, weight=None):
- vals, gradients = [], []
-
- for meas in measurements:
- pr = meas.observables[signal]
- pr += meas.sat_clock_err * SPEED_OF_LIGHT
-
- w = (1 / meas.observables_std[signal]) if weight is None else weight
-
- val, *gradient = posfix_functions[meas.constellation_id](*inp, pr, *meas.sat_pos, w)
- vals.append(val)
- gradients.append(gradient)
- return np.asarray(vals), np.asarray(gradients)
-
- return Fx_pos
-
-
-def gauss_newton(fun, b, xtol=1e-8, max_n=25):
- for _ in range(max_n):
- # Compute function and jacobian on current estimate
- r, J = fun(b)
-
- # Update estimate
- delta = np.linalg.pinv(J) @ r
- b -= delta
-
- # Check step size for stopping condition
- if np.linalg.norm(delta) < xtol:
- break
- return b
-
-
-def get_posfix_sympy_fun(constellation):
- # Unknowns
- x, y, z = sympy.Symbol('x'), sympy.Symbol('y'), sympy.Symbol('z')
- bc = sympy.Symbol('bc')
- bg = sympy.Symbol('bg')
- var = [x, y, z, bc, bg]
-
- # Knowns
- pr = sympy.Symbol('pr')
- sat_x, sat_y, sat_z = sympy.Symbol('sat_x'), sympy.Symbol('sat_y'), sympy.Symbol('sat_z')
- weight = sympy.Symbol('weight')
-
- theta = EARTH_ROTATION_RATE * (pr - bc) / SPEED_OF_LIGHT
- val = sympy.sqrt(
- (sat_x * sympy.cos(theta) + sat_y * sympy.sin(theta) - x) ** 2 +
- (sat_y * sympy.cos(theta) - sat_x * sympy.sin(theta) - y) ** 2 +
- (sat_z - z) ** 2
- )
-
- if constellation == ConstellationId.GLONASS:
- res = weight * (val - (pr - bc - bg))
- elif constellation == ConstellationId.GPS:
- res = weight * (val - (pr - bc))
- else:
- raise NotImplementedError(f"Constellation {constellation} not supported")
-
- res = [res] + [sympy.diff(res, v) for v in var]
-
- return sympy.lambdify([x, y, z, bc, bg, pr, sat_x, sat_y, sat_z, weight], res, modules=["numpy"])
diff --git a/selfdrive/locationd/locationd.cc b/selfdrive/locationd/locationd.cc
index 4325900c0e..442adcd347 100755
--- a/selfdrive/locationd/locationd.cc
+++ b/selfdrive/locationd/locationd.cc
@@ -25,8 +25,15 @@ const double MAX_FILTER_REWIND_TIME = 0.8; // s
// TODO: GPS sensor time offsets are empirically calculated
// They should be replaced with synced time from a real clock
-const double GPS_LOCATION_SENSOR_TIME_OFFSET = 0.630; // s
-const double GPS_LOCATION_EXTERNAL_SENSOR_TIME_OFFSET = 0.095; // s
+const double GPS_QUECTEL_SENSOR_TIME_OFFSET = 0.630; // s
+const double GPS_UBLOX_SENSOR_TIME_OFFSET = 0.095; // s
+const float GPS_MUL_FACTOR = 10.0;
+const float GPS_POS_STD_THRESHOLD = 50.0;
+const float GPS_VEL_STD_THRESHOLD = 5.0;
+const float GPS_POS_ERROR_RESET_THRESHOLD = 200.0;
+const float GPS_POS_STD_RESET_THRESHOLD = 5.0;
+const float GPS_VEL_STD_RESET_THRESHOLD = 0.5;
+const float GPS_ORIENTATION_ERROR_RESET_THRESHOLD = 5.0;
static VectorXd floatlist2vector(const capnp::List::Reader& floatlist) {
VectorXd res(floatlist.size());
@@ -316,8 +323,8 @@ void Localizer::handle_gps(double current_time, const cereal::GpsLocationData::R
VectorXd ecef_pos = this->converter->ned2ecef({ 0.0, 0.0, 0.0 }).to_vector();
VectorXd ecef_vel = this->converter->ned2ecef({ log.getVNED()[0], log.getVNED()[1], log.getVNED()[2] }).to_vector() - ecef_pos;
- MatrixXdr ecef_pos_R = Vector3d::Constant(std::pow(10.0 * log.getAccuracy(),2) + std::pow(10.0 * log.getVerticalAccuracy(),2)).asDiagonal();
- MatrixXdr ecef_vel_R = Vector3d::Constant(std::pow(log.getSpeedAccuracy() * 10.0, 2)).asDiagonal();
+ MatrixXdr ecef_pos_R = Vector3d::Constant(std::pow(GPS_MUL_FACTOR * log.getAccuracy(),2) + std::pow(GPS_MUL_FACTOR * log.getVerticalAccuracy(),2)).asDiagonal();
+ MatrixXdr ecef_vel_R = Vector3d::Constant(std::pow(GPS_MUL_FACTOR * log.getSpeedAccuracy(), 2)).asDiagonal();
this->unix_timestamp_millis = log.getUnixTimestampMillis();
double gps_est_error = (this->kf->get_x().segment(STATE_ECEF_POS_START) - ecef_pos).norm();
@@ -348,6 +355,77 @@ void Localizer::handle_gps(double current_time, const cereal::GpsLocationData::R
this->kf->predict_and_observe(sensor_time, OBSERVATION_ECEF_VEL, { ecef_vel }, { ecef_vel_R });
}
+void Localizer::handle_gnss(double current_time, const cereal::GnssMeasurements::Reader& log) {
+
+ this->gps_valid = log.getPositionECEF().getValid() && log.getVelocityECEF().getValid();
+ if (!this->gps_valid) {
+ this->determine_gps_mode(current_time);
+ return;
+ }
+ this->gps_mode = true;
+
+ double sensor_time = log.getMeasTime() * 1e-9;
+ if (ublox_available)
+ sensor_time -= GPS_UBLOX_SENSOR_TIME_OFFSET;
+ else
+ sensor_time -= GPS_QUECTEL_SENSOR_TIME_OFFSET;
+
+ auto ecef_pos_v = log.getPositionECEF().getValue();
+ VectorXd ecef_pos = Vector3d(ecef_pos_v[0], ecef_pos_v[1], ecef_pos_v[2]);
+
+ // indexed at 0 cause all std values are the same MAE
+ auto ecef_pos_std = log.getPositionECEF().getStd()[0];
+ MatrixXdr ecef_pos_R = Vector3d::Constant(pow(GPS_MUL_FACTOR*ecef_pos_std, 2)).asDiagonal();
+
+ auto ecef_vel_v = log.getVelocityECEF().getValue();
+ VectorXd ecef_vel = Vector3d(ecef_vel_v[0], ecef_vel_v[1], ecef_vel_v[2]);
+
+ // indexed at 0 cause all std values are the same MAE
+ auto ecef_vel_std = log.getVelocityECEF().getStd()[0];
+ MatrixXdr ecef_vel_R = Vector3d::Constant(pow(GPS_MUL_FACTOR*ecef_vel_std, 2)).asDiagonal();
+
+ double gps_est_error = (this->kf->get_x().segment(STATE_ECEF_POS_START) - ecef_pos).norm();
+
+ VectorXd orientation_ecef = quat2euler(vector2quat(this->kf->get_x().segment(STATE_ECEF_ORIENTATION_START)));
+ VectorXd orientation_ned = ned_euler_from_ecef({ ecef_pos[0], ecef_pos[1], ecef_pos[2] }, orientation_ecef);
+
+ LocalCoord convs((ECEF){ .x = ecef_pos[0], .y = ecef_pos[1], .z = ecef_pos[2] });
+ ECEF next_ecef = {.x = ecef_pos[0] + ecef_vel[0], .y = ecef_pos[1] + ecef_vel[1], .z = ecef_pos[2] + ecef_vel[2]};
+ VectorXd ned_vel = convs.ecef2ned(next_ecef).to_vector();
+ double bearing_rad = atan2(ned_vel[1], ned_vel[0]);
+
+ VectorXd orientation_ned_gps = Vector3d(0.0, 0.0, bearing_rad);
+ VectorXd orientation_error = (orientation_ned - orientation_ned_gps).array() - M_PI;
+ for (int i = 0; i < orientation_error.size(); i++) {
+ orientation_error(i) = std::fmod(orientation_error(i), 2.0 * M_PI);
+ if (orientation_error(i) < 0.0) {
+ orientation_error(i) += 2.0 * M_PI;
+ }
+ orientation_error(i) -= M_PI;
+ }
+ VectorXd initial_pose_ecef_quat = quat2vector(euler2quat(ecef_euler_from_ned({ ecef_pos(0), ecef_pos(1), ecef_pos(2) }, orientation_ned_gps)));
+
+ if (ecef_pos_std > GPS_POS_STD_THRESHOLD || ecef_vel_std > GPS_VEL_STD_THRESHOLD) {
+ this->gps_valid = false;
+ this->determine_gps_mode(current_time);
+ return;
+ }
+
+ if ((gps_est_error > GPS_POS_ERROR_RESET_THRESHOLD && ecef_pos_std < GPS_POS_STD_RESET_THRESHOLD) || this->last_gps_msg == 0) {
+ // always reset on first gps message and if the location is off but the accuracy is high
+ LOGE("Locationd vs gnssMeasurement position difference too large, kalman reset");
+ this->reset_kalman(NAN, initial_pose_ecef_quat, ecef_pos, ecef_vel, ecef_pos_R, ecef_vel_R);
+ } else if (ecef_vel_std < GPS_VEL_STD_RESET_THRESHOLD && orientation_error.norm() > GPS_ORIENTATION_ERROR_RESET_THRESHOLD) {
+ LOGE("Locationd vs gnssMeasurement orientation difference too large, kalman reset");
+ this->reset_kalman(NAN, initial_pose_ecef_quat, ecef_pos, ecef_vel, ecef_pos_R, ecef_vel_R);
+ this->kf->predict_and_observe(sensor_time, OBSERVATION_ECEF_ORIENTATION_FROM_GPS, { initial_pose_ecef_quat });
+ }
+
+ this->last_gps_msg = current_time;
+ this->kf->predict_and_observe(sensor_time, OBSERVATION_ECEF_POS, { ecef_pos }, { ecef_pos_R });
+ this->kf->predict_and_observe(sensor_time, OBSERVATION_ECEF_VEL, { ecef_vel }, { ecef_vel_R });
+}
+
void Localizer::handle_car_state(double current_time, const cereal::CarState::Reader& log) {
this->car_speed = std::abs(log.getVEgo());
if (log.getStandstill()) {
@@ -497,9 +575,11 @@ void Localizer::handle_msg(const cereal::Event::Reader& log) {
} else if (log.isGyroscope()) {
this->handle_sensor(t, log.getGyroscope());
} else if (log.isGpsLocation()) {
- this->handle_gps(t, log.getGpsLocation(), GPS_LOCATION_SENSOR_TIME_OFFSET);
+ this->handle_gps(t, log.getGpsLocation(), GPS_QUECTEL_SENSOR_TIME_OFFSET);
} else if (log.isGpsLocationExternal()) {
- this->handle_gps(t, log.getGpsLocationExternal(), GPS_LOCATION_EXTERNAL_SENSOR_TIME_OFFSET);
+ this->handle_gps(t, log.getGpsLocationExternal(), GPS_UBLOX_SENSOR_TIME_OFFSET);
+ //} else if (log.isGnssMeasurements()) {
+ // this->handle_gnss(t, log.getGnssMeasurements());
} else if (log.isCarState()) {
this->handle_car_state(t, log.getCarState());
} else if (log.isCameraOdometry()) {
diff --git a/selfdrive/locationd/locationd.h b/selfdrive/locationd/locationd.h
index f0872d9f56..7a282be9d7 100755
--- a/selfdrive/locationd/locationd.h
+++ b/selfdrive/locationd/locationd.h
@@ -52,6 +52,7 @@ public:
void handle_msg(const cereal::Event::Reader& log);
void handle_sensor(double current_time, const cereal::SensorEventData::Reader& log);
void handle_gps(double current_time, const cereal::GpsLocationData::Reader& log, const double sensor_time_offset);
+ void handle_gnss(double current_time, const cereal::GnssMeasurements::Reader& log);
void handle_car_state(double current_time, const cereal::CarState::Reader& log);
void handle_cam_odo(double current_time, const cereal::CameraOdometry::Reader& log);
void handle_live_calib(double current_time, const cereal::LiveCalibrationData::Reader& log);
@@ -77,6 +78,7 @@ private:
bool device_fell = false;
bool gps_mode = false;
bool gps_valid = false;
+ double last_gps_msg = 0;
bool ublox_available = true;
bool observation_timings_invalid = false;
std::map observation_values_invalid;
diff --git a/selfdrive/locationd/test/test_ublox_processing.py b/selfdrive/locationd/test/test_ublox_processing.py
index 427003b24c..7aa588d43e 100755
--- a/selfdrive/locationd/test/test_ublox_processing.py
+++ b/selfdrive/locationd/test/test_ublox_processing.py
@@ -4,7 +4,8 @@ import numpy as np
from laika import AstroDog
from laika.helpers import ConstellationId
-from laika.raw_gnss import calc_pos_fix, correct_measurements, process_measurements, read_raw_ublox
+from laika.raw_gnss import correct_measurements, process_measurements, read_raw_ublox
+from laika.opt import calc_pos_fix
from selfdrive.test.openpilotci import get_url
from tools.lib.logreader import LogReader
@@ -54,14 +55,14 @@ class TestUbloxProcessing(unittest.TestCase):
processed_meas = process_measurements(measurements, dog)
count_processed_measurements += len(processed_meas)
pos_fix = calc_pos_fix(processed_meas)
- if len(pos_fix) > 0 and all(pos_fix[0] != 0):
+ if len(pos_fix) > 0 and all(p != 0 for p in pos_fix[0]):
position_fix_found += 1
corrected_meas = correct_measurements(processed_meas, pos_fix[0][:3], dog)
count_corrected_measurements += len(corrected_meas)
pos_fix = calc_pos_fix(corrected_meas)
- if len(pos_fix) > 0 and all(pos_fix[0] != 0):
+ if len(pos_fix) > 0 and all(p != 0 for p in pos_fix[0]):
pos_ests.append(pos_fix[0])
position_fix_found_after_correcting += 1
diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py
index bc55e33cbf..c5465fc025 100755
--- a/selfdrive/test/process_replay/process_replay.py
+++ b/selfdrive/test/process_replay/process_replay.py
@@ -251,8 +251,10 @@ def ublox_rcv_callback(msg):
def laika_rcv_callback(msg, CP, cfg, fsm):
if msg.which() == 'ubloxGnss' and msg.ubloxGnss.which() == "measurementReport":
return ["gnssMeasurements"], True
+ elif msg.which() == 'qcomGnss' and msg.qcomGnss.which() == "drMeasurementReport":
+ return ["gnssMeasurements"], True
else:
- return [], True
+ return [], False
CONFIGS = [
@@ -360,24 +362,11 @@ CONFIGS = [
tolerance=None,
fake_pubsubmaster=False,
),
- ProcessConfig(
- proc_name="laikad",
- subtest_name="Offline",
- pub_sub={
- "ubloxGnss": ["gnssMeasurements"],
- "clocks": []
- },
- ignore=["logMonoTime"],
- init_callback=get_car_params,
- should_recv_callback=laika_rcv_callback,
- tolerance=NUMPY_TOLERANCE,
- fake_pubsubmaster=True,
- environ={"LAIKAD_NO_INTERNET": "1"},
- ),
ProcessConfig(
proc_name="laikad",
pub_sub={
"ubloxGnss": ["gnssMeasurements"],
+ "qcomGnss": ["gnssMeasurements"],
"clocks": []
},
ignore=["logMonoTime"],
@@ -474,6 +463,12 @@ def python_replay_process(cfg, lr, fingerprint=None):
all_msgs = sorted(lr, key=lambda msg: msg.logMonoTime)
pub_msgs = [msg for msg in all_msgs if msg.which() in list(cfg.pub_sub.keys())]
+ # laikad needs decision between submaster ubloxGnss and qcomGnss, prio given to ubloxGnss
+ if cfg.proc_name == "laikad":
+ args = (*args, not any(m.which() == "ubloxGnss" for m in pub_msgs))
+ service = "qcomGnss" if args[2] else "ubloxGnss"
+ pub_msgs = [m for m in pub_msgs if m.which() == service or m.which() == 'clocks']
+
controlsState = None
initialized = False
for msg in lr:
diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit
index 1d586b0334..603d2b2d96 100644
--- a/selfdrive/test/process_replay/ref_commit
+++ b/selfdrive/test/process_replay/ref_commit
@@ -1 +1 @@
-05ba201bcf97b6c1067dbcde2a60f71f43469c56
+557ffbf5a1c9cafba1ff8d6f3e2642df98b2d6e6
\ No newline at end of file
From e01809857174533e61a25d4bcb85b708031aa8cb Mon Sep 17 00:00:00 2001
From: Dean Lee
Date: Sat, 31 Dec 2022 05:57:29 +0800
Subject: [PATCH 013/484] Cabana: add dynamic/static mode to logs view (#26832)
---
tools/cabana/historylog.cc | 141 +++++++++++++++++++++++--------------
tools/cabana/historylog.h | 23 ++++--
2 files changed, 105 insertions(+), 59 deletions(-)
diff --git a/tools/cabana/historylog.cc b/tools/cabana/historylog.cc
index 0fd939c6f7..485a21cc1b 100644
--- a/tools/cabana/historylog.cc
+++ b/tools/cabana/historylog.cc
@@ -7,12 +7,6 @@
// HistoryLogModel
-HistoryLogModel::HistoryLogModel(QObject *parent) : QAbstractTableModel(parent) {
- QObject::connect(can, &CANMessages::seekedTo, [this]() {
- if (!msg_id.isEmpty()) setMessage(msg_id);
- });
-}
-
QVariant HistoryLogModel::data(const QModelIndex &index, int role) const {
if (role == Qt::DisplayRole) {
const auto &m = messages[index.row()];
@@ -29,17 +23,19 @@ QVariant HistoryLogModel::data(const QModelIndex &index, int role) const {
}
void HistoryLogModel::setMessage(const QString &message_id) {
- beginResetModel();
+ msg_id = message_id;
sigs.clear();
- messages.clear();
- has_more_data = true;
- if (auto dbc_msg = dbc()->msg(message_id)) {
+ if (auto dbc_msg = dbc()->msg(msg_id)) {
sigs = dbc_msg->getSignals();
}
- if (msg_id != message_id || sigs.empty()) {
- filter_cmp = nullptr;
- }
- msg_id = message_id;
+ filter_cmp = nullptr;
+ refresh();
+}
+
+void HistoryLogModel::refresh() {
+ beginResetModel();
+ last_fetch_time = 0;
+ messages.clear();
updateState();
endResetModel();
}
@@ -60,33 +56,40 @@ QVariant HistoryLogModel::headerData(int section, Qt::Orientation orientation, i
return {};
}
-void HistoryLogModel::setFilter(int sig_idx, const QString &value, std::function cmp) {
- if (sig_idx < sigs.size()) {
- filter_sig_idx = sig_idx;
- filter_value = value.toDouble();
- filter_cmp = value.isEmpty() ? nullptr : cmp;
- beginResetModel();
- messages.clear();
- updateState();
- endResetModel();
+void HistoryLogModel::setDynamicMode(int state) {
+ dynamic_mode = state != 0;
+ refresh();
+}
+
+void HistoryLogModel::segmentsMerged() {
+ if (!dynamic_mode) {
+ has_more_data = true;
}
}
+void HistoryLogModel::setFilter(int sig_idx, const QString &value, std::function cmp) {
+ filter_sig_idx = sig_idx;
+ filter_value = value.toDouble();
+ filter_cmp = value.isEmpty() ? nullptr : cmp;
+ refresh();
+}
+
void HistoryLogModel::updateState() {
if (!msg_id.isEmpty()) {
- uint64_t last_mono_time = messages.empty() ? 0 : messages.front().mono_time;
- auto new_msgs = fetchData(last_mono_time, (can->currentSec() + can->routeStartTime()) * 1e9);
+ uint64_t current_time = (can->currentSec() + can->routeStartTime()) * 1e9;
+ auto new_msgs = dynamic_mode ? fetchData(current_time, last_fetch_time) : fetchData(0);
if ((has_more_data = !new_msgs.empty())) {
beginInsertRows({}, 0, new_msgs.size() - 1);
messages.insert(messages.begin(), std::move_iterator(new_msgs.begin()), std::move_iterator(new_msgs.end()));
endInsertRows();
}
+ last_fetch_time = current_time;
}
}
void HistoryLogModel::fetchMore(const QModelIndex &parent) {
if (!messages.empty()) {
- auto new_msgs = fetchData(0, messages.back().mono_time);
+ auto new_msgs = fetchData(messages.back().mono_time);
if ((has_more_data = !new_msgs.empty())) {
beginInsertRows({}, messages.size(), messages.size() + new_msgs.size() - 1);
messages.insert(messages.end(), std::move_iterator(new_msgs.begin()), std::move_iterator(new_msgs.end()));
@@ -95,19 +98,12 @@ void HistoryLogModel::fetchMore(const QModelIndex &parent) {
}
}
-std::deque HistoryLogModel::fetchData(uint64_t min_mono_time, uint64_t max_mono_time) {
- auto events = can->events();
- auto it = std::lower_bound(events->begin(), events->end(), max_mono_time, [=](auto &e, uint64_t ts) {
- return e->mono_time < ts;
- });
- if (it == events->end() || it == events->begin())
- return {};
-
+template
+std::deque HistoryLogModel::fetchData(InputIt first, InputIt last, uint64_t min_time) {
std::deque msgs;
const auto [src, address] = DBCManager::parseId(msg_id);
- uint32_t cnt = 0;
QVector values(sigs.size());
- for (--it; it != events->begin() && (*it)->mono_time > min_mono_time; --it) {
+ for (auto it = first; it != last && (*it)->mono_time > min_time; ++it) {
if ((*it)->which == cereal::Event::Which::CAN) {
for (const auto &c : (*it)->event.getCan()) {
if (src == c.getSrc() && address == c.getAddress()) {
@@ -120,7 +116,7 @@ std::deque HistoryLogModel::fetchData(uint64_t min_mon
m.mono_time = (*it)->mono_time;
m.data = toHex(QByteArray((char *)dat.begin(), dat.size()));
m.sig_values = values;
- if (++cnt >= batch_size && min_mono_time == 0)
+ if (msgs.size() >= batch_size && min_time == 0)
return msgs;
}
}
@@ -129,6 +125,25 @@ std::deque HistoryLogModel::fetchData(uint64_t min_mon
}
return msgs;
}
+template std::deque HistoryLogModel::fetchData<>(std::vector::iterator first, std::vector::iterator last, uint64_t min_time);
+template std::deque HistoryLogModel::fetchData<>(std::vector::reverse_iterator first, std::vector::reverse_iterator last, uint64_t min_time);
+
+std::deque HistoryLogModel::fetchData(uint64_t from_time, uint64_t min_time) {
+ auto events = can->events();
+ if (dynamic_mode) {
+ auto it = std::lower_bound(events->rbegin(), events->rend(), from_time, [=](auto &e, uint64_t ts) {
+ return e->mono_time > ts;
+ });
+ if (it != events->rend()) ++it;
+ return fetchData(it, events->rend(), min_time);
+ } else {
+ assert(min_time == 0);
+ auto it = std::upper_bound(events->begin(), events->end(), from_time, [=](uint64_t ts, auto &e) {
+ return ts < e->mono_time;
+ });
+ return fetchData(it, events->end(), 0);
+ }
+}
// HeaderView
@@ -166,9 +181,9 @@ HistoryLog::HistoryLog(QWidget *parent) : QTableView(parent) {
LogsWidget::LogsWidget(QWidget *parent) : QWidget(parent) {
QVBoxLayout *main_layout = new QVBoxLayout(this);
- filter_container = new QWidget(this);
- QHBoxLayout *h = new QHBoxLayout(filter_container);
+ QHBoxLayout *h = new QHBoxLayout();
signals_cb = new QComboBox(this);
+ signals_cb->setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::Preferred);
h->addWidget(signals_cb);
comp_box = new QComboBox();
comp_box->addItems({">", "=", "!=", "<"});
@@ -177,7 +192,9 @@ LogsWidget::LogsWidget(QWidget *parent) : QWidget(parent) {
value_edit->setClearButtonEnabled(true);
value_edit->setValidator(new QDoubleValidator(-500000, 500000, 6, this));
h->addWidget(value_edit);
- main_layout->addWidget(filter_container);
+ dynamic_mode = new QCheckBox(tr("Dynamic"));
+ h->addWidget(dynamic_mode, 0, Qt::AlignRight);
+ main_layout->addLayout(h);
model = new HistoryLogModel(this);
logs = new HistoryLog(this);
@@ -185,33 +202,38 @@ LogsWidget::LogsWidget(QWidget *parent) : QWidget(parent) {
main_layout->addWidget(logs);
QObject::connect(logs, &QTableView::doubleClicked, this, &LogsWidget::doubleClicked);
- QObject::connect(signals_cb, SIGNAL(currentIndexChanged(int)), this, SLOT(setFilter()));
- QObject::connect(comp_box, SIGNAL(currentIndexChanged(int)), this, SLOT(setFilter()));
+ QObject::connect(signals_cb, SIGNAL(activated(int)), this, SLOT(setFilter()));
+ QObject::connect(comp_box, SIGNAL(activated(int)), this, SLOT(setFilter()));
QObject::connect(value_edit, &QLineEdit::textChanged, this, &LogsWidget::setFilter);
+ QObject::connect(dynamic_mode, &QCheckBox::stateChanged, model, &HistoryLogModel::setDynamicMode);
+ QObject::connect(can, &CANMessages::seekedTo, model, &HistoryLogModel::refresh);
+ QObject::connect(can, &CANMessages::eventsMerged, model, &HistoryLogModel::segmentsMerged);
}
void LogsWidget::setMessage(const QString &message_id) {
- blockSignals(true);
+ model->setMessage(message_id);
+ cur_filter_text = "";
value_edit->setText("");
signals_cb->clear();
comp_box->setCurrentIndex(0);
- sigs.clear();
- if (auto dbc_msg = dbc()->msg(message_id)) {
- sigs = dbc_msg->getSignals();
- for (auto s : sigs) {
+ bool has_signals = model->sigs.size() > 0;
+ if (has_signals) {
+ for (auto s : model->sigs) {
signals_cb->addItem(s->name.c_str());
}
}
- filter_container->setVisible(!sigs.empty());
- model->setMessage(message_id);
- blockSignals(false);
+ comp_box->setVisible(has_signals);
+ value_edit->setVisible(has_signals);
+ signals_cb->setVisible(has_signals);
}
-static bool not_equal(double l, double r) {
- return l != r;
-}
+static bool not_equal(double l, double r) { return l != r; }
void LogsWidget::setFilter() {
+ if (cur_filter_text.isEmpty() && value_edit->text().isEmpty()) {
+ return;
+ }
+
std::function cmp;
switch (comp_box->currentIndex()) {
case 0: cmp = std::greater{}; break;
@@ -220,6 +242,19 @@ void LogsWidget::setFilter() {
case 3: cmp = std::less{}; break;
}
model->setFilter(signals_cb->currentIndex(), value_edit->text(), cmp);
+ cur_filter_text = value_edit->text();
+}
+
+void LogsWidget::showEvent(QShowEvent *event) {
+ if (dynamic_mode->isChecked()) {
+ model->refresh();
+ }
+}
+
+void LogsWidget::updateState() {
+ if (dynamic_mode->isChecked()) {
+ model->updateState();
+ }
}
void LogsWidget::doubleClicked(const QModelIndex &index) {
diff --git a/tools/cabana/historylog.h b/tools/cabana/historylog.h
index c636f9b48f..f20f51637a 100644
--- a/tools/cabana/historylog.h
+++ b/tools/cabana/historylog.h
@@ -1,6 +1,7 @@
#pragma once
#include
+#include
#include
#include
#include
@@ -17,8 +18,10 @@ public:
};
class HistoryLogModel : public QAbstractTableModel {
+ Q_OBJECT
+
public:
- HistoryLogModel(QObject *parent);
+ HistoryLogModel(QObject *parent) : QAbstractTableModel(parent) {}
void setMessage(const QString &message_id);
void updateState();
void setFilter(int sig_idx, const QString &value, std::function cmp);
@@ -28,6 +31,9 @@ public:
inline bool canFetchMore(const QModelIndex &parent) const override { return has_more_data; }
int rowCount(const QModelIndex &parent = QModelIndex()) const override { return messages.size(); }
int columnCount(const QModelIndex &parent = QModelIndex()) const override { return std::max(1ul, sigs.size()) + 1; }
+ void setDynamicMode(int state);
+ void segmentsMerged();
+ void refresh();
struct Message {
uint64_t mono_time = 0;
@@ -35,15 +41,20 @@ public:
QString data;
};
- std::deque fetchData(uint64_t min_mono_time, uint64_t max_mono_time);
+ template
+ std::deque fetchData(InputIt first, InputIt last, uint64_t min_time);
+ std::deque fetchData(uint64_t from_time, uint64_t min_time = 0);
+
QString msg_id;
bool has_more_data = true;
const int batch_size = 50;
int filter_sig_idx = -1;
double filter_value = 0;
+ uint64_t last_fetch_time = 0;
std::function filter_cmp = nullptr;
std::deque messages;
std::vector sigs;
+ bool dynamic_mode = false;
};
class HistoryLog : public QTableView {
@@ -58,7 +69,7 @@ class LogsWidget : public QWidget {
public:
LogsWidget(QWidget *parent);
void setMessage(const QString &message_id);
- void updateState() { model->updateState(); }
+ void updateState();
signals:
void openChart(const QString &msg_id, const Signal *sig);
@@ -68,12 +79,12 @@ private slots:
private:
void doubleClicked(const QModelIndex &index);
- void showEvent(QShowEvent *event) override { model->setMessage(model->msg_id); };
+ void showEvent(QShowEvent *event) override;
HistoryLog *logs;
HistoryLogModel *model;
- QWidget *filter_container;
+ QCheckBox *dynamic_mode;
QComboBox *signals_cb, *comp_box;
QLineEdit *value_edit;
- std::vector sigs;
+ QString cur_filter_text;
};
From 28d0459c69a6f9bcf511fe982ba573cb7842e385 Mon Sep 17 00:00:00 2001
From: Adeeb Shihadeh
Date: Fri, 30 Dec 2022 14:44:59 -0800
Subject: [PATCH 014/484] update_requirements: skip pre-commit install on mac
---
update_requirements.sh | 18 ++++++++++--------
1 file changed, 10 insertions(+), 8 deletions(-)
diff --git a/update_requirements.sh b/update_requirements.sh
index e5dedea7a6..b430df59e5 100755
--- a/update_requirements.sh
+++ b/update_requirements.sh
@@ -69,11 +69,13 @@ else
RUN="poetry run"
fi
-echo "pre-commit hooks install..."
-shopt -s nullglob
-for f in .pre-commit-config.yaml */.pre-commit-config.yaml; do
- cd $DIR/$(dirname $f)
- if [ -e ".git" ]; then
- $RUN pre-commit install
- fi
-done
+if [ "$(uname)" != "Darwin" ]; then
+ echo "pre-commit hooks install..."
+ shopt -s nullglob
+ for f in .pre-commit-config.yaml */.pre-commit-config.yaml; do
+ cd $DIR/$(dirname $f)
+ if [ -e ".git" ]; then
+ $RUN pre-commit install
+ fi
+ done
+fi
From a7155a43b726266084554e7cfa11d8a7bba88238 Mon Sep 17 00:00:00 2001
From: Erich Moraga <33645296+ErichMoraga@users.noreply.github.com>
Date: Fri, 30 Dec 2022 18:16:24 -0600
Subject: [PATCH 015/484] Add several missing HIGHLANDERH_TSS2 firmwares
(#26844)
* Add several missing HIGHLANDERH_TSS2 firmwares
`@joeswisher#3240` 2023 Highlander Hybrid DongleID/route 1cdd18b56163c309|2022-12-29--23-18-05
* docs.py gen'd CARS.md w/ 2023 Highlander Hybrid update
---
docs/CARS.md | 2 +-
selfdrive/car/toyota/values.py | 6 +++++-
2 files changed, 6 insertions(+), 2 deletions(-)
diff --git a/docs/CARS.md b/docs/CARS.md
index ce067609aa..f3667c4cea 100644
--- a/docs/CARS.md
+++ b/docs/CARS.md
@@ -182,7 +182,7 @@ A supported vehicle is one that just works when you install a comma three. All s
|Toyota|Highlander 2017-19|All|openpilot available[2](#footnotes)|0 mph|0 mph|[](##)|[](##)|Toyota|
|Toyota|Highlander 2020-23|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota|
|Toyota|Highlander Hybrid 2017-19|All|openpilot available[2](#footnotes)|0 mph|0 mph|[](##)|[](##)|Toyota|
-|Toyota|Highlander Hybrid 2020-22|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota|
+|Toyota|Highlander Hybrid 2020-23|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota|
|Toyota|Mirai 2021|All|openpilot|0 mph|0 mph|[](##)|[](##)|Toyota|
|Toyota|Prius 2016|Toyota Safety Sense P|openpilot available[2](#footnotes)|0 mph|0 mph|[](##)|[](##)|Toyota|
|Toyota|Prius 2017-20|All|openpilot available[2](#footnotes)|0 mph|0 mph|[](##)|[](##)|Toyota|
diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py
index 80c0ccbb83..64a0bed0b2 100644
--- a/selfdrive/car/toyota/values.py
+++ b/selfdrive/car/toyota/values.py
@@ -131,7 +131,7 @@ CAR_INFO: Dict[str, Union[ToyotaCarInfo, List[ToyotaCarInfo]]] = {
CAR.HIGHLANDER: ToyotaCarInfo("Toyota Highlander 2017-19", video_link="https://www.youtube.com/watch?v=0wS0wXSLzoo"),
CAR.HIGHLANDER_TSS2: ToyotaCarInfo("Toyota Highlander 2020-23"),
CAR.HIGHLANDERH: ToyotaCarInfo("Toyota Highlander Hybrid 2017-19"),
- CAR.HIGHLANDERH_TSS2: ToyotaCarInfo("Toyota Highlander Hybrid 2020-22"),
+ CAR.HIGHLANDERH_TSS2: ToyotaCarInfo("Toyota Highlander Hybrid 2020-23"),
CAR.PRIUS: [
ToyotaCarInfo("Toyota Prius 2016", "Toyota Safety Sense P", "https://www.youtube.com/watch?v=8zopPJI8XQ0"),
ToyotaCarInfo("Toyota Prius 2017-20", video_link="https://www.youtube.com/watch?v=8zopPJI8XQ0"),
@@ -1023,11 +1023,13 @@ FW_VERSIONS = {
(Ecu.eps, 0x7a1, None): [
b'8965B48241\x00\x00\x00\x00\x00\x00',
b'8965B48310\x00\x00\x00\x00\x00\x00',
+ b'8965B48400\x00\x00\x00\x00\x00\x00',
],
(Ecu.abs, 0x7b0, None): [
b'\x01F15264872300\x00\x00\x00\x00',
b'\x01F15264872400\x00\x00\x00\x00',
b'\x01F15264872500\x00\x00\x00\x00',
+ b'\x01F15264872600\x00\x00\x00\x00',
b'\x01F15264873500\x00\x00\x00\x00',
b'\x01F152648C6300\x00\x00\x00\x00',
b'\x01F152648J4000\x00\x00\x00\x00',
@@ -1041,6 +1043,7 @@ FW_VERSIONS = {
b'\x01896630EE4100\x00\x00\x00\x00',
b'\x01896630EE5000\x00\x00\x00\x00',
b'\x01896630EE6000\x00\x00\x00\x00',
+ b'\x01896630EF8000\x00\x00\x00\x00',
b'\x02896630E66000\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00',
b'\x02896630E66100\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00',
b'\x01896630EA1000\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00',
@@ -1056,6 +1059,7 @@ FW_VERSIONS = {
b'\x028646F0E02100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00',
b'\x028646F4803000\x00\x00\x00\x008646G5301200\x00\x00\x00\x00',
b'\x028646F4803000\x00\x00\x00\x008646G3304000\x00\x00\x00\x00',
+ b'\x028646F4803200\x00\x00\x00\x008646G3304000\x00\x00\x00\x00',
],
},
CAR.LEXUS_IS: {
From 52b72dd71b77e1937691174a790fc8cc348298a3 Mon Sep 17 00:00:00 2001
From: Adeeb Shihadeh
Date: Fri, 30 Dec 2022 17:16:22 -0800
Subject: [PATCH 016/484] LGTM.com is deprecated (#26846)
---
README.md | 3 ---
lgtm.yml | 19 -------------------
2 files changed, 22 deletions(-)
delete mode 100644 lgtm.yml
diff --git a/README.md b/README.md
index cfeb625bfe..88b7aeb2bb 100755
--- a/README.md
+++ b/README.md
@@ -143,7 +143,4 @@ NO WARRANTY EXPRESSED OR IMPLIED.**
[](https://github.com/commaai/openpilot/actions)
-[](https://lgtm.com/projects/g/commaai/openpilot/alerts/)
-[](https://lgtm.com/projects/g/commaai/openpilot/context:python)
-[](https://lgtm.com/projects/g/commaai/openpilot/context:cpp)
[](https://codecov.io/gh/commaai/openpilot)
diff --git a/lgtm.yml b/lgtm.yml
deleted file mode 100644
index 6ce9353562..0000000000
--- a/lgtm.yml
+++ /dev/null
@@ -1,19 +0,0 @@
-path_classifiers:
- library:
- - external
- - third_party
- - pyextra
- - tools/lib/mkvparse
-extraction:
- cpp:
- after_prepare:
- - "pip3 install --upgrade --user pkgconfig cython setuptools wheel"
- - "pip3 install --upgrade --user jinja2 pyyaml cython pycapnp numpy sympy tqdm\
- \ cffi logentries zmq scons"
- - "export PATH=/opt/work/.local/bin:$PATH"
- index:
- build_command: "scons"
- javascript:
- index:
- filters:
- - exclude: "*"
From e3a41b3c255a5c72064f66c4d2504e1655bf2ac9 Mon Sep 17 00:00:00 2001
From: Adeeb Shihadeh
Date: Fri, 30 Dec 2022 20:25:33 -0800
Subject: [PATCH 017/484] add spidev2 package (#26847)
---
poetry.lock | 43 ++++++++++++++++++++++++++++++++++++++++++-
pyproject.toml | 1 +
2 files changed, 43 insertions(+), 1 deletion(-)
diff --git a/poetry.lock b/poetry.lock
index f7bc4669a3..9ab86329d7 100644
--- a/poetry.lock
+++ b/poetry.lock
@@ -1352,6 +1352,14 @@ category = "dev"
optional = false
python-versions = "*"
+[[package]]
+name = "ioctl-opt"
+version = "1.2.2"
+description = "Functions to compute fnctl.ioctl's opt argument"
+category = "main"
+optional = false
+python-versions = "*"
+
[[package]]
name = "ipykernel"
version = "6.16.1"
@@ -3881,6 +3889,17 @@ category = "main"
optional = false
python-versions = "*"
+[[package]]
+name = "spidev2"
+version = "0.9.0"
+description = "Pure-python interface to Linux spidev."
+category = "main"
+optional = false
+python-versions = "*"
+
+[package.dependencies]
+ioctl-opt = "*"
+
[[package]]
name = "sqlalchemy"
version = "1.4.42"
@@ -4425,7 +4444,7 @@ testing = ["coverage (>=5.0.3)", "zope.event", "zope.testing"]
[metadata]
lock-version = "1.1"
python-versions = "~3.8"
-content-hash = "d894380c87f5558e032708cc1230aed172ad3e1db9aa112e2e105bebefff4e20"
+content-hash = "2ab9d6aee6cc2c7bb5ba9763a54779ef9535cb752ec0038736a442992a04d459"
[metadata.files]
adal = [
@@ -5624,6 +5643,9 @@ inputs = [
{file = "inputs-0.5-py2.py3-none-any.whl", hash = "sha256:13f894564e52134cf1e3862b1811da034875eb1f2b62e6021e3776e9669a96ec"},
{file = "inputs-0.5.tar.gz", hash = "sha256:a31d5b96a3525f1232f326be9e7ce8ccaf873c6b1fb84d9f3c9bc3d79b23eae4"},
]
+ioctl-opt = [
+ {file = "ioctl-opt-1.2.2.tar.gz", hash = "sha256:9628bbd6728f90d019759f54d20b741ddbf9f8db8d41976da4332492f669d643"},
+]
ipykernel = [
{file = "ipykernel-6.16.1-py3-none-any.whl", hash = "sha256:32eb7bdc5af57185e9a42b0dcef66413ef91a0490b378eae46cbdf0d4e0b5912"},
{file = "ipykernel-6.16.1.tar.gz", hash = "sha256:3a27a550c1d682e7825f0f7732b0142b79ef1b21cd2e713cacac0c9847535f13"},
@@ -6429,6 +6451,7 @@ onnx = [
]
onnx2torch = [
{file = "onnx2torch-1.5.4-py3-none-any.whl", hash = "sha256:fd1a0fe05072bfb9f3d86d9330299b130b41f11bd4ae634db17078974e711725"},
+ {file = "onnx2torch-1.5.4.tar.gz", hash = "sha256:df837b557a63540223d85fde4a1d679fde0ca8d8bb89d5379c030b01eddc9c24"},
]
onnxoptimizer = [
{file = "onnxoptimizer-0.3.1-cp37-cp37m-macosx_10_15_x86_64.whl", hash = "sha256:e73a5e2e3ca4db9bff54f7131768749c861677b97ee811a136fcf1a52783cf6e"},
@@ -6810,6 +6833,7 @@ pycryptodome = [
{file = "pycryptodome-3.15.0-cp27-cp27m-manylinux2010_i686.whl", hash = "sha256:7c9ed8aa31c146bef65d89a1b655f5f4eab5e1120f55fc297713c89c9e56ff0b"},
{file = "pycryptodome-3.15.0-cp27-cp27m-manylinux2010_x86_64.whl", hash = "sha256:5099c9ca345b2f252f0c28e96904643153bae9258647585e5e6f649bb7a1844a"},
{file = "pycryptodome-3.15.0-cp27-cp27m-manylinux2014_aarch64.whl", hash = "sha256:2ec709b0a58b539a4f9d33fb8508264c3678d7edb33a68b8906ba914f71e8c13"},
+ {file = "pycryptodome-3.15.0-cp27-cp27m-musllinux_1_1_aarch64.whl", hash = "sha256:2ae53125de5b0d2c95194d957db9bb2681da8c24d0fb0fe3b056de2bcaf5d837"},
{file = "pycryptodome-3.15.0-cp27-cp27m-win32.whl", hash = "sha256:fd2184aae6ee2a944aaa49113e6f5787cdc5e4db1eb8edb1aea914bd75f33a0c"},
{file = "pycryptodome-3.15.0-cp27-cp27m-win_amd64.whl", hash = "sha256:7e3a8f6ee405b3bd1c4da371b93c31f7027944b2bcce0697022801db93120d83"},
{file = "pycryptodome-3.15.0-cp27-cp27mu-manylinux1_i686.whl", hash = "sha256:b9c5b1a1977491533dfd31e01550ee36ae0249d78aae7f632590db833a5012b8"},
@@ -6817,12 +6841,14 @@ pycryptodome = [
{file = "pycryptodome-3.15.0-cp27-cp27mu-manylinux2010_i686.whl", hash = "sha256:2aa55aae81f935a08d5a3c2042eb81741a43e044bd8a81ea7239448ad751f763"},
{file = "pycryptodome-3.15.0-cp27-cp27mu-manylinux2010_x86_64.whl", hash = "sha256:c3640deff4197fa064295aaac10ab49a0d55ef3d6a54ae1499c40d646655c89f"},
{file = "pycryptodome-3.15.0-cp27-cp27mu-manylinux2014_aarch64.whl", hash = "sha256:045d75527241d17e6ef13636d845a12e54660aa82e823b3b3341bcf5af03fa79"},
+ {file = "pycryptodome-3.15.0-cp27-cp27mu-musllinux_1_1_aarch64.whl", hash = "sha256:eb6fce570869e70cc8ebe68eaa1c26bed56d40ad0f93431ee61d400525433c54"},
{file = "pycryptodome-3.15.0-cp35-abi3-macosx_10_9_x86_64.whl", hash = "sha256:9ee40e2168f1348ae476676a2e938ca80a2f57b14a249d8fe0d3cdf803e5a676"},
{file = "pycryptodome-3.15.0-cp35-abi3-manylinux1_i686.whl", hash = "sha256:4c3ccad74eeb7b001f3538643c4225eac398c77d617ebb3e57571a897943c667"},
{file = "pycryptodome-3.15.0-cp35-abi3-manylinux1_x86_64.whl", hash = "sha256:1b22bcd9ec55e9c74927f6b1f69843cb256fb5a465088ce62837f793d9ffea88"},
{file = "pycryptodome-3.15.0-cp35-abi3-manylinux2010_i686.whl", hash = "sha256:57f565acd2f0cf6fb3e1ba553d0cb1f33405ec1f9c5ded9b9a0a5320f2c0bd3d"},
{file = "pycryptodome-3.15.0-cp35-abi3-manylinux2010_x86_64.whl", hash = "sha256:4b52cb18b0ad46087caeb37a15e08040f3b4c2d444d58371b6f5d786d95534c2"},
{file = "pycryptodome-3.15.0-cp35-abi3-manylinux2014_aarch64.whl", hash = "sha256:092a26e78b73f2530b8bd6b3898e7453ab2f36e42fd85097d705d6aba2ec3e5e"},
+ {file = "pycryptodome-3.15.0-cp35-abi3-musllinux_1_1_aarch64.whl", hash = "sha256:50ca7e587b8e541eb6c192acf92449d95377d1f88908c0a32ac5ac2703ebe28b"},
{file = "pycryptodome-3.15.0-cp35-abi3-win32.whl", hash = "sha256:e244ab85c422260de91cda6379e8e986405b4f13dc97d2876497178707f87fc1"},
{file = "pycryptodome-3.15.0-cp35-abi3-win_amd64.whl", hash = "sha256:c77126899c4b9c9827ddf50565e93955cb3996813c18900c16b2ea0474e130e9"},
{file = "pycryptodome-3.15.0-pp27-pypy_73-macosx_10_9_x86_64.whl", hash = "sha256:9eaadc058106344a566dc51d3d3a758ab07f8edde013712bc8d22032a86b264f"},
@@ -7417,6 +7443,18 @@ setproctitle = [
{file = "setproctitle-1.3.2-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:7f2719a398e1a2c01c2a63bf30377a34d0b6ef61946ab9cf4d550733af8f1ef1"},
{file = "setproctitle-1.3.2-cp310-cp310-win32.whl", hash = "sha256:e425be62524dc0c593985da794ee73eb8a17abb10fe692ee43bb39e201d7a099"},
{file = "setproctitle-1.3.2-cp310-cp310-win_amd64.whl", hash = "sha256:e85e50b9c67854f89635a86247412f3ad66b132a4d8534ac017547197c88f27d"},
+ {file = "setproctitle-1.3.2-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:2a97d51c17d438cf5be284775a322d57b7ca9505bb7e118c28b1824ecaf8aeaa"},
+ {file = "setproctitle-1.3.2-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:587c7d6780109fbd8a627758063d08ab0421377c0853780e5c356873cdf0f077"},
+ {file = "setproctitle-1.3.2-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d7d17c8bd073cbf8d141993db45145a70b307385b69171d6b54bcf23e5d644de"},
+ {file = "setproctitle-1.3.2-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:e932089c35a396dc31a5a1fc49889dd559548d14cb2237adae260382a090382e"},
+ {file = "setproctitle-1.3.2-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:8e4f8f12258a8739c565292a551c3db62cca4ed4f6b6126664e2381acb4931bf"},
+ {file = "setproctitle-1.3.2-cp311-cp311-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:570d255fd99c7f14d8f91363c3ea96bd54f8742275796bca67e1414aeca7d8c3"},
+ {file = "setproctitle-1.3.2-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:a8e0881568c5e6beff91ef73c0ec8ac2a9d3ecc9edd6bd83c31ca34f770910c4"},
+ {file = "setproctitle-1.3.2-cp311-cp311-musllinux_1_1_i686.whl", hash = "sha256:4bba3be4c1fabf170595b71f3af46c6d482fbe7d9e0563999b49999a31876f77"},
+ {file = "setproctitle-1.3.2-cp311-cp311-musllinux_1_1_ppc64le.whl", hash = "sha256:37ece938110cab2bb3957e3910af8152ca15f2b6efdf4f2612e3f6b7e5459b80"},
+ {file = "setproctitle-1.3.2-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:db684d6bbb735a80bcbc3737856385b55d53f8a44ce9b46e9a5682c5133a9bf7"},
+ {file = "setproctitle-1.3.2-cp311-cp311-win32.whl", hash = "sha256:ca58cd260ea02759238d994cfae844fc8b1e206c684beb8f38877dcab8451dfc"},
+ {file = "setproctitle-1.3.2-cp311-cp311-win_amd64.whl", hash = "sha256:88486e6cce2a18a033013d17b30a594f1c5cb42520c49c19e6ade40b864bb7ff"},
{file = "setproctitle-1.3.2-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:92c626edc66169a1b09e9541b9c0c9f10488447d8a2b1d87c8f0672e771bc927"},
{file = "setproctitle-1.3.2-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:710e16fa3bade3b026907e4a5e841124983620046166f355bbb84be364bf2a02"},
{file = "setproctitle-1.3.2-cp37-cp37m-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:1f29b75e86260b0ab59adb12661ef9f113d2f93a59951373eb6d68a852b13e83"},
@@ -7611,6 +7649,9 @@ spidev = [
{file = "spidev-3.6-cp39-cp39-linux_armv7l.whl", hash = "sha256:280abc00a1ef7780ef62c3f294f52a2527b6c47d8c269fea98664970bcaf6da5"},
{file = "spidev-3.6.tar.gz", hash = "sha256:14dbc37594a4aaef85403ab617985d3c3ef464d62bc9b769ef552db53701115b"},
]
+spidev2 = [
+ {file = "spidev2-0.9.0.tar.gz", hash = "sha256:152da2911a8660283ceac3a75dd869953379bcbcf079e5436af5aae736876086"},
+]
sqlalchemy = [
{file = "SQLAlchemy-1.4.42-cp27-cp27m-macosx_10_14_x86_64.whl", hash = "sha256:28e881266a172a4d3c5929182fde6bb6fba22ac93f137d5380cc78a11a9dd124"},
{file = "SQLAlchemy-1.4.42-cp27-cp27m-manylinux_2_5_x86_64.manylinux1_x86_64.whl", hash = "sha256:ca9389a00f639383c93ed00333ed763812f80b5ae9e772ea32f627043f8c9c88"},
diff --git a/pyproject.toml b/pyproject.toml
index e99b278341..af9fcc6e6e 100644
--- a/pyproject.toml
+++ b/pyproject.toml
@@ -51,6 +51,7 @@ six = "^1.16.0"
smbus2 = "^0.4.2"
sounddevice = "^0.4.5"
spidev = { version = "^3.6", platform = "linux" }
+spidev2 = { version = "^0.9.0", platform = "linux" }
sympy = "^1.10.1"
timezonefinder = "^6.0.1"
tqdm = "^4.64.0"
From 65414bcd8d2fa23d0c6dce8070fb468c08a85dde Mon Sep 17 00:00:00 2001
From: Adeeb Shihadeh
Date: Sat, 31 Dec 2022 11:30:28 -0800
Subject: [PATCH 018/484] controlsd: remove laikad from ignored process list
---
selfdrive/controls/controlsd.py | 2 +-
1 file changed, 1 insertion(+), 1 deletion(-)
diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py
index 36f0b559c2..fea19adbdb 100755
--- a/selfdrive/controls/controlsd.py
+++ b/selfdrive/controls/controlsd.py
@@ -38,7 +38,7 @@ REPLAY = "REPLAY" in os.environ
SIMULATION = "SIMULATION" in os.environ
NOSENSOR = "NOSENSOR" in os.environ
IGNORE_PROCESSES = {"uploader", "deleter", "loggerd", "logmessaged", "tombstoned", "statsd",
- "logcatd", "proclogd", "clocksd", "updated", "timezoned", "manage_athenad", "laikad"} | \
+ "logcatd", "proclogd", "clocksd", "updated", "timezoned", "manage_athenad"} | \
{k for k, v in managed_processes.items() if not v.enabled}
ThermalStatus = log.DeviceState.ThermalStatus
From 304796bafe0c0608e40b20fc44923f9edf462240 Mon Sep 17 00:00:00 2001
From: Shane Smiskol
Date: Sat, 31 Dec 2022 19:51:03 -0800
Subject: [PATCH 019/484] ui: draw radarState leads (#26852)
use radarState
---
selfdrive/ui/qt/onroad.cc | 20 +++++++++++---------
selfdrive/ui/qt/onroad.h | 2 +-
2 files changed, 12 insertions(+), 10 deletions(-)
diff --git a/selfdrive/ui/qt/onroad.cc b/selfdrive/ui/qt/onroad.cc
index 95ad813dff..1b4b880fbf 100644
--- a/selfdrive/ui/qt/onroad.cc
+++ b/selfdrive/ui/qt/onroad.cc
@@ -498,13 +498,13 @@ void AnnotatedCameraWidget::drawLaneLines(QPainter &painter, const UIState *s) {
painter.restore();
}
-void AnnotatedCameraWidget::drawLead(QPainter &painter, const cereal::ModelDataV2::LeadDataV3::Reader &lead_data, const QPointF &vd) {
+void AnnotatedCameraWidget::drawLead(QPainter &painter, const cereal::RadarState::LeadData::Reader &lead_data, const QPointF &vd) {
painter.save();
const float speedBuff = 10.;
const float leadBuff = 40.;
- const float d_rel = lead_data.getX()[0];
- const float v_rel = lead_data.getV()[0];
+ const float d_rel = lead_data.getDRel();
+ const float v_rel = lead_data.getVRel();
float fillAlpha = 0;
if (d_rel < leadBuff) {
@@ -539,6 +539,7 @@ void AnnotatedCameraWidget::paintGL() {
SubMaster &sm = *(s->sm);
const double start_draw_t = millis_since_boot();
const cereal::ModelDataV2::Reader &model = sm["modelV2"].getModelV2();
+ const cereal::RadarState::Reader &radar_state = sm["radarState"].getRadarState();
// draw camera frame
{
@@ -589,19 +590,20 @@ void AnnotatedCameraWidget::paintGL() {
if (sm.rcv_frame("modelV2") > s->scene.started_frame) {
update_model(s, sm["modelV2"].getModelV2());
if (sm.rcv_frame("radarState") > s->scene.started_frame) {
- update_leads(s, sm["radarState"].getRadarState(), sm["modelV2"].getModelV2().getPosition());
+ update_leads(s, radar_state, sm["modelV2"].getModelV2().getPosition());
}
}
drawLaneLines(painter, s);
if (s->scene.longitudinal_control) {
- const auto leads = model.getLeadsV3();
- if (leads[0].getProb() > .5) {
- drawLead(painter, leads[0], s->scene.lead_vertices[0]);
+ auto lead_one = radar_state.getLeadOne();
+ auto lead_two = radar_state.getLeadTwo();
+ if (lead_one.getStatus()) {
+ drawLead(painter, lead_one, s->scene.lead_vertices[0]);
}
- if (leads[1].getProb() > .5 && (std::abs(leads[1].getX()[0] - leads[0].getX()[0]) > 3.0)) {
- drawLead(painter, leads[1], s->scene.lead_vertices[1]);
+ if (lead_two.getStatus() && (std::abs(lead_one.getDRel() - lead_two.getDRel()) > 3.0)) {
+ drawLead(painter, lead_two, s->scene.lead_vertices[1]);
}
}
}
diff --git a/selfdrive/ui/qt/onroad.h b/selfdrive/ui/qt/onroad.h
index 9e18355970..3dbb05b674 100644
--- a/selfdrive/ui/qt/onroad.h
+++ b/selfdrive/ui/qt/onroad.h
@@ -80,7 +80,7 @@ protected:
void showEvent(QShowEvent *event) override;
void updateFrameMat() override;
void drawLaneLines(QPainter &painter, const UIState *s);
- void drawLead(QPainter &painter, const cereal::ModelDataV2::LeadDataV3::Reader &lead_data, const QPointF &vd);
+ void drawLead(QPainter &painter, const cereal::RadarState::LeadData::Reader &lead_data, const QPointF &vd);
void drawHud(QPainter &p);
inline QColor redColor(int alpha = 255) { return QColor(201, 34, 49, alpha); }
inline QColor whiteColor(int alpha = 255) { return QColor(255, 255, 255, alpha); }
From cd8e03d53ed210aec46a2ff728cb4a830314a21a Mon Sep 17 00:00:00 2001
From: Adeeb Shihadeh
Date: Sat, 31 Dec 2022 21:00:50 -0800
Subject: [PATCH 020/484] move all third party stuff into third_party/ (#26853)
* mv fastcluster
* move msm_kgsl.h
* camerad include
* update path
* mv pyextra
* fix tici build
* add acados_template to release build
Co-authored-by: Comma Device
---
.pre-commit-config.yaml | 12 ++++++------
Dockerfile.openpilot | 1 -
README.md | 1 -
SConstruct | 5 ++---
docs/Makefile | 2 +-
docs/docker/Dockerfile | 1 -
launch_chffrplus.sh | 2 +-
mypy.ini | 2 +-
release/files_common | 11 ++++-------
selfdrive/controls/lib/lateral_mpc_lib/SConscript | 6 +++---
selfdrive/controls/lib/lateral_mpc_lib/lat_mpc.py | 2 +-
.../controls/lib/longitudinal_mpc_lib/SConscript | 6 +++---
.../controls/lib/longitudinal_mpc_lib/long_mpc.py | 2 +-
selfdrive/controls/radard.py | 2 +-
selfdrive/controls/tests/test_clustering.py | 4 ++--
selfdrive/manager/manager.py | 2 --
selfdrive/modeld/thneed/thneed.h | 2 +-
system/camerad/SConscript | 14 +++++---------
{pyextra => third_party}/.gitignore | 0
third_party/SConscript | 2 ++
.../acados}/acados_template/.gitignore | 0
.../acados}/acados_template/__init__.py | 0
.../acados}/acados_template/acados_layout.json | 0
.../acados}/acados_template/acados_model.py | 0
.../acados}/acados_template/acados_ocp.py | 0
.../acados}/acados_template/acados_ocp_solver.py | 0
.../acados_template/acados_ocp_solver_pyx.pyx | 0
.../acados}/acados_template/acados_sim.py | 0
.../acados}/acados_template/acados_sim_layout.json | 0
.../acados}/acados_template/acados_sim_solver.py | 0
.../acados_template/acados_solver_common.pxd | 0
.../acados}/acados_template/builders.py | 0
.../c_templates_tera/CMakeLists.in.txt | 0
.../acados_template/c_templates_tera/CPPLINT.cfg | 0
.../acados_template/c_templates_tera/Makefile.in | 0
.../c_templates_tera/acados_mex_create.in.c | 0
.../c_templates_tera/acados_mex_free.in.c | 0
.../c_templates_tera/acados_mex_set.in.c | 0
.../c_templates_tera/acados_mex_solve.in.c | 0
.../c_templates_tera/acados_sim_solver.in.c | 0
.../c_templates_tera/acados_sim_solver.in.h | 0
.../c_templates_tera/acados_sim_solver_sfun.in.c | 0
.../c_templates_tera/acados_solver.in.c | 0
.../c_templates_tera/acados_solver.in.h | 0
.../c_templates_tera/acados_solver.in.pxd | 0
.../c_templates_tera/acados_solver_sfun.in.c | 0
.../c_templates_tera/cost_y_0_fun.in.h | 0
.../c_templates_tera/cost_y_e_fun.in.h | 0
.../c_templates_tera/cost_y_fun.in.h | 0
.../c_templates_tera/external_cost.in.h | 0
.../c_templates_tera/external_cost_0.in.h | 0
.../c_templates_tera/external_cost_e.in.h | 0
.../c_templates_tera/h_constraint.in.h | 0
.../c_templates_tera/h_e_constraint.in.h | 0
.../acados_template/c_templates_tera/main.in.c | 0
.../acados_template/c_templates_tera/main_mex.in.c | 0
.../acados_template/c_templates_tera/main_sim.in.c | 0
.../c_templates_tera/make_main_mex.in.m | 0
.../acados_template/c_templates_tera/make_mex.in.m | 0
.../c_templates_tera/make_sfun.in.m | 0
.../c_templates_tera/make_sfun_sim.in.m | 0
.../c_templates_tera/mex_solver.in.m | 0
.../acados_template/c_templates_tera/model.in.h | 0
.../c_templates_tera/phi_constraint.in.h | 0
.../c_templates_tera/phi_e_constraint.in.h | 0
.../acados_template/generate_c_code_constraint.py | 0
.../generate_c_code_discrete_dynamics.py | 0
.../generate_c_code_explicit_ode.py | 0
.../generate_c_code_external_cost.py | 0
.../acados_template/generate_c_code_gnsf.py | 0
.../generate_c_code_implicit_ode.py | 0
.../acados_template/generate_c_code_nls_cost.py | 0
.../acados_template/simulink_default_opts.json | 0
.../acados}/acados_template/utils.py | 0
third_party/acados/build.sh | 5 ++---
.../lib => third_party}/cluster/.gitignore | 0
.../controls/lib => third_party}/cluster/LICENSE | 0
.../controls/lib => third_party}/cluster/README | 0
.../lib => third_party}/cluster/SConscript | 0
.../lib => third_party}/cluster/__init__.py | 0
.../lib => third_party}/cluster/fastcluster.cpp | 0
.../lib => third_party}/cluster/fastcluster.h | 0
.../cluster/fastcluster_R_dm.cpp | 0
.../lib => third_party}/cluster/fastcluster_dm.cpp | 0
.../lib => third_party}/cluster/fastcluster_py.py | 0
.../controls/lib => third_party}/cluster/test.cpp | 0
.../linux}/include/media/cam_cpas.h | 0
.../linux}/include/media/cam_defs.h | 0
.../linux}/include/media/cam_fd.h | 0
.../linux}/include/media/cam_icp.h | 0
.../linux}/include/media/cam_isp.h | 0
.../linux}/include/media/cam_isp_ife.h | 0
.../linux}/include/media/cam_isp_vfe.h | 0
.../linux}/include/media/cam_jpeg.h | 0
.../linux}/include/media/cam_lrme.h | 0
.../linux}/include/media/cam_req_mgr.h | 0
.../linux}/include/media/cam_sensor.h | 0
.../linux}/include/media/cam_sensor_cmn_header.h | 0
.../linux}/include/media/cam_sync.h | 0
.../linux}/include/msm_cam_sensor.h | 0
.../linux}/include/msm_camsensor_sdk.h | 0
.../linux}/include/msm_kgsl.h | 0
.../linux}/include/msmb_camera.h | 0
.../linux}/include/msmb_isp.h | 0
.../linux}/include/msmb_ispif.h | 0
tools/gpstest/fuzzy_testing.py | 2 +-
tools/sim/Dockerfile.sim | 1 -
107 files changed, 37 insertions(+), 50 deletions(-)
rename {pyextra => third_party}/.gitignore (100%)
rename {pyextra => third_party/acados}/acados_template/.gitignore (100%)
rename {pyextra => third_party/acados}/acados_template/__init__.py (100%)
rename {pyextra => third_party/acados}/acados_template/acados_layout.json (100%)
rename {pyextra => third_party/acados}/acados_template/acados_model.py (100%)
rename {pyextra => third_party/acados}/acados_template/acados_ocp.py (100%)
rename {pyextra => third_party/acados}/acados_template/acados_ocp_solver.py (100%)
rename {pyextra => third_party/acados}/acados_template/acados_ocp_solver_pyx.pyx (100%)
rename {pyextra => third_party/acados}/acados_template/acados_sim.py (100%)
rename {pyextra => third_party/acados}/acados_template/acados_sim_layout.json (100%)
rename {pyextra => third_party/acados}/acados_template/acados_sim_solver.py (100%)
rename {pyextra => third_party/acados}/acados_template/acados_solver_common.pxd (100%)
rename {pyextra => third_party/acados}/acados_template/builders.py (100%)
rename {pyextra => third_party/acados}/acados_template/c_templates_tera/CMakeLists.in.txt (100%)
rename {pyextra => third_party/acados}/acados_template/c_templates_tera/CPPLINT.cfg (100%)
rename {pyextra => third_party/acados}/acados_template/c_templates_tera/Makefile.in (100%)
rename {pyextra => third_party/acados}/acados_template/c_templates_tera/acados_mex_create.in.c (100%)
rename {pyextra => third_party/acados}/acados_template/c_templates_tera/acados_mex_free.in.c (100%)
rename {pyextra => third_party/acados}/acados_template/c_templates_tera/acados_mex_set.in.c (100%)
rename {pyextra => third_party/acados}/acados_template/c_templates_tera/acados_mex_solve.in.c (100%)
rename {pyextra => third_party/acados}/acados_template/c_templates_tera/acados_sim_solver.in.c (100%)
rename {pyextra => third_party/acados}/acados_template/c_templates_tera/acados_sim_solver.in.h (100%)
rename {pyextra => third_party/acados}/acados_template/c_templates_tera/acados_sim_solver_sfun.in.c (100%)
rename {pyextra => third_party/acados}/acados_template/c_templates_tera/acados_solver.in.c (100%)
rename {pyextra => third_party/acados}/acados_template/c_templates_tera/acados_solver.in.h (100%)
rename {pyextra => third_party/acados}/acados_template/c_templates_tera/acados_solver.in.pxd (100%)
rename {pyextra => third_party/acados}/acados_template/c_templates_tera/acados_solver_sfun.in.c (100%)
rename {pyextra => third_party/acados}/acados_template/c_templates_tera/cost_y_0_fun.in.h (100%)
rename {pyextra => third_party/acados}/acados_template/c_templates_tera/cost_y_e_fun.in.h (100%)
rename {pyextra => third_party/acados}/acados_template/c_templates_tera/cost_y_fun.in.h (100%)
rename {pyextra => third_party/acados}/acados_template/c_templates_tera/external_cost.in.h (100%)
rename {pyextra => third_party/acados}/acados_template/c_templates_tera/external_cost_0.in.h (100%)
rename {pyextra => third_party/acados}/acados_template/c_templates_tera/external_cost_e.in.h (100%)
rename {pyextra => third_party/acados}/acados_template/c_templates_tera/h_constraint.in.h (100%)
rename {pyextra => third_party/acados}/acados_template/c_templates_tera/h_e_constraint.in.h (100%)
rename {pyextra => third_party/acados}/acados_template/c_templates_tera/main.in.c (100%)
rename {pyextra => third_party/acados}/acados_template/c_templates_tera/main_mex.in.c (100%)
rename {pyextra => third_party/acados}/acados_template/c_templates_tera/main_sim.in.c (100%)
rename {pyextra => third_party/acados}/acados_template/c_templates_tera/make_main_mex.in.m (100%)
rename {pyextra => third_party/acados}/acados_template/c_templates_tera/make_mex.in.m (100%)
rename {pyextra => third_party/acados}/acados_template/c_templates_tera/make_sfun.in.m (100%)
rename {pyextra => third_party/acados}/acados_template/c_templates_tera/make_sfun_sim.in.m (100%)
rename {pyextra => third_party/acados}/acados_template/c_templates_tera/mex_solver.in.m (100%)
rename {pyextra => third_party/acados}/acados_template/c_templates_tera/model.in.h (100%)
rename {pyextra => third_party/acados}/acados_template/c_templates_tera/phi_constraint.in.h (100%)
rename {pyextra => third_party/acados}/acados_template/c_templates_tera/phi_e_constraint.in.h (100%)
rename {pyextra => third_party/acados}/acados_template/generate_c_code_constraint.py (100%)
rename {pyextra => third_party/acados}/acados_template/generate_c_code_discrete_dynamics.py (100%)
rename {pyextra => third_party/acados}/acados_template/generate_c_code_explicit_ode.py (100%)
rename {pyextra => third_party/acados}/acados_template/generate_c_code_external_cost.py (100%)
rename {pyextra => third_party/acados}/acados_template/generate_c_code_gnsf.py (100%)
rename {pyextra => third_party/acados}/acados_template/generate_c_code_implicit_ode.py (100%)
rename {pyextra => third_party/acados}/acados_template/generate_c_code_nls_cost.py (100%)
rename {pyextra => third_party/acados}/acados_template/simulink_default_opts.json (100%)
rename {pyextra => third_party/acados}/acados_template/utils.py (100%)
rename {selfdrive/controls/lib => third_party}/cluster/.gitignore (100%)
rename {selfdrive/controls/lib => third_party}/cluster/LICENSE (100%)
rename {selfdrive/controls/lib => third_party}/cluster/README (100%)
rename {selfdrive/controls/lib => third_party}/cluster/SConscript (100%)
rename {selfdrive/controls/lib => third_party}/cluster/__init__.py (100%)
rename {selfdrive/controls/lib => third_party}/cluster/fastcluster.cpp (100%)
rename {selfdrive/controls/lib => third_party}/cluster/fastcluster.h (100%)
rename {selfdrive/controls/lib => third_party}/cluster/fastcluster_R_dm.cpp (100%)
rename {selfdrive/controls/lib => third_party}/cluster/fastcluster_dm.cpp (100%)
rename {selfdrive/controls/lib => third_party}/cluster/fastcluster_py.py (100%)
rename {selfdrive/controls/lib => third_party}/cluster/test.cpp (100%)
rename {system/camerad => third_party/linux}/include/media/cam_cpas.h (100%)
rename {system/camerad => third_party/linux}/include/media/cam_defs.h (100%)
rename {system/camerad => third_party/linux}/include/media/cam_fd.h (100%)
rename {system/camerad => third_party/linux}/include/media/cam_icp.h (100%)
rename {system/camerad => third_party/linux}/include/media/cam_isp.h (100%)
rename {system/camerad => third_party/linux}/include/media/cam_isp_ife.h (100%)
rename {system/camerad => third_party/linux}/include/media/cam_isp_vfe.h (100%)
rename {system/camerad => third_party/linux}/include/media/cam_jpeg.h (100%)
rename {system/camerad => third_party/linux}/include/media/cam_lrme.h (100%)
rename {system/camerad => third_party/linux}/include/media/cam_req_mgr.h (100%)
rename {system/camerad => third_party/linux}/include/media/cam_sensor.h (100%)
rename {system/camerad => third_party/linux}/include/media/cam_sensor_cmn_header.h (100%)
rename {system/camerad => third_party/linux}/include/media/cam_sync.h (100%)
rename {system/camerad => third_party/linux}/include/msm_cam_sensor.h (100%)
rename {system/camerad => third_party/linux}/include/msm_camsensor_sdk.h (100%)
rename {selfdrive/modeld/thneed => third_party/linux}/include/msm_kgsl.h (100%)
rename {system/camerad => third_party/linux}/include/msmb_camera.h (100%)
rename {system/camerad => third_party/linux}/include/msmb_isp.h (100%)
rename {system/camerad => third_party/linux}/include/msmb_ispif.h (100%)
diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml
index 91b9c61628..edbca52fed 100644
--- a/.pre-commit-config.yaml
+++ b/.pre-commit-config.yaml
@@ -7,7 +7,7 @@ repos:
rev: v4.1.0
hooks:
- id: check-ast
- exclude: '^(pyextra)/'
+ exclude: '^(third_party)/'
- id: check-json
- id: check-xml
- id: check-yaml
@@ -19,7 +19,7 @@ repos:
rev: v2.2.1
hooks:
- id: codespell
- exclude: '^(pyextra/)|(third_party/)|(body/)|(cereal/)|(rednose/)|(panda/)|(laika/)|(opendbc/)|(laika_repo/)|(rednose_repo/)|(include/)|(selfdrive/ui/translations/.*.ts)|(selfdrive/controls/lib/cluster)'
+ exclude: '^(third_party/)|(body/)|(cereal/)|(rednose/)|(panda/)|(laika/)|(opendbc/)|(laika_repo/)|(rednose_repo/)|(selfdrive/ui/translations/.*.ts)'
args:
# if you've got a short variable name that's getting flagged, add it here
- -L bu,ro,te,ue,alo,hda,ois,nam,nams,ned,som,parm,setts,inout,warmup
@@ -31,12 +31,12 @@ repos:
entry: mypy
language: system
types: [python]
- exclude: '^(pyextra/)|(cereal/)|(opendbc/)|(panda/)|(laika/)|(laika_repo/)|(rednose/)|(rednose_repo/)|(tinygrad/)|(tinygrad_repo/)|(xx/)'
+ exclude: '^(third_party/)|(cereal/)|(opendbc/)|(panda/)|(laika/)|(laika_repo/)|(rednose/)|(rednose_repo/)|(tinygrad/)|(tinygrad_repo/)|(xx/)'
- repo: https://github.com/PyCQA/flake8
rev: 4.0.1
hooks:
- id: flake8
- exclude: '^(pyextra/)|(cereal/)|(rednose/)|(panda/)|(laika/)|(opendbc/)|(laika_repo/)|(rednose_repo/)|(tinygrad/)|(tinygrad_repo/)|(selfdrive/debug/)/'
+ exclude: '^(third_party/)|(cereal/)|(rednose/)|(panda/)|(laika/)|(opendbc/)|(laika_repo/)|(rednose_repo/)|(tinygrad/)|(tinygrad_repo/)|(selfdrive/debug/)/'
additional_dependencies: ['flake8-no-implicit-concat']
args:
- --indent-size=2
@@ -51,7 +51,7 @@ repos:
entry: pylint
language: system
types: [python]
- exclude: '^(pyextra/)|(cereal/)|(rednose/)|(panda/)|(laika/)|(laika_repo/)|(rednose_repo/)|(tinygrad/)|(tinygrad_repo/)'
+ exclude: '^(third_party/)|(cereal/)|(rednose/)|(panda/)|(laika/)|(laika_repo/)|(rednose_repo/)|(tinygrad/)|(tinygrad_repo/)'
args:
- -j0
- -rn
@@ -64,7 +64,7 @@ repos:
entry: cppcheck
language: system
types: [c++]
- exclude: '^(third_party/)|(pyextra/)|(cereal/)|(body/)|(rednose/)|(rednose_repo/)|(opendbc/)|(panda/)|(tools/)|(selfdrive/modeld/thneed/debug/)|(selfdrive/modeld/test/)|(selfdrive/camerad/test/)|(installer/)'
+ exclude: '^(third_party/)|(cereal/)|(body/)|(rednose/)|(rednose_repo/)|(opendbc/)|(panda/)|(tools/)|(selfdrive/modeld/thneed/debug/)|(selfdrive/modeld/test/)|(selfdrive/camerad/test/)|(installer/)'
args:
- --error-exitcode=1
- --language=c++
diff --git a/Dockerfile.openpilot b/Dockerfile.openpilot
index 102da78d7d..acc0fcc784 100644
--- a/Dockerfile.openpilot
+++ b/Dockerfile.openpilot
@@ -10,7 +10,6 @@ WORKDIR ${OPENPILOT_PATH}
COPY SConstruct ${OPENPILOT_PATH}
-COPY ./pyextra ${OPENPILOT_PATH}/pyextra
COPY ./third_party ${OPENPILOT_PATH}/third_party
COPY ./site_scons ${OPENPILOT_PATH}/site_scons
COPY ./laika ${OPENPILOT_PATH}/laika
diff --git a/README.md b/README.md
index 88b7aeb2bb..4896d9ff72 100755
--- a/README.md
+++ b/README.md
@@ -103,7 +103,6 @@ Directory Structure
├── opendbc # Files showing how to interpret data from cars
├── panda # Code used to communicate on CAN
├── third_party # External libraries
- ├── pyextra # Extra python packages
└── system # Generic services
├── camerad # Driver to capture images from the camera sensors
├── clocksd # Broadcasts current time
diff --git a/SConstruct b/SConstruct
index 54b008004e..b148a9116a 100644
--- a/SConstruct
+++ b/SConstruct
@@ -71,10 +71,10 @@ if arch == "aarch64" and AGNOS:
lenv = {
"PATH": os.environ['PATH'],
"LD_LIBRARY_PATH": [Dir(f"#third_party/acados/{arch}/lib").abspath],
- "PYTHONPATH": Dir("#").abspath + ":" + Dir("#pyextra/").abspath,
+ "PYTHONPATH": Dir("#").abspath,
"ACADOS_SOURCE_DIR": Dir("#third_party/acados/include/acados").abspath,
- "ACADOS_PYTHON_INTERFACE_PATH": Dir("#pyextra/acados_template").abspath,
+ "ACADOS_PYTHON_INTERFACE_PATH": Dir("#third_party/acados/acados_template").abspath,
"TERA_PATH": Dir("#").abspath + f"/third_party/acados/{arch}/t_renderer"
}
@@ -422,7 +422,6 @@ SConscript(['common/transformations/SConscript'])
SConscript(['selfdrive/modeld/SConscript'])
-SConscript(['selfdrive/controls/lib/cluster/SConscript'])
SConscript(['selfdrive/controls/lib/lateral_mpc_lib/SConscript'])
SConscript(['selfdrive/controls/lib/longitudinal_mpc_lib/SConscript'])
diff --git a/docs/Makefile b/docs/Makefile
index d0aa841c4d..dee660f770 100644
--- a/docs/Makefile
+++ b/docs/Makefile
@@ -41,7 +41,7 @@ clean:
@echo "Building rst files..."
sphinx-apidoc -o "$(DOCSBUILDDIR)" ../ \
- ../xx ../laika_repo ../rednose_repo ../pyextra ../notebooks ../panda_jungle \
+ ../xx ../laika_repo ../rednose_repo ../notebooks ../panda_jungle \
../third_party \
../panda/examples \
../scripts \
diff --git a/docs/docker/Dockerfile b/docs/docker/Dockerfile
index 0d5883f566..a1cdbbeaf0 100644
--- a/docs/docker/Dockerfile
+++ b/docs/docker/Dockerfile
@@ -11,7 +11,6 @@ WORKDIR ${OPENPILOT_PATH}
COPY SConstruct ${OPENPILOT_PATH}
-COPY ./pyextra ${OPENPILOT_PATH}/pyextra
COPY ./third_party ${OPENPILOT_PATH}/third_party
COPY ./site_scons ${OPENPILOT_PATH}/site_scons
COPY ./laika ${OPENPILOT_PATH}/laika
diff --git a/launch_chffrplus.sh b/launch_chffrplus.sh
index 911774a4eb..9fe9b1bd15 100755
--- a/launch_chffrplus.sh
+++ b/launch_chffrplus.sh
@@ -74,7 +74,7 @@ function launch {
# handle pythonpath
ln -sfn $(pwd) /data/pythonpath
- export PYTHONPATH="$PWD:$PWD/pyextra"
+ export PYTHONPATH="$PWD"
# hardware specific init
agnos_init
diff --git a/mypy.ini b/mypy.ini
index 39b1b007a7..9b6d00d2c4 100644
--- a/mypy.ini
+++ b/mypy.ini
@@ -2,7 +2,7 @@
python_version = 3.8
plugins = numpy.typing.mypy_plugin
files = body, common, docs, scripts, selfdrive, site_scons, system, tools
-exclude = ^(pyextra/)|(cereal/)|(opendbc/)|(panda/)|(laika/)|(laika_repo/)|(rednose/)|(rednose_repo/)|(tinygrad/)|(tinygrad_repo/)|(xx/)
+exclude = ^(cereal/)|(opendbc/)|(panda/)|(laika/)|(laika_repo/)|(rednose/)|(rednose_repo/)|(tinygrad/)|(tinygrad_repo/)|(xx/)
; third-party packages
ignore_missing_imports = True
diff --git a/release/files_common b/release/files_common
index a06543abbf..d0afa30dea 100644
--- a/release/files_common
+++ b/release/files_common
@@ -192,8 +192,6 @@ selfdrive/controls/lib/pid.py
selfdrive/controls/lib/radar_helpers.py
selfdrive/controls/lib/vehicle_model.py
-selfdrive/controls/lib/cluster/*
-
selfdrive/controls/lib/lateral_mpc_lib/.gitignore
selfdrive/controls/lib/longitudinal_mpc_lib/.gitignore
selfdrive/controls/lib/lateral_mpc_lib/*
@@ -328,7 +326,6 @@ system/camerad/SConscript
system/camerad/main.cc
system/camerad/snapshot/*
-system/camerad/include/*
system/camerad/cameras/camera_common.h
system/camerad/cameras/camera_common.cc
system/camerad/cameras/sensor2_i2c.h
@@ -384,7 +381,6 @@ selfdrive/modeld/thneed/thneed.h
selfdrive/modeld/thneed/thneed_common.cc
selfdrive/modeld/thneed/thneed_qcom2.cc
selfdrive/modeld/thneed/serialize.cc
-selfdrive/modeld/thneed/include/*
selfdrive/modeld/runners/snpemodel.cc
selfdrive/modeld/runners/snpemodel.h
@@ -412,8 +408,11 @@ selfdrive/assets/offroad/*
selfdrive/assets/sounds/*
selfdrive/assets/training/*
+third_party/.gitignore
third_party/SConscript
+third_party/cluster/*
+
third_party/linux/**
third_party/opencl/**
@@ -436,15 +435,13 @@ third_party/snpe/dsp**
third_party/acados/x86_64/**
third_party/acados/larch64/**
third_party/acados/include/**
+third_party/acados/acados_template/**
third_party/qt5/larch64/bin/**
scripts/update_now.sh
scripts/stop_updater.sh
-pyextra/.gitignore
-pyextra/acados_template/**
-
rednose/.gitignore
rednose/**
laika/**
diff --git a/selfdrive/controls/lib/lateral_mpc_lib/SConscript b/selfdrive/controls/lib/lateral_mpc_lib/SConscript
index df1e2a2a1a..868b5a873c 100644
--- a/selfdrive/controls/lib/lateral_mpc_lib/SConscript
+++ b/selfdrive/controls/lib/lateral_mpc_lib/SConscript
@@ -44,7 +44,7 @@ generated_files = [
] + build_files
acados_dir = '#third_party/acados'
-acados_templates_dir = '#pyextra/acados_template/c_templates_tera'
+acados_templates_dir = '#third_party/acados/acados_template/c_templates_tera'
source_list = ['lat_mpc.py',
f'{acados_dir}/include/acados_c/ocp_nlp_interface.h',
@@ -70,8 +70,8 @@ lib_solver = lenv.SharedLibrary(f"{gen}/acados_ocp_solver_lat",
LIBS=['m', 'acados', 'hpipm', 'blasfeo', 'qpOASES_e'])
# generate cython stuff
-acados_ocp_solver_pyx = File("#pyextra/acados_template/acados_ocp_solver_pyx.pyx")
-acados_ocp_solver_common = File("#pyextra/acados_template/acados_solver_common.pxd")
+acados_ocp_solver_pyx = File("#third_party/acados/acados_template/acados_ocp_solver_pyx.pyx")
+acados_ocp_solver_common = File("#third_party/acados/acados_template/acados_solver_common.pxd")
libacados_ocp_solver_pxd = File(f'{gen}/acados_solver.pxd')
libacados_ocp_solver_c = File(f'{gen}/acados_ocp_solver_pyx.c')
diff --git a/selfdrive/controls/lib/lateral_mpc_lib/lat_mpc.py b/selfdrive/controls/lib/lateral_mpc_lib/lat_mpc.py
index 9607532ace..536f436fce 100755
--- a/selfdrive/controls/lib/lateral_mpc_lib/lat_mpc.py
+++ b/selfdrive/controls/lib/lateral_mpc_lib/lat_mpc.py
@@ -8,7 +8,7 @@ from common.realtime import sec_since_boot
from selfdrive.modeld.constants import T_IDXS
if __name__ == '__main__': # generating code
- from pyextra.acados_template import AcadosModel, AcadosOcp, AcadosOcpSolver
+ from third_party.acados.acados_template import AcadosModel, AcadosOcp, AcadosOcpSolver
else:
from selfdrive.controls.lib.lateral_mpc_lib.c_generated_code.acados_ocp_solver_pyx import AcadosOcpSolverCython # pylint: disable=no-name-in-module, import-error
diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/SConscript b/selfdrive/controls/lib/longitudinal_mpc_lib/SConscript
index 5a9e69c297..e5b2360607 100644
--- a/selfdrive/controls/lib/longitudinal_mpc_lib/SConscript
+++ b/selfdrive/controls/lib/longitudinal_mpc_lib/SConscript
@@ -51,7 +51,7 @@ generated_files = [
] + build_files
acados_dir = '#third_party/acados'
-acados_templates_dir = '#pyextra/acados_template/c_templates_tera'
+acados_templates_dir = '#third_party/acados/acados_template/c_templates_tera'
source_list = ['long_mpc.py',
f'{acados_dir}/include/acados_c/ocp_nlp_interface.h',
@@ -77,8 +77,8 @@ lib_solver = lenv.SharedLibrary(f"{gen}/acados_ocp_solver_long",
LIBS=['m', 'acados', 'hpipm', 'blasfeo', 'qpOASES_e'])
# generate cython stuff
-acados_ocp_solver_pyx = File("#pyextra/acados_template/acados_ocp_solver_pyx.pyx")
-acados_ocp_solver_common = File("#pyextra/acados_template/acados_solver_common.pxd")
+acados_ocp_solver_pyx = File("#third_party/acados/acados_template/acados_ocp_solver_pyx.pyx")
+acados_ocp_solver_common = File("#third_party/acados/acados_template/acados_solver_common.pxd")
libacados_ocp_solver_pxd = File(f'{gen}/acados_solver.pxd')
libacados_ocp_solver_c = File(f'{gen}/acados_ocp_solver_pyx.c')
diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py b/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py
index 79a9ec4f0c..dc27fd27a9 100644
--- a/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py
+++ b/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py
@@ -9,7 +9,7 @@ from selfdrive.modeld.constants import index_function
from selfdrive.controls.lib.radar_helpers import _LEAD_ACCEL_TAU
if __name__ == '__main__': # generating code
- from pyextra.acados_template import AcadosModel, AcadosOcp, AcadosOcpSolver
+ from third_party.acados.acados_template import AcadosModel, AcadosOcp, AcadosOcpSolver
else:
from selfdrive.controls.lib.longitudinal_mpc_lib.c_generated_code.acados_ocp_solver_pyx import AcadosOcpSolverCython # pylint: disable=no-name-in-module, import-error
diff --git a/selfdrive/controls/radard.py b/selfdrive/controls/radard.py
index 3d958139d6..db87604e98 100755
--- a/selfdrive/controls/radard.py
+++ b/selfdrive/controls/radard.py
@@ -8,9 +8,9 @@ from cereal import car
from common.numpy_fast import interp
from common.params import Params
from common.realtime import Ratekeeper, Priority, config_realtime_process
-from selfdrive.controls.lib.cluster.fastcluster_py import cluster_points_centroid
from selfdrive.controls.lib.radar_helpers import Cluster, Track, RADAR_TO_CAMERA
from system.swaglog import cloudlog
+from third_party.cluster.fastcluster_py import cluster_points_centroid
class KalmanParams():
diff --git a/selfdrive/controls/tests/test_clustering.py b/selfdrive/controls/tests/test_clustering.py
index 290b267029..99c24d5938 100644
--- a/selfdrive/controls/tests/test_clustering.py
+++ b/selfdrive/controls/tests/test_clustering.py
@@ -7,8 +7,8 @@ from fastcluster import linkage_vector
from scipy.cluster import _hierarchy
from scipy.spatial.distance import pdist
-from selfdrive.controls.lib.cluster.fastcluster_py import hclust, ffi
-from selfdrive.controls.lib.cluster.fastcluster_py import cluster_points_centroid
+from third_party.cluster.fastcluster_py import hclust, ffi
+from third_party.cluster.fastcluster_py import cluster_points_centroid
def fcluster(Z, t, criterion='inconsistent', depth=2, R=None, monocrit=None):
diff --git a/selfdrive/manager/manager.py b/selfdrive/manager/manager.py
index 928507f65b..369c529626 100755
--- a/selfdrive/manager/manager.py
+++ b/selfdrive/manager/manager.py
@@ -23,8 +23,6 @@ from system.version import is_dirty, get_commit, get_version, get_origin, get_sh
terms_version, training_version, is_tested_branch
-sys.path.append(os.path.join(BASEDIR, "pyextra"))
-
def manager_init() -> None:
# update system time from panda
diff --git a/selfdrive/modeld/thneed/thneed.h b/selfdrive/modeld/thneed/thneed.h
index 65475ccf7f..6475577734 100644
--- a/selfdrive/modeld/thneed/thneed.h
+++ b/selfdrive/modeld/thneed/thneed.h
@@ -12,7 +12,7 @@
#include
-#include "selfdrive/modeld/thneed/include/msm_kgsl.h"
+#include "msm_kgsl.h"
using namespace std;
diff --git a/system/camerad/SConscript b/system/camerad/SConscript
index ddc763b53d..3ecc3f6d72 100644
--- a/system/camerad/SConscript
+++ b/system/camerad/SConscript
@@ -2,17 +2,13 @@ Import('env', 'arch', 'cereal', 'messaging', 'common', 'gpucommon', 'visionipc')
libs = ['m', 'pthread', common, 'jpeg', 'OpenCL', 'yuv', cereal, messaging, 'zmq', 'capnp', 'kj', visionipc, gpucommon, 'atomic']
-cenv = env.Clone()
-cenv['CPPPATH'].append('include/')
-
-camera_obj = cenv.Object(['cameras/camera_qcom2.cc', 'cameras/camera_common.cc', 'cameras/camera_util.cc'])
-cenv.Program('camerad', [
+camera_obj = env.Object(['cameras/camera_qcom2.cc', 'cameras/camera_common.cc', 'cameras/camera_util.cc'])
+env.Program('camerad', [
'main.cc',
camera_obj,
], LIBS=libs)
if GetOption("test") and arch == "x86_64":
- cenv.Program('test/ae_gray_test', [
- 'test/ae_gray_test.cc',
- camera_obj,
- ], LIBS=libs)
+ env.Program('test/ae_gray_test',
+ ['test/ae_gray_test.cc', camera_obj],
+ LIBS=libs)
diff --git a/pyextra/.gitignore b/third_party/.gitignore
similarity index 100%
rename from pyextra/.gitignore
rename to third_party/.gitignore
diff --git a/third_party/SConscript b/third_party/SConscript
index e5bbfaa07a..e8d1789ee0 100644
--- a/third_party/SConscript
+++ b/third_party/SConscript
@@ -4,3 +4,5 @@ env.Library('json11', ['json11/json11.cpp'], CCFLAGS=env['CCFLAGS'] + ['-Wno-unq
env.Append(CPPPATH=[Dir('json11')])
env.Library('kaitai', ['kaitai/kaitaistream.cpp'], CPPDEFINES=['KS_STR_ENCODING_NONE'])
+
+SConscript(['cluster/SConscript'])
diff --git a/pyextra/acados_template/.gitignore b/third_party/acados/acados_template/.gitignore
similarity index 100%
rename from pyextra/acados_template/.gitignore
rename to third_party/acados/acados_template/.gitignore
diff --git a/pyextra/acados_template/__init__.py b/third_party/acados/acados_template/__init__.py
similarity index 100%
rename from pyextra/acados_template/__init__.py
rename to third_party/acados/acados_template/__init__.py
diff --git a/pyextra/acados_template/acados_layout.json b/third_party/acados/acados_template/acados_layout.json
similarity index 100%
rename from pyextra/acados_template/acados_layout.json
rename to third_party/acados/acados_template/acados_layout.json
diff --git a/pyextra/acados_template/acados_model.py b/third_party/acados/acados_template/acados_model.py
similarity index 100%
rename from pyextra/acados_template/acados_model.py
rename to third_party/acados/acados_template/acados_model.py
diff --git a/pyextra/acados_template/acados_ocp.py b/third_party/acados/acados_template/acados_ocp.py
similarity index 100%
rename from pyextra/acados_template/acados_ocp.py
rename to third_party/acados/acados_template/acados_ocp.py
diff --git a/pyextra/acados_template/acados_ocp_solver.py b/third_party/acados/acados_template/acados_ocp_solver.py
similarity index 100%
rename from pyextra/acados_template/acados_ocp_solver.py
rename to third_party/acados/acados_template/acados_ocp_solver.py
diff --git a/pyextra/acados_template/acados_ocp_solver_pyx.pyx b/third_party/acados/acados_template/acados_ocp_solver_pyx.pyx
similarity index 100%
rename from pyextra/acados_template/acados_ocp_solver_pyx.pyx
rename to third_party/acados/acados_template/acados_ocp_solver_pyx.pyx
diff --git a/pyextra/acados_template/acados_sim.py b/third_party/acados/acados_template/acados_sim.py
similarity index 100%
rename from pyextra/acados_template/acados_sim.py
rename to third_party/acados/acados_template/acados_sim.py
diff --git a/pyextra/acados_template/acados_sim_layout.json b/third_party/acados/acados_template/acados_sim_layout.json
similarity index 100%
rename from pyextra/acados_template/acados_sim_layout.json
rename to third_party/acados/acados_template/acados_sim_layout.json
diff --git a/pyextra/acados_template/acados_sim_solver.py b/third_party/acados/acados_template/acados_sim_solver.py
similarity index 100%
rename from pyextra/acados_template/acados_sim_solver.py
rename to third_party/acados/acados_template/acados_sim_solver.py
diff --git a/pyextra/acados_template/acados_solver_common.pxd b/third_party/acados/acados_template/acados_solver_common.pxd
similarity index 100%
rename from pyextra/acados_template/acados_solver_common.pxd
rename to third_party/acados/acados_template/acados_solver_common.pxd
diff --git a/pyextra/acados_template/builders.py b/third_party/acados/acados_template/builders.py
similarity index 100%
rename from pyextra/acados_template/builders.py
rename to third_party/acados/acados_template/builders.py
diff --git a/pyextra/acados_template/c_templates_tera/CMakeLists.in.txt b/third_party/acados/acados_template/c_templates_tera/CMakeLists.in.txt
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/CMakeLists.in.txt
rename to third_party/acados/acados_template/c_templates_tera/CMakeLists.in.txt
diff --git a/pyextra/acados_template/c_templates_tera/CPPLINT.cfg b/third_party/acados/acados_template/c_templates_tera/CPPLINT.cfg
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/CPPLINT.cfg
rename to third_party/acados/acados_template/c_templates_tera/CPPLINT.cfg
diff --git a/pyextra/acados_template/c_templates_tera/Makefile.in b/third_party/acados/acados_template/c_templates_tera/Makefile.in
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/Makefile.in
rename to third_party/acados/acados_template/c_templates_tera/Makefile.in
diff --git a/pyextra/acados_template/c_templates_tera/acados_mex_create.in.c b/third_party/acados/acados_template/c_templates_tera/acados_mex_create.in.c
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/acados_mex_create.in.c
rename to third_party/acados/acados_template/c_templates_tera/acados_mex_create.in.c
diff --git a/pyextra/acados_template/c_templates_tera/acados_mex_free.in.c b/third_party/acados/acados_template/c_templates_tera/acados_mex_free.in.c
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/acados_mex_free.in.c
rename to third_party/acados/acados_template/c_templates_tera/acados_mex_free.in.c
diff --git a/pyextra/acados_template/c_templates_tera/acados_mex_set.in.c b/third_party/acados/acados_template/c_templates_tera/acados_mex_set.in.c
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/acados_mex_set.in.c
rename to third_party/acados/acados_template/c_templates_tera/acados_mex_set.in.c
diff --git a/pyextra/acados_template/c_templates_tera/acados_mex_solve.in.c b/third_party/acados/acados_template/c_templates_tera/acados_mex_solve.in.c
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/acados_mex_solve.in.c
rename to third_party/acados/acados_template/c_templates_tera/acados_mex_solve.in.c
diff --git a/pyextra/acados_template/c_templates_tera/acados_sim_solver.in.c b/third_party/acados/acados_template/c_templates_tera/acados_sim_solver.in.c
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/acados_sim_solver.in.c
rename to third_party/acados/acados_template/c_templates_tera/acados_sim_solver.in.c
diff --git a/pyextra/acados_template/c_templates_tera/acados_sim_solver.in.h b/third_party/acados/acados_template/c_templates_tera/acados_sim_solver.in.h
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/acados_sim_solver.in.h
rename to third_party/acados/acados_template/c_templates_tera/acados_sim_solver.in.h
diff --git a/pyextra/acados_template/c_templates_tera/acados_sim_solver_sfun.in.c b/third_party/acados/acados_template/c_templates_tera/acados_sim_solver_sfun.in.c
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/acados_sim_solver_sfun.in.c
rename to third_party/acados/acados_template/c_templates_tera/acados_sim_solver_sfun.in.c
diff --git a/pyextra/acados_template/c_templates_tera/acados_solver.in.c b/third_party/acados/acados_template/c_templates_tera/acados_solver.in.c
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/acados_solver.in.c
rename to third_party/acados/acados_template/c_templates_tera/acados_solver.in.c
diff --git a/pyextra/acados_template/c_templates_tera/acados_solver.in.h b/third_party/acados/acados_template/c_templates_tera/acados_solver.in.h
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/acados_solver.in.h
rename to third_party/acados/acados_template/c_templates_tera/acados_solver.in.h
diff --git a/pyextra/acados_template/c_templates_tera/acados_solver.in.pxd b/third_party/acados/acados_template/c_templates_tera/acados_solver.in.pxd
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/acados_solver.in.pxd
rename to third_party/acados/acados_template/c_templates_tera/acados_solver.in.pxd
diff --git a/pyextra/acados_template/c_templates_tera/acados_solver_sfun.in.c b/third_party/acados/acados_template/c_templates_tera/acados_solver_sfun.in.c
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/acados_solver_sfun.in.c
rename to third_party/acados/acados_template/c_templates_tera/acados_solver_sfun.in.c
diff --git a/pyextra/acados_template/c_templates_tera/cost_y_0_fun.in.h b/third_party/acados/acados_template/c_templates_tera/cost_y_0_fun.in.h
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/cost_y_0_fun.in.h
rename to third_party/acados/acados_template/c_templates_tera/cost_y_0_fun.in.h
diff --git a/pyextra/acados_template/c_templates_tera/cost_y_e_fun.in.h b/third_party/acados/acados_template/c_templates_tera/cost_y_e_fun.in.h
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/cost_y_e_fun.in.h
rename to third_party/acados/acados_template/c_templates_tera/cost_y_e_fun.in.h
diff --git a/pyextra/acados_template/c_templates_tera/cost_y_fun.in.h b/third_party/acados/acados_template/c_templates_tera/cost_y_fun.in.h
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/cost_y_fun.in.h
rename to third_party/acados/acados_template/c_templates_tera/cost_y_fun.in.h
diff --git a/pyextra/acados_template/c_templates_tera/external_cost.in.h b/third_party/acados/acados_template/c_templates_tera/external_cost.in.h
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/external_cost.in.h
rename to third_party/acados/acados_template/c_templates_tera/external_cost.in.h
diff --git a/pyextra/acados_template/c_templates_tera/external_cost_0.in.h b/third_party/acados/acados_template/c_templates_tera/external_cost_0.in.h
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/external_cost_0.in.h
rename to third_party/acados/acados_template/c_templates_tera/external_cost_0.in.h
diff --git a/pyextra/acados_template/c_templates_tera/external_cost_e.in.h b/third_party/acados/acados_template/c_templates_tera/external_cost_e.in.h
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/external_cost_e.in.h
rename to third_party/acados/acados_template/c_templates_tera/external_cost_e.in.h
diff --git a/pyextra/acados_template/c_templates_tera/h_constraint.in.h b/third_party/acados/acados_template/c_templates_tera/h_constraint.in.h
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/h_constraint.in.h
rename to third_party/acados/acados_template/c_templates_tera/h_constraint.in.h
diff --git a/pyextra/acados_template/c_templates_tera/h_e_constraint.in.h b/third_party/acados/acados_template/c_templates_tera/h_e_constraint.in.h
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/h_e_constraint.in.h
rename to third_party/acados/acados_template/c_templates_tera/h_e_constraint.in.h
diff --git a/pyextra/acados_template/c_templates_tera/main.in.c b/third_party/acados/acados_template/c_templates_tera/main.in.c
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/main.in.c
rename to third_party/acados/acados_template/c_templates_tera/main.in.c
diff --git a/pyextra/acados_template/c_templates_tera/main_mex.in.c b/third_party/acados/acados_template/c_templates_tera/main_mex.in.c
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/main_mex.in.c
rename to third_party/acados/acados_template/c_templates_tera/main_mex.in.c
diff --git a/pyextra/acados_template/c_templates_tera/main_sim.in.c b/third_party/acados/acados_template/c_templates_tera/main_sim.in.c
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/main_sim.in.c
rename to third_party/acados/acados_template/c_templates_tera/main_sim.in.c
diff --git a/pyextra/acados_template/c_templates_tera/make_main_mex.in.m b/third_party/acados/acados_template/c_templates_tera/make_main_mex.in.m
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/make_main_mex.in.m
rename to third_party/acados/acados_template/c_templates_tera/make_main_mex.in.m
diff --git a/pyextra/acados_template/c_templates_tera/make_mex.in.m b/third_party/acados/acados_template/c_templates_tera/make_mex.in.m
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/make_mex.in.m
rename to third_party/acados/acados_template/c_templates_tera/make_mex.in.m
diff --git a/pyextra/acados_template/c_templates_tera/make_sfun.in.m b/third_party/acados/acados_template/c_templates_tera/make_sfun.in.m
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/make_sfun.in.m
rename to third_party/acados/acados_template/c_templates_tera/make_sfun.in.m
diff --git a/pyextra/acados_template/c_templates_tera/make_sfun_sim.in.m b/third_party/acados/acados_template/c_templates_tera/make_sfun_sim.in.m
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/make_sfun_sim.in.m
rename to third_party/acados/acados_template/c_templates_tera/make_sfun_sim.in.m
diff --git a/pyextra/acados_template/c_templates_tera/mex_solver.in.m b/third_party/acados/acados_template/c_templates_tera/mex_solver.in.m
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/mex_solver.in.m
rename to third_party/acados/acados_template/c_templates_tera/mex_solver.in.m
diff --git a/pyextra/acados_template/c_templates_tera/model.in.h b/third_party/acados/acados_template/c_templates_tera/model.in.h
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/model.in.h
rename to third_party/acados/acados_template/c_templates_tera/model.in.h
diff --git a/pyextra/acados_template/c_templates_tera/phi_constraint.in.h b/third_party/acados/acados_template/c_templates_tera/phi_constraint.in.h
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/phi_constraint.in.h
rename to third_party/acados/acados_template/c_templates_tera/phi_constraint.in.h
diff --git a/pyextra/acados_template/c_templates_tera/phi_e_constraint.in.h b/third_party/acados/acados_template/c_templates_tera/phi_e_constraint.in.h
similarity index 100%
rename from pyextra/acados_template/c_templates_tera/phi_e_constraint.in.h
rename to third_party/acados/acados_template/c_templates_tera/phi_e_constraint.in.h
diff --git a/pyextra/acados_template/generate_c_code_constraint.py b/third_party/acados/acados_template/generate_c_code_constraint.py
similarity index 100%
rename from pyextra/acados_template/generate_c_code_constraint.py
rename to third_party/acados/acados_template/generate_c_code_constraint.py
diff --git a/pyextra/acados_template/generate_c_code_discrete_dynamics.py b/third_party/acados/acados_template/generate_c_code_discrete_dynamics.py
similarity index 100%
rename from pyextra/acados_template/generate_c_code_discrete_dynamics.py
rename to third_party/acados/acados_template/generate_c_code_discrete_dynamics.py
diff --git a/pyextra/acados_template/generate_c_code_explicit_ode.py b/third_party/acados/acados_template/generate_c_code_explicit_ode.py
similarity index 100%
rename from pyextra/acados_template/generate_c_code_explicit_ode.py
rename to third_party/acados/acados_template/generate_c_code_explicit_ode.py
diff --git a/pyextra/acados_template/generate_c_code_external_cost.py b/third_party/acados/acados_template/generate_c_code_external_cost.py
similarity index 100%
rename from pyextra/acados_template/generate_c_code_external_cost.py
rename to third_party/acados/acados_template/generate_c_code_external_cost.py
diff --git a/pyextra/acados_template/generate_c_code_gnsf.py b/third_party/acados/acados_template/generate_c_code_gnsf.py
similarity index 100%
rename from pyextra/acados_template/generate_c_code_gnsf.py
rename to third_party/acados/acados_template/generate_c_code_gnsf.py
diff --git a/pyextra/acados_template/generate_c_code_implicit_ode.py b/third_party/acados/acados_template/generate_c_code_implicit_ode.py
similarity index 100%
rename from pyextra/acados_template/generate_c_code_implicit_ode.py
rename to third_party/acados/acados_template/generate_c_code_implicit_ode.py
diff --git a/pyextra/acados_template/generate_c_code_nls_cost.py b/third_party/acados/acados_template/generate_c_code_nls_cost.py
similarity index 100%
rename from pyextra/acados_template/generate_c_code_nls_cost.py
rename to third_party/acados/acados_template/generate_c_code_nls_cost.py
diff --git a/pyextra/acados_template/simulink_default_opts.json b/third_party/acados/acados_template/simulink_default_opts.json
similarity index 100%
rename from pyextra/acados_template/simulink_default_opts.json
rename to third_party/acados/acados_template/simulink_default_opts.json
diff --git a/pyextra/acados_template/utils.py b/third_party/acados/acados_template/utils.py
similarity index 100%
rename from pyextra/acados_template/utils.py
rename to third_party/acados/acados_template/utils.py
diff --git a/third_party/acados/build.sh b/third_party/acados/build.sh
index 0481e8159b..9b18b2b67d 100755
--- a/third_party/acados/build.sh
+++ b/third_party/acados/build.sh
@@ -43,11 +43,10 @@ mkdir -p $INSTALL_DIR
rm $DIR/acados_repo/lib/*.json
-rm -rf $DIR/include
+rm -rf $DIR/include $DIR/acados_template
cp -r $DIR/acados_repo/include $DIR
cp -r $DIR/acados_repo/lib $INSTALL_DIR
-rm -rf $DIR/../../pyextra/acados_template
-cp -r $DIR/acados_repo/interfaces/acados_template/acados_template $DIR/../../pyextra
+cp -r $DIR/acados_repo/interfaces/acados_template/acados_template $DIR/
#pip3 install -e $DIR/acados/interfaces/acados_template
# build tera
diff --git a/selfdrive/controls/lib/cluster/.gitignore b/third_party/cluster/.gitignore
similarity index 100%
rename from selfdrive/controls/lib/cluster/.gitignore
rename to third_party/cluster/.gitignore
diff --git a/selfdrive/controls/lib/cluster/LICENSE b/third_party/cluster/LICENSE
similarity index 100%
rename from selfdrive/controls/lib/cluster/LICENSE
rename to third_party/cluster/LICENSE
diff --git a/selfdrive/controls/lib/cluster/README b/third_party/cluster/README
similarity index 100%
rename from selfdrive/controls/lib/cluster/README
rename to third_party/cluster/README
diff --git a/selfdrive/controls/lib/cluster/SConscript b/third_party/cluster/SConscript
similarity index 100%
rename from selfdrive/controls/lib/cluster/SConscript
rename to third_party/cluster/SConscript
diff --git a/selfdrive/controls/lib/cluster/__init__.py b/third_party/cluster/__init__.py
similarity index 100%
rename from selfdrive/controls/lib/cluster/__init__.py
rename to third_party/cluster/__init__.py
diff --git a/selfdrive/controls/lib/cluster/fastcluster.cpp b/third_party/cluster/fastcluster.cpp
similarity index 100%
rename from selfdrive/controls/lib/cluster/fastcluster.cpp
rename to third_party/cluster/fastcluster.cpp
diff --git a/selfdrive/controls/lib/cluster/fastcluster.h b/third_party/cluster/fastcluster.h
similarity index 100%
rename from selfdrive/controls/lib/cluster/fastcluster.h
rename to third_party/cluster/fastcluster.h
diff --git a/selfdrive/controls/lib/cluster/fastcluster_R_dm.cpp b/third_party/cluster/fastcluster_R_dm.cpp
similarity index 100%
rename from selfdrive/controls/lib/cluster/fastcluster_R_dm.cpp
rename to third_party/cluster/fastcluster_R_dm.cpp
diff --git a/selfdrive/controls/lib/cluster/fastcluster_dm.cpp b/third_party/cluster/fastcluster_dm.cpp
similarity index 100%
rename from selfdrive/controls/lib/cluster/fastcluster_dm.cpp
rename to third_party/cluster/fastcluster_dm.cpp
diff --git a/selfdrive/controls/lib/cluster/fastcluster_py.py b/third_party/cluster/fastcluster_py.py
similarity index 100%
rename from selfdrive/controls/lib/cluster/fastcluster_py.py
rename to third_party/cluster/fastcluster_py.py
diff --git a/selfdrive/controls/lib/cluster/test.cpp b/third_party/cluster/test.cpp
similarity index 100%
rename from selfdrive/controls/lib/cluster/test.cpp
rename to third_party/cluster/test.cpp
diff --git a/system/camerad/include/media/cam_cpas.h b/third_party/linux/include/media/cam_cpas.h
similarity index 100%
rename from system/camerad/include/media/cam_cpas.h
rename to third_party/linux/include/media/cam_cpas.h
diff --git a/system/camerad/include/media/cam_defs.h b/third_party/linux/include/media/cam_defs.h
similarity index 100%
rename from system/camerad/include/media/cam_defs.h
rename to third_party/linux/include/media/cam_defs.h
diff --git a/system/camerad/include/media/cam_fd.h b/third_party/linux/include/media/cam_fd.h
similarity index 100%
rename from system/camerad/include/media/cam_fd.h
rename to third_party/linux/include/media/cam_fd.h
diff --git a/system/camerad/include/media/cam_icp.h b/third_party/linux/include/media/cam_icp.h
similarity index 100%
rename from system/camerad/include/media/cam_icp.h
rename to third_party/linux/include/media/cam_icp.h
diff --git a/system/camerad/include/media/cam_isp.h b/third_party/linux/include/media/cam_isp.h
similarity index 100%
rename from system/camerad/include/media/cam_isp.h
rename to third_party/linux/include/media/cam_isp.h
diff --git a/system/camerad/include/media/cam_isp_ife.h b/third_party/linux/include/media/cam_isp_ife.h
similarity index 100%
rename from system/camerad/include/media/cam_isp_ife.h
rename to third_party/linux/include/media/cam_isp_ife.h
diff --git a/system/camerad/include/media/cam_isp_vfe.h b/third_party/linux/include/media/cam_isp_vfe.h
similarity index 100%
rename from system/camerad/include/media/cam_isp_vfe.h
rename to third_party/linux/include/media/cam_isp_vfe.h
diff --git a/system/camerad/include/media/cam_jpeg.h b/third_party/linux/include/media/cam_jpeg.h
similarity index 100%
rename from system/camerad/include/media/cam_jpeg.h
rename to third_party/linux/include/media/cam_jpeg.h
diff --git a/system/camerad/include/media/cam_lrme.h b/third_party/linux/include/media/cam_lrme.h
similarity index 100%
rename from system/camerad/include/media/cam_lrme.h
rename to third_party/linux/include/media/cam_lrme.h
diff --git a/system/camerad/include/media/cam_req_mgr.h b/third_party/linux/include/media/cam_req_mgr.h
similarity index 100%
rename from system/camerad/include/media/cam_req_mgr.h
rename to third_party/linux/include/media/cam_req_mgr.h
diff --git a/system/camerad/include/media/cam_sensor.h b/third_party/linux/include/media/cam_sensor.h
similarity index 100%
rename from system/camerad/include/media/cam_sensor.h
rename to third_party/linux/include/media/cam_sensor.h
diff --git a/system/camerad/include/media/cam_sensor_cmn_header.h b/third_party/linux/include/media/cam_sensor_cmn_header.h
similarity index 100%
rename from system/camerad/include/media/cam_sensor_cmn_header.h
rename to third_party/linux/include/media/cam_sensor_cmn_header.h
diff --git a/system/camerad/include/media/cam_sync.h b/third_party/linux/include/media/cam_sync.h
similarity index 100%
rename from system/camerad/include/media/cam_sync.h
rename to third_party/linux/include/media/cam_sync.h
diff --git a/system/camerad/include/msm_cam_sensor.h b/third_party/linux/include/msm_cam_sensor.h
similarity index 100%
rename from system/camerad/include/msm_cam_sensor.h
rename to third_party/linux/include/msm_cam_sensor.h
diff --git a/system/camerad/include/msm_camsensor_sdk.h b/third_party/linux/include/msm_camsensor_sdk.h
similarity index 100%
rename from system/camerad/include/msm_camsensor_sdk.h
rename to third_party/linux/include/msm_camsensor_sdk.h
diff --git a/selfdrive/modeld/thneed/include/msm_kgsl.h b/third_party/linux/include/msm_kgsl.h
similarity index 100%
rename from selfdrive/modeld/thneed/include/msm_kgsl.h
rename to third_party/linux/include/msm_kgsl.h
diff --git a/system/camerad/include/msmb_camera.h b/third_party/linux/include/msmb_camera.h
similarity index 100%
rename from system/camerad/include/msmb_camera.h
rename to third_party/linux/include/msmb_camera.h
diff --git a/system/camerad/include/msmb_isp.h b/third_party/linux/include/msmb_isp.h
similarity index 100%
rename from system/camerad/include/msmb_isp.h
rename to third_party/linux/include/msmb_isp.h
diff --git a/system/camerad/include/msmb_ispif.h b/third_party/linux/include/msmb_ispif.h
similarity index 100%
rename from system/camerad/include/msmb_ispif.h
rename to third_party/linux/include/msmb_ispif.h
diff --git a/tools/gpstest/fuzzy_testing.py b/tools/gpstest/fuzzy_testing.py
index df6691c558..bd204e7ae7 100755
--- a/tools/gpstest/fuzzy_testing.py
+++ b/tools/gpstest/fuzzy_testing.py
@@ -69,7 +69,7 @@ rc_p: Any = None
def exec_remote_checker(lat, lon, duration, ip_addr):
global rc_p
# TODO: good enough for testing
- remote_cmd = "export PYTHONPATH=/data/pythonpath:/data/pythonpath/pyextra && "
+ remote_cmd = "export PYTHONPATH=/data/pythonpath && "
remote_cmd += "cd /data/openpilot && "
remote_cmd += f"timeout {duration} /usr/local/pyenv/shims/python tools/gpstest/remote_checker.py "
remote_cmd += f"{lat} {lon}"
diff --git a/tools/sim/Dockerfile.sim b/tools/sim/Dockerfile.sim
index 3692d48e0f..be16f8c863 100644
--- a/tools/sim/Dockerfile.sim
+++ b/tools/sim/Dockerfile.sim
@@ -15,7 +15,6 @@ RUN mkdir -p $HOME/openpilot
COPY SConstruct $HOME/openpilot/
COPY ./third_party $HOME/openpilot/third_party
-COPY ./pyextra $HOME/openpilot/pyextra
COPY ./site_scons $HOME/openpilot/site_scons
COPY ./rednose $HOME/openpilot/rednose
COPY ./laika $HOME/openpilot/laika
From 3d44b6b3ac6d1f207e01d4cbf225bd929255ca1e Mon Sep 17 00:00:00 2001
From: Adeeb Shihadeh
Date: Sun, 1 Jan 2023 19:15:44 -0800
Subject: [PATCH 021/484] alt amp config (#26858)
* alt amp config
* fix
* not executable
* comment
* consistency
Co-authored-by: Comma Device
---
system/hardware/tici/amplifier.py | 52 ++++++++++++++++++++++++-------
system/hardware/tici/hardware.py | 14 +++++++--
2 files changed, 53 insertions(+), 13 deletions(-)
mode change 100755 => 100644 system/hardware/tici/amplifier.py
diff --git a/system/hardware/tici/amplifier.py b/system/hardware/tici/amplifier.py
old mode 100755
new mode 100644
index a8b2798630..8233834d11
--- a/system/hardware/tici/amplifier.py
+++ b/system/hardware/tici/amplifier.py
@@ -1,4 +1,3 @@
-#!/usr/bin/env python
from smbus2 import SMBus
from collections import namedtuple
@@ -63,11 +62,43 @@ BASE_CONFIG = [
AmpConfig("Zero-crossing detection disabled", 0b0, 0x49, 5, 0b00100000),
]
-BASE_CONFIG += configs_from_eq_params(0x84, EQParams(0x274F, 0xC0FF, 0x3BF9, 0x0B3C, 0x1656))
-BASE_CONFIG += configs_from_eq_params(0x8E, EQParams(0x1009, 0xC6BF, 0x2952, 0x1C97, 0x30DF))
-BASE_CONFIG += configs_from_eq_params(0x98, EQParams(0x0F75, 0xCBE5, 0x0ED2, 0x2528, 0x3E42))
-BASE_CONFIG += configs_from_eq_params(0xA2, EQParams(0x091F, 0x3D4C, 0xCE11, 0x1266, 0x2807))
-BASE_CONFIG += configs_from_eq_params(0xAC, EQParams(0x0A9E, 0x3F20, 0xE573, 0x0A8B, 0x3A3B))
+CONFIGS = {
+ "tici": [
+ *configs_from_eq_params(0x84, EQParams(0x274F, 0xC0FF, 0x3BF9, 0x0B3C, 0x1656)),
+ *configs_from_eq_params(0x8E, EQParams(0x1009, 0xC6BF, 0x2952, 0x1C97, 0x30DF)),
+ *configs_from_eq_params(0x98, EQParams(0x0F75, 0xCBE5, 0x0ED2, 0x2528, 0x3E42)),
+ *configs_from_eq_params(0xA2, EQParams(0x091F, 0x3D4C, 0xCE11, 0x1266, 0x2807)),
+ *configs_from_eq_params(0xAC, EQParams(0x0A9E, 0x3F20, 0xE573, 0x0A8B, 0x3A3B)),
+ ],
+ "tizi": [
+ AmpConfig("Left speaker output from left DAC", 0b1, 0x2B, 0, 0b11111111),
+ AmpConfig("Left Speaker Mixer Gain", 0b00, 0x2D, 0, 0b00000011),
+ AmpConfig("Left speaker output volume", 0x1F, 0x3D, 0, 0b00011111),
+ AmpConfig("Right speaker output volume", 0x1F, 0x3E, 0, 0b00011111),
+ AmpConfig("DAI1 attenuation (DV1)", 0x4, 0x2F, 0, 0b00001111),
+ AmpConfig("DAI2 attenuation (DV2)", 0x4, 0x31, 0, 0b00001111),
+ AmpConfig("DAI2: DC blocking", 0b0, 0x20, 0, 0b00000001),
+ AmpConfig("ALC enable", 0b0, 0x43, 7, 0b10000000),
+ AmpConfig("DAI2 EQ attenuation", 0x2, 0x32, 0, 0b00001111),
+ AmpConfig("Excursion limiter upper corner freq", 0b001, 0x41, 4, 0b01110000),
+ AmpConfig("Excursion limiter threshold", 0b100, 0x42, 0, 0b00001111),
+ AmpConfig("Distortion limit (THDCLP)", 0x0, 0x46, 4, 0b11110000),
+ AmpConfig("Distortion limiter release time constant", 0b1, 0x46, 0, 0b00000001),
+ AmpConfig("Left DAC input mixer: DAI1 left", 0b0, 0x22, 7, 0b10000000),
+ AmpConfig("Left DAC input mixer: DAI1 right", 0b0, 0x22, 6, 0b01000000),
+ AmpConfig("Left DAC input mixer: DAI2 left", 0b1, 0x22, 5, 0b00100000),
+ AmpConfig("Left DAC input mixer: DAI2 right", 0b0, 0x22, 4, 0b00010000),
+ AmpConfig("Right DAC input mixer: DAI2 left", 0b0, 0x22, 1, 0b00000010),
+ AmpConfig("Right DAC input mixer: DAI2 right", 0b1, 0x22, 0, 0b00000001),
+ AmpConfig("Volume adjustment smoothing disabled", 0b1, 0x49, 6, 0b01000000),
+
+ *configs_from_eq_params(0x84, EQParams(0x3084, 0xC023, 0x3D60, 0x042B, 0x1222)),
+ *configs_from_eq_params(0x8E, EQParams(0x2FB2, 0xC05C, 0x3BD3, 0x06C5, 0x16BB)),
+ *configs_from_eq_params(0x98, EQParams(0x21F5, 0xDF73, 0x2DFE, 0x371A, 0x2C80)),
+ *configs_from_eq_params(0xA2, EQParams(0x2A5A, 0x0AD0, 0x14FA, 0x3F14, 0x3C76)),
+ *configs_from_eq_params(0xAC, EQParams(0x1577, 0x3FAE, 0xEE60, 0x0664, 0x3D86)),
+ ],
+}
class Amplifier:
AMP_I2C_BUS = 0
@@ -91,14 +122,13 @@ class Amplifier:
def set_global_shutdown(self, amp_disabled):
self.set_config(AmpConfig("Global shutdown", 0b0 if amp_disabled else 0b1, 0x51, 7, 0b10000000))
- def initialize_configuration(self):
+ def initialize_configuration(self, model):
self.set_global_shutdown(amp_disabled=True)
for config in BASE_CONFIG:
self.set_config(config)
- self.set_global_shutdown(amp_disabled=False)
-
+ for config in CONFIGS[model]:
+ self.set_config(config)
-if __name__ == "__main__":
- Amplifier(debug=True).initialize_configuration()
+ self.set_global_shutdown(amp_disabled=False)
diff --git a/system/hardware/tici/hardware.py b/system/hardware/tici/hardware.py
index b5f5e00410..c0fbc66fae 100644
--- a/system/hardware/tici/hardware.py
+++ b/system/hardware/tici/hardware.py
@@ -85,6 +85,16 @@ class Tici(HardwareBase):
def amplifier(self):
return Amplifier()
+ @cached_property
+ def model(self):
+ with open("/sys/firmware/devicetree/base/model") as f:
+ model = f.read().strip('\x00')
+ model = model.split('comma ')[-1]
+ # TODO: remove this with AGNOS 7+
+ if model.startswith('Qualcomm'):
+ model = 'tici'
+ return model
+
def get_os_version(self):
with open("/VERSION") as f:
return f.read().strip()
@@ -401,7 +411,7 @@ class Tici(HardwareBase):
# amplifier, 100mW at idle
self.amplifier.set_global_shutdown(amp_disabled=powersave_enabled)
if not powersave_enabled:
- self.amplifier.initialize_configuration()
+ self.amplifier.initialize_configuration(self.model)
# *** CPU config ***
@@ -430,7 +440,7 @@ class Tici(HardwareBase):
return 0
def initialize_hardware(self):
- self.amplifier.initialize_configuration()
+ self.amplifier.initialize_configuration(self.model)
# Allow thermald to write engagement status to kmsg
os.system("sudo chmod a+w /dev/kmsg")
From 922bedaf47effb448c056a1844c13ecd7a26a244 Mon Sep 17 00:00:00 2001
From: Adeeb Shihadeh
Date: Sun, 1 Jan 2023 19:47:02 -0800
Subject: [PATCH 022/484] tici: remove hardcoded max brightness (#26859)
* tici: remove hardcoded max brightness
* fix that one
* cleanup
Co-authored-by: Comma Device
---
system/hardware/tici/hardware.h | 4 +++-
system/hardware/tici/hardware.py | 11 +++++++++--
2 files changed, 12 insertions(+), 3 deletions(-)
diff --git a/system/hardware/tici/hardware.h b/system/hardware/tici/hardware.h
index d388f9c48a..521a257627 100644
--- a/system/hardware/tici/hardware.h
+++ b/system/hardware/tici/hardware.h
@@ -25,9 +25,11 @@ public:
static void reboot() { std::system("sudo reboot"); };
static void poweroff() { std::system("sudo poweroff"); };
static void set_brightness(int percent) {
+ std::string max = util::read_file("/sys/class/backlight/panel0-backlight/max_brightness");
+
std::ofstream brightness_control("/sys/class/backlight/panel0-backlight/brightness");
if (brightness_control.is_open()) {
- brightness_control << (percent * (int)(1023/100.)) << "\n";
+ brightness_control << (int)(percent * (std::stof(max)/100.)) << "\n";
brightness_control.close();
}
};
diff --git a/system/hardware/tici/hardware.py b/system/hardware/tici/hardware.py
index c0fbc66fae..9c1cc930c1 100644
--- a/system/hardware/tici/hardware.py
+++ b/system/hardware/tici/hardware.py
@@ -395,15 +395,22 @@ class Tici(HardwareBase):
def set_screen_brightness(self, percentage):
try:
+ with open("/sys/class/backlight/panel0-backlight/max_brightness") as f:
+ max_brightness = float(f.read().strip())
+
+ val = int(percentage * (max_brightness / 100.))
with open("/sys/class/backlight/panel0-backlight/brightness", "w") as f:
- f.write(str(int(percentage * 10.23)))
+ f.write(str(val))
except Exception:
pass
def get_screen_brightness(self):
try:
+ with open("/sys/class/backlight/panel0-backlight/max_brightness") as f:
+ max_brightness = float(f.read().strip())
+
with open("/sys/class/backlight/panel0-backlight/brightness") as f:
- return int(float(f.read()) / 10.23)
+ return int(float(f.read()) / (max_brightness / 100.))
except Exception:
return 0
From b5a2dfa93ed053b5e1e04f6a3b76735126c1e00f Mon Sep 17 00:00:00 2001
From: Dean Lee
Date: Tue, 3 Jan 2023 03:57:51 +0800
Subject: [PATCH 023/484] replay: only keep one init_data in merged events
(#26863)
don't merge init_data
---
tools/replay/replay.cc | 8 ++++++--
1 file changed, 6 insertions(+), 2 deletions(-)
diff --git a/tools/replay/replay.cc b/tools/replay/replay.cc
index a01371abe1..998c93b938 100644
--- a/tools/replay/replay.cc
+++ b/tools/replay/replay.cc
@@ -269,8 +269,12 @@ void Replay::mergeSegments(const SegmentMap::iterator &begin, const SegmentMap::
new_events_->reserve(new_events_size);
for (int n : segments_need_merge) {
const auto &e = segments_[n]->log->events;
- auto middle = new_events_->insert(new_events_->end(), e.begin(), e.end());
- std::inplace_merge(new_events_->begin(), middle, new_events_->end(), Event::lessThan());
+ if (e.size() > 0) {
+ auto insert_from = e.begin();
+ if (new_events_->size() > 0 && (*insert_from)->which == cereal::Event::Which::INIT_DATA) ++insert_from;
+ auto middle = new_events_->insert(new_events_->end(), insert_from, e.end());
+ std::inplace_merge(new_events_->begin(), middle, new_events_->end(), Event::lessThan());
+ }
}
updateEvents([&]() {
From 88fd2ea84ff7c465a2c2f7de13635f112d604637 Mon Sep 17 00:00:00 2001
From: Dean Lee
Date: Tue, 3 Jan 2023 05:31:08 +0800
Subject: [PATCH 024/484] replay: add option --prefix to set OPENPILOT_PREFIX
(#26862)
---
tools/replay/main.cc | 9 +++++++++
1 file changed, 9 insertions(+)
diff --git a/tools/replay/main.cc b/tools/replay/main.cc
index 8621a9b978..6b624aa1fa 100644
--- a/tools/replay/main.cc
+++ b/tools/replay/main.cc
@@ -1,6 +1,7 @@
#include
#include
+#include "common/prefix.h"
#include "tools/replay/consoleui.h"
#include "tools/replay/replay.h"
@@ -27,6 +28,7 @@ int main(int argc, char *argv[]) {
parser.addOption({{"s", "start"}, "start from ", "seconds"});
parser.addOption({"demo", "use a demo route instead of providing your own"});
parser.addOption({"data_dir", "local directory with routes", "data_dir"});
+ parser.addOption({"prefix", "set OPENPILOT_PREFIX", "prefix"});
for (auto &[name, _, desc] : flags) {
parser.addOption({name, desc});
}
@@ -47,6 +49,13 @@ int main(int argc, char *argv[]) {
replay_flags |= flag;
}
}
+
+ std::unique_ptr op_prefix;
+ auto prefix = parser.value("prefix");
+ if (!prefix.isEmpty()) {
+ op_prefix.reset(new OpenpilotPrefix(prefix.toStdString()));
+ }
+
Replay *replay = new Replay(route, allow, block, nullptr, replay_flags, parser.value("data_dir"), &app);
if (!parser.value("c").isEmpty()) {
replay->setSegmentCacheLimit(parser.value("c").toInt());
From 8b4c5631a4c8f259fe7e7db1789556c2b26e0f7e Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Harald=20Sch=C3=A4fer?=
Date: Mon, 2 Jan 2023 22:25:39 -0800
Subject: [PATCH 025/484] Ev6 upper jerk limit (#26868)
---
opendbc | 2 +-
selfdrive/car/hyundai/hyundaicanfd.py | 2 +-
2 files changed, 2 insertions(+), 2 deletions(-)
diff --git a/opendbc b/opendbc
index 4a7ad636ff..d585a9bf29 160000
--- a/opendbc
+++ b/opendbc
@@ -1 +1 @@
-Subproject commit 4a7ad636ff806146a93f7ae541e463a7dfa5696d
+Subproject commit d585a9bf2908b2c83bf02b567b9e1f5bfc587a01
diff --git a/selfdrive/car/hyundai/hyundaicanfd.py b/selfdrive/car/hyundai/hyundaicanfd.py
index c492e6a5ff..43c9642342 100644
--- a/selfdrive/car/hyundai/hyundaicanfd.py
+++ b/selfdrive/car/hyundai/hyundaicanfd.py
@@ -83,6 +83,7 @@ def create_acc_control(packer, CP, enabled, accel_last, accel, stopping, gas_ove
"aReqRaw": a_raw,
"VSetDis": set_speed,
"JerkLowerLimit": jerk if enabled else 1,
+ "JerkUpperLimit": 3.0,
"ACC_ObjDist": 1,
"ObjValid": 0,
@@ -90,7 +91,6 @@ def create_acc_control(packer, CP, enabled, accel_last, accel, stopping, gas_ove
"SET_ME_2": 0x4,
"SET_ME_3": 0x3,
"SET_ME_TMP_64": 0x64,
- "NEW_SIGNAL_10": 4,
"DISTANCE_SETTING": 4,
}
From 2c293bf728f59a36830898e0f0d4111cd6708619 Mon Sep 17 00:00:00 2001
From: Shane Smiskol
Date: Wed, 4 Jan 2023 12:06:01 -0800
Subject: [PATCH 026/484] Hyundai CAN-FD: set request accel when stopping
(#26877)
Update hyundaicanfd.py
---
selfdrive/car/hyundai/hyundaicanfd.py | 2 --
1 file changed, 2 deletions(-)
diff --git a/selfdrive/car/hyundai/hyundaicanfd.py b/selfdrive/car/hyundai/hyundaicanfd.py
index 43c9642342..af7239571c 100644
--- a/selfdrive/car/hyundai/hyundaicanfd.py
+++ b/selfdrive/car/hyundai/hyundaicanfd.py
@@ -72,8 +72,6 @@ def create_acc_control(packer, CP, enabled, accel_last, accel, stopping, gas_ove
else:
a_raw = accel
a_val = clip(accel, accel_last - jn, accel_last + jn)
- if stopping:
- a_raw = 0
values = {
"ACCMode": 0 if not enabled else (2 if gas_override else 1),
From b48b2f09b203db3e6bb26c671dd7e9b328207bc4 Mon Sep 17 00:00:00 2001
From: Luckst4r <67570890+Luckst4r@users.noreply.github.com>
Date: Wed, 4 Jan 2023 17:17:01 -0600
Subject: [PATCH 027/484] Genesis GV70 2023: add missing FW versions (#26876)
* Update values.py
Fingerprint GV70
* Update selfdrive/car/hyundai/values.py
Co-authored-by: Shane Smiskol
---
selfdrive/car/hyundai/values.py | 2 ++
1 file changed, 2 insertions(+)
diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py
index 4d3f44d65f..782c3989a7 100644
--- a/selfdrive/car/hyundai/values.py
+++ b/selfdrive/car/hyundai/values.py
@@ -1517,9 +1517,11 @@ FW_VERSIONS = {
CAR.GENESIS_GV70_1ST_GEN: {
(Ecu.fwdCamera, 0x7c4, None): [
b'\xf1\x00JK1 MFC AT USA LHD 1.00 1.04 99211-AR000 210204',
+ b'\xf1\x00JK1 MFC AT USA LHD 1.00 1.01 99211-AR200 220125',
],
(Ecu.fwdRadar, 0x7d0, None): [
b'\xf1\x00JK1_ SCC FHCUP 1.00 1.02 99110-AR000 ',
+ b'\xf1\x00JK1_ SCC FHCUP 1.00 1.00 99110-AR200 ',
],
},
CAR.GENESIS_GV60_EV_1ST_GEN: {
From 083bcb6f0271518537ccfc69bdcc20ae50efd600 Mon Sep 17 00:00:00 2001
From: mitchellgoffpc
Date: Fri, 6 Jan 2023 12:08:22 -0800
Subject: [PATCH 028/484] Added omegaconf to xx dependencies
---
poetry.lock | 29 ++++++++++++++++++++++++++++-
pyproject.toml | 1 +
2 files changed, 29 insertions(+), 1 deletion(-)
diff --git a/poetry.lock b/poetry.lock
index 9ab86329d7..8edfbb868c 100644
--- a/poetry.lock
+++ b/poetry.lock
@@ -80,6 +80,14 @@ develop = ["imgaug (>=0.4.0)", "pytest"]
imgaug = ["imgaug (>=0.4.0)"]
tests = ["pytest"]
+[[package]]
+name = "antlr4-python3-runtime"
+version = "4.9.3"
+description = "ANTLR 4.9.3 runtime for Python 3.7"
+category = "dev"
+optional = false
+python-versions = "*"
+
[[package]]
name = "anyio"
version = "3.6.2"
@@ -2431,6 +2439,18 @@ rsa = ["cryptography (>=3.0.0)"]
signals = ["blinker (>=1.4.0)"]
signedtoken = ["cryptography (>=3.0.0)", "pyjwt (>=2.0.0,<3)"]
+[[package]]
+name = "omegaconf"
+version = "2.3.0"
+description = "A flexible configuration library"
+category = "dev"
+optional = false
+python-versions = ">=3.6"
+
+[package.dependencies]
+antlr4-python3-runtime = ">=4.9.0,<4.10.0"
+PyYAML = ">=5.1.0"
+
[[package]]
name = "onnx"
version = "1.12.0"
@@ -4444,7 +4464,7 @@ testing = ["coverage (>=5.0.3)", "zope.event", "zope.testing"]
[metadata]
lock-version = "1.1"
python-versions = "~3.8"
-content-hash = "2ab9d6aee6cc2c7bb5ba9763a54779ef9535cb752ec0038736a442992a04d459"
+content-hash = "3c2597d2199a29ef79dd4d5fbc5e2350d86c82a3fe6716d13b93ebc268053eb9"
[metadata.files]
adal = [
@@ -4557,6 +4577,9 @@ albumentations = [
{file = "albumentations-1.3.0-py3-none-any.whl", hash = "sha256:294165d87d03bc8323e484927f0a5c1a3c64b0e7b9c32a979582a6c93c363bdf"},
{file = "albumentations-1.3.0.tar.gz", hash = "sha256:be1af36832c8893314f2a5550e8ac19801e04770734c1b70fa3c996b41f37bed"},
]
+antlr4-python3-runtime = [
+ {file = "antlr4-python3-runtime-4.9.3.tar.gz", hash = "sha256:f224469b4168294902bb1efa80a8bf7855f24c99aef99cbefc1bcd3cce77881b"},
+]
anyio = [
{file = "anyio-3.6.2-py3-none-any.whl", hash = "sha256:fbbe32bd270d2a2ef3ed1c5d45041250284e31fc0a4df4a5a6071842051a51e3"},
{file = "anyio-3.6.2.tar.gz", hash = "sha256:25ea0d673ae30af41a0c442f81cf3b38c7e79fdc7b60335a4c14e05eb0947421"},
@@ -6426,6 +6449,10 @@ oauthlib = [
{file = "oauthlib-3.2.2-py3-none-any.whl", hash = "sha256:8139f29aac13e25d502680e9e19963e83f16838d48a0d71c287fe40e7067fbca"},
{file = "oauthlib-3.2.2.tar.gz", hash = "sha256:9859c40929662bec5d64f34d01c99e093149682a3f38915dc0655d5a633dd918"},
]
+omegaconf = [
+ {file = "omegaconf-2.3.0-py3-none-any.whl", hash = "sha256:7b4df175cdb08ba400f45cae3bdcae7ba8365db4d165fc65fd04b050ab63b46b"},
+ {file = "omegaconf-2.3.0.tar.gz", hash = "sha256:d5d4b6d29955cc50ad50c46dc269bcd92c6e00f5f90d23ab5fee7bfca4ba4cc7"},
+]
onnx = [
{file = "onnx-1.12.0-cp310-cp310-macosx_10_12_x86_64.whl", hash = "sha256:bdbd2578424c70836f4d0f9dda16c21868ddb07cc8192f9e8a176908b43d694b"},
{file = "onnx-1.12.0-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:213e73610173f6b2e99f99a4b0636f80b379c417312079d603806e48ada4ca8b"},
diff --git a/pyproject.toml b/pyproject.toml
index af9fcc6e6e..ed3a821e29 100644
--- a/pyproject.toml
+++ b/pyproject.toml
@@ -171,6 +171,7 @@ torchvision = { url = "https://download.pytorch.org/whl/cu113/torchvision-0.12.0
triton = "^1.1.1"
Werkzeug = "^2.1.2"
zerorpc = { git = "https://github.com/commaai/zerorpc-python.git", branch = "master" }
+omegaconf = "^2.3.0"
[build-system]
From 18b011636ef623023e53bd7326d9871c4ce07f97 Mon Sep 17 00:00:00 2001
From: Jason Young <46612682+jyoung8607@users.noreply.github.com>
Date: Fri, 6 Jan 2023 19:31:24 -0500
Subject: [PATCH 029/484] =?UTF-8?q?VW=20MQB:=20Add=20FW=20for=202019=20?=
=?UTF-8?q?=C5=A0koda=20Octavia=20(#26886)?=
MIME-Version: 1.0
Content-Type: text/plain; charset=UTF-8
Content-Transfer-Encoding: 8bit
---
selfdrive/car/volkswagen/values.py | 3 +++
1 file changed, 3 insertions(+)
diff --git a/selfdrive/car/volkswagen/values.py b/selfdrive/car/volkswagen/values.py
index d1f6bfb02c..24ea0a03ba 100755
--- a/selfdrive/car/volkswagen/values.py
+++ b/selfdrive/car/volkswagen/values.py
@@ -1023,6 +1023,7 @@ FW_VERSIONS = {
},
CAR.SKODA_OCTAVIA_MK3: {
(Ecu.engine, 0x7e0, None): [
+ b'\xf1\x8704C906025L \xf1\x896198',
b'\xf1\x8704E906016ER\xf1\x895823',
b'\xf1\x8704E906027HD\xf1\x893742',
b'\xf1\x8704E906027MH\xf1\x894786',
@@ -1034,6 +1035,7 @@ FW_VERSIONS = {
b'\xf1\x870CW300041L \xf1\x891601',
b'\xf1\x870CW300041N \xf1\x891605',
b'\xf1\x870CW300043B \xf1\x891601',
+ b'\xf1\x870CW300043P \xf1\x891605',
b'\xf1\x870D9300041C \xf1\x894936',
b'\xf1\x870D9300041J \xf1\x894902',
b'\xf1\x870D9300041P \xf1\x894507',
@@ -1043,6 +1045,7 @@ FW_VERSIONS = {
b'\xf1\x873Q0959655AQ\xf1\x890200\xf1\x82\r11120011100010312212113100',
b'\xf1\x873Q0959655AS\xf1\x890200\xf1\x82\r11120011100010022212110200',
b'\xf1\x873Q0959655BH\xf1\x890703\xf1\x82\0163221003221002105755331052100',
+ b'\xf1\x873Q0959655CM\xf1\x890720\xf1\x82\x0e3221003221002105755331052100',
b'\xf1\x873Q0959655CN\xf1\x890720\xf1\x82\x0e3221003221002105755331052100',
b'\xf1\x875QD959655 \xf1\x890388\xf1\x82\x111101000011110006110411111111119111',
],
From b994b93b164bb9dc2a8689dff0f271d2d68ced55 Mon Sep 17 00:00:00 2001
From: Eric Brown
Date: Fri, 6 Jan 2023 17:46:21 -0700
Subject: [PATCH 030/484] GM: check radarOffCan in radar_interface (#26885)
Remove hardcoded vehicle list, replace with radarOffCan check
---
selfdrive/car/gm/radar_interface.py | 8 +++-----
1 file changed, 3 insertions(+), 5 deletions(-)
diff --git a/selfdrive/car/gm/radar_interface.py b/selfdrive/car/gm/radar_interface.py
index 6904e6f899..5cb211812d 100755
--- a/selfdrive/car/gm/radar_interface.py
+++ b/selfdrive/car/gm/radar_interface.py
@@ -3,7 +3,7 @@ import math
from cereal import car
from common.conversions import Conversions as CV
from opendbc.can.parser import CANParser
-from selfdrive.car.gm.values import DBC, CAR, CanBus
+from selfdrive.car.gm.values import DBC, CanBus
from selfdrive.car.interfaces import RadarInterfaceBase
RADAR_HEADER_MSG = 1120
@@ -16,9 +16,6 @@ LAST_RADAR_MSG = RADAR_HEADER_MSG + NUM_SLOTS
def create_radar_can_parser(car_fingerprint):
- if car_fingerprint not in (CAR.VOLT, CAR.MALIBU, CAR.HOLDEN_ASTRA, CAR.ACADIA, CAR.CADILLAC_ATS, CAR.ESCALADE_ESV):
- return None
-
# C1A-ARS3-A by Continental
radar_targets = list(range(SLOT_1_MSG, SLOT_1_MSG + NUM_SLOTS))
signals = list(zip(['FLRRNumValidTargets',
@@ -34,11 +31,12 @@ def create_radar_can_parser(car_fingerprint):
return CANParser(DBC[car_fingerprint]['radar'], signals, checks, CanBus.OBSTACLE)
+
class RadarInterface(RadarInterfaceBase):
def __init__(self, CP):
super().__init__(CP)
- self.rcp = create_radar_can_parser(CP.carFingerprint)
+ self.rcp = None if CP.radarOffCan else create_radar_can_parser(CP.carFingerprint)
self.trigger_msg = LAST_RADAR_MSG
self.updated_messages = set()
From 4145bc837948f530eb17c3f93728a1347e4eceb3 Mon Sep 17 00:00:00 2001
From: Mauricio Alvarez Leon <65101411+BBBmau@users.noreply.github.com>
Date: Fri, 6 Jan 2023 16:49:27 -0800
Subject: [PATCH 031/484] Hyundai: add FW versions for Sonata 2023 (#26880)
* Update Hyundai Sonata year to 2023
* update docs
* update docs
* update docs
* Update values.py
* and engine
Co-authored-by: Laptop Researcher
Co-authored-by: Shane Smiskol
---
docs/CARS.md | 2 +-
selfdrive/car/hyundai/values.py | 6 +++++-
2 files changed, 6 insertions(+), 2 deletions(-)
diff --git a/docs/CARS.md b/docs/CARS.md
index f3667c4cea..d53ea39893 100644
--- a/docs/CARS.md
+++ b/docs/CARS.md
@@ -82,7 +82,7 @@ A supported vehicle is one that just works when you install a comma three. All s
|Hyundai|Santa Fe Hybrid 2022|All|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai L|
|Hyundai|Santa Fe Plug-in Hybrid 2022|All|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai L|
|Hyundai|Sonata 2018-19|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai E|
-|Hyundai|Sonata 2020-22|All|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai A|
+|Hyundai|Sonata 2020-23|All|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai A|
|Hyundai|Sonata Hybrid 2020-22|All|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai A|
|Hyundai|Tucson 2021|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|19 mph|0 mph|[](##)|[](##)|Hyundai L|
|Hyundai|Tucson 2022[5](#footnotes)|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai N|
diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py
index 782c3989a7..dd7f347863 100644
--- a/selfdrive/car/hyundai/values.py
+++ b/selfdrive/car/hyundai/values.py
@@ -160,7 +160,7 @@ CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = {
CAR.SANTA_FE_2022: HyundaiCarInfo("Hyundai Santa Fe 2021-22", "All", "https://youtu.be/VnHzSTygTS4", harness=Harness.hyundai_l),
CAR.SANTA_FE_HEV_2022: HyundaiCarInfo("Hyundai Santa Fe Hybrid 2022", "All", harness=Harness.hyundai_l),
CAR.SANTA_FE_PHEV_2022: HyundaiCarInfo("Hyundai Santa Fe Plug-in Hybrid 2022", "All", harness=Harness.hyundai_l),
- CAR.SONATA: HyundaiCarInfo("Hyundai Sonata 2020-22", "All", "https://www.youtube.com/watch?v=ix63r9kE3Fw", harness=Harness.hyundai_a),
+ CAR.SONATA: HyundaiCarInfo("Hyundai Sonata 2020-23", "All", "https://www.youtube.com/watch?v=ix63r9kE3Fw", harness=Harness.hyundai_a),
CAR.SONATA_LF: HyundaiCarInfo("Hyundai Sonata 2018-19", harness=Harness.hyundai_e),
CAR.TUCSON: [
HyundaiCarInfo("Hyundai Tucson 2021", min_enable_speed=19 * CV.MPH_TO_MS, harness=Harness.hyundai_l),
@@ -512,6 +512,7 @@ FW_VERSIONS = {
b'HM6M1_0a0_G20',
b'HM6M2_0a0_BD0',
b'\xf1\x8739110-2S278\xf1\x82DNDVD5GMCCXXXL5B',
+ b'\xf1\x8739110-2S041\xf1\x81HM6M1_0a0_M00',
],
(Ecu.eps, 0x7d4, None): [
b'\xf1\x00DN8 MDPS C 1,00 1,01 56310L0010\x00 4DNAC101', # modified firmware
@@ -529,6 +530,7 @@ FW_VERSIONS = {
b'\xf1\x8756310L0210\x00\xf1\x00DN8 MDPS C 1.00 1.01 56310L0210\x00 4DNAC101',
b'\xf1\x8757700-L0000\xf1\x00DN8 MDPS R 1.00 1.00 57700-L0000 4DNAP100',
b'\xf1\x00DN8 MDPS R 1.00 1.00 57700-L0000 4DNAP101',
+ b'\xf1\x00DN8 MDPS C 1.00 1.01 56310-L0210 4DNAC102',
],
(Ecu.fwdCamera, 0x7c4, None): [
b'\xf1\x00DN8 MFC AT KOR LHD 1.00 1.02 99211-L1000 190422',
@@ -538,6 +540,7 @@ FW_VERSIONS = {
b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.03 99211-L0000 210603',
b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.05 99211-L1000 201109',
b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.06 99211-L1000 210325',
+ b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.07 99211-L1000 211223',
],
(Ecu.transmission, 0x7e1, None): [
b'\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v',
@@ -548,6 +551,7 @@ FW_VERSIONS = {
b'\xf1\x00HT6WA250BLHT6WA910A1SDN8G25NB1\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
b'\xf1\x00HT6WA250BLHT6WA910A1SDN8G25NB1\x00\x00\x00\x00\x00\x00\x96\xa1\xf1\x92',
b'\xf1\x00HT6WA280BLHT6WAD10A1SDN8G25NB2\x00\x00\x00\x00\x00\x00\x08\xc9O:',
+ b'\xf1\x00HT6WA280BLHT6WAD10A1SDN8G25NB4\x00\x00\x00\x00\x00\x00g!l[',
b'\xf1\x00T02601BL T02730A1 VDN8T25XXX730NS5\xf7_\x92\xf5',
b'\xf1\x00T02601BL T02832A1 VDN8T25XXX832NS8G\x0e\xfeE',
b'\xf1\x87954A02N060\x00\x00\x00\x00\x00\xf1\x81T02730A1 \xf1\x00T02601BL T02730A1 VDN8T25XXX730NS5\xf7_\x92\xf5',
From b74f2d102daa6acea69d0c673dbb0172f31897f3 Mon Sep 17 00:00:00 2001
From: Jason Wen <47793918+sunnyhaibin@users.noreply.github.com>
Date: Fri, 6 Jan 2023 19:54:56 -0500
Subject: [PATCH 032/484] Hyundai: Add FW Versions for Tucson 2023 (#26887)
---
selfdrive/car/hyundai/values.py | 1 +
1 file changed, 1 insertion(+)
diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py
index dd7f347863..1adf78aa84 100644
--- a/selfdrive/car/hyundai/values.py
+++ b/selfdrive/car/hyundai/values.py
@@ -1477,6 +1477,7 @@ FW_VERSIONS = {
CAR.TUCSON_4TH_GEN: {
(Ecu.fwdCamera, 0x7c4, None): [
b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.01 99211-N9240 14T',
+ b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-CW010 14X',
],
(Ecu.fwdRadar, 0x7d0, None): [
b'\xf1\x00NX4__ 1.01 1.00 99110-N9100 ',
From 0d85a2c373c3e139237c6bc969be79312a99bd63 Mon Sep 17 00:00:00 2001
From: Rafael Pinilla <80814874+Rafale83@users.noreply.github.com>
Date: Sat, 7 Jan 2023 18:40:52 +0100
Subject: [PATCH 033/484] European Lexus UX250h 2019: add engine FW (#26895)
* Update values.py
Added mention to all 2019 Lexus UX250h Fw in CORROLLAH section
* Update values.py
Syntax error in REMs
---
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 64a0bed0b2..e945130e90 100644
--- a/selfdrive/car/toyota/values.py
+++ b/selfdrive/car/toyota/values.py
@@ -831,6 +831,7 @@ FW_VERSIONS = {
b'\x01896630ZJ1000\x00\x00\x00\x00',
b'\x01896630ZU8000\x00\x00\x00\x00',
b'\x01896637621000\x00\x00\x00\x00',
+ b'\x01896637623000\x00\x00\x00\x00',
b'\x01896637624000\x00\x00\x00\x00',
b'\x01896637626000\x00\x00\x00\x00',
b'\x01896637639000\x00\x00\x00\x00',
From bf34110572cb801564346ffb2f234cd152a7b100 Mon Sep 17 00:00:00 2001
From: Adeeb Shihadeh
Date: Sat, 7 Jan 2023 11:05:56 -0800
Subject: [PATCH 034/484] docs: update CAN FD footnote (#26896)
* docs: update CAN FD footnote
* touch up
---
docs/CARS.md | 2 +-
selfdrive/car/hyundai/values.py | 6 +++---
2 files changed, 4 insertions(+), 4 deletions(-)
diff --git a/docs/CARS.md b/docs/CARS.md
index d53ea39893..930b52c8a2 100644
--- a/docs/CARS.md
+++ b/docs/CARS.md
@@ -236,7 +236,7 @@ A supported vehicle is one that just works when you install a comma three. All s
2By default, this car will use the stock Adaptive Cruise Control (ACC) for longitudinal control. If the Driver Support Unit (DSU) is disconnected, openpilot ACC will replace stock ACC. NOTE: disconnecting the DSU disables Automatic Emergency Braking (AEB).
3Requires a community built ASCM harness. NOTE: disconnecting the ASCM disables Automatic Emergency Braking (AEB).
42019 Honda Civic 1.6L Diesel Sedan does not have ALC below 12mph.
-5Requires a red panda, additional harness box, additional OBD-C cable, USB-A to USB-A cable, and a USB-A to USB-C OTG dongle.
+5Requires a red panda for this CAN FD. All the hardware needed is sold in the CAN FD kit.
6openpilot operates above 28mph for Camry 4CYL L, 4CYL LE and 4CYL SE which don't have Full-Speed Range Dynamic Radar Cruise Control.
7Not including the China market Kamiq, which is based on the (currently) unsupported PQ34 platform.
8Refers only to the MQB-based European B8 Passat, not the NMS Passat in the USA/China/Mideast markets.
diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py
index 1adf78aa84..dc19c5511d 100644
--- a/selfdrive/car/hyundai/values.py
+++ b/selfdrive/car/hyundai/values.py
@@ -123,9 +123,9 @@ class CAR:
class Footnote(Enum):
CANFD = CarFootnote(
- "Requires a red panda, additional harness box, " +
- "additional OBD-C cable, USB-A to USB-A cable, and a USB-A to USB-C OTG dongle.",
- Column.MODEL, shop_footnote=True)
+ "Requires a red panda for this CAN FD. " +
+ "All the hardware needed is sold in the CAN FD kit.",
+ Column.MODEL, docs_only=True)
@dataclass
From 2c7df6efc87f4f16aa0801ed40bc0e2542578031 Mon Sep 17 00:00:00 2001
From: Dean Lee
Date: Sun, 8 Jan 2023 03:07:30 +0800
Subject: [PATCH 035/484] replay: show absolute time (#26869)
---
tools/replay/consoleui.cc | 12 ++----------
tools/replay/replay.h | 1 +
tools/replay/route.cc | 1 +
tools/replay/route.h | 3 +++
4 files changed, 7 insertions(+), 10 deletions(-)
diff --git a/tools/replay/consoleui.cc b/tools/replay/consoleui.cc
index 77357a2873..5ad702590c 100644
--- a/tools/replay/consoleui.cc
+++ b/tools/replay/consoleui.cc
@@ -50,14 +50,6 @@ void add_str(WINDOW *w, const char *str, Color color = Color::Default, bool bold
if (color != Color::Default) wattroff(w, COLOR_PAIR(color));
}
-std::string format_seconds(int s) {
- int total_minutes = s / 60;
- int seconds = s % 60;
- int hours = total_minutes / 60;
- int minutes = total_minutes % 60;
- return util::string_format("%02d:%02d:%02d", hours, minutes, seconds);
-}
-
} // namespace
ConsoleUI::ConsoleUI(Replay *replay, QObject *parent) : replay(replay), sm({"carState", "liveParameters"}), QObject(parent) {
@@ -177,8 +169,8 @@ void ConsoleUI::updateStatus() {
}
auto [status_str, status_color] = status_text[status];
write_item(0, 0, "STATUS: ", status_str, " ", false, status_color);
- std::string suffix = " / " + format_seconds(replay->totalSeconds());
- write_item(0, 25, "TIME: ", format_seconds(replay->currentSeconds()), suffix, true);
+ std::string current_segment = " - " + std::to_string((int)(replay->currentSeconds() / 60));
+ write_item(0, 25, "TIME: ", replay->currentDateTime().toString("ddd MMMM dd hh:mm:ss").toStdString(), current_segment, true);
auto p = sm["liveParameters"].getLiveParameters();
write_item(1, 0, "STIFFNESS: ", util::string_format("%.2f %%", p.getStiffnessFactor() * 100), " ");
diff --git a/tools/replay/replay.h b/tools/replay/replay.h
index 2c68443df0..6788a97d03 100644
--- a/tools/replay/replay.h
+++ b/tools/replay/replay.h
@@ -64,6 +64,7 @@ public:
inline void removeFlag(REPLAY_FLAGS flag) { flags_ &= ~flag; }
inline const Route* route() const { return route_.get(); }
inline double currentSeconds() const { return double(cur_mono_time_ - route_start_ts_) / 1e9; }
+ inline QDateTime currentDateTime() const { return route_->datetime().addSecs(currentSeconds()); }
inline uint64_t routeStartTime() const { return route_start_ts_; }
inline int toSeconds(uint64_t mono_time) const { return (mono_time - route_start_ts_) / 1e9; }
inline int totalSeconds() const { return segments_.size() * 60; }
diff --git a/tools/replay/route.cc b/tools/replay/route.cc
index f0d6ec5a12..9d57b9118e 100644
--- a/tools/replay/route.cc
+++ b/tools/replay/route.cc
@@ -31,6 +31,7 @@ bool Route::load() {
rInfo("invalid route format");
return false;
}
+ date_time_ = QDateTime::fromString(route_.timestamp, "yyyy-MM-dd--HH-mm-ss");
return data_dir_.isEmpty() ? loadFromServer() : loadFromLocal();
}
diff --git a/tools/replay/route.h b/tools/replay/route.h
index 6b78ebad87..86adf6a14d 100644
--- a/tools/replay/route.h
+++ b/tools/replay/route.h
@@ -1,5 +1,6 @@
#pragma once
+#include
#include
#include "tools/replay/framereader.h"
@@ -27,6 +28,7 @@ public:
Route(const QString &route, const QString &data_dir = {});
bool load();
inline const QString &name() const { return route_.str; }
+ inline const QDateTime datetime() const { return date_time_; }
inline const QString &dir() const { return data_dir_; }
inline const RouteIdentifier &identifier() const { return route_; }
inline const std::map &segments() const { return segments_; }
@@ -41,6 +43,7 @@ protected:
RouteIdentifier route_ = {};
QString data_dir_;
std::map segments_;
+ QDateTime date_time_;
};
class Segment : public QObject {
From ae256dceba4fff8c036777b118873d2fbcfab42c Mon Sep 17 00:00:00 2001
From: Cameron Clough
Date: Sat, 7 Jan 2023 13:18:28 -0800
Subject: [PATCH 036/484] revert: docs: update CAN FD footnote (#26896)
partial revert, we still need the footnote to be exported for the shop
---
selfdrive/car/hyundai/values.py | 3 ++-
1 file changed, 2 insertions(+), 1 deletion(-)
diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py
index dc19c5511d..16f1f42679 100644
--- a/selfdrive/car/hyundai/values.py
+++ b/selfdrive/car/hyundai/values.py
@@ -122,10 +122,11 @@ class CAR:
class Footnote(Enum):
+ # footnotes which mention "red panda" will be replaced with the CAN FD panda kit on the shop page
CANFD = CarFootnote(
"Requires a red panda for this CAN FD. " +
"All the hardware needed is sold in the CAN FD kit.",
- Column.MODEL, docs_only=True)
+ Column.MODEL, shop_footnote=True)
@dataclass
From b6440304d59d13b918842f68ce9f3417e3e0ecbc Mon Sep 17 00:00:00 2001
From: Kurt Nistelberger
Date: Sat, 7 Jan 2023 18:53:14 -0700
Subject: [PATCH 037/484] Navigation: add destination marker (#26873)
* add navigation destination marker
* fix removal
* update default marker icon
* update default marker
Co-authored-by: Kurt Nistelberger
---
.../assets/navigation/default_marker.svg | 5 +++++
selfdrive/ui/qt/maps/map.cc | 19 +++++++++++++++++--
selfdrive/ui/qt/maps/map.h | 2 ++
3 files changed, 24 insertions(+), 2 deletions(-)
create mode 100644 selfdrive/assets/navigation/default_marker.svg
diff --git a/selfdrive/assets/navigation/default_marker.svg b/selfdrive/assets/navigation/default_marker.svg
new file mode 100644
index 0000000000..116a45e251
--- /dev/null
+++ b/selfdrive/assets/navigation/default_marker.svg
@@ -0,0 +1,5 @@
+
+
diff --git a/selfdrive/ui/qt/maps/map.cc b/selfdrive/ui/qt/maps/map.cc
index b5519daccf..3e1d08740d 100644
--- a/selfdrive/ui/qt/maps/map.cc
+++ b/selfdrive/ui/qt/maps/map.cc
@@ -47,7 +47,7 @@ MapWindow::MapWindow(const QMapboxGLSettings &settings) : m_settings(settings),
map_eta->setVisible(false);
auto last_gps_position = coordinate_from_param("LastGPSPosition");
- if (last_gps_position) {
+ if (last_gps_position.has_value()) {
last_position = *last_gps_position;
}
@@ -82,6 +82,7 @@ void MapWindow::initLayers() {
m_map->setPaintProperty("navLayer", "line-color", QColor("#31a1ee"));
m_map->setPaintProperty("navLayer", "line-width", 7.5);
m_map->setLayoutProperty("navLayer", "line-cap", "round");
+ m_map->addAnnotationIcon("default_marker", QImage("../assets/navigation/default_marker.svg"));
}
if (!m_map->layerExists("carPosLayer")) {
qDebug() << "Initializing carPosLayer";
@@ -220,7 +221,6 @@ void MapWindow::updateState(const UIState &s) {
emit instructionsChanged(i);
}
} else {
- m_map->setPitch(MIN_PITCH);
clearRoute();
}
}
@@ -237,6 +237,7 @@ void MapWindow::updateState(const UIState &s) {
m_map->setLayoutProperty("navLayer", "visibility", "visible");
route_rcv_frame = sm.rcv_frame("navRoute");
+ update_destination_marker();
}
}
@@ -274,6 +275,7 @@ void MapWindow::clearRoute() {
if (!m_map.isNull()) {
m_map->setLayoutProperty("navLayer", "visibility", "none");
m_map->setPitch(MIN_PITCH);
+ update_destination_marker();
}
map_instructions->hideIfNoError();
@@ -361,6 +363,19 @@ void MapWindow::offroadTransition(bool offroad) {
last_bearing = {};
}
+void MapWindow::update_destination_marker() {
+ if (marker_id != -1) {
+ m_map->removeAnnotation(marker_id);
+ marker_id = -1;
+ }
+
+ auto nav_dest = coordinate_from_param("NavDestination");
+ if (nav_dest.has_value()) {
+ auto ano = QMapbox::SymbolAnnotation {*nav_dest, "default_marker"};
+ marker_id = m_map->addAnnotation(QVariant::fromValue(ano));
+ }
+}
+
MapInstructions::MapInstructions(QWidget * parent) : QWidget(parent) {
is_rhd = Params().getBool("IsRhdDetected");
QHBoxLayout *main_layout = new QHBoxLayout(this);
diff --git a/selfdrive/ui/qt/maps/map.h b/selfdrive/ui/qt/maps/map.h
index c3d5e92530..8151bdecfd 100644
--- a/selfdrive/ui/qt/maps/map.h
+++ b/selfdrive/ui/qt/maps/map.h
@@ -79,6 +79,7 @@ private:
QMapboxGLSettings m_settings;
QScopedPointer m_map;
+ QMapbox::AnnotationID marker_id = -1;
void initLayers();
@@ -111,6 +112,7 @@ private:
MapETA* map_eta;
void clearRoute();
+ void update_destination_marker();
uint64_t route_rcv_frame = 0;
private slots:
From 2b611862becd0cafbe6949961da04dfa4d252b4e Mon Sep 17 00:00:00 2001
From: Kurt Nistelberger
Date: Sat, 7 Jan 2023 17:56:16 -0800
Subject: [PATCH 038/484] match style
---
selfdrive/ui/qt/maps/map.cc | 6 +++---
selfdrive/ui/qt/maps/map.h | 2 +-
2 files changed, 4 insertions(+), 4 deletions(-)
diff --git a/selfdrive/ui/qt/maps/map.cc b/selfdrive/ui/qt/maps/map.cc
index 3e1d08740d..c625564f1d 100644
--- a/selfdrive/ui/qt/maps/map.cc
+++ b/selfdrive/ui/qt/maps/map.cc
@@ -237,7 +237,7 @@ void MapWindow::updateState(const UIState &s) {
m_map->setLayoutProperty("navLayer", "visibility", "visible");
route_rcv_frame = sm.rcv_frame("navRoute");
- update_destination_marker();
+ updateDestinationMarker();
}
}
@@ -275,7 +275,7 @@ void MapWindow::clearRoute() {
if (!m_map.isNull()) {
m_map->setLayoutProperty("navLayer", "visibility", "none");
m_map->setPitch(MIN_PITCH);
- update_destination_marker();
+ updateDestinationMarker();
}
map_instructions->hideIfNoError();
@@ -363,7 +363,7 @@ void MapWindow::offroadTransition(bool offroad) {
last_bearing = {};
}
-void MapWindow::update_destination_marker() {
+void MapWindow::updateDestinationMarker() {
if (marker_id != -1) {
m_map->removeAnnotation(marker_id);
marker_id = -1;
diff --git a/selfdrive/ui/qt/maps/map.h b/selfdrive/ui/qt/maps/map.h
index 8151bdecfd..0d8b93a5f4 100644
--- a/selfdrive/ui/qt/maps/map.h
+++ b/selfdrive/ui/qt/maps/map.h
@@ -112,7 +112,7 @@ private:
MapETA* map_eta;
void clearRoute();
- void update_destination_marker();
+ void updateDestinationMarker();
uint64_t route_rcv_frame = 0;
private slots:
From 2204a7153f3f63716eedf81a8aeee9f2ed3e3c2e Mon Sep 17 00:00:00 2001
From: Dean Lee
Date: Mon, 9 Jan 2023 07:51:08 +0800
Subject: [PATCH 039/484] replay: remove need for fake dongle id (#26899)
---
tools/replay/route.cc | 6 +++---
1 file changed, 3 insertions(+), 3 deletions(-)
diff --git a/tools/replay/route.cc b/tools/replay/route.cc
index 9d57b9118e..619aeb3f5f 100644
--- a/tools/replay/route.cc
+++ b/tools/replay/route.cc
@@ -19,15 +19,15 @@ Route::Route(const QString &route, const QString &data_dir) : data_dir_(data_dir
}
RouteIdentifier Route::parseRoute(const QString &str) {
- QRegExp rx(R"(^([a-z0-9]{16})([|_/])(\d{4}-\d{2}-\d{2}--\d{2}-\d{2}-\d{2})(?:(--|/)(\d*))?$)");
+ QRegExp rx(R"(^(?:([a-z0-9]{16})([|_/]))?(\d{4}-\d{2}-\d{2}--\d{2}-\d{2}-\d{2})(?:(--|/)(\d*))?$)");
if (rx.indexIn(str) == -1) return {};
const QStringList list = rx.capturedTexts();
- return {list[1], list[3], list[5].toInt(), list[1] + "|" + list[3]};
+ return {.dongle_id = list[1], .timestamp = list[3], .segment_id = list[5].toInt(), .str = list[1] + "|" + list[3]};
}
bool Route::load() {
- if (route_.str.isEmpty()) {
+ if (route_.str.isEmpty() || (data_dir_.isEmpty() && route_.dongle_id.isEmpty())) {
rInfo("invalid route format");
return false;
}
From 19a15eeb539c8e8f53166b8885e09d6276d32fd8 Mon Sep 17 00:00:00 2001
From: Willem Melching
Date: Mon, 9 Jan 2023 19:30:30 +0100
Subject: [PATCH 040/484] MacOS: homebrew arm-none-eabi-gcc works again
(#26903)
Revert "Fix gcc-arm-embedded for m1 mac (#24515)"
This reverts commit 01a237ef02cf989a3e2dc8a529d5a0338a09e123.
---
tools/mac_setup.sh | 7 +------
1 file changed, 1 insertion(+), 6 deletions(-)
diff --git a/tools/mac_setup.sh b/tools/mac_setup.sh
index e85292da03..dd2041e0cb 100755
--- a/tools/mac_setup.sh
+++ b/tools/mac_setup.sh
@@ -52,14 +52,9 @@ brew "zeromq"
brew "protobuf"
brew "protobuf-c"
brew "swig"
+cask "gcc-arm-embedded"
EOS
-# Install gcc-arm-embedded 10.3-2021.10. 11.x is broken on M1 Macs with Xcode 13.3~
-brew uninstall gcc-arm-embedded || true
-curl -L https://github.com/Homebrew/homebrew-cask/raw/d407663b8017a0a062c7fc0b929faf2e16abd1ff/Casks/gcc-arm-embedded.rb > /tmp/gcc-arm-embedded.rb
-brew install --cask /tmp/gcc-arm-embedded.rb
-rm /tmp/gcc-arm-embedded.rb
-
echo "[ ] finished brew install t=$SECONDS"
BREW_PREFIX=$(brew --prefix)
From a421c9464eec3a6b994df5ec010ff51b27aa4bbc Mon Sep 17 00:00:00 2001
From: Dean Lee
Date: Tue, 10 Jan 2023 05:48:04 +0800
Subject: [PATCH 041/484] replay: sync vision buffer (#26904)
---
tools/replay/camera.cc | 2 +-
1 file changed, 1 insertion(+), 1 deletion(-)
diff --git a/tools/replay/camera.cc b/tools/replay/camera.cc
index 72b385dca8..66898c9244 100644
--- a/tools/replay/camera.cc
+++ b/tools/replay/camera.cc
@@ -56,7 +56,7 @@ void CameraServer::cameraThread(Camera &cam) {
.timestamp_eof = eidx.getTimestampEof(),
};
yuv->set_frame_id(eidx.getFrameId());
- vipc_server_->send(yuv, &extra, false);
+ vipc_server_->send(yuv, &extra);
} else {
rError("camera[%d] failed to get frame: %lu", cam.type, eidx.getSegmentId());
}
From a40efbdfcc3619528a2634d6b291c928c2374b4b Mon Sep 17 00:00:00 2001
From: Tim Wilson
Date: Mon, 9 Jan 2023 16:01:55 -0700
Subject: [PATCH 042/484] GM camera ACC: always set long tune (#26892)
* GM: set long tune for camera car w/o exp. mode
* same tuning
* update refs
Co-authored-by: Shane Smiskol
---
selfdrive/car/gm/interface.py | 18 +++++++++---------
selfdrive/test/process_replay/ref_commit | 2 +-
2 files changed, 10 insertions(+), 10 deletions(-)
diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py
index 195df36a7f..856dcbaae5 100755
--- a/selfdrive/car/gm/interface.py
+++ b/selfdrive/car/gm/interface.py
@@ -68,20 +68,20 @@ class CarInterface(CarInterfaceBase):
ret.safetyConfigs[0].safetyParam |= Panda.FLAG_GM_HW_CAM
ret.minEnableSpeed = 5 * CV.KPH_TO_MS
+ # Tuning for experimental long
+ ret.longitudinalTuning.kpV = [2.0, 1.5]
+ ret.longitudinalTuning.kiV = [0.72]
+ ret.stopAccel = -2.0
+ ret.stoppingDecelRate = 2.0 # reach brake quickly after enabling
+ ret.vEgoStopping = 0.25
+ ret.vEgoStarting = 0.25
+ ret.longitudinalActuatorDelayUpperBound = 0.5
+
if experimental_long:
ret.pcmCruise = False
ret.openpilotLongitudinalControl = True
ret.safetyConfigs[0].safetyParam |= Panda.FLAG_GM_HW_CAM_LONG
- # Tuning
- ret.longitudinalTuning.kpV = [2.0, 1.5]
- ret.longitudinalTuning.kiV = [0.72]
- ret.stopAccel = -2.0
- ret.stoppingDecelRate = 2.0 # reach brake quickly after enabling
- ret.vEgoStopping = 0.25
- ret.vEgoStarting = 0.25
- ret.longitudinalActuatorDelayUpperBound = 0.5
-
else: # ASCM, OBD-II harness
ret.openpilotLongitudinalControl = True
ret.networkLocation = NetworkLocation.gateway
diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit
index 603d2b2d96..24ec1c62de 100644
--- a/selfdrive/test/process_replay/ref_commit
+++ b/selfdrive/test/process_replay/ref_commit
@@ -1 +1 @@
-557ffbf5a1c9cafba1ff8d6f3e2642df98b2d6e6
\ No newline at end of file
+6d30c77af7b3210b03f65b433c0a043a96ee39bc
\ No newline at end of file
From dac7a24677ab680a0ff8fe209cc73cb14d6672a5 Mon Sep 17 00:00:00 2001
From: Shane Smiskol
Date: Mon, 9 Jan 2023 16:21:47 -0800
Subject: [PATCH 043/484] car interfaces: test longitudinal params are set
correctly (#26894)
* add long unit tests and fix
* revert
* remove debug
* cleanup
Co-authored-by: Laptop Researcher
---
selfdrive/car/tests/test_car_interfaces.py | 6 ++++++
1 file changed, 6 insertions(+)
diff --git a/selfdrive/car/tests/test_car_interfaces.py b/selfdrive/car/tests/test_car_interfaces.py
index 48d85584b3..11e7be7f44 100755
--- a/selfdrive/car/tests/test_car_interfaces.py
+++ b/selfdrive/car/tests/test_car_interfaces.py
@@ -35,6 +35,12 @@ class TestCarInterfaces(unittest.TestCase):
self.assertGreater(car_params.centerToFront, 0)
self.assertGreater(car_params.maxLateralAccel, 0)
+ # Longitudinal sanity checks
+ self.assertEqual(len(car_params.longitudinalTuning.kpV), len(car_params.longitudinalTuning.kpBP))
+ self.assertEqual(len(car_params.longitudinalTuning.kiV), len(car_params.longitudinalTuning.kiBP))
+ self.assertEqual(len(car_params.longitudinalTuning.deadzoneV), len(car_params.longitudinalTuning.deadzoneBP))
+
+ # Lateral sanity checks
if car_params.steerControlType != car.CarParams.SteerControlType.angle:
tune = car_params.lateralTuning
if tune.which() == 'pid':
From 9b9c2a657ed0ba326727339269654f9497997a70 Mon Sep 17 00:00:00 2001
From: David Peterson
Date: Mon, 9 Jan 2023 20:25:43 -0500
Subject: [PATCH 044/484] Car docs: add video for Nissan Leaf (#26901)
MIME-Version: 1.0
Content-Type: text/plain; charset=UTF-8
Content-Transfer-Encoding: 8bit
* CAR.LEAF: NissanCarInfo("Nissan Leaf 2018-22”), video_link= "https://youtu.be/vaMbtAh_0cY&t=0s"),
Add Youtube video 2019 Leaf
* Update selfdrive/car/nissan/values.py
Co-authored-by: Shane Smiskol
---
selfdrive/car/nissan/values.py | 2 +-
1 file changed, 1 insertion(+), 1 deletion(-)
diff --git a/selfdrive/car/nissan/values.py b/selfdrive/car/nissan/values.py
index 6371b56be8..e9af828e2b 100644
--- a/selfdrive/car/nissan/values.py
+++ b/selfdrive/car/nissan/values.py
@@ -39,7 +39,7 @@ class NissanCarInfo(CarInfo):
CAR_INFO: Dict[str, Optional[Union[NissanCarInfo, List[NissanCarInfo]]]] = {
CAR.XTRAIL: NissanCarInfo("Nissan X-Trail 2017"),
- CAR.LEAF: NissanCarInfo("Nissan Leaf 2018-22"),
+ CAR.LEAF: NissanCarInfo("Nissan Leaf 2018-22", video_link="https://youtu.be/vaMbtAh_0cY"),
CAR.LEAF_IC: None, # same platforms
CAR.ROGUE: NissanCarInfo("Nissan Rogue 2018-20"),
CAR.ALTIMA: NissanCarInfo("Nissan Altima 2019-20", harness=Harness.nissan_b),
From 1a907b4c7a3167ad21b992fd74e2439019163086 Mon Sep 17 00:00:00 2001
From: Jason Wen <47793918+sunnyhaibin@users.noreply.github.com>
Date: Mon, 9 Jan 2023 21:14:02 -0500
Subject: [PATCH 045/484] HKG: add FW Versions for 2019 Kia Stinger (#26897)
* HKG: Add FW Versions for 2019 Kia Stinger
* Update selfdrive/car/hyundai/values.py
* fix
* use shorter query
Co-authored-by: Shane Smiskol
---
selfdrive/car/hyundai/values.py | 4 ++++
1 file changed, 4 insertions(+)
diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py
index 16f1f42679..736ebbb553 100644
--- a/selfdrive/car/hyundai/values.py
+++ b/selfdrive/car/hyundai/values.py
@@ -799,6 +799,7 @@ FW_VERSIONS = {
b'\xf1\x00CK__ SCC F_CUP 1.00 1.01 96400-J5100 ',
b'\xf1\x00CK__ SCC F_CUP 1.00 1.03 96400-J5100 ',
b'\xf1\x00CK__ SCC F_CUP 1.00 1.01 96400-J5000 ',
+ b'\xf1\x00CK__ SCC F_CUP 1.00 1.02 96400-J5100 ',
],
(Ecu.engine, 0x7e0, None): [
b'\xf1\x81606DE051\x00\x00\x00\x00\x00\x00\x00\x00',
@@ -806,6 +807,7 @@ FW_VERSIONS = {
b'\xf1\x82CKJN3TMSDE0B\x00\x00\x00\x00',
b'\xf1\x82CKKN3TMD_H0A\x00\x00\x00\x00',
b'\xe0\x19\xff\xe7\xe7g\x01\xa2\x00\x0f\x00\x9e\x00\x06\x00\xff\xff\xff\xff\xff\xff\x00\x00\xff\xff\xff\xff\xff\xff\x00\x00\x0f\x0e\x0f\x0f\x0e\r\x00\x00\x7f\x02.\xff\x00\x00~p\x00\x00\x00\x00u\xff\xf9\xff\x00\x00\x00\x00V\t\xd5\x01\xc0\x00\x00\x00\x007\xfb\xfc\x0b\x8d\x00',
+ b'\xf1\x81640H0051\x00\x00\x00\x00\x00\x00\x00\x00',
],
(Ecu.eps, 0x7d4, None): [
b'\xf1\x00CK MDPS R 1.00 1.04 57700-J5200 4C2CL104',
@@ -813,6 +815,7 @@ FW_VERSIONS = {
b'\xf1\x00CK MDPS R 1.00 1.04 57700-J5420 4C4VL104',
b'\xf1\x00CK MDPS R 1.00 1.06 57700-J5420 4C4VL106',
b'\xf1\x00CK MDPS R 1.00 1.07 57700-J5220 4C2VL107',
+ b'\xf1\x00CK MDPS R 1.00 1.06 57700-J5220 4C2VL106',
],
(Ecu.fwdCamera, 0x7c4, None): [
b'\xf1\x00CK MFC AT USA LHD 1.00 1.03 95740-J5000 170822',
@@ -820,6 +823,7 @@ FW_VERSIONS = {
b'\xf1\x00CK MFC AT EUR LHD 1.00 1.03 95740-J5000 170822',
],
(Ecu.transmission, 0x7e1, None): [
+ b'\xf1\x00bcsh8p54 E25\x00\x00\x00\x00\x00\x00\x00SCK0T33NB2\xb3\xee\xba\xdc',
b'\xf1\x87VCJLE17622572DK0vd6D\x99\x98y\x97vwVffUfvfC%CuT&Dx\x87o\xff{\x1c\xf1\x81E21\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 E21\x00\x00\x00\x00\x00\x00\x00SCK0T33NB0\x88\xa2\xe6\xf0',
b'\xf1\x87VDHLG17000192DK2xdFffT\xa5VUD$DwT\x86wveVeeD&T\x99\xba\x8f\xff\xcc\x99\xf1\x81E21\x00\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 E21\x00\x00\x00\x00\x00\x00\x00SCK0T33NB0\x88\xa2\xe6\xf0',
b'\xf1\x87VDHLG17000192DK2xdFffT\xa5VUD$DwT\x86wveVeeD&T\x99\xba\x8f\xff\xcc\x99\xf1\x89E21\x00\x00\x00\x00\x00\x00\x00\xf1\x82SCK0T33NB0',
From d12146fbd657042bb6a74caa4c10b08a09ba074d Mon Sep 17 00:00:00 2001
From: Erich Moraga <33645296+ErichMoraga@users.noreply.github.com>
Date: Mon, 9 Jan 2023 20:57:51 -0600
Subject: [PATCH 046/484] Add several missing LEXUS_RC firmwares (#26905)
* Add several missing LEXUS_RC firmwares
`@Vranesh#9912` 2020 RC350 DongleID/route d6303cdeea512a4e|2023-01-09--17-11-55
* lexus now has two engines
* todo
Co-authored-by: Shane Smiskol
---
selfdrive/car/fw_query_definitions.py | 1 +
selfdrive/car/toyota/values.py | 9 ++++++++-
2 files changed, 9 insertions(+), 1 deletion(-)
diff --git a/selfdrive/car/fw_query_definitions.py b/selfdrive/car/fw_query_definitions.py
index c7e4d4eb30..a1695733fa 100755
--- a/selfdrive/car/fw_query_definitions.py
+++ b/selfdrive/car/fw_query_definitions.py
@@ -62,6 +62,7 @@ class Request:
@dataclass
class FwQueryConfig:
requests: List[Request]
+ # TODO: make this automatic and remove hardcoded lists, or do fingerprinting with ecus
# Overrides and removes from essential ecus for specific models and ecus (exact matching)
non_essential_ecus: Dict[capnp.lib.capnp._EnumModule, List[str]] = field(default_factory=dict)
# Ecus added for data collection, not to be fingerprinted on
diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py
index e945130e90..586b1a835e 100644
--- a/selfdrive/car/toyota/values.py
+++ b/selfdrive/car/toyota/values.py
@@ -230,7 +230,7 @@ FW_QUERY_CONFIG = FwQueryConfig(
# FIXME: On some models, abs can sometimes be missing
Ecu.abs: [CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.SIENNA, CAR.LEXUS_IS],
# On some models, the engine can show on two different addresses
- Ecu.engine: [CAR.CAMRY, CAR.COROLLA_TSS2, CAR.CHR, CAR.LEXUS_IS],
+ Ecu.engine: [CAR.CAMRY, CAR.COROLLA_TSS2, CAR.CHR, CAR.LEXUS_IS, CAR.LEXUS_RC],
}
)
@@ -1738,22 +1738,29 @@ FW_VERSIONS = {
],
},
CAR.LEXUS_RC: {
+ (Ecu.engine, 0x700, None): [
+ b'\x01896632478200\x00\x00\x00\x00',
+ ],
(Ecu.engine, 0x7e0, None): [
b'\x0232484000\x00\x00\x00\x00\x00\x00\x00\x0052422000\x00\x00\x00\x00\x00\x00\x00\x00',
],
(Ecu.abs, 0x7b0, None): [
+ b'F152624150\x00\x00\x00\x00\x00\x00',
b'F152624221\x00\x00\x00\x00\x00\x00',
],
(Ecu.dsu, 0x791, None): [
+ b'881512407000\x00\x00\x00\x00',
b'881512409100\x00\x00\x00\x00',
],
(Ecu.eps, 0x7a1, None): [
b'8965B24081\x00\x00\x00\x00\x00\x00',
+ b'8965B24320\x00\x00\x00\x00\x00\x00',
],
(Ecu.fwdRadar, 0x750, 0xf): [
b'8821F4702300\x00\x00\x00\x00',
],
(Ecu.fwdCamera, 0x750, 0x6d): [
+ b'8646F2401200\x00\x00\x00\x00',
b'8646F2402200\x00\x00\x00\x00',
],
},
From 9e364ff76f9c0b23ebe557b95b4a584dff052e97 Mon Sep 17 00:00:00 2001
From: Kyle Dibble-Dabney <6963660+dibble9012@users.noreply.github.com>
Date: Mon, 9 Jan 2023 22:01:03 -0500
Subject: [PATCH 047/484] Added fingerprint for 2023 EV6, fwdCamera (#26900)
---
selfdrive/car/hyundai/values.py | 1 +
1 file changed, 1 insertion(+)
diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py
index 736ebbb553..1a81e1b167 100644
--- a/selfdrive/car/hyundai/values.py
+++ b/selfdrive/car/hyundai/values.py
@@ -1466,6 +1466,7 @@ FW_VERSIONS = {
b'\xf1\x00CV1 MFC AT EUR LHD 1.00 1.05 99210-CV000 211027',
b'\xf1\x00CV1 MFC AT EUR LHD 1.00 1.06 99210-CV000 220328',
b'\xf1\x00CV1 MFC AT EUR RHD 1.00 1.00 99210-CV100 220630',
+ b'\xf1\x00CV1 MFC AT USA LHD 1.00 1.00 99210-CV100 220630',
],
},
CAR.IONIQ_5: {
From 4e9bddee5cbabe4807e690a93408a23ce66225d5 Mon Sep 17 00:00:00 2001
From: Shane Smiskol
Date: Tue, 10 Jan 2023 13:02:43 -0800
Subject: [PATCH 048/484] longcontrol: enter stopping state immediately
(#26879)
* enter stopping state immediately
* Update selfdrive/controls/lib/longcontrol.py
---
selfdrive/controls/lib/longcontrol.py | 4 +---
1 file changed, 1 insertion(+), 3 deletions(-)
diff --git a/selfdrive/controls/lib/longcontrol.py b/selfdrive/controls/lib/longcontrol.py
index 545a4c43ff..e8095813f2 100644
--- a/selfdrive/controls/lib/longcontrol.py
+++ b/selfdrive/controls/lib/longcontrol.py
@@ -30,10 +30,8 @@ def long_control_state_trans(CP, active, long_control_state, v_ego, v_target,
long_control_state = LongCtrlState.off
else:
- if long_control_state == LongCtrlState.off:
+ if long_control_state in (LongCtrlState.off, LongCtrlState.pid):
long_control_state = LongCtrlState.pid
-
- elif long_control_state == LongCtrlState.pid:
if stopping_condition:
long_control_state = LongCtrlState.stopping
From b45dda2d0a365946e4cfc3c4a08023c05e2d58c7 Mon Sep 17 00:00:00 2001
From: Shane Smiskol
Date: Tue, 10 Jan 2023 14:46:43 -0800
Subject: [PATCH 049/484] Longitudinal tests: test forceDecel (#26765)
* test with forceDecel
* test all combos
* fix
* fix
* fix
* ...
* remove print
* clean up
* just set cruise to 0
* update ref commit
Co-authored-by: Bruce Wayne
---
.../lib/longitudinal_mpc_lib/long_mpc.py | 2 +-
.../controls/lib/longitudinal_planner.py | 7 +-
.../test/longitudinal_maneuvers/maneuver.py | 6 ++
.../test/longitudinal_maneuvers/plant.py | 4 +-
.../test_longitudinal.py | 68 +++++++++++--------
selfdrive/test/process_replay/ref_commit | 2 +-
6 files changed, 51 insertions(+), 38 deletions(-)
diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py b/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py
index dc27fd27a9..c017951232 100644
--- a/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py
+++ b/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py
@@ -306,7 +306,7 @@ class LongitudinalMpc:
self.cruise_min_a = min_a
self.max_a = max_a
- def update(self, carstate, radarstate, v_cruise, x, v, a, j):
+ def update(self, radarstate, v_cruise, x, v, a, j):
v_ego = self.x0[1]
self.status = radarstate.leadOne.status or radarstate.leadTwo.status
diff --git a/selfdrive/controls/lib/longitudinal_planner.py b/selfdrive/controls/lib/longitudinal_planner.py
index a0f6318323..0febfbafd9 100755
--- a/selfdrive/controls/lib/longitudinal_planner.py
+++ b/selfdrive/controls/lib/longitudinal_planner.py
@@ -15,7 +15,6 @@ from selfdrive.controls.lib.drive_helpers import V_CRUISE_MAX, CONTROL_N
from system.swaglog import cloudlog
LON_MPC_STEP = 0.2 # first step is 0.2s
-AWARENESS_DECEL = -0.2 # car smoothly decel at .2m/s^2 when user is distracted
A_CRUISE_MIN = -1.2
A_CRUISE_MAX_VALS = [1.6, 1.2, 0.8, 0.6]
A_CRUISE_MAX_BP = [0., 10.0, 25., 40.]
@@ -111,9 +110,7 @@ class LongitudinalPlanner:
self.v_model_error = sm['modelV2'].temporalPose.trans[0] - v_ego
if force_slow_decel:
- # if required so, force a smooth deceleration
- accel_limits_turns[1] = min(accel_limits_turns[1], AWARENESS_DECEL)
- accel_limits_turns[0] = min(accel_limits_turns[0], accel_limits_turns[1])
+ v_cruise = 0.0
# clip limits, cannot init MPC outside of bounds
accel_limits_turns[0] = min(accel_limits_turns[0], self.a_desired + 0.05)
accel_limits_turns[1] = max(accel_limits_turns[1], self.a_desired - 0.05)
@@ -122,7 +119,7 @@ class LongitudinalPlanner:
self.mpc.set_accel_limits(accel_limits_turns[0], accel_limits_turns[1])
self.mpc.set_cur_state(self.v_desired_filter.x, self.a_desired)
x, v, a, j = self.parse_model(sm['modelV2'], self.v_model_error)
- self.mpc.update(sm['carState'], sm['radarState'], v_cruise, x, v, a, j)
+ self.mpc.update(sm['radarState'], v_cruise, x, v, a, j)
self.v_desired_trajectory = np.interp(T_IDXS[:CONTROL_N], T_IDXS_MPC, self.mpc.v_solution)
self.a_desired_trajectory = np.interp(T_IDXS[:CONTROL_N], T_IDXS_MPC, self.mpc.a_solution)
diff --git a/selfdrive/test/longitudinal_maneuvers/maneuver.py b/selfdrive/test/longitudinal_maneuvers/maneuver.py
index 65935f8979..00ddfe627e 100644
--- a/selfdrive/test/longitudinal_maneuvers/maneuver.py
+++ b/selfdrive/test/longitudinal_maneuvers/maneuver.py
@@ -19,6 +19,7 @@ class Maneuver:
self.ensure_start = kwargs.get("ensure_start", False)
self.enabled = kwargs.get("enabled", True)
self.e2e = kwargs.get("e2e", False)
+ self.force_decel = kwargs.get("force_decel", False)
self.duration = duration
self.title = title
@@ -32,6 +33,7 @@ class Maneuver:
only_lead2=self.only_lead2,
only_radar=self.only_radar,
e2e=self.e2e,
+ force_decel=self.force_decel,
)
valid = True
@@ -60,6 +62,10 @@ class Maneuver:
if self.ensure_start and log['v_rel'] > 0 and log['speeds'][-1] <= 0.1:
print('LongitudinalPlanner not starting!')
valid = False
+ if self.force_decel and log['speed'] > 1e-1 and log['acceleration'] > -0.04:
+ print('Not stopping with force decel')
+ valid = False
+
print("maneuver end", valid)
return valid, np.array(logs)
diff --git a/selfdrive/test/longitudinal_maneuvers/plant.py b/selfdrive/test/longitudinal_maneuvers/plant.py
index 8e150d800c..59cb0e1fe3 100755
--- a/selfdrive/test/longitudinal_maneuvers/plant.py
+++ b/selfdrive/test/longitudinal_maneuvers/plant.py
@@ -15,7 +15,7 @@ class Plant:
messaging_initialized = False
def __init__(self, lead_relevancy=False, speed=0.0, distance_lead=2.0,
- enabled=True, only_lead2=False, only_radar=False, e2e=False):
+ enabled=True, only_lead2=False, only_radar=False, e2e=False, force_decel=False):
self.rate = 1. / DT_MDL
if not Plant.messaging_initialized:
@@ -39,6 +39,7 @@ class Plant:
self.only_lead2 = only_lead2
self.only_radar = only_radar
self.e2e = e2e
+ self.force_decel = force_decel
self.rk = Ratekeeper(self.rate, print_delay_threshold=100.0)
self.ts = 1. / self.rate
@@ -111,6 +112,7 @@ class Plant:
control.controlsState.longControlState = LongCtrlState.pid if self.enabled else LongCtrlState.off
control.controlsState.vCruise = float(v_cruise * 3.6)
control.controlsState.experimentalMode = self.e2e
+ control.controlsState.forceDecel = self.force_decel
car_state.carState.vEgo = float(self.speed)
car_state.carState.standstill = self.speed < 0.01
diff --git a/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py b/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py
index 686b35e456..bc477ca9fe 100755
--- a/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py
+++ b/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py
@@ -1,6 +1,7 @@
#!/usr/bin/env python3
+import itertools
import os
-from parameterized import parameterized
+from parameterized import parameterized_class
import unittest
from common.params import Params
@@ -9,8 +10,8 @@ from selfdrive.test.longitudinal_maneuvers.maneuver import Maneuver
# TODO: make new FCW tests
-def create_maneuvers(e2e):
- return [
+def create_maneuvers(kwargs):
+ maneuvers = [
Maneuver(
'approach stopped car at 25m/s, initial distance: 120m',
duration=20.,
@@ -19,7 +20,7 @@ def create_maneuvers(e2e):
initial_distance_lead=120.,
speed_lead_values=[30., 0.],
breakpoints=[0., 1.],
- e2e=e2e,
+ **kwargs,
),
Maneuver(
'approach stopped car at 20m/s, initial distance 90m',
@@ -29,7 +30,7 @@ def create_maneuvers(e2e):
initial_distance_lead=90.,
speed_lead_values=[20., 0.],
breakpoints=[0., 1.],
- e2e=e2e,
+ **kwargs,
),
Maneuver(
'steady state following a car at 20m/s, then lead decel to 0mph at 1m/s^2',
@@ -39,7 +40,7 @@ def create_maneuvers(e2e):
initial_distance_lead=35.,
speed_lead_values=[20., 20., 0.],
breakpoints=[0., 15., 35.0],
- e2e=e2e,
+ **kwargs,
),
Maneuver(
'steady state following a car at 20m/s, then lead decel to 0mph at 2m/s^2',
@@ -49,7 +50,7 @@ def create_maneuvers(e2e):
initial_distance_lead=35.,
speed_lead_values=[20., 20., 0.],
breakpoints=[0., 15., 25.0],
- e2e=e2e,
+ **kwargs,
),
Maneuver(
'steady state following a car at 20m/s, then lead decel to 0mph at 3m/s^2',
@@ -59,7 +60,7 @@ def create_maneuvers(e2e):
initial_distance_lead=35.,
speed_lead_values=[20., 20., 0.],
breakpoints=[0., 15., 21.66],
- e2e=e2e,
+ **kwargs,
),
Maneuver(
'steady state following a car at 20m/s, then lead decel to 0mph at 3+m/s^2',
@@ -71,7 +72,7 @@ def create_maneuvers(e2e):
prob_lead_values=[0., 1., 1.],
cruise_values=[20., 20., 20.],
breakpoints=[2., 2.01, 8.8],
- e2e=e2e,
+ **kwargs,
),
Maneuver(
"approach stopped car at 20m/s, with prob_lead_values",
@@ -83,7 +84,7 @@ def create_maneuvers(e2e):
prob_lead_values=[0.0, 0., 1.],
cruise_values=[20., 20., 20.],
breakpoints=[0.0, 2., 2.01],
- e2e=e2e,
+ **kwargs,
),
Maneuver(
"approach slower cut-in car at 20m/s",
@@ -94,7 +95,7 @@ def create_maneuvers(e2e):
speed_lead_values=[15., 15.],
breakpoints=[1., 11.],
only_lead2=True,
- e2e=e2e,
+ **kwargs,
),
Maneuver(
"stay stopped behind radar override lead",
@@ -106,7 +107,7 @@ def create_maneuvers(e2e):
prob_lead_values=[0., 0.],
breakpoints=[1., 11.],
only_radar=True,
- e2e=e2e,
+ **kwargs,
),
Maneuver(
"NaN recovery",
@@ -117,10 +118,20 @@ def create_maneuvers(e2e):
speed_lead_values=[0., 0., 0.0],
breakpoints=[1., 1.01, 11.],
cruise_values=[float("nan"), 15., 15.],
- e2e=e2e,
+ **kwargs,
),
- # controls relies on planner commanding to move for stock-ACC resume spamming
Maneuver(
+ 'cruising at 25 m/s while disabled',
+ duration=20.,
+ initial_speed=25.,
+ lead_relevancy=False,
+ enabled=False,
+ **kwargs,
+ ),
+ ]
+ if not kwargs['force_decel']:
+ # controls relies on planner commanding to move for stock-ACC resume spamming
+ maneuvers.append(Maneuver(
"resume from a stop",
duration=20.,
initial_speed=0.,
@@ -129,20 +140,16 @@ def create_maneuvers(e2e):
speed_lead_values=[0., 0., 2.],
breakpoints=[1., 10., 15.],
ensure_start=True,
- e2e=e2e,
- ),
- Maneuver(
- 'cruising at 25 m/s while disabled',
- duration=20.,
- initial_speed=25.,
- lead_relevancy=False,
- enabled=False,
- e2e=e2e,
- ),
- ]
+ **kwargs,
+ ))
+ return maneuvers
+@parameterized_class(("e2e", "force_decel"), itertools.product([True, False], repeat=2))
class LongitudinalControl(unittest.TestCase):
+ e2e: bool
+ force_decel: bool
+
@classmethod
def setUpClass(cls):
os.environ['SIMULATION'] = "1"
@@ -154,11 +161,12 @@ class LongitudinalControl(unittest.TestCase):
params.put_bool("Passive", bool(os.getenv("PASSIVE")))
params.put_bool("OpenpilotEnabledToggle", True)
- @parameterized.expand([(man,) for e2e in [True, False] for man in create_maneuvers(e2e)])
- def test_maneuver(self, maneuver):
- print(maneuver.title, f'in {"e2e" if maneuver.e2e else "acc"} mode')
- valid, _ = maneuver.evaluate()
- self.assertTrue(valid, msg=maneuver.title)
+ def test_maneuver(self):
+ for maneuver in create_maneuvers({"e2e": self.e2e, "force_decel": self.force_decel}):
+ with self.subTest(title=maneuver.title, e2e=maneuver.e2e, force_decel=maneuver.force_decel):
+ print(maneuver.title, f'in {"e2e" if maneuver.e2e else "acc"} mode')
+ valid, _ = maneuver.evaluate()
+ self.assertTrue(valid)
if __name__ == "__main__":
diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit
index 24ec1c62de..c23ff8a140 100644
--- a/selfdrive/test/process_replay/ref_commit
+++ b/selfdrive/test/process_replay/ref_commit
@@ -1 +1 @@
-6d30c77af7b3210b03f65b433c0a043a96ee39bc
\ No newline at end of file
+c39b74fdc14bb22a1c95cd5deedd4f4fcadf8494
From 5f66a9a6213f6c42161584979a2f760f9ad9df47 Mon Sep 17 00:00:00 2001
From: Adeeb Shihadeh
Date: Tue, 10 Jan 2023 16:20:27 -0800
Subject: [PATCH 050/484] jenkins fixups
---
Jenkinsfile | 3 ++-
selfdrive/test/process_replay/model_replay.py | 2 +-
selfdrive/test/setup_device_ci.sh | 3 ++-
3 files changed, 5 insertions(+), 3 deletions(-)
diff --git a/Jenkinsfile b/Jenkinsfile
index 37621dde5c..f49ccf4315 100644
--- a/Jenkinsfile
+++ b/Jenkinsfile
@@ -90,7 +90,8 @@ pipeline {
}
}
steps {
- sh "git config --global --add safe.directory ${WORKSPACE}"
+ sh "git config --global --add safe.directory '*'"
+ sh "git submodule update --init --recursive"
sh "git lfs pull"
lock(resource: "", label: "simulator", inversePrecedence: true, quantity: 1) {
sh "${WORKSPACE}/tools/sim/build_container.sh"
diff --git a/selfdrive/test/process_replay/model_replay.py b/selfdrive/test/process_replay/model_replay.py
index 324801fead..68cbb28aaf 100755
--- a/selfdrive/test/process_replay/model_replay.py
+++ b/selfdrive/test/process_replay/model_replay.py
@@ -223,7 +223,7 @@ if __name__ == "__main__":
try:
expected_msgs = 2*MAX_FRAMES
if not NO_NAV:
- expected_msgs += NAV_FRAMES*2
+ expected_msgs += NAV_FRAMES*3
cmp_log = list(LogReader(BASE_URL + log_fn))[:expected_msgs]
ignore = [
diff --git a/selfdrive/test/setup_device_ci.sh b/selfdrive/test/setup_device_ci.sh
index 9e06b98662..b7d586a83b 100755
--- a/selfdrive/test/setup_device_ci.sh
+++ b/selfdrive/test/setup_device_ci.sh
@@ -56,7 +56,7 @@ cd $SOURCE_DIR
rm -f .git/index.lock
git reset --hard
-git fetch --verbose origin $GIT_COMMIT
+git fetch --no-tags --no-recurse-submodules -j4 --verbose --depth 1 origin $GIT_COMMIT
find . -maxdepth 1 -not -path './.git' -not -name '.' -not -name '..' -exec rm -rf '{}' \;
git reset --hard $GIT_COMMIT
git checkout $GIT_COMMIT
@@ -69,6 +69,7 @@ git lfs pull
(ulimit -n 65535 && git lfs prune)
echo "git checkout done, t=$SECONDS"
+du -hs $SOURCE_DIR $SOURCE_DIR/.git
rsync -a --delete $SOURCE_DIR $TEST_DIR
From f0d0d999813ee3c5cc49c2b47623296c70d37318 Mon Sep 17 00:00:00 2001
From: Shane Smiskol
Date: Tue, 10 Jan 2023 19:59:39 -0800
Subject: [PATCH 051/484] process replay: test body with joystick mode (#26916)
* no need to check sm
* fix
* Update ref_commit
* revert
---
selfdrive/controls/controlsd.py | 2 +-
selfdrive/test/process_replay/ref_commit | 2 +-
2 files changed, 2 insertions(+), 2 deletions(-)
diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py
index fea19adbdb..b5d5e3d8a2 100755
--- a/selfdrive/controls/controlsd.py
+++ b/selfdrive/controls/controlsd.py
@@ -103,7 +103,7 @@ class Controls:
else:
self.CI, self.CP = CI, CI.CP
- self.joystick_mode = self.params.get_bool("JoystickDebugMode") or (self.CP.notCar and sm is None)
+ self.joystick_mode = self.params.get_bool("JoystickDebugMode") or self.CP.notCar
# set alternative experiences from parameters
self.disengage_on_accelerator = self.params.get_bool("DisengageOnAccelerator")
diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit
index c23ff8a140..76f2ef06ba 100644
--- a/selfdrive/test/process_replay/ref_commit
+++ b/selfdrive/test/process_replay/ref_commit
@@ -1 +1 @@
-c39b74fdc14bb22a1c95cd5deedd4f4fcadf8494
+d9432dcfb875a76be051137969e371c9926611e9
From cb88b3ed6528a7ad840be7bcd33fe7023b4f3719 Mon Sep 17 00:00:00 2001
From: Jason Young <46612682+jyoung8607@users.noreply.github.com>
Date: Tue, 10 Jan 2023 23:51:10 -0500
Subject: [PATCH 052/484] controlsd: set latActive with max minimum steer speed
(#26805)
* refactor minimum lateral speed handling
* rename for clarity
* simplify without joystick at standstill
* intermediate standstill variable, check notCar
* check joystick for now
* cmt
Co-authored-by: Shane Smiskol
---
selfdrive/controls/controlsd.py | 6 ++++--
selfdrive/controls/lib/latcontrol.py | 2 +-
selfdrive/controls/lib/latcontrol_angle.py | 4 ++--
selfdrive/controls/lib/latcontrol_indi.py | 4 ++--
selfdrive/controls/lib/latcontrol_pid.py | 4 ++--
selfdrive/controls/lib/latcontrol_torque.py | 4 ++--
6 files changed, 13 insertions(+), 11 deletions(-)
diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py
index b5d5e3d8a2..1d92cd4fb2 100755
--- a/selfdrive/controls/controlsd.py
+++ b/selfdrive/controls/controlsd.py
@@ -17,7 +17,7 @@ from selfdrive.boardd.boardd import can_list_to_can_capnp
from selfdrive.car.car_helpers import get_car, get_startup_event, get_one_can
from selfdrive.controls.lib.lateral_planner import CAMERA_OFFSET
from selfdrive.controls.lib.drive_helpers import VCruiseHelper, get_lag_adjusted_curvature
-from selfdrive.controls.lib.latcontrol import LatControl
+from selfdrive.controls.lib.latcontrol import LatControl, MIN_LATERAL_CONTROL_SPEED
from selfdrive.controls.lib.longcontrol import LongControl
from selfdrive.controls.lib.latcontrol_pid import LatControlPID
from selfdrive.controls.lib.latcontrol_indi import LatControlINDI
@@ -569,9 +569,11 @@ class Controls:
CC = car.CarControl.new_message()
CC.enabled = self.enabled
+
# Check which actuators can be enabled
+ standstill = CS.vEgo <= max(self.CP.minSteerSpeed, MIN_LATERAL_CONTROL_SPEED) or CS.standstill
CC.latActive = self.active and not CS.steerFaultTemporary and not CS.steerFaultPermanent and \
- CS.vEgo > self.CP.minSteerSpeed and not CS.standstill
+ (not standstill or self.joystick_mode)
CC.longActive = self.enabled and not self.events.any(ET.OVERRIDE_LONGITUDINAL) and self.CP.openpilotLongitudinalControl
actuators = CC.actuators
diff --git a/selfdrive/controls/lib/latcontrol.py b/selfdrive/controls/lib/latcontrol.py
index cefbc1078c..d38959c560 100644
--- a/selfdrive/controls/lib/latcontrol.py
+++ b/selfdrive/controls/lib/latcontrol.py
@@ -3,7 +3,7 @@ from abc import abstractmethod, ABC
from common.numpy_fast import clip
from common.realtime import DT_CTRL
-MIN_STEER_SPEED = 0.3
+MIN_LATERAL_CONTROL_SPEED = 0.3 # m/s
class LatControl(ABC):
diff --git a/selfdrive/controls/lib/latcontrol_angle.py b/selfdrive/controls/lib/latcontrol_angle.py
index d692f80b4b..9ed140d38e 100644
--- a/selfdrive/controls/lib/latcontrol_angle.py
+++ b/selfdrive/controls/lib/latcontrol_angle.py
@@ -1,7 +1,7 @@
import math
from cereal import log
-from selfdrive.controls.lib.latcontrol import LatControl, MIN_STEER_SPEED
+from selfdrive.controls.lib.latcontrol import LatControl
STEER_ANGLE_SATURATION_THRESHOLD = 2.5 # Degrees
@@ -14,7 +14,7 @@ class LatControlAngle(LatControl):
def update(self, active, CS, VM, params, last_actuators, steer_limited, desired_curvature, desired_curvature_rate, llk):
angle_log = log.ControlsState.LateralAngleState.new_message()
- if CS.vEgo < MIN_STEER_SPEED or not active:
+ if not active:
angle_log.active = False
angle_steers_des = float(CS.steeringAngleDeg)
else:
diff --git a/selfdrive/controls/lib/latcontrol_indi.py b/selfdrive/controls/lib/latcontrol_indi.py
index 2bc3cef76b..dca82c6729 100644
--- a/selfdrive/controls/lib/latcontrol_indi.py
+++ b/selfdrive/controls/lib/latcontrol_indi.py
@@ -5,7 +5,7 @@ from cereal import log
from common.filter_simple import FirstOrderFilter
from common.numpy_fast import clip, interp
from common.realtime import DT_CTRL
-from selfdrive.controls.lib.latcontrol import LatControl, MIN_STEER_SPEED
+from selfdrive.controls.lib.latcontrol import LatControl
class LatControlINDI(LatControl):
@@ -82,7 +82,7 @@ class LatControlINDI(LatControl):
rate_des = VM.get_steer_from_curvature(-desired_curvature_rate, CS.vEgo, 0)
indi_log.steeringRateDesiredDeg = math.degrees(rate_des)
- if CS.vEgo < MIN_STEER_SPEED or not active:
+ if not active:
indi_log.active = False
self.steer_filter.x = 0.0
output_steer = 0
diff --git a/selfdrive/controls/lib/latcontrol_pid.py b/selfdrive/controls/lib/latcontrol_pid.py
index 6bd678073e..6696d2e304 100644
--- a/selfdrive/controls/lib/latcontrol_pid.py
+++ b/selfdrive/controls/lib/latcontrol_pid.py
@@ -1,7 +1,7 @@
import math
from cereal import log
-from selfdrive.controls.lib.latcontrol import LatControl, MIN_STEER_SPEED
+from selfdrive.controls.lib.latcontrol import LatControl
from selfdrive.controls.lib.pid import PIDController
@@ -28,7 +28,7 @@ class LatControlPID(LatControl):
pid_log.steeringAngleDesiredDeg = angle_steers_des
pid_log.angleError = error
- if CS.vEgo < MIN_STEER_SPEED or not active:
+ if not active:
output_steer = 0.0
pid_log.active = False
self.pid.reset()
diff --git a/selfdrive/controls/lib/latcontrol_torque.py b/selfdrive/controls/lib/latcontrol_torque.py
index d10d39d945..2f56094379 100644
--- a/selfdrive/controls/lib/latcontrol_torque.py
+++ b/selfdrive/controls/lib/latcontrol_torque.py
@@ -2,7 +2,7 @@ import math
from cereal import log
from common.numpy_fast import interp
-from selfdrive.controls.lib.latcontrol import LatControl, MIN_STEER_SPEED
+from selfdrive.controls.lib.latcontrol import LatControl
from selfdrive.controls.lib.pid import PIDController
from selfdrive.controls.lib.vehicle_model import ACCELERATION_DUE_TO_GRAVITY
@@ -39,7 +39,7 @@ class LatControlTorque(LatControl):
def update(self, active, CS, VM, params, last_actuators, steer_limited, desired_curvature, desired_curvature_rate, llk):
pid_log = log.ControlsState.LateralTorqueState.new_message()
- if CS.vEgo < MIN_STEER_SPEED or not active:
+ if not active:
output_torque = 0.0
pid_log.active = False
else:
From 29470d2d2d5f53d4b26a220192a08adbde5eeb5d Mon Sep 17 00:00:00 2001
From: Shane Smiskol
Date: Tue, 10 Jan 2023 22:28:54 -0800
Subject: [PATCH 053/484] VW: match panda standstill check (#25761)
* test models: check panda standstill
* match panda
* reverse exception
* check == 0
* bumppanda
Co-authored-by: Adeeb Shihadeh
---
panda | 2 +-
selfdrive/car/tests/test_models.py | 2 +-
selfdrive/car/volkswagen/carstate.py | 4 ++--
3 files changed, 4 insertions(+), 4 deletions(-)
diff --git a/panda b/panda
index 345147fe2b..0b3b906036 160000
--- a/panda
+++ b/panda
@@ -1 +1 @@
-Subproject commit 345147fe2bc3a06c44709426f9fcd298588b9fe4
+Subproject commit 0b3b9060365739eeeddb1528cfe4018fec4efe7a
diff --git a/selfdrive/car/tests/test_models.py b/selfdrive/car/tests/test_models.py
index 641c109316..b6f78c4b47 100755
--- a/selfdrive/car/tests/test_models.py
+++ b/selfdrive/car/tests/test_models.py
@@ -238,7 +238,7 @@ class TestCarModelBase(unittest.TestCase):
# TODO: check rest of panda's carstate (steering, ACC main on, etc.)
checks['gasPressed'] += CS.gasPressed != self.safety.get_gas_pressed_prev()
- if self.CP.carName not in ("hyundai", "volkswagen", "body"):
+ if self.CP.carName not in ("hyundai", "body"):
# TODO: fix standstill mismatches for other makes
checks['standstill'] += CS.standstill == self.safety.get_vehicle_moving()
diff --git a/selfdrive/car/volkswagen/carstate.py b/selfdrive/car/volkswagen/carstate.py
index 7ea9aa871b..64d1246880 100644
--- a/selfdrive/car/volkswagen/carstate.py
+++ b/selfdrive/car/volkswagen/carstate.py
@@ -44,7 +44,7 @@ class CarState(CarStateBase):
ret.vEgoRaw = float(np.mean([ret.wheelSpeeds.fl, ret.wheelSpeeds.fr, ret.wheelSpeeds.rl, ret.wheelSpeeds.rr]))
ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw)
- ret.standstill = ret.vEgo < 0.1
+ ret.standstill = ret.vEgoRaw == 0
# Update steering angle, rate, yaw rate, and driver input torque. VW send
# the sign/direction in a separate signal so they must be recombined.
@@ -160,7 +160,7 @@ class CarState(CarStateBase):
# vEgo obtained from Bremse_1 vehicle speed rather than Bremse_3 wheel speeds because Bremse_3 isn't present on NSF
ret.vEgoRaw = pt_cp.vl["Bremse_1"]["Geschwindigkeit_neu__Bremse_1_"] * CV.KPH_TO_MS
ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw)
- ret.standstill = ret.vEgo < 0.1
+ ret.standstill = ret.vEgoRaw == 0
# Update steering angle, rate, yaw rate, and driver input torque. VW send
# the sign/direction in a separate signal so they must be recombined.
From f41caec2dec08aa3bbf8e0b3b6efa7600a8f6f0f Mon Sep 17 00:00:00 2001
From: Adeeb Shihadeh
Date: Wed, 11 Jan 2023 15:02:24 -0800
Subject: [PATCH 054/484] bump cereal, can in qlogs
---
cereal | 2 +-
1 file changed, 1 insertion(+), 1 deletion(-)
diff --git a/cereal b/cereal
index f200875ca3..c0d9abf6f7 160000
--- a/cereal
+++ b/cereal
@@ -1 +1 @@
-Subproject commit f200875ca300d3a7b9293c4effcc9456e359e505
+Subproject commit c0d9abf6f7c7de140c41af10e322e226d900ef99
From 9884957e3e07e09df6c021222949a4a77e2bd8ff Mon Sep 17 00:00:00 2001
From: Dean Lee
Date: Thu, 12 Jan 2023 07:32:13 +0800
Subject: [PATCH 055/484] cabana: sync play button state (#26917)
sync play button
---
tools/cabana/canmessages.cc | 5 +++++
tools/cabana/canmessages.h | 4 +++-
tools/cabana/videowidget.cc | 13 +++++--------
tools/cabana/videowidget.h | 1 -
4 files changed, 13 insertions(+), 10 deletions(-)
diff --git a/tools/cabana/canmessages.cc b/tools/cabana/canmessages.cc
index ad3ee80e3d..6e19eb440f 100644
--- a/tools/cabana/canmessages.cc
+++ b/tools/cabana/canmessages.cc
@@ -91,6 +91,11 @@ void CANMessages::seekTo(double ts) {
emit updated();
}
+void CANMessages::pause(bool pause) {
+ replay->pause(pause);
+ emit (pause ? paused() : resume());
+}
+
void CANMessages::settingChanged() {
replay->setSegmentCacheLimit(settings.cached_segment_limit);
}
diff --git a/tools/cabana/canmessages.h b/tools/cabana/canmessages.h
index 4dac4fe9df..ea43933565 100644
--- a/tools/cabana/canmessages.h
+++ b/tools/cabana/canmessages.h
@@ -38,10 +38,12 @@ public:
inline const std::vector *events() const { return replay->events(); }
inline void setSpeed(float speed) { replay->setSpeed(speed); }
inline bool isPaused() const { return replay->isPaused(); }
- inline void pause(bool pause) { replay->pause(pause); }
+ void pause(bool pause);
inline const std::vector> getTimeline() { return replay->getTimeline(); }
signals:
+ void paused();
+ void resume();
void seekedTo(double sec);
void streamStarted();
void eventsMerged();
diff --git a/tools/cabana/videowidget.cc b/tools/cabana/videowidget.cc
index 7e40ba2adb..ed4354ce65 100644
--- a/tools/cabana/videowidget.cc
+++ b/tools/cabana/videowidget.cc
@@ -63,22 +63,19 @@ VideoWidget::VideoWidget(QWidget *parent) : QFrame(parent) {
}
main_layout->addLayout(control_layout);
- QObject::connect(can, &CANMessages::updated, this, &VideoWidget::updateState);
QObject::connect(slider, &QSlider::sliderReleased, [this]() { can->seekTo(slider->value() / 1000.0); });
QObject::connect(slider, &QSlider::valueChanged, [=](int value) { time_label->setText(formatTime(value / 1000)); });
- QObject::connect(cam_widget, &CameraWidget::clicked, [this]() { pause(!can->isPaused()); });
- QObject::connect(play_btn, &QPushButton::clicked, [=]() { pause(!can->isPaused()); });
+ QObject::connect(cam_widget, &CameraWidget::clicked, []() { can->pause(!can->isPaused()); });
+ QObject::connect(play_btn, &QPushButton::clicked, []() { can->pause(!can->isPaused()); });
+ QObject::connect(can, &CANMessages::updated, this, &VideoWidget::updateState);
+ QObject::connect(can, &CANMessages::paused, [this]() { play_btn->setText("▶"); });
+ QObject::connect(can, &CANMessages::resume, [this]() { play_btn->setText("⏸"); });
QObject::connect(can, &CANMessages::streamStarted, [this]() {
end_time_label->setText(formatTime(can->totalSeconds()));
slider->setRange(0, can->totalSeconds() * 1000);
});
}
-void VideoWidget::pause(bool pause) {
- play_btn->setText(!pause ? "⏸" : "▶");
- can->pause(pause);
-}
-
void VideoWidget::rangeChanged(double min, double max, bool is_zoomed) {
if (!is_zoomed) {
min = 0;
diff --git a/tools/cabana/videowidget.h b/tools/cabana/videowidget.h
index 86cdc6f114..ec8bc4bec4 100644
--- a/tools/cabana/videowidget.h
+++ b/tools/cabana/videowidget.h
@@ -44,7 +44,6 @@ public:
protected:
void updateState();
- void pause(bool pause);
CameraWidget *cam_widget;
QLabel *end_time_label;
From 35626303b16734b17cb3dd266c5dd6f18f8941a9 Mon Sep 17 00:00:00 2001
From: Jason Young <46612682+jyoung8607@users.noreply.github.com>
Date: Wed, 11 Jan 2023 18:45:15 -0500
Subject: [PATCH 056/484] VW MQB: Add FW for 2019 Volkswagen Golf (#26920)
---
selfdrive/car/volkswagen/values.py | 3 +++
1 file changed, 3 insertions(+)
diff --git a/selfdrive/car/volkswagen/values.py b/selfdrive/car/volkswagen/values.py
index 24ea0a03ba..af73683e22 100755
--- a/selfdrive/car/volkswagen/values.py
+++ b/selfdrive/car/volkswagen/values.py
@@ -373,6 +373,7 @@ FW_VERSIONS = {
b'\xf1\x8704L906056CR\xf1\x895813',
b'\xf1\x8704L906056HE\xf1\x893758',
b'\xf1\x8704L906056HN\xf1\x896590',
+ b'\xf1\x8704L906056HT\xf1\x896591',
b'\xf1\x870EA906016A \xf1\x898343',
b'\xf1\x870EA906016E \xf1\x894219',
b'\xf1\x870EA906016F \xf1\x894238',
@@ -405,6 +406,7 @@ FW_VERSIONS = {
b'\xf1\x870CW300041H \xf1\x891010',
b'\xf1\x870CW300042F \xf1\x891604',
b'\xf1\x870CW300043B \xf1\x891601',
+ b'\xf1\x870CW300043E \xf1\x891603',
b'\xf1\x870CW300044S \xf1\x894530',
b'\xf1\x870CW300044T \xf1\x895245',
b'\xf1\x870CW300045 \xf1\x894531',
@@ -442,6 +444,7 @@ FW_VERSIONS = {
b'\xf1\x875Q0959655AA\xf1\x890388\xf1\x82\x111413001113120053114317121C111C9113',
b'\xf1\x875Q0959655BH\xf1\x890336\xf1\x82\x1314160011123300314211012230229333463100',
b'\xf1\x875Q0959655BS\xf1\x890403\xf1\x82\x1314160011123300314240012250229333463100',
+ b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x13141600111233003142404A2251229333463100',
b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x13141600111233003142404A2252229333463100',
b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x13141600111233003142405A2252229333463100',
b'\xf1\x875Q0959655C \xf1\x890361\xf1\x82\x111413001112120004110415121610169112',
From ccb43271977174e1a6de11b15ad07cd04c2ed056 Mon Sep 17 00:00:00 2001
From: Jason Wen <47793918+sunnyhaibin@users.noreply.github.com>
Date: Wed, 11 Jan 2023 19:14:05 -0500
Subject: [PATCH 057/484] HKG CAN-FD: set cruise state available with car
signal (#26812)
* HKG CAN-FD: set cruise state available with car signal
* Whoops
* Check this signal
* No should be in SCC_CONTROL
* use TCS
* add back
* match CAN
* think these are missing
Co-authored-by: Shane Smiskol
---
selfdrive/car/hyundai/carstate.py | 21 +++++++++++++++------
1 file changed, 15 insertions(+), 6 deletions(-)
diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py
index fc196528d7..53389279f7 100644
--- a/selfdrive/car/hyundai/carstate.py
+++ b/selfdrive/car/hyundai/carstate.py
@@ -156,6 +156,9 @@ class CarState(CarStateBase):
def update_canfd(self, cp, cp_cam):
ret = car.CarState.new_message()
+ self.is_metric = cp.vl["CRUISE_BUTTONS_ALT"]["DISTANCE_UNIT"] != 1
+ speed_factor = CV.KPH_TO_MS if self.is_metric else CV.MPH_TO_MS
+
if self.CP.carFingerprint in (EV_CAR | HYBRID_CAR):
if self.CP.carFingerprint in EV_CAR:
ret.gas = cp.vl["ACCELERATOR"]["ACCELERATOR_PEDAL"] / 255.
@@ -197,14 +200,18 @@ class CarState(CarStateBase):
ret.leftBlindspot = cp.vl["BLINDSPOTS_REAR_CORNERS"]["FL_INDICATOR"] != 0
ret.rightBlindspot = cp.vl["BLINDSPOTS_REAR_CORNERS"]["FR_INDICATOR"] != 0
- ret.cruiseState.available = True
- self.is_metric = cp.vl["CRUISE_BUTTONS_ALT"]["DISTANCE_UNIT"] != 1
- if not self.CP.openpilotLongitudinalControl:
- speed_factor = CV.KPH_TO_MS if self.is_metric else CV.MPH_TO_MS
+ # cruise state
+ if self.CP.openpilotLongitudinalControl:
+ # These are not used for engage/disengage since openpilot keeps track of state using the buttons
+ ret.cruiseState.available = cp.vl["TCS"]["ACCEnable"] == 0
+ ret.cruiseState.enabled = cp.vl["TCS"]["ACC_REQ"] == 1
+ ret.cruiseState.standstill = False
+ else:
cp_cruise_info = cp_cam if self.CP.flags & HyundaiFlags.CANFD_CAMERA_SCC else cp
- ret.cruiseState.speed = cp_cruise_info.vl["SCC_CONTROL"]["VSetDis"] * speed_factor
- ret.cruiseState.standstill = cp_cruise_info.vl["SCC_CONTROL"]["CRUISE_STANDSTILL"] == 1
+ ret.cruiseState.available = cp_cruise_info.vl["SCC_CONTROL"]["MainMode_ACC"] == 1
ret.cruiseState.enabled = cp_cruise_info.vl["SCC_CONTROL"]["ACCMode"] in (1, 2)
+ ret.cruiseState.standstill = cp_cruise_info.vl["SCC_CONTROL"]["CRUISE_STANDSTILL"] == 1
+ ret.cruiseState.speed = cp_cruise_info.vl["SCC_CONTROL"]["VSetDis"] * speed_factor
self.cruise_info = copy.copy(cp_cruise_info.vl["SCC_CONTROL"])
cruise_btn_msg = "CRUISE_BUTTONS_ALT" if self.CP.flags & HyundaiFlags.CANFD_ALT_BUTTONS else "CRUISE_BUTTONS"
@@ -435,6 +442,7 @@ class CarState(CarStateBase):
("DriverBraking", "TCS"),
("ACCEnable", "TCS"),
+ ("ACC_REQ", "TCS"),
("COUNTER", cruise_btn_msg),
("CRUISE_BUTTONS", cruise_btn_msg),
@@ -476,6 +484,7 @@ class CarState(CarStateBase):
("ACCMode", "SCC_CONTROL"),
("VSetDis", "SCC_CONTROL"),
("CRUISE_STANDSTILL", "SCC_CONTROL"),
+ ("MainMode_ACC", "SCC_CONTROL"),
]
checks += [
("SCC_CONTROL", 50),
From a24afa18d3b43f9ea02a15d99ba8eb07b8cc9709 Mon Sep 17 00:00:00 2001
From: Shane Smiskol
Date: Wed, 11 Jan 2023 17:22:24 -0800
Subject: [PATCH 058/484] Hyundai CAN-FD: set available from TCS ACC available
(#26921)
* available on TCS signal always
* cmt enh
* better comment
* better
---
selfdrive/car/hyundai/carstate.py | 5 ++---
1 file changed, 2 insertions(+), 3 deletions(-)
diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py
index 53389279f7..47621d3c2c 100644
--- a/selfdrive/car/hyundai/carstate.py
+++ b/selfdrive/car/hyundai/carstate.py
@@ -201,14 +201,14 @@ class CarState(CarStateBase):
ret.rightBlindspot = cp.vl["BLINDSPOTS_REAR_CORNERS"]["FR_INDICATOR"] != 0
# cruise state
+ # CAN FD cars enable on main button press, set available if no TCS faults preventing engagement
+ ret.cruiseState.available = cp.vl["TCS"]["ACCEnable"] == 0
if self.CP.openpilotLongitudinalControl:
# These are not used for engage/disengage since openpilot keeps track of state using the buttons
- ret.cruiseState.available = cp.vl["TCS"]["ACCEnable"] == 0
ret.cruiseState.enabled = cp.vl["TCS"]["ACC_REQ"] == 1
ret.cruiseState.standstill = False
else:
cp_cruise_info = cp_cam if self.CP.flags & HyundaiFlags.CANFD_CAMERA_SCC else cp
- ret.cruiseState.available = cp_cruise_info.vl["SCC_CONTROL"]["MainMode_ACC"] == 1
ret.cruiseState.enabled = cp_cruise_info.vl["SCC_CONTROL"]["ACCMode"] in (1, 2)
ret.cruiseState.standstill = cp_cruise_info.vl["SCC_CONTROL"]["CRUISE_STANDSTILL"] == 1
ret.cruiseState.speed = cp_cruise_info.vl["SCC_CONTROL"]["VSetDis"] * speed_factor
@@ -484,7 +484,6 @@ class CarState(CarStateBase):
("ACCMode", "SCC_CONTROL"),
("VSetDis", "SCC_CONTROL"),
("CRUISE_STANDSTILL", "SCC_CONTROL"),
- ("MainMode_ACC", "SCC_CONTROL"),
]
checks += [
("SCC_CONTROL", 50),
From 257a45dd18d30971dce0a02f285874423b2bfe9d Mon Sep 17 00:00:00 2001
From: Shane Smiskol
Date: Wed, 11 Jan 2023 20:25:01 -0800
Subject: [PATCH 059/484] HKG: filter on steering pressed (#26924)
* filter on can steering pressed
* Update ref_commit
---
selfdrive/car/hyundai/carstate.py | 2 +-
selfdrive/test/process_replay/ref_commit | 2 +-
2 files changed, 2 insertions(+), 2 deletions(-)
diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py
index 47621d3c2c..da1a7bfa78 100644
--- a/selfdrive/car/hyundai/carstate.py
+++ b/selfdrive/car/hyundai/carstate.py
@@ -86,7 +86,7 @@ class CarState(CarStateBase):
50, cp.vl["CGW1"]["CF_Gway_TurnSigLh"], cp.vl["CGW1"]["CF_Gway_TurnSigRh"])
ret.steeringTorque = cp.vl["MDPS12"]["CR_Mdps_StrColTq"]
ret.steeringTorqueEps = cp.vl["MDPS12"]["CR_Mdps_OutTq"]
- ret.steeringPressed = abs(ret.steeringTorque) > self.params.STEER_THRESHOLD
+ ret.steeringPressed = self.update_steering_pressed(abs(ret.steeringTorque) > self.params.STEER_THRESHOLD, 5)
ret.steerFaultTemporary = cp.vl["MDPS12"]["CF_Mdps_ToiUnavail"] != 0 or cp.vl["MDPS12"]["CF_Mdps_ToiFlt"] != 0
# cruise state
diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit
index 76f2ef06ba..157d146ade 100644
--- a/selfdrive/test/process_replay/ref_commit
+++ b/selfdrive/test/process_replay/ref_commit
@@ -1 +1 @@
-d9432dcfb875a76be051137969e371c9926611e9
+ff0348b1957c8f992125df77a36b3c0553a26e6a
From 2d403cbf9c14ed51e1e6d65bd33330a5775dec66 Mon Sep 17 00:00:00 2001
From: Niels Ole Salscheider
Date: Thu, 12 Jan 2023 05:33:45 +0100
Subject: [PATCH 060/484] VW MQB: Add FW for 2017 Seat Leon (#26883)
* VW MQB: Add FW for 2017 Seat Leon
* missing srs
Co-authored-by: Comma Device
Co-authored-by: Shane Smiskol
---
selfdrive/car/volkswagen/values.py | 4 ++++
1 file changed, 4 insertions(+)
diff --git a/selfdrive/car/volkswagen/values.py b/selfdrive/car/volkswagen/values.py
index af73683e22..f627e517be 100755
--- a/selfdrive/car/volkswagen/values.py
+++ b/selfdrive/car/volkswagen/values.py
@@ -937,19 +937,23 @@ FW_VERSIONS = {
b'\xf1\x8704L906026BP\xf1\x891198',
b'\xf1\x8704L906026BP\xf1\x897608',
b'\xf1\x8705E906018AS\xf1\x899596',
+ b'\xf1\x878V0906264H \xf1\x890005',
],
(Ecu.transmission, 0x7e1, None): [
+ b'\xf1\x870CW300041G \xf1\x891003',
b'\xf1\x870CW300050J \xf1\x891908',
b'\xf1\x870D9300042M \xf1\x895016',
],
(Ecu.srs, 0x715, None): [
b'\xf1\x873Q0959655AC\xf1\x890189\xf1\x82\r11110011110011021511110200',
b'\xf1\x873Q0959655AS\xf1\x890200\xf1\x82\r12110012120012021612110200',
+ b'\xf1\x873Q0959655BH\xf1\x890703\xf1\x82\x0e1312001313001305171311052900',
b'\xf1\x873Q0959655CM\xf1\x890720\xf1\x82\0161312001313001305171311052900',
],
(Ecu.eps, 0x712, None): [
b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\00521N01342A1',
b'\xf1\x875Q0909144P \xf1\x891043\xf1\x82\00511N01805A0',
+ b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521N01309A1',
b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\00521N05808A1',
],
(Ecu.fwdRadar, 0x757, None): [
From 69f8ac0b6508559549e99c5f12b7d9105ce1baa8 Mon Sep 17 00:00:00 2001
From: Jason Wen <47793918+sunnyhaibin@users.noreply.github.com>
Date: Thu, 12 Jan 2023 00:17:58 -0500
Subject: [PATCH 061/484] HKG: Car Port for Kia Sorento 2022 (#26874)
* HKG: Car Port for Kia Sorento 2022
* Harness K
* SCC is on bus 4
* Add test route
* seems reasonable
* more interesting segment
Co-authored-by: Shane Smiskol
---
RELEASES.md | 1 +
docs/CARS.md | 3 ++-
selfdrive/car/hyundai/interface.py | 9 ++++++---
selfdrive/car/hyundai/values.py | 17 ++++++++++++++---
selfdrive/car/tests/routes.py | 1 +
selfdrive/car/torque_data/override.yaml | 1 +
6 files changed, 25 insertions(+), 7 deletions(-)
diff --git a/RELEASES.md b/RELEASES.md
index eea69d295f..1b5ef8f7a7 100644
--- a/RELEASES.md
+++ b/RELEASES.md
@@ -6,6 +6,7 @@ Version 0.9.1 (2022-12-XX)
* Chevrolet Bolt EV 2022-23 support thanks to JasonJShuler!
* Genesis GV60 2023 support thanks to sunnyhaibin!
* Hyundai Tucson 2022-23 support
+* Kia Sorento 2022-23 support thanks to sunnyhaibin!
* Kia Sorento Plug-in Hybrid 2022 support thanks to sunnyhaibin!
Version 0.9.0 (2022-11-21)
diff --git a/docs/CARS.md b/docs/CARS.md
index 930b52c8a2..ac374501dc 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.
-# 222 Supported Cars
+# 223 Supported Cars
|Make|Model|Supported Package|ACC|No ACC accel below|No ALC below|Steering Torque|Resume from stop|Harness|
|---|---|---|:---:|:---:|:---:|:---:|:---:|:---:|
@@ -110,6 +110,7 @@ A supported vehicle is one that just works when you install a comma three. All s
|Kia|Seltos 2021|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai A|
|Kia|Sorento 2018|Advanced Smart Cruise Control|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai C|
|Kia|Sorento 2019|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai E|
+|Kia|Sorento 2022-23[5](#footnotes)|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai K|
|Kia|Sorento Plug-in Hybrid 2022-23[5](#footnotes)|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai A|
|Kia|Sportage 2023[5](#footnotes)|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[](##)|[](##)|Hyundai N|
|Kia|Sportage Hybrid 2023[5](#footnotes)|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|0 mph|0 mph|[](##)|[](##)|Hyundai N|
diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py
index 6881be5a33..6d6d9833df 100644
--- a/selfdrive/car/hyundai/interface.py
+++ b/selfdrive/car/hyundai/interface.py
@@ -185,10 +185,13 @@ class CarInterface(CarInterfaceBase):
ret.mass = 1767. + STD_CARGO_KG # SX Prestige trim support only
ret.wheelbase = 2.756
ret.steerRatio = 13.6
- elif candidate == CAR.KIA_SORENTO_PHEV_4TH_GEN:
- ret.mass = 4095.8 * CV.LB_TO_KG + STD_CARGO_KG # weight from EX and above trims, average of FWD and AWD versions (EX, X-Line EX AWD, SX, SX Pestige, X-Line SX Prestige AWD)
+ elif candidate in (CAR.KIA_SORENTO_4TH_GEN, CAR.KIA_SORENTO_PHEV_4TH_GEN):
ret.wheelbase = 2.81
- ret.steerRatio = 13.27 # steering ratio according to Kia News https://www.kiamedia.com/us/en/models/sorento-phev/2022/specifications
+ ret.steerRatio = 13.5 # average of the platforms
+ if candidate == CAR.KIA_SORENTO_4TH_GEN:
+ ret.mass = 3957 * CV.LB_TO_KG + STD_CARGO_KG
+ else:
+ ret.mass = 4537 * CV.LB_TO_KG + STD_CARGO_KG
# Genesis
elif candidate == CAR.GENESIS_GV60_EV_1ST_GEN:
diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py
index 1a81e1b167..229ca992d5 100644
--- a/selfdrive/car/hyundai/values.py
+++ b/selfdrive/car/hyundai/values.py
@@ -105,6 +105,7 @@ class CAR:
KIA_SELTOS = "KIA SELTOS 2021"
KIA_SPORTAGE_5TH_GEN = "KIA SPORTAGE 5TH GEN"
KIA_SORENTO = "KIA SORENTO GT LINE 2018"
+ KIA_SORENTO_4TH_GEN = "KIA SORENTO 4TH GEN"
KIA_SORENTO_PHEV_4TH_GEN = "KIA SORENTO PLUG-IN HYBRID 4TH GEN"
KIA_SPORTAGE_HYBRID_5TH_GEN = "KIA SPORTAGE HYBRID 5TH GEN"
KIA_STINGER = "KIA STINGER GT2 2018"
@@ -211,7 +212,8 @@ CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = {
HyundaiCarInfo("Kia Sorento 2018", "Advanced Smart Cruise Control", "https://www.youtube.com/watch?v=Fkh3s6WHJz8", harness=Harness.hyundai_c),
HyundaiCarInfo("Kia Sorento 2019", video_link="https://www.youtube.com/watch?v=Fkh3s6WHJz8", harness=Harness.hyundai_e),
],
- CAR.KIA_SORENTO_PHEV_4TH_GEN: HyundaiCarInfo("Kia Sorento Plug-in Hybrid 2022-23", "Smart Cruise Control (SCC)", harness=Harness.hyundai_a),
+ CAR.KIA_SORENTO_4TH_GEN: HyundaiCarInfo("Kia Sorento 2022-23", harness=Harness.hyundai_k),
+ CAR.KIA_SORENTO_PHEV_4TH_GEN: HyundaiCarInfo("Kia Sorento Plug-in Hybrid 2022-23", harness=Harness.hyundai_a),
CAR.KIA_SPORTAGE_HYBRID_5TH_GEN: HyundaiCarInfo("Kia Sportage Hybrid 2023", harness=Harness.hyundai_n),
CAR.KIA_STINGER: HyundaiCarInfo("Kia Stinger 2018-20", video_link="https://www.youtube.com/watch?v=MJ94qoofYw0", harness=Harness.hyundai_c),
CAR.KIA_STINGER_2022: HyundaiCarInfo("Kia Stinger 2022", "All", harness=Harness.hyundai_k),
@@ -1543,6 +1545,14 @@ FW_VERSIONS = {
b'\xf1\x00JW1_ RDR ----- 1.00 1.00 99110-CU000 ',
],
},
+ CAR.KIA_SORENTO_4TH_GEN: {
+ (Ecu.fwdCamera, 0x7c4, None): [
+ b'\xf1\x00MQ4 MFC AT USA LHD 1.00 1.05 99210-R5000 210623',
+ ],
+ (Ecu.fwdRadar, 0x7d0, None): [
+ b'\xf1\x00MQ4_ SCC FHCUP 1.00 1.06 99110-P2000 ',
+ ],
+ },
}
CHECKSUM = {
@@ -1560,10 +1570,10 @@ FEATURES = {
"use_fca": {CAR.SONATA, CAR.SONATA_HYBRID, CAR.ELANTRA, CAR.ELANTRA_2021, CAR.ELANTRA_HEV_2021, CAR.KIA_STINGER, CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.KONA_EV, CAR.KIA_FORTE, CAR.KIA_NIRO_EV, CAR.PALISADE, CAR.GENESIS_G70, CAR.GENESIS_G70_2020, CAR.KONA, CAR.SANTA_FE, CAR.KIA_SELTOS, CAR.KONA_HEV, CAR.SANTA_FE_2022, CAR.KIA_K5_2021, CAR.IONIQ_HEV_2022, CAR.SANTA_FE_HEV_2022, CAR.SANTA_FE_PHEV_2022, CAR.TUCSON, CAR.KONA_EV_2022, CAR.KIA_STINGER_2022},
}
-CANFD_CAR = {CAR.KIA_EV6, CAR.IONIQ_5, CAR.TUCSON_4TH_GEN, CAR.TUCSON_HYBRID_4TH_GEN, CAR.KIA_SPORTAGE_HYBRID_5TH_GEN, CAR.SANTA_CRUZ_1ST_GEN, CAR.KIA_SPORTAGE_5TH_GEN, CAR.GENESIS_GV70_1ST_GEN, CAR.KIA_SORENTO_PHEV_4TH_GEN, CAR.GENESIS_GV60_EV_1ST_GEN}
+CANFD_CAR = {CAR.KIA_EV6, CAR.IONIQ_5, CAR.TUCSON_4TH_GEN, CAR.TUCSON_HYBRID_4TH_GEN, CAR.KIA_SPORTAGE_HYBRID_5TH_GEN, CAR.SANTA_CRUZ_1ST_GEN, CAR.KIA_SPORTAGE_5TH_GEN, CAR.GENESIS_GV70_1ST_GEN, CAR.KIA_SORENTO_PHEV_4TH_GEN, CAR.GENESIS_GV60_EV_1ST_GEN, CAR.KIA_SORENTO_4TH_GEN}
# The radar does SCC on these cars when HDA I, rather than the camera
-CANFD_RADAR_SCC_CAR = {CAR.GENESIS_GV70_1ST_GEN, CAR.KIA_SORENTO_PHEV_4TH_GEN}
+CANFD_RADAR_SCC_CAR = {CAR.GENESIS_GV70_1ST_GEN, CAR.KIA_SORENTO_PHEV_4TH_GEN, CAR.KIA_SORENTO_4TH_GEN}
# The camera does SCC on these cars, rather than the radar
CAMERA_SCC_CAR = {CAR.KONA_EV_2022, }
@@ -1628,4 +1638,5 @@ DBC = {
CAR.GENESIS_GV70_1ST_GEN: dbc_dict('hyundai_canfd', None),
CAR.KIA_SORENTO_PHEV_4TH_GEN: dbc_dict('hyundai_canfd', None),
CAR.GENESIS_GV60_EV_1ST_GEN: dbc_dict('hyundai_canfd', None),
+ CAR.KIA_SORENTO_4TH_GEN: dbc_dict('hyundai_canfd', None),
}
diff --git a/selfdrive/car/tests/routes.py b/selfdrive/car/tests/routes.py
index 3edc406e19..ac0521cc68 100644
--- a/selfdrive/car/tests/routes.py
+++ b/selfdrive/car/tests/routes.py
@@ -100,6 +100,7 @@ routes = [
CarTestRoute("db68bbe12250812c|2022-12-05--00-54-12", HYUNDAI.TUCSON_4TH_GEN), # 2023
CarTestRoute("36e10531feea61a4|2022-07-25--13-37-42", HYUNDAI.TUCSON_HYBRID_4TH_GEN),
CarTestRoute("5875672fc1d4bf57|2020-07-23--21-33-28", HYUNDAI.KIA_SORENTO),
+ CarTestRoute("1d0d000db3370fd0|2023-01-04--22-28-42", HYUNDAI.KIA_SORENTO_4TH_GEN, segment=5),
CarTestRoute("628935d7d3e5f4f7|2022-11-30--01-12-46", HYUNDAI.KIA_SORENTO_PHEV_4TH_GEN),
CarTestRoute("9c917ba0d42ffe78|2020-04-17--12-43-19", HYUNDAI.PALISADE),
CarTestRoute("05a8f0197fdac372|2022-10-19--14-14-09", HYUNDAI.IONIQ_5), # HDA2
diff --git a/selfdrive/car/torque_data/override.yaml b/selfdrive/car/torque_data/override.yaml
index d7b2ec4079..3a9f92c046 100644
--- a/selfdrive/car/torque_data/override.yaml
+++ b/selfdrive/car/torque_data/override.yaml
@@ -36,6 +36,7 @@ KIA SPORTAGE HYBRID 5TH GEN: [2.5, 2.5, 0.1]
GENESIS GV70 1ST GEN: [2.42, 2.42, 0.1]
KIA SORENTO PLUG-IN HYBRID 4TH GEN: [2.5, 2.5, 0.1]
GENESIS GV60 ELECTRIC 1ST GEN: [2.5, 2.5, 0.1]
+KIA SORENTO 4TH GEN: [2.5, 2.5, 0.1]
# Dashcam or fallback configured as ideal car
mock: [10.0, 10, 0.0]
From f3fa4d759d5967e8590492005b8ede8bd17a6981 Mon Sep 17 00:00:00 2001
From: Dean Lee
Date: Thu, 12 Jan 2023 13:21:11 +0800
Subject: [PATCH 062/484] cabana: fix find similar bits (#26918)
* dynamic find bit
* change
* Revert "change"
This reverts commit 12cf513e2725a52ee40b8999521adcd6ecb00221.
* change sorting and headers
* make perc a float
Co-authored-by: Shane Smiskol
---
tools/cabana/tools/findsimilarbits.cc | 44 ++++++++++++++++++++-------
tools/cabana/tools/findsimilarbits.h | 9 ++++--
2 files changed, 39 insertions(+), 14 deletions(-)
diff --git a/tools/cabana/tools/findsimilarbits.cc b/tools/cabana/tools/findsimilarbits.cc
index 5fa5bcf7b8..cb5dbc0845 100644
--- a/tools/cabana/tools/findsimilarbits.cc
+++ b/tools/cabana/tools/findsimilarbits.cc
@@ -25,14 +25,28 @@ FindSimilarBitsDlg::FindSimilarBitsDlg(QWidget *parent) : QDialog(parent) {
}
bus_combo->model()->sort(0);
bus_combo->setCurrentIndex(0);
+
+ msg_cb = new QComboBox(this);
+ for (auto &[address, msg] : dbc()->messages()) {
+ msg_cb->addItem(msg.name, address);
+ }
+ msg_cb->model()->sort(0);
+ msg_cb->setCurrentIndex(0);
+
+ byte_idx_sb = new QSpinBox(this);
+ byte_idx_sb->setRange(0, 63);
+
+ bit_idx_sb = new QSpinBox(this);
+ bit_idx_sb->setRange(0, 7);
+
form_layout->addWidget(new QLabel("Bus"));
form_layout->addWidget(bus_combo);
+ form_layout->addWidget(msg_cb);
+ form_layout->addWidget(new QLabel("Byte Index"));
+ form_layout->addWidget(byte_idx_sb);
+ form_layout->addWidget(new QLabel("Bit Index"));
+ form_layout->addWidget(bit_idx_sb);
- bit_combo = new QComboBox(this);
- bit_combo->addItems({"0", "1"});
- bit_combo->setCurrentIndex(1);
- form_layout->addWidget(new QLabel("Bit"));
- form_layout->addWidget(bit_combo);
min_msgs = new QLineEdit(this);
min_msgs->setValidator(new QIntValidator(this));
@@ -56,10 +70,11 @@ FindSimilarBitsDlg::FindSimilarBitsDlg(QWidget *parent) : QDialog(parent) {
void FindSimilarBitsDlg::find() {
search_btn->setEnabled(false);
table->clear();
- auto msg_mismatched = calcBits(bus_combo->currentText().toUInt(), bit_combo->currentIndex(), min_msgs->text().toInt());
+ uint32_t selected_address = msg_cb->currentData().toUInt();
+ auto msg_mismatched = calcBits(bus_combo->currentText().toUInt(), selected_address, byte_idx_sb->value(), bit_idx_sb->value(), min_msgs->text().toInt());
table->setRowCount(msg_mismatched.size());
table->setColumnCount(6);
- table->setHorizontalHeaderLabels({"address", "byte idx", "bit idx", "mismatches", "total", "perc%"});
+ table->setHorizontalHeaderLabels({"address", "byte idx", "bit idx", "mismatches", "total msgs", "% mismatched"});
for (int i = 0; i < msg_mismatched.size(); ++i) {
auto &m = msg_mismatched[i];
table->setItem(i, 0, new QTableWidgetItem(QString("%1").arg(m.address, 1, 16)));
@@ -72,18 +87,25 @@ void FindSimilarBitsDlg::find() {
search_btn->setEnabled(true);
}
-QList FindSimilarBitsDlg::calcBits(uint8_t bus, int bit_to_find, int min_msgs_cnt) {
+QList FindSimilarBitsDlg::calcBits(uint8_t bus, uint32_t selected_address, int byte_idx, int bit_idx, int min_msgs_cnt) {
QHash> mismatches;
QHash msg_count;
auto events = can->events();
+ qDebug() << bus << selected_address << byte_idx << bit_idx;
+ int bit_to_find = -1;
for (auto e : *events) {
if (e->which == cereal::Event::Which::CAN) {
for (const auto &c : e->event.getCan()) {
if (c.getSrc() == bus) {
+ const auto dat = c.getDat();
uint32_t address = c.getAddress();
+ if (address == selected_address && dat.size() > byte_idx) {
+ bit_to_find = ((dat[byte_idx] >> (7 - bit_idx)) & 1) != 0;
+ }
++msg_count[address];
+ if (bit_to_find == -1) continue;
+
auto &mismatched = mismatches[address];
- const auto dat = c.getDat();
if (mismatched.size() < dat.size() * 8) {
mismatched.resize(dat.size() * 8);
}
@@ -104,12 +126,12 @@ QList FindSimilarBitsDlg::calcBits(uint8_
if (auto cnt = msg_count[it.key()]; cnt > min_msgs_cnt) {
auto &mismatched = it.value();
for (int i = 0; i < mismatched.size(); ++i) {
- if (uint32_t perc = (mismatched[i] / (double)cnt) * 100; perc < 50) {
+ if (float perc = (mismatched[i] / (double)cnt) * 100; perc < 50) {
result.push_back({it.key(), (uint32_t)i / 8, (uint32_t)i % 8, mismatched[i], cnt, perc});
}
}
}
}
- std::sort(result.begin(), result.end(), [](auto &l, auto &r) { return l.perc > r.perc; });
+ std::sort(result.begin(), result.end(), [](auto &l, auto &r) { return l.perc < r.perc; });
return result;
}
diff --git a/tools/cabana/tools/findsimilarbits.h b/tools/cabana/tools/findsimilarbits.h
index 79db4a1c69..8083999909 100644
--- a/tools/cabana/tools/findsimilarbits.h
+++ b/tools/cabana/tools/findsimilarbits.h
@@ -3,6 +3,7 @@
#include
#include
#include
+#include
#include
class FindSimilarBitsDlg : public QDialog {
@@ -11,13 +12,15 @@ public:
private:
struct mismatched_struct {
- uint32_t address, byte_idx, bit_idx, mismatches, total, perc;
+ uint32_t address, byte_idx, bit_idx, mismatches, total;
+ float perc;
};
- QList calcBits(uint8_t bus, int bit_to_find, int min_msgs_cnt);
+ QList calcBits(uint8_t bus, uint32_t selected_address, int byte_idx, int bit_idx, int min_msgs_cnt);
void find();
QTableWidget *table;
- QComboBox *bus_combo, *bit_combo;
+ QComboBox *bus_combo, *msg_cb;
+ QSpinBox *byte_idx_sb, *bit_idx_sb;
QPushButton *search_btn;
QLineEdit *min_msgs;
};
From a0f55f72fcc119f7a2ff902c1e347b3779c2c318 Mon Sep 17 00:00:00 2001
From: Kurt Nistelberger
Date: Wed, 11 Jan 2023 22:31:25 -0800
Subject: [PATCH 063/484] increase nav default marker
---
selfdrive/assets/navigation/default_marker.svg | 2 +-
1 file changed, 1 insertion(+), 1 deletion(-)
diff --git a/selfdrive/assets/navigation/default_marker.svg b/selfdrive/assets/navigation/default_marker.svg
index 116a45e251..43d5290a96 100644
--- a/selfdrive/assets/navigation/default_marker.svg
+++ b/selfdrive/assets/navigation/default_marker.svg
@@ -1,5 +1,5 @@
-