Merge remote-tracking branch 'upstream/master' into civic22_long

pull/25364/head
royjr 3 years ago
commit 42ecea714b
  1. 11
      SConstruct
  2. 5
      selfdrive/assets/img_couch.svg
  3. 2
      selfdrive/car/gm/values.py
  4. 2
      selfdrive/modeld/models/supercombo.onnx
  5. 2
      selfdrive/test/process_replay/model_replay_ref_commit
  6. 1
      selfdrive/ui/qt/offroad/experimental_mode.cc
  7. 18
      selfdrive/ui/translations/main_ko.ts
  8. 108
      tools/cabana/binaryview.cc
  9. 5
      tools/cabana/binaryview.h
  10. 6
      tools/cabana/canmessages.h
  11. 341
      tools/cabana/chartswidget.cc
  12. 56
      tools/cabana/chartswidget.h
  13. 9
      tools/cabana/dbcmanager.cc
  14. 1
      tools/cabana/dbcmanager.h
  15. 20
      tools/cabana/detailwidget.cc
  16. 1
      tools/cabana/detailwidget.h
  17. 4
      tools/cabana/mainwin.cc
  18. 2
      tools/cabana/settings.cc
  19. 2
      tools/cabana/settings.h
  20. 21
      tools/cabana/signaledit.cc
  21. 4
      tools/cabana/signaledit.h

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

@ -1,3 +1,4 @@
<svg width="598" height="598" viewBox="0 0 598 598" fill="none" xmlns="http://www.w3.org/2000/svg">
<path d="M523.25 236.708H510.792V174.417C511.555 158.737 506.091 143.391 495.59 131.723C485.089 120.055 470.401 113.011 454.729 112.125H143.271C127.599 113.011 112.911 120.055 102.409 131.723C91.9096 143.391 86.4454 158.737 87.2083 174.417V236.708H74.75C64.8416 236.72 55.3404 240.66 48.3343 247.668C41.3268 254.674 37.3865 264.175 37.375 274.083V398.667C37.3867 408.575 41.3266 418.076 48.3343 425.082C55.3404 432.09 64.8416 436.03 74.75 436.042H87.2083V473.417C87.2083 477.867 89.5832 481.98 93.4375 484.207C97.2918 486.432 102.042 486.432 105.896 484.207C109.75 481.98 112.125 477.866 112.125 473.417V436.042H485.875V473.417C485.875 477.867 488.25 481.98 492.104 484.207C495.958 486.432 500.708 486.432 504.563 484.207C508.417 481.98 510.792 477.866 510.792 473.417V436.042H523.25C533.158 436.03 542.66 432.09 549.666 425.082C556.673 418.076 560.614 408.575 560.625 398.667V274.083C560.613 264.175 556.673 254.674 549.666 247.668C542.66 240.66 533.158 236.72 523.25 236.708ZM143.271 137.042H454.729C463.783 137.949 472.117 142.373 477.941 149.364C483.765 156.352 486.615 165.349 485.875 174.417V239.006C478.608 241.565 472.313 246.311 467.851 252.593C463.39 258.873 460.982 266.381 460.958 274.086V336.377H137.042V274.086C137.018 266.381 134.61 258.873 130.149 252.593C125.687 246.312 119.392 241.566 112.125 239.006V174.417C111.385 165.349 114.235 156.352 120.059 149.364C125.884 142.374 134.217 137.949 143.271 137.042V137.042ZM62.2917 398.667V274.083C62.2936 270.78 63.6076 267.613 65.9435 265.277C68.2794 262.941 71.4466 261.627 74.7501 261.625H99.6667C102.97 261.627 106.137 262.941 108.473 265.277C110.809 267.613 112.123 270.78 112.125 274.083V411.125H74.7501C71.4467 411.123 68.2797 409.809 65.9436 407.473C63.6074 405.137 62.2937 401.97 62.2917 398.667L62.2917 398.667ZM137.042 361.292H460.958V411.125H137.042V361.292ZM535.708 398.667C535.706 401.97 534.392 405.137 532.056 407.473C529.721 409.809 526.553 411.123 523.25 411.125H485.875V274.083C485.877 270.78 487.191 267.613 489.527 265.277C491.863 262.941 495.03 261.627 498.333 261.625H523.25C526.553 261.627 529.72 262.941 532.057 265.277C534.393 267.613 535.706 270.78 535.708 274.083L535.708 398.667Z" fill="black" fill-opacity="0.4"/>
<?xml version="1.0" encoding="utf-8"?>
<svg viewBox="0 0 300 300" xmlns="http://www.w3.org/2000/svg">
<path d="M 278.364 122.673 C 282.129 126.545 284.418 132.064 284.5 137.465 L 284.5 200.562 C 284.419 205.963 282.129 211.48 278.364 215.352 C 274.492 219.119 268.972 221.407 263.571 221.488 L 259.262 221.488 L 259.262 238.417 C 259.128 241.171 257.425 244.12 255.107 245.614 C 252.655 246.875 249.249 246.874 246.796 245.613 C 244.48 244.12 242.777 241.171 242.643 238.417 L 242.643 221.488 L 57.357 221.488 L 57.357 238.417 C 57.223 241.171 55.519 244.121 53.203 245.614 C 50.75 246.875 47.344 246.875 44.892 245.614 C 42.575 244.12 40.872 241.171 40.738 238.417 L 40.738 221.488 L 36.427 221.488 C 31.027 221.407 25.508 219.119 21.636 215.352 C 17.871 211.48 15.582 205.961 15.5 200.56 L 15.5 137.463 C 15.581 132.062 17.871 126.545 21.636 122.673 C 25.508 118.906 31.029 116.618 36.429 116.536 L 40.738 116.536 L 40.738 87.024 C 40.426 78.719 43.434 70.271 48.95 64.028 C 54.579 57.887 62.818 53.986 71.131 53.441 L 228.982 53.444 C 237.295 53.989 245.421 57.888 251.05 64.028 C 256.566 70.272 259.574 78.719 259.262 87.024 L 259.262 116.536 L 263.573 116.536 C 268.974 116.618 274.492 118.906 278.364 122.673 Z M 60.911 75.581 C 58.147 78.782 56.932 82.617 57.35 86.825 L 57.357 118.356 C 60.791 119.893 63.643 122.022 66.115 125.423 C 68.512 128.877 69.916 133.256 69.976 137.46 L 69.976 167.014 L 230.024 167.014 L 230.024 137.466 C 230.084 133.262 231.488 128.877 233.884 125.423 C 236.357 122.021 239.208 119.892 242.643 118.356 L 242.643 86.988 C 243.06 82.779 241.852 78.782 239.089 75.581 C 236.438 72.283 232.951 70.432 228.785 70.059 L 71.215 70.059 C 67.049 70.433 63.563 72.283 60.911 75.581 Z M 33.383 203.605 C 34.241 204.572 35.14 204.944 36.431 204.87 L 53.357 204.87 L 53.357 137.465 C 53.432 136.174 53.06 135.278 52.093 134.42 C 51.236 133.454 50.336 133.08 49.046 133.155 L 36.429 133.155 C 35.139 133.08 34.295 133.506 33.382 134.419 C 32.47 135.332 32.044 136.176 32.119 137.466 L 32.119 200.56 C 32.044 201.851 32.416 202.747 33.383 203.605 Z M 69.976 204.87 L 230.024 204.87 L 230.024 183.631 L 69.976 183.631 L 69.976 204.87 Z M 267.881 137.465 C 267.956 136.174 267.584 135.278 266.618 134.419 C 265.758 133.453 264.86 133.08 263.57 133.155 L 250.953 133.155 C 249.663 133.08 248.766 133.452 247.908 134.419 C 246.941 135.277 246.568 136.176 246.643 137.466 L 246.643 204.87 L 263.571 204.87 C 264.862 204.944 265.759 204.572 266.616 203.606 C 267.583 202.748 267.956 201.849 267.881 200.559 L 267.881 137.465 Z" fill="black" style="stroke-width: 4px; vector-effect: non-scaling-stroke; fill-opacity: 0.4;"/>
</svg>

Before

Width:  |  Height:  |  Size: 2.3 KiB

After

Width:  |  Height:  |  Size: 2.6 KiB

@ -100,7 +100,7 @@ CAR_INFO: Dict[str, Union[GMCarInfo, List[GMCarInfo]]] = {
CAR.BOLT_EUV: GMCarInfo("Chevrolet Bolt EUV 2022-23", "Premier or Premier Redline Trim without Super Cruise Package", "https://youtu.be/xvwzGMUA210", footnotes=[], harness=Harness.gm),
CAR.SILVERADO: [
GMCarInfo("Chevrolet Silverado 1500 2020-21", "Safety Package II", footnotes=[], harness=Harness.gm),
GMCarInfo("GMC Sierra 1500 2020-21", "Driver Alert Package II", footnotes=[], harness=Harness.gm),
GMCarInfo("GMC Sierra 1500 2020-21", "Driver Alert Package II", "https://youtu.be/5HbNoBLzRwE", footnotes=[], harness=Harness.gm),
],
CAR.EQUINOX: GMCarInfo("Chevrolet Equinox 2019-22", footnotes=[], harness=Harness.gm),
}

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

@ -1 +1 @@
30efb4238327d723e17a3bda7e7c19c18f8a3b18
ca02aa240e629920ad88a6510213cb0a153af92b

@ -3,6 +3,7 @@
#include <QDebug>
#include <QHBoxLayout>
#include <QPainter>
#include <QPainterPath>
#include <QStyle>
#include "selfdrive/ui/ui.h"

@ -285,11 +285,11 @@
<name>ExperimentalModeButton</name>
<message>
<source>EXPERIMENTAL MODE ON</source>
<translation type="unfinished"></translation>
<translation> </translation>
</message>
<message>
<source>CHILL MODE ON</source>
<translation type="unfinished"></translation>
<translation> </translation>
</message>
</context>
<context>
@ -875,7 +875,7 @@ location set</source>
</message>
<message>
<source>Uninstall</source>
<translation></translation>
<translation></translation>
</message>
</context>
<context>
@ -1015,15 +1015,15 @@ location set</source>
</message>
<message>
<source>On this car, openpilot defaults to the car&apos;s built-in ACC instead of openpilot&apos;s longitudinal control. Enable this to switch to openpilot longitudinal control. Enabling Experimental mode is recommended when using experimental openpilot longitudinal control.</source>
<translation type="unfinished"></translation>
<translation> openpilot ACC로 . openpilot . openpilot .</translation>
</message>
<message>
<source>Experimental mode is currently unavailable on this car, since the car&apos;s stock ACC is used for longitudinal control.</source>
<translation type="unfinished"></translation>
<translation> ACC가 .</translation>
</message>
<message>
<source>Enable experimental longitudinal control to allow experimental mode.</source>
<translation type="unfinished"></translation>
<translation> .</translation>
</message>
<message>
<source>openpilot defaults to driving in &lt;b&gt;chill mode&lt;/b&gt;. Experimental mode enables &lt;b&gt;alpha-level features&lt;/b&gt; that aren&apos;t ready for chill mode. Experimental features are listed below:</source>
@ -1035,15 +1035,15 @@ location set</source>
</message>
<message>
<source>Let the driving model control the gas and brakes. openpilot will drive as it thinks a human would, including stopping for red lights and stop signs. Since the driving model decides the speed to drive, the set speed will only act as an upper bound. This is an alpha quality feature; mistakes should be expected.</source>
<translation type="unfinished"></translation>
<translation> . openpilot은 . . .</translation>
</message>
<message>
<source>New Driving Visualization</source>
<translation type="unfinished"></translation>
<translation> </translation>
</message>
<message>
<source>The driving visualization will transition to the road-facing wide-angle camera at low speeds to better show some turns. The Experimental mode logo will also be shown in the top right corner.</source>
<translation type="unfinished"></translation>
<translation> . .</translation>
</message>
</context>
<context>

@ -23,11 +23,13 @@ BinaryView::BinaryView(QWidget *parent) : QTableView(parent) {
delegate = new BinaryItemDelegate(this);
setItemDelegate(delegate);
horizontalHeader()->setSectionResizeMode(QHeaderView::Stretch);
verticalHeader()->setSectionsClickable(false);
horizontalHeader()->hide();
setHorizontalScrollBarPolicy(Qt::ScrollBarAlwaysOff);
setVerticalScrollBarPolicy(Qt::ScrollBarAlwaysOff);
setSizeAdjustPolicy(QAbstractScrollArea::AdjustToContents);
setFrameShape(QFrame::NoFrame);
setShowGrid(false);
setSizePolicy(QSizePolicy::Preferred, QSizePolicy::Minimum);
setMouseTracking(true);
}
@ -46,46 +48,30 @@ void BinaryView::setSelection(const QRect &rect, QItemSelectionModel::SelectionF
return;
QItemSelection selection;
auto [tl, br] = std::minmax(anchor_index, index);
if ((resize_sig && resize_sig->is_little_endian) || (!resize_sig && index < anchor_index)) {
// little_endian selection
if (tl.row() == br.row()) {
selection.merge({model->index(tl.row(), tl.column()), model->index(tl.row(), br.column())}, flags);
} else {
for (int row = tl.row(); row <= br.row(); ++row) {
int left_col = (row == br.row()) ? br.column() : 0;
int right_col = (row == tl.row()) ? tl.column() : 7;
selection.merge({model->index(row, left_col), model->index(row, right_col)}, flags);
}
}
} else {
// big endian selection
for (int row = tl.row(); row <= br.row(); ++row) {
int left_col = (row == tl.row()) ? tl.column() : 0;
int right_col = (row == br.row()) ? br.column() : 7;
selection.merge({model->index(row, left_col), model->index(row, right_col)}, flags);
}
auto [start, size, is_lb] = getSelection(index);
for (int i = start; i < start + size; ++i) {
auto idx = model->bitIndex(i, is_lb);
selection.merge({idx, idx}, flags);
}
selectionModel()->select(selection, flags);
}
void BinaryView::mousePressEvent(QMouseEvent *event) {
delegate->setSelectionColor(style()->standardPalette().color(QPalette::Active, QPalette::Highlight));
if (auto index = indexAt(event->pos()); index.isValid() && index.column() != 8) {
if (auto index = indexAt(event->pos()); index.isValid() && index.column() != 8) {
anchor_index = index;
auto item = (const BinaryViewModel::Item *)anchor_index.internalPointer();
if (item && item->sigs.size() > 0) {
int bit_idx = get_bit_index(anchor_index, true);
for (auto s : item->sigs) {
if (bit_idx == s->lsb || bit_idx == s->msb) {
resize_sig = s;
delegate->setSelectionColor(item->bg_color);
break;
}
int bit_idx = get_bit_index(anchor_index, true);
for (auto s : item->sigs) {
if (bit_idx == s->lsb || bit_idx == s->msb) {
anchor_index = model->bitIndex(bit_idx == s->lsb ? s->msb : s->lsb, true);
resize_sig = s;
delegate->setSelectionColor(item->bg_color);
break;
}
}
}
QTableView::mousePressEvent(event);
event->accept();
}
void BinaryView::mouseMoveEvent(QMouseEvent *event) {
@ -104,28 +90,14 @@ void BinaryView::mouseReleaseEvent(QMouseEvent *event) {
auto release_index = indexAt(event->pos());
if (release_index.isValid() && anchor_index.isValid()) {
if (release_index.column() == 8) {
release_index = model->index(release_index.row(), 7);
}
bool little_endian = (resize_sig && resize_sig->is_little_endian) || (!resize_sig && release_index < anchor_index);
int release_bit_idx = get_bit_index(release_index, little_endian);
int archor_bit_idx = get_bit_index(anchor_index, little_endian);
if (resize_sig) {
auto [sig_from, sig_to] = getSignalRange(resize_sig);
int start_bit, end_bit;
if (archor_bit_idx == sig_from) {
std::tie(start_bit, end_bit) = std::minmax(release_bit_idx, sig_to);
if (start_bit >= sig_from && start_bit <= sig_to)
start_bit = std::min(start_bit + 1, sig_to);
} else {
std::tie(start_bit, end_bit) = std::minmax(release_bit_idx, sig_from);
if (end_bit >= sig_from && end_bit <= sig_to)
end_bit = std::max(end_bit - 1, sig_from);
}
emit resizeSignal(resize_sig, start_bit, end_bit - start_bit + 1);
if (selectionModel()->hasSelection()) {
auto [start_bit, size, is_lb] = getSelection(release_index);
resize_sig ? emit resizeSignal(resize_sig, start_bit, size)
: emit addSignal(start_bit, size, is_lb);
} else {
auto [sart_bit, end_bit] = std::minmax(archor_bit_idx, release_bit_idx);
emit addSignal(sart_bit, end_bit - sart_bit + 1, little_endian);
auto item = (const BinaryViewModel::Item *)anchor_index.internalPointer();
if (item && item->sigs.size() > 0)
emit signalClicked(item->sigs.back());
}
}
clearSelection();
@ -156,6 +128,17 @@ QSet<const Signal *> BinaryView::getOverlappingSignals() const {
return overlapping;
}
std::tuple<int, int, bool> BinaryView::getSelection(QModelIndex index) {
if (index.column() == 8) {
index = model->index(index.row(), 7);
}
bool is_lb = (resize_sig && resize_sig->is_little_endian) || (!resize_sig && index < anchor_index);
int cur_bit_idx = get_bit_index(index, is_lb);
int anchor_bit_idx = get_bit_index(anchor_index, is_lb);
auto [start_bit, end_bit] = std::minmax(cur_bit_idx, anchor_bit_idx);
return {start_bit, end_bit - start_bit + 1, is_lb};
}
// BinaryViewModel
void BinaryViewModel::setMessage(const QString &message_id) {
@ -166,19 +149,19 @@ void BinaryViewModel::setMessage(const QString &message_id) {
row_count = dbc_msg->size;
items.resize(row_count * column_count);
int i = 0;
for (auto &[name, sig] : dbc_msg->sigs) {
auto [start, end] = getSignalRange(&sig);
for (auto sig : dbc_msg->getSignals()) {
auto [start, end] = getSignalRange(sig);
for (int j = start; j <= end; ++j) {
int bit_index = sig.is_little_endian ? bigEndianBitIndex(j) : j;
int bit_index = sig->is_little_endian ? bigEndianBitIndex(j) : j;
int idx = column_count * (bit_index / 8) + bit_index % 8;
if (idx >= items.size()) {
qWarning() << "signal " << name << "out of bounds.start_bit:" << sig.start_bit << "size:" << sig.size;
qWarning() << "signal " << sig->name.c_str() << "out of bounds.start_bit:" << sig->start_bit << "size:" << sig->size;
break;
}
if (j == start) sig.is_little_endian ? items[idx].is_lsb = true : items[idx].is_msb = true;
if (j == end) sig.is_little_endian ? items[idx].is_msb = true : items[idx].is_lsb = true;
if (j == start) sig->is_little_endian ? items[idx].is_lsb = true : items[idx].is_msb = true;
if (j == end) sig->is_little_endian ? items[idx].is_msb = true : items[idx].is_lsb = true;
items[idx].bg_color = getColor(i);
items[idx].sigs.push_back(&sig);
items[idx].sigs.push_back(sig);
}
++i;
}
@ -203,7 +186,7 @@ void BinaryViewModel::updateState() {
char hex[3] = {'\0'};
for (int i = 0; i < std::min(binary.size(), row_count); ++i) {
for (int j = 0; j < column_count - 1; ++j) {
items[i * column_count + j].val = QChar((binary[i] >> (7 - j)) & 1 ? '1' : '0');
items[i * column_count + j].val = ((binary[i] >> (7 - j)) & 1) != 0 ? '1' : '0';
}
hex[0] = toHex(binary[i] >> 4);
hex[1] = toHex(binary[i] & 0xf);
@ -250,17 +233,16 @@ void BinaryItemDelegate::paint(QPainter *painter, const QStyleOptionViewItem &op
painter->save();
// background
bool hover = item->sigs.contains(bin_view->hoveredSignal());
QColor bg_color = hover ? hoverColor(item->bg_color) : item->bg_color;
if (option.state & QStyle::State_Selected) {
bg_color = selection_color;
painter->fillRect(option.rect, selection_color);
} else if (!bin_view->selectionModel()->hasSelection() || !item->sigs.contains(bin_view->resize_sig)) {
painter->fillRect(option.rect, item->bg_color);
}
painter->fillRect(option.rect, bg_color);
// text
if (index.column() == 8) { // hex column
painter->setFont(hex_font);
} else if (hover) {
} else if (option.state & QStyle::State_Selected || (!bin_view->resize_sig && item->sigs.contains(bin_view->hovered_sig))) {
painter->setPen(Qt::white);
}
painter->drawText(option.rect, Qt::AlignCenter, item->val);

@ -32,6 +32,7 @@ public:
QVariant data(const QModelIndex &index, int role = Qt::DisplayRole) const { return {}; }
int rowCount(const QModelIndex &parent = QModelIndex()) const override { return row_count; }
int columnCount(const QModelIndex &parent = QModelIndex()) const override { return column_count; }
inline QModelIndex bitIndex(int bit, bool is_lb) const { return index(bit / 8, is_lb ? (7 - bit % 8) : bit % 8); }
QModelIndex index(int row, int column, const QModelIndex &parent = QModelIndex()) const override {
return createIndex(row, column, (void *)&items[row * column_count + column]);
}
@ -63,15 +64,16 @@ public:
void setMessage(const QString &message_id);
void highlight(const Signal *sig);
QSet<const Signal*> getOverlappingSignals() const;
inline const Signal *hoveredSignal() const { return hovered_sig; }
inline void updateState() { model->updateState(); }
signals:
void signalClicked(const Signal *sig);
void signalHovered(const Signal *sig);
void addSignal(int start_bit, int size, bool little_endian);
void resizeSignal(const Signal *sig, int from, int size);
private:
std::tuple<int, int, bool> getSelection(QModelIndex index);
void setSelection(const QRect &rect, QItemSelectionModel::SelectionFlags flags) override;
void mousePressEvent(QMouseEvent *event) override;
void mouseMoveEvent(QMouseEvent *event) override;
@ -83,4 +85,5 @@ private:
BinaryItemDelegate *delegate;
const Signal *resize_sig = nullptr;
const Signal *hovered_sig = nullptr;
friend class BinaryItemDelegate;
};

@ -80,11 +80,5 @@ inline const QString &getColor(int i) {
return SIGNAL_COLORS[i % std::size(SIGNAL_COLORS)];
}
inline QColor hoverColor(const QColor &color) {
QColor c = color.convertTo(QColor::Hsv);
c.setHsv(color.hue(), 180, 180);
return c;
}
// A global pointer referring to the unique CANMessages object
extern CANMessages *can;

@ -4,11 +4,9 @@
#include <QGraphicsLayout>
#include <QRubberBand>
#include <QTimer>
#include <QToolBar>
#include <QToolButton>
#include <QtCharts/QLineSeries>
#include <QtCharts/QValueAxis>
#include <QtConcurrent>
#include <QToolBar>
// ChartsWidget
@ -19,7 +17,7 @@ ChartsWidget::ChartsWidget(QWidget *parent) : QWidget(parent) {
// toolbar
QToolBar *toolbar = new QToolBar(tr("Charts"), this);
title_label = new QLabel();
title_label->setSizePolicy(QSizePolicy::Expanding,QSizePolicy::Preferred);
title_label->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Preferred);
toolbar->addWidget(title_label);
toolbar->addWidget(range_label = new QLabel());
reset_zoom_btn = toolbar->addAction("");
@ -42,21 +40,10 @@ ChartsWidget::ChartsWidget(QWidget *parent) : QWidget(parent) {
main_layout->addWidget(charts_scroll);
QObject::connect(dbc(), &DBCManager::DBCFileChanged, [this]() { removeAll(nullptr); });
QObject::connect(dbc(), &DBCManager::signalRemoved, this, &ChartsWidget::removeAll);
QObject::connect(dbc(), &DBCManager::signalUpdated, this, &ChartsWidget::signalUpdated);
QObject::connect(dbc(), &DBCManager::msgRemoved, [this](uint32_t address) {
for (auto c : charts.toVector())
if (DBCManager::parseId(c->id).second == address) removeChart(c);
});
QObject::connect(dbc(), &DBCManager::msgUpdated, [this](uint32_t address) {
for (auto c : charts) {
if (DBCManager::parseId(c->id).second == address) c->updateTitle();
}
});
QObject::connect(dbc(), &DBCManager::DBCFileChanged, this, &ChartsWidget::removeAll);
QObject::connect(can, &CANMessages::eventsMerged, this, &ChartsWidget::eventsMerged);
QObject::connect(can, &CANMessages::updated, this, &ChartsWidget::updateState);
QObject::connect(remove_all_btn, &QAction::triggered, [this]() { removeAll(); });
QObject::connect(remove_all_btn, &QAction::triggered, this, &ChartsWidget::removeAll);
QObject::connect(reset_zoom_btn, &QAction::triggered, this, &ChartsWidget::zoomReset);
QObject::connect(dock_btn, &QAction::triggered, [this]() {
emit dock(!docking);
@ -81,8 +68,8 @@ void ChartsWidget::zoomIn(double min, double max) {
zoomed_range = {min, max};
is_zoomed = zoomed_range != display_range;
updateToolBar();
emit rangeChanged(min, max, is_zoomed);
updateState();
emit rangeChanged(min, max, is_zoomed);
}
void ChartsWidget::zoomReset() {
@ -108,14 +95,14 @@ void ChartsWidget::updateState() {
if (prev_range != display_range) {
QFutureSynchronizer<void> future_synchronizer;
for (auto c : charts)
future_synchronizer.addFuture(QtConcurrent::run(c, &ChartView::updateSeries, display_range));
future_synchronizer.addFuture(QtConcurrent::run(c, &ChartView::setEventsRange, display_range));
}
}
const auto &range = is_zoomed ? zoomed_range : display_range;
for (auto c : charts) {
c->setRange(range.first, range.second);
c->updateLineMarker(current_sec);
c->setDisplayRange(range.first, range.second);
c->scene()->invalidate({}, QGraphicsScene::ForegroundLayer);
}
}
@ -128,49 +115,45 @@ void ChartsWidget::updateToolBar() {
dock_btn->setToolTip(docking ? tr("Undock charts") : tr("Dock charts"));
}
void ChartsWidget::showChart(const QString &id, const Signal *sig, bool show) {
auto it = std::find_if(charts.begin(), charts.end(), [=](auto c) { return c->id == id && c->signal == sig; });
if (it != charts.end()) {
if (!show) removeChart((*it));
} else if (show) {
auto chart = new ChartView(id, sig, this);
chart->updateSeries(display_range);
QObject::connect(chart, &ChartView::remove, [=]() { removeChart(chart); });
QObject::connect(chart, &ChartView::zoomIn, this, &ChartsWidget::zoomIn);
QObject::connect(chart, &ChartView::zoomReset, this, &ChartsWidget::zoomReset);
charts_layout->insertWidget(0, chart);
charts.push_back(chart);
emit chartOpened(chart->id, chart->signal);
ChartView *ChartsWidget::findChart(const QString &id, const Signal *sig) {
for (auto c : charts)
if (c->hasSeries(id, sig)) return c;
return nullptr;
}
void ChartsWidget::showChart(const QString &id, const Signal *sig, bool show, bool merge) {
if (!show) {
if (ChartView *chart = findChart(id, sig)) {
chart->removeSeries(id, sig);
}
} else {
ChartView *chart = merge && charts.size() > 0 ? charts.back() : nullptr;
if (!chart) {
chart = new ChartView(this);
chart->setEventsRange(display_range);
QObject::connect(chart, &ChartView::remove, [=]() { removeChart(chart); });
QObject::connect(chart, &ChartView::zoomIn, this, &ChartsWidget::zoomIn);
QObject::connect(chart, &ChartView::zoomReset, this, &ChartsWidget::zoomReset);
QObject::connect(chart, &ChartView::seriesRemoved, this, &ChartsWidget::chartClosed);
charts_layout->insertWidget(0, chart);
charts.push_back(chart);
}
chart->addSeries(id, sig);
emit chartOpened(id, sig);
updateState();
}
updateToolBar();
}
bool ChartsWidget::isChartOpened(const QString &id, const Signal *sig) {
auto it = std::find_if(charts.begin(), charts.end(), [=](auto c) { return c->id == id && c->signal == sig; });
return it != charts.end();
}
void ChartsWidget::removeChart(ChartView *chart) {
charts.removeOne(chart);
chart->deleteLater();
updateToolBar();
emit chartClosed(chart->id, chart->signal);
}
void ChartsWidget::removeAll(const Signal *sig) {
void ChartsWidget::removeAll() {
for (auto c : charts.toVector())
if (!sig || c->signal == sig) removeChart(c);
}
void ChartsWidget::signalUpdated(const Signal *sig) {
for (auto c : charts) {
if (c->signal == sig) {
c->updateTitle();
c->updateSeries(display_range);
c->setRange(display_range.first, display_range.second, true);
}
}
removeChart(c);
}
bool ChartsWidget::eventFilter(QObject *obj, QEvent *event) {
@ -183,21 +166,18 @@ bool ChartsWidget::eventFilter(QObject *obj, QEvent *event) {
// ChartView
ChartView::ChartView(const QString &id, const Signal *sig, QWidget *parent)
: id(id), signal(sig), QChartView(nullptr, parent) {
QLineSeries *series = new QLineSeries();
ChartView::ChartView(QWidget *parent) : QChartView(nullptr, parent) {
QChart *chart = new QChart();
chart->setBackgroundRoundness(0);
chart->addSeries(series);
chart->createDefaultAxes();
chart->legend()->hide();
axis_x = new QValueAxis(this);
axis_y = new QValueAxis(this);
chart->addAxis(axis_x, Qt::AlignBottom);
chart->addAxis(axis_y, Qt::AlignLeft);
chart->legend()->setShowToolTips(true);
chart->layout()->setContentsMargins(0, 0, 0, 0);
// top margin for title
chart->setMargins({0, 11, 0, 0});
line_marker = new QGraphicsLineItem(chart);
line_marker->setZValue(chart->zValue() + 10);
track_line = new QGraphicsLineItem(chart);
track_line->setPen(QPen(Qt::darkGray, 1, Qt::DashLine));
track_ellipse = new QGraphicsEllipseItem(chart);
@ -213,45 +193,125 @@ ChartView::ChartView(const QString &id, const Signal *sig, QWidget *parent)
remove_btn->setToolTip(tr("Remove Chart"));
close_btn_proxy = new QGraphicsProxyWidget(chart);
close_btn_proxy->setWidget(remove_btn);
close_btn_proxy->setZValue(chart->zValue() + 11);
setChart(chart);
setRenderHint(QPainter::Antialiasing);
setRubberBand(QChartView::HorizontalRubberBand);
updateFromSettings();
updateTitle();
QTimer *timer = new QTimer(this);
timer->setInterval(100);
timer->setSingleShot(true);
timer->callOnTimeout(this, &ChartView::adjustChartMargins);
QObject::connect(dbc(), &DBCManager::signalRemoved, this, &ChartView::signalRemoved);
QObject::connect(dbc(), &DBCManager::signalUpdated, this, &ChartView::signalUpdated);
QObject::connect(dbc(), &DBCManager::msgRemoved, this, &ChartView::msgRemoved);
QObject::connect(dbc(), &DBCManager::msgUpdated, this, &ChartView::msgUpdated);
QObject::connect(&settings, &Settings::changed, this, &ChartView::updateFromSettings);
QObject::connect(remove_btn, &QToolButton::clicked, [=]() { emit remove(id, sig); });
QObject::connect(remove_btn, &QToolButton::clicked, this, &ChartView::remove);
QObject::connect(chart, &QChart::plotAreaChanged, [=](const QRectF &plotArea) {
// use a singleshot timer to avoid recursion call.
timer->start();
});
}
ChartView::~ChartView() {
for (auto &s : sigs)
emit seriesRemoved(s.msg_id, s.sig);
}
void ChartView::addSeries(const QString &msg_id, const Signal *sig) {
QLineSeries *series = new QLineSeries(this);
chart()->addSeries(series);
series->attachAxis(axis_x);
series->attachAxis(axis_y);
auto [source, address] = DBCManager::parseId(msg_id);
sigs.push_back({.msg_id = msg_id, .address = address, .source = source, .sig = sig, .series = series});
updateTitle();
updateSeries(sig);
}
void ChartView::removeSeries(const QString &msg_id, const Signal *sig) {
auto it = std::find_if(sigs.begin(), sigs.end(), [&](auto &s) { return s.msg_id == msg_id && s.sig == sig; });
if (it != sigs.end()) {
it = removeSeries(it);
}
}
bool ChartView::hasSeries(const QString &msg_id, const Signal *sig) const {
auto it = std::find_if(sigs.begin(), sigs.end(), [&](auto &s) { return s.msg_id == msg_id && s.sig == sig; });
return it != sigs.end();
}
QList<ChartView::SigItem>::iterator ChartView::removeSeries(const QList<ChartView::SigItem>::iterator &it) {
chart()->removeSeries(it->series);
it->series->deleteLater();
emit seriesRemoved(it->msg_id, it->sig);
auto ret = sigs.erase(it);
if (!sigs.isEmpty()) {
updateAxisY();
} else {
emit remove();
}
return ret;
}
void ChartView::signalUpdated(const Signal *sig) {
auto it = std::find_if(sigs.begin(), sigs.end(), [=](auto &s) { return s.sig == sig; });
if (it != sigs.end()) {
updateTitle();
// TODO: don't update series if only name changed.
updateSeries(sig);
}
}
void ChartView::signalRemoved(const Signal *sig) {
for (auto it = sigs.begin(); it != sigs.end(); /**/) {
it = (it->sig == sig) ? removeSeries(it) : ++it;
}
}
void ChartView::msgUpdated(uint32_t address) {
auto it = std::find_if(sigs.begin(), sigs.end(), [=](auto &s) { return s.address == address; });
if (it != sigs.end())
updateTitle();
}
void ChartView::msgRemoved(uint32_t address) {
for (auto it = sigs.begin(); it != sigs.end(); /**/) {
it = (it->address == address) ? removeSeries(it) : ++it;
}
}
void ChartView::resizeEvent(QResizeEvent *event) {
QChartView::resizeEvent(event);
close_btn_proxy->setPos(event->size().width() - close_btn_proxy->size().width() - 11, 8);
}
void ChartView::updateTitle() {
chart()->setTitle(tr("<font color=\"gray\" text-align:left>%1 %2</font> <b>%3</b>").arg(dbc()->msg(id)->name).arg(id).arg(signal->name.c_str()));
for (auto &s : sigs) {
s.series->setName(QString("<b>%1</b> <font color=\"gray\">%2 %3</font>").arg(s.sig->name.c_str()).arg(msgName(s.msg_id)).arg(s.msg_id));
}
}
void ChartView::updateFromSettings() {
setFixedHeight(settings.chart_height);
chart()->setTheme(settings.chart_theme == 0 ? QChart::ChartThemeLight : QChart::QChart::ChartThemeDark);
auto color = chart()->titleBrush().color();
line_marker->setPen(QPen(color, 2));
}
void ChartView::setRange(double min, double max, bool force_update) {
auto axis_x = dynamic_cast<QValueAxis *>(chart()->axisX());
if (force_update || (min != axis_x->min() || max != axis_x->max())) {
void ChartView::setEventsRange(const std::pair<double, double> &range) {
if (range != events_range) {
events_range = range;
updateSeries();
}
}
void ChartView::setDisplayRange(double min, double max) {
if (min != axis_x->min() || max != axis_x->max()) {
axis_x->setRange(min, max);
updateAxisY();
}
@ -263,61 +323,75 @@ void ChartView::adjustChartMargins() {
if (chart()->plotArea().left() != aligned_pos) {
const float left_margin = chart()->margins().left() + aligned_pos - chart()->plotArea().left();
chart()->setMargins(QMargins(left_margin, 11, 0, 0));
updateLineMarker(can->currentSec());
}
}
void ChartView::updateLineMarker(double current_sec) {
auto axis_x = dynamic_cast<QValueAxis *>(chart()->axisX());
int x = chart()->plotArea().left() +
chart()->plotArea().width() * (current_sec - axis_x->min()) / (axis_x->max() - axis_x->min());
if (int(line_marker->line().x1()) != x) {
line_marker->setLine(x, chart()->plotArea().top() - chart()->margins().top() + 3, x, height());
}
}
void ChartView::updateSeries(const std::pair<double, double> range) {
void ChartView::updateSeries(const Signal *sig) {
auto events = can->events();
if (!events) return;
vals.clear();
vals.reserve((range.second - range.first) * 1000); // [n]seconds * 1000hz
auto [bus, address] = DBCManager::parseId(id);
double route_start_time = can->routeStartTime();
Event begin_event(cereal::Event::Which::INIT_DATA, (route_start_time + range.first) * 1e9);
auto begin = std::lower_bound(events->begin(), events->end(), &begin_event, Event::lessThan());
double end_ns = (route_start_time + range.second) * 1e9;
for (auto it = begin; it != events->end() && (*it)->mono_time <= end_ns; ++it) {
if ((*it)->which == cereal::Event::Which::CAN) {
for (const auto &c : (*it)->event.getCan()) {
if (bus == c.getSrc() && address == c.getAddress()) {
auto dat = c.getDat();
double value = get_raw_value((uint8_t *)dat.begin(), dat.size(), *signal);
double ts = ((*it)->mono_time / (double)1e9) - route_start_time; // seconds
vals.push_back({ts, value});
for (int i = 0; i < sigs.size(); ++i) {
if (auto &s = sigs[i]; !sig || s.sig == sig) {
s.vals.clear();
s.vals.reserve((events_range.second - events_range.first) * 1000); // [n]seconds * 1000hz
s.min_y = std::numeric_limits<double>::max();
s.max_y = std::numeric_limits<double>::lowest();
double route_start_time = can->routeStartTime();
Event begin_event(cereal::Event::Which::INIT_DATA, (route_start_time + events_range.first) * 1e9);
auto begin = std::lower_bound(events->begin(), events->end(), &begin_event, Event::lessThan());
double end_ns = (route_start_time + events_range.second) * 1e9;
for (auto it = begin; it != events->end() && (*it)->mono_time <= end_ns; ++it) {
if ((*it)->which == cereal::Event::Which::CAN) {
for (const auto &c : (*it)->event.getCan()) {
if (s.source == c.getSrc() && s.address == c.getAddress()) {
auto dat = c.getDat();
double value = get_raw_value((uint8_t *)dat.begin(), dat.size(), *s.sig);
double ts = ((*it)->mono_time / (double)1e9) - route_start_time; // seconds
s.vals.push_back({ts, value});
if (value < s.min_y) s.min_y = value;
if (value > s.max_y) s.max_y = value;
}
}
}
}
QLineSeries *series = (QLineSeries *)chart()->series()[i];
series->replace(s.vals);
}
}
QLineSeries *series = (QLineSeries *)chart()->series()[0];
series->replace(vals);
updateAxisY();
}
// auto zoom on yaxis
void ChartView::updateAxisY() {
const auto axis_x = dynamic_cast<QValueAxis *>(chart()->axisX());
const auto axis_y = dynamic_cast<QValueAxis *>(chart()->axisY());
auto begin = std::lower_bound(vals.begin(), vals.end(), axis_x->min(), [](auto &p, double x) { return p.x() < x; });
if (begin == vals.end())
return;
auto end = std::upper_bound(vals.begin(), vals.end(), axis_x->max(), [](double x, auto &p) { return x < p.x(); });
const auto [min, max] = std::minmax_element(begin, end, [](auto &p1, auto &p2) { return p1.y() < p2.y(); });
if (max->y() == min->y()) {
axis_y->setRange(min->y() - 1, max->y() + 1);
double min_y = std::numeric_limits<double>::max();
double max_y = std::numeric_limits<double>::lowest();
if (events_range == std::pair{axis_x->min(), axis_x->max()}) {
for (auto &s : sigs) {
if (s.min_y < min_y) min_y = s.min_y;
if (s.max_y > max_y) max_y = s.max_y;
}
} else {
for (auto &s : sigs) {
auto begin = std::lower_bound(s.vals.begin(), s.vals.end(), axis_x->min(), [](auto &p, double x) { return p.x() < x; });
if (begin == s.vals.end())
return;
auto end = std::upper_bound(s.vals.begin(), s.vals.end(), axis_x->max(), [](double x, auto &p) { return x < p.x(); });
const auto [min, max] = std::minmax_element(begin, end, [](auto &p1, auto &p2) { return p1.y() < p2.y(); });
if (min->y() < min_y) min_y = min->y();
if (max->y() > max_y) max_y = max->y();
}
}
if (max_y == min_y) {
axis_y->setRange(min_y - 1, max_y + 1);
} else {
double range = max->y() - min->y();
axis_y->setRange(min->y() - range * 0.05, max->y() + range * 0.05);
double range = max_y - min_y;
axis_y->setRange(min_y - range * 0.05, max_y + range * 0.05);
axis_y->applyNiceNumbers();
}
}
@ -333,7 +407,6 @@ void ChartView::mouseReleaseEvent(QMouseEvent *event) {
rubber->hide();
QRectF rect = rubber->geometry().normalized();
rect.translate(-chart()->plotArea().topLeft());
const auto axis_x = dynamic_cast<QValueAxis *>(chart()->axisX());
double min = axis_x->min() + (rect.left() / chart()->plotArea().width()) * (axis_x->max() - axis_x->min());
double max = axis_x->min() + (rect.right() / chart()->plotArea().width()) * (axis_x->max() - axis_x->min());
if (rubber->width() <= 0) {
@ -343,7 +416,6 @@ void ChartView::mouseReleaseEvent(QMouseEvent *event) {
// zoom in if selected range is greater than 0.5s
emit zoomIn(min, max);
}
viewport()->update();
event->accept();
} else if (event->button() == Qt::RightButton) {
emit zoomReset();
@ -351,33 +423,52 @@ void ChartView::mouseReleaseEvent(QMouseEvent *event) {
} else {
QGraphicsView::mouseReleaseEvent(event);
}
setViewportUpdateMode(QGraphicsView::MinimalViewportUpdate);
}
void ChartView::mouseMoveEvent(QMouseEvent *ev) {
auto rubber = findChild<QRubberBand *>();
bool is_zooming = rubber && rubber->isVisible();
if (!is_zooming) {
const auto plot_area = chart()->plotArea();
auto axis_x = dynamic_cast<QValueAxis *>(chart()->axisX());
const auto plot_area = chart()->plotArea();
if (!is_zooming && plot_area.contains(ev->pos())) {
double x = std::clamp((double)ev->pos().x(), plot_area.left(), plot_area.right() - 1);
double sec = axis_x->min() + (axis_x->max() - axis_x->min()) * (x - plot_area.left()) / plot_area.width();
auto value = std::upper_bound(vals.begin(), vals.end(), sec, [](double x, auto &p) { return x < p.x(); });
if (value != vals.end()) {
QPointF pos = chart()->mapToPosition((*value));
QStringList text_list;
QPointF pos = plot_area.bottomRight();
double tm = 0.0;
for (auto &s : sigs) {
auto value = std::upper_bound(s.vals.begin(), s.vals.end(), sec, [](double x, auto &p) { return x < p.x(); });
if (value != s.vals.end()) {
text_list.push_back(QString("&nbsp;%1 : %2&nbsp;").arg(sigs.size() > 1 ? s.sig->name.c_str() : "Value").arg(value->y()));
tm = value->x();
auto y_pos = chart()->mapToPosition(*value);
if (y_pos.y() < pos.y()) pos = y_pos;
}
}
if (!text_list.isEmpty()) {
value_text->setHtml("<div style=\"background-color: darkGray;color: white;\">&nbsp;Time: " +
QString::number(tm, 'f', 3) + "&nbsp;<br />" + text_list.join("<br />") + "</div>");
track_line->setLine(pos.x(), plot_area.top(), pos.x(), plot_area.bottom());
track_ellipse->setRect(pos.x() - 5, pos.y() - 5, 10, 10);
value_text->setHtml(tr("<div style='background-color:darkGray'><font color='white'>%1, %2)</font></div>")
.arg(value->x(), 0, 'f', 3).arg(value->y()));
int text_x = pos.x() + 8;
if ((text_x + value_text->boundingRect().width()) > plot_area.right()) {
text_x = pos.x() - value_text->boundingRect().width() - 8;
QRectF text_rect = value_text->boundingRect();
if ((text_x + text_rect.width()) > plot_area.right()) {
text_x = pos.x() - text_rect.width() - 8;
}
value_text->setPos(text_x, pos.y() - 10);
value_text->setPos(text_x, pos.y() - text_rect.height() / 2);
track_ellipse->setRect(pos.x() - 5, pos.y() - 5, 10, 10);
}
item_group->setVisible(value != vals.end());
item_group->setVisible(!text_list.isEmpty());
} else {
setViewportUpdateMode(QGraphicsView::FullViewportUpdate);
item_group->setVisible(false);
}
QChartView::mouseMoveEvent(ev);
}
void ChartView::drawForeground(QPainter *painter, const QRectF &rect) {
qreal x = chart()->plotArea().left() +
chart()->plotArea().width() * (can->currentSec() - axis_x->min()) / (axis_x->max() - axis_x->min());
painter->setPen(QPen(chart()->titleBrush().color(), 2));
painter->drawLine(QPointF{x, chart()->plotArea().top() - 2}, QPointF{x, chart()->plotArea().bottom() + 2});
}

@ -8,6 +8,8 @@
#include <QPushButton>
#include <QVBoxLayout>
#include <QtCharts/QChartView>
#include <QtCharts/QLineSeries>
#include <QtCharts/QValueAxis>
#include "tools/cabana/canmessages.h"
#include "tools/cabana/dbcmanager.h"
@ -18,35 +20,59 @@ class ChartView : public QChartView {
Q_OBJECT
public:
ChartView(const QString &id, const Signal *sig, QWidget *parent = nullptr);
void updateSeries(const std::pair<double, double> range);
void setRange(double min, double max, bool force_update = false);
void updateLineMarker(double current_sec);
void updateFromSettings();
void updateTitle();
ChartView(QWidget *parent = nullptr);
~ChartView();
void addSeries(const QString &msg_id, const Signal *sig);
void removeSeries(const QString &msg_id, const Signal *sig);
bool hasSeries(const QString &msg_id, const Signal *sig) const;
void updateSeries(const Signal *sig = nullptr);
void setEventsRange(const std::pair<double, double> &range);
void setDisplayRange(double min, double max);
QString id;
const Signal *signal;
struct SigItem {
QString msg_id;
uint8_t source = 0;
uint32_t address = 0;
const Signal *sig = nullptr;
QLineSeries *series = nullptr;
double min_y = 0;
double max_y = 0;
QVector<QPointF> vals;
};
signals:
void seriesRemoved(const QString &id, const Signal *sig);
void zoomIn(double min, double max);
void zoomReset();
void remove(const QString &msg_id, const Signal *sig);
void remove();
private slots:
void msgRemoved(uint32_t address);
void msgUpdated(uint32_t address);
void signalUpdated(const Signal *sig);
void signalRemoved(const Signal *sig);
private:
QList<ChartView::SigItem>::iterator removeSeries(const QList<ChartView::SigItem>::iterator &it);
void mouseReleaseEvent(QMouseEvent *event) override;
void mouseMoveEvent(QMouseEvent *ev) override;
void leaveEvent(QEvent *event) override;
void resizeEvent(QResizeEvent *event) override;
void adjustChartMargins();
void updateAxisY();
void updateTitle();
void updateFromSettings();
void drawForeground(QPainter *painter, const QRectF &rect) override;
QValueAxis *axis_x;
QValueAxis *axis_y;
QGraphicsItemGroup *item_group;
QGraphicsLineItem *line_marker, *track_line;
QGraphicsLineItem *track_line;
QGraphicsEllipseItem *track_ellipse;
QGraphicsTextItem *value_text;
QGraphicsProxyWidget *close_btn_proxy;
QVector<QPointF> vals;
std::pair<double, double> events_range = {0, 0};
QList<SigItem> sigs;
};
class ChartsWidget : public QWidget {
@ -54,9 +80,9 @@ class ChartsWidget : public QWidget {
public:
ChartsWidget(QWidget *parent = nullptr);
void showChart(const QString &id, const Signal *sig, bool show);
void showChart(const QString &id, const Signal *sig, bool show, bool merge);
void removeChart(ChartView *chart);
bool isChartOpened(const QString &id, const Signal *sig);
inline bool isChartOpened(const QString &id, const Signal *sig) { return findChart(id, sig) != nullptr; }
signals:
void dock(bool floating);
@ -69,10 +95,10 @@ private:
void updateState();
void zoomIn(double min, double max);
void zoomReset();
void signalUpdated(const Signal *sig);
void updateToolBar();
void removeAll(const Signal *sig = nullptr);
void removeAll();
bool eventFilter(QObject *obj, QEvent *event) override;
ChartView *findChart(const QString &id, const Signal *sig);
QLabel *title_label;
QLabel *range_label;

@ -107,6 +107,15 @@ DBCManager *dbc() {
return &dbc_manager;
}
// DBCMsg
std::vector<const Signal*> DBCMsg::getSignals() const {
std::vector<const Signal*> ret;
for (auto &[name, sig] : sigs) ret.push_back(&sig);
std::sort(ret.begin(), ret.end(), [](auto l, auto r) { return l->start_bit < r->start_bit; });
return ret;
}
// helper functions
static QVector<int> BIG_ENDIAN_START_BITS = []() {

@ -9,6 +9,7 @@ struct DBCMsg {
QString name;
uint32_t size;
std::map<QString, Signal> sigs;
std::vector<const Signal*> getSignals() const;
};
class DBCManager : public QObject {

@ -17,6 +17,7 @@
DetailWidget::DetailWidget(ChartsWidget *charts, QWidget *parent) : charts(charts), QWidget(parent) {
undo_stack = new QUndoStack(this);
setMinimumWidth(500);
QVBoxLayout *main_layout = new QVBoxLayout(this);
main_layout->setContentsMargins(0, 0, 0, 0);
main_layout->setSpacing(0);
@ -90,6 +91,7 @@ DetailWidget::DetailWidget(ChartsWidget *charts, QWidget *parent) : charts(chart
tab_widget->addTab(history_log, "Logs");
main_layout->addWidget(tab_widget);
QObject::connect(binary_view, &BinaryView::signalClicked, this, &DetailWidget::showForm);
QObject::connect(binary_view, &BinaryView::resizeSignal, this, &DetailWidget::resizeSignal);
QObject::connect(binary_view, &BinaryView::addSignal, this, &DetailWidget::addSignal);
QObject::connect(tab_widget, &QTabWidget::currentChanged, [this]() { updateState(); });
@ -149,7 +151,7 @@ void DetailWidget::dbcMsgChanged(int show_form_idx) {
QStringList warnings;
const DBCMsg *msg = dbc()->msg(msg_id);
if (msg) {
for (auto &[name, sig] : msg->sigs) {
for (auto sig : msg->getSignals()) {
SignalEdit *form = i < signal_list.size() ? signal_list[i] : nullptr;
if (!form) {
form = new SignalEdit(i);
@ -162,8 +164,8 @@ void DetailWidget::dbcMsgChanged(int show_form_idx) {
signals_layout->addWidget(form);
signal_list.push_back(form);
}
form->setSignal(msg_id, &sig);
form->setChartOpened(charts->isChartOpened(msg_id, &sig));
form->setSignal(msg_id, sig);
form->setChartOpened(charts->isChartOpened(msg_id, sig));
++i;
}
if (msg->size != can->lastMessage(msg_id).dat.size())
@ -197,9 +199,15 @@ void DetailWidget::updateState(const QHash<QString, CanData> * msgs) {
void DetailWidget::showFormClicked() {
auto s = qobject_cast<SignalEdit *>(sender());
showForm(s->sig);
}
void DetailWidget::showForm(const Signal *sig) {
setUpdatesEnabled(false);
for (auto f : signal_list)
f->updateForm(f == s && !f->isFormVisible());
for (auto f : signal_list) {
f->updateForm(f->sig == sig && !f->isFormVisible());
if (f->sig == sig) scroll->ensureWidgetVisible(f);
}
setUpdatesEnabled(true);
}
@ -235,7 +243,7 @@ void DetailWidget::addSignal(int start_bit, int size, bool little_endian) {
}
}
}
Signal sig = {.is_little_endian = little_endian};
Signal sig = {.is_little_endian = little_endian, .factor = 1};
for (int i = 1; /**/; ++i) {
sig.name = "NEW_SIGNAL_" + std::to_string(i);
if (msg->sigs.count(sig.name.c_str()) == 0) break;

@ -28,6 +28,7 @@ public:
QUndoStack *undo_stack = nullptr;
private:
void showForm(const Signal *sig);
void showFormClicked();
void updateChartState(const QString &id, const Signal *sig, bool opened);
void showTabBarContextMenu(const QPoint &pt);

@ -55,6 +55,9 @@ MainWindow::MainWindow() : QMainWindow() {
charts_widget = new ChartsWidget(this);
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
@ -247,6 +250,7 @@ void MainWindow::closeEvent(QCloseEvent *event) {
if (floating_window)
floating_window->deleteLater();
settings.splitter_state = splitter->saveState();
settings.save();
QWidget::closeEvent(event);
}

@ -21,6 +21,7 @@ void Settings::save() {
s.setValue("chart_theme", chart_theme);
s.setValue("max_chart_x_range", max_chart_x_range);
s.setValue("last_dir", last_dir);
s.setValue("splitter_state", splitter_state);
}
void Settings::load() {
@ -32,6 +33,7 @@ void Settings::load() {
chart_theme = s.value("chart_theme", 0).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();
}
// SettingsDlg

@ -1,5 +1,6 @@
#pragma once
#include <QByteArray>
#include <QComboBox>
#include <QDialog>
#include <QSpinBox>
@ -19,6 +20,7 @@ public:
int chart_theme = 0;
int max_chart_x_range = 3 * 60; // 3 minutes
QString last_dir;
QByteArray splitter_state;
signals:
void changed();

@ -2,6 +2,7 @@
#include <QDoubleValidator>
#include <QFormLayout>
#include <QGuiApplication>
#include <QHBoxLayout>
#include <QScrollArea>
#include <QToolBar>
@ -116,11 +117,18 @@ SignalEdit::SignalEdit(int index, QWidget *parent) : form_idx(index), QWidget(pa
hline->setFrameShadow(QFrame::Sunken);
main_layout->addWidget(hline);
save_timer = new QTimer(this);
save_timer->setInterval(300);
save_timer->setSingleShot(true);
save_timer->callOnTimeout(this, &SignalEdit::saveSignal);
QObject::connect(title, &ElidedLabel::clicked, this, &SignalEdit::showFormClicked);
QObject::connect(plot_btn, &QToolButton::clicked, [this](bool checked) { emit showChart(msg_id, sig, checked); });
QObject::connect(plot_btn, &QToolButton::clicked, [this](bool checked) {
emit showChart(msg_id, sig, checked, QGuiApplication::keyboardModifiers() & Qt::ShiftModifier);
});
QObject::connect(seek_btn, &QToolButton::clicked, [this]() { SignalFindDlg(msg_id, sig, this).exec(); });
QObject::connect(remove_btn, &QToolButton::clicked, [this]() { emit remove(sig); });
QObject::connect(form, &SignalForm::changed, this, &SignalEdit::saveSignal);
QObject::connect(form, &SignalForm::changed, [this]() { save_timer->start(); });
setSizePolicy(QSizePolicy::Preferred, QSizePolicy::Fixed);
}
@ -167,14 +175,16 @@ void SignalEdit::saveSignal() {
}
void SignalEdit::setChartOpened(bool opened) {
plot_btn->setToolTip(opened ? tr("Close Plot") : tr("Show Plot"));
plot_btn->setToolTip(opened ? tr("Close Plot") : tr("Show Plot\nSHIFT click to add to previous opened chart"));
plot_btn->setChecked(opened);
}
void SignalEdit::updateForm(bool visible) {
if (visible && sig) {
form->changed_by_user = false;
form->name->setText(sig->name.c_str());
if (form->name->text() != sig->name.c_str()) {
form->name->setText(sig->name.c_str());
}
form->endianness->setCurrentIndex(sig->is_little_endian ? 0 : 1);
form->sign->setCurrentIndex(sig->is_signed ? 0 : 1);
form->factor->setText(QString::number(sig->factor));
@ -189,9 +199,8 @@ void SignalEdit::updateForm(bool visible) {
}
void SignalEdit::signalHovered(const Signal *s) {
auto bg_color = sig == s ? hoverColor(getColor(form_idx)) : QColor(getColor(form_idx));
auto color = sig == s ? "white" : "black";
color_label->setStyleSheet(QString("color:%1; background-color:%2").arg(color).arg(bg_color.name()));
color_label->setStyleSheet(QString("color:%1; background-color:%2").arg(color).arg(getColor(form_idx)));
}
void SignalEdit::enterEvent(QEvent *event) {

@ -5,6 +5,7 @@
#include <QLabel>
#include <QLineEdit>
#include <QSpinBox>
#include <QTimer>
#include <QToolButton>
#include "selfdrive/ui/qt/widgets/controls.h"
@ -41,7 +42,7 @@ public:
signals:
void highlight(const Signal *sig);
void showChart(const QString &name, const Signal *sig, bool show);
void showChart(const QString &name, const Signal *sig, bool show, bool merge);
void remove(const Signal *sig);
void save(const Signal *sig, const Signal &new_sig);
void showFormClicked();
@ -57,6 +58,7 @@ protected:
QLabel *icon;
int form_idx = 0;
QToolButton *plot_btn;
QTimer *save_timer;
};
class SignalFindDlg : public QDialog {

Loading…
Cancel
Save