mirror of https://github.com/commaai/openpilot.git
cabana: supports switching streams on the fly (#28081)
* open stream
* use std::atomic::exchange
* emit streamStarted immediately
old-commit-hash: a26e6d1633
This commit is contained in:
parent
72c64ed1bc
commit
c1fecfb6dd
|
@ -1,7 +1,6 @@
|
|||
#include <QApplication>
|
||||
#include <QCommandLineParser>
|
||||
|
||||
#include "common/prefix.h"
|
||||
#include "selfdrive/ui/qt/util.h"
|
||||
#include "tools/cabana/mainwin.h"
|
||||
#include "tools/cabana/streamselector.h"
|
||||
|
@ -35,17 +34,15 @@ int main(int argc, char *argv[]) {
|
|||
|
||||
QString dbc_file = cmd_parser.isSet("dbc") ? cmd_parser.value("dbc") : "";
|
||||
|
||||
std::unique_ptr<OpenpilotPrefix> op_prefix;
|
||||
std::unique_ptr<AbstractStream> stream;
|
||||
|
||||
AbstractStream *stream = nullptr;
|
||||
if (cmd_parser.isSet("stream")) {
|
||||
stream.reset(new DeviceStream(&app, cmd_parser.value("zmq")));
|
||||
stream = new DeviceStream(&app, cmd_parser.value("zmq"));
|
||||
} else if (cmd_parser.isSet("panda") || cmd_parser.isSet("panda-serial")) {
|
||||
PandaStreamConfig config = {};
|
||||
if (cmd_parser.isSet("panda-serial")) {
|
||||
config.serial = cmd_parser.value("panda-serial");
|
||||
}
|
||||
stream.reset(new PandaStream(&app, config));
|
||||
stream = new PandaStream(&app, config);
|
||||
} else {
|
||||
uint32_t replay_flags = REPLAY_FLAG_NONE;
|
||||
if (cmd_parser.isSet("ecam")) {
|
||||
|
@ -65,36 +62,26 @@ int main(int argc, char *argv[]) {
|
|||
}
|
||||
|
||||
if (route.isEmpty()) {
|
||||
AbstractStream *out_stream = nullptr;
|
||||
StreamSelector dlg;
|
||||
dlg.addStreamWidget(ReplayStream::widget(&out_stream));
|
||||
dlg.addStreamWidget(PandaStream::widget(&out_stream));
|
||||
dlg.addStreamWidget(DeviceStream::widget(&out_stream));
|
||||
StreamSelector dlg(&stream);
|
||||
if (!dlg.exec()) {
|
||||
return 0;
|
||||
}
|
||||
dbc_file = dlg.dbcFile();
|
||||
stream.reset(out_stream);
|
||||
} else {
|
||||
// TODO: Remove when OpenpilotPrefix supports ZMQ
|
||||
#ifndef __APPLE__
|
||||
op_prefix.reset(new OpenpilotPrefix());
|
||||
#endif
|
||||
auto replay_stream = new ReplayStream(&app);
|
||||
stream.reset(replay_stream);
|
||||
if (!replay_stream->loadRoute(route, cmd_parser.value("data_dir"), replay_flags)) {
|
||||
return 0;
|
||||
}
|
||||
stream = replay_stream;
|
||||
}
|
||||
}
|
||||
|
||||
MainWindow w;
|
||||
|
||||
// Load DBC
|
||||
if (!dbc_file.isEmpty()) {
|
||||
w.loadFile(dbc_file);
|
||||
}
|
||||
|
||||
assert(stream != nullptr);
|
||||
stream->start();
|
||||
w.show();
|
||||
return app.exec();
|
||||
}
|
||||
|
|
|
@ -398,6 +398,7 @@ void ChartsWidget::removeAll() {
|
|||
tabbar->removeTab(1);
|
||||
}
|
||||
tab_charts.clear();
|
||||
zoomReset();
|
||||
|
||||
if (!charts.isEmpty()) {
|
||||
for (auto c : charts) {
|
||||
|
|
|
@ -124,4 +124,3 @@ public:
|
|||
ChartsWidget *charts;
|
||||
std::pair<double, double> prev_range, range;
|
||||
};
|
||||
|
||||
|
|
|
@ -5,6 +5,7 @@
|
|||
#include <QMessageBox>
|
||||
|
||||
#include "tools/cabana/commands.h"
|
||||
#include "tools/cabana/mainwin.h"
|
||||
|
||||
// DetailWidget
|
||||
|
||||
|
@ -218,7 +219,7 @@ void EditMessageDialog::validateName(const QString &text) {
|
|||
|
||||
// CenterWidget
|
||||
|
||||
CenterWidget::CenterWidget(ChartsWidget *charts, QWidget *parent) : charts(charts), QWidget(parent) {
|
||||
CenterWidget::CenterWidget(QWidget *parent) : QWidget(parent) {
|
||||
QVBoxLayout *main_layout = new QVBoxLayout(this);
|
||||
main_layout->setContentsMargins(0, 0, 0, 0);
|
||||
main_layout->addWidget(welcome_widget = createWelcomeWidget());
|
||||
|
@ -228,7 +229,7 @@ void CenterWidget::setMessage(const MessageId &msg_id) {
|
|||
if (!detail_widget) {
|
||||
delete welcome_widget;
|
||||
welcome_widget = nullptr;
|
||||
layout()->addWidget(detail_widget = new DetailWidget(charts, this));
|
||||
layout()->addWidget(detail_widget = new DetailWidget(((MainWindow*)parentWidget())->charts_widget, this));
|
||||
}
|
||||
detail_widget->setMessage(msg_id);
|
||||
}
|
||||
|
|
|
@ -10,6 +10,7 @@
|
|||
#include "tools/cabana/historylog.h"
|
||||
#include "tools/cabana/signalview.h"
|
||||
|
||||
class MainWindow;
|
||||
class EditMessageDialog : public QDialog {
|
||||
public:
|
||||
EditMessageDialog(const MessageId &msg_id, const QString &title, int size, QWidget *parent);
|
||||
|
@ -54,7 +55,7 @@ private:
|
|||
class CenterWidget : public QWidget {
|
||||
Q_OBJECT
|
||||
public:
|
||||
CenterWidget(ChartsWidget* charts, QWidget *parent);
|
||||
CenterWidget(QWidget *parent);
|
||||
void setMessage(const MessageId &msg_id);
|
||||
void clear();
|
||||
|
||||
|
@ -62,5 +63,4 @@ private:
|
|||
QWidget *createWelcomeWidget();
|
||||
DetailWidget *detail_widget = nullptr;
|
||||
QWidget *welcome_widget = nullptr;
|
||||
ChartsWidget *charts;
|
||||
};
|
||||
|
|
|
@ -18,7 +18,6 @@
|
|||
|
||||
#include "tools/cabana/commands.h"
|
||||
#include "tools/cabana/streamselector.h"
|
||||
#include "tools/cabana/streams/replaystream.h"
|
||||
#include "tools/cabana/tools/findsignal.h"
|
||||
|
||||
static MainWindow *main_win = nullptr;
|
||||
|
@ -29,8 +28,7 @@ void qLogMessageHandler(QtMsgType type, const QMessageLogContext &context, const
|
|||
|
||||
MainWindow::MainWindow() : QMainWindow() {
|
||||
createDockWindows();
|
||||
center_widget = new CenterWidget(charts_widget, this);
|
||||
setCentralWidget(center_widget);
|
||||
setCentralWidget(center_widget = new CenterWidget(this));
|
||||
createActions();
|
||||
createStatusBar();
|
||||
createShortcuts();
|
||||
|
@ -68,23 +66,18 @@ MainWindow::MainWindow() : QMainWindow() {
|
|||
|
||||
QObject::connect(this, &MainWindow::showMessage, statusBar(), &QStatusBar::showMessage);
|
||||
QObject::connect(this, &MainWindow::updateProgressBar, this, &MainWindow::updateDownloadProgress);
|
||||
QObject::connect(messages_widget, &MessagesWidget::msgSelectionChanged, center_widget, &CenterWidget::setMessage);
|
||||
QObject::connect(charts_widget, &ChartsWidget::dock, this, &MainWindow::dockCharts);
|
||||
QObject::connect(can, &AbstractStream::streamStarted, this, &MainWindow::streamStarted);
|
||||
QObject::connect(can, &AbstractStream::sourcesUpdated, dbc(), &DBCManager::updateSources);
|
||||
QObject::connect(can, &AbstractStream::sourcesUpdated, this, &MainWindow::updateLoadSaveMenus);
|
||||
QObject::connect(dbc(), &DBCManager::DBCFileChanged, this, &MainWindow::DBCFileChanged);
|
||||
QObject::connect(UndoStack::instance(), &QUndoStack::cleanChanged, this, &MainWindow::undoStackCleanChanged);
|
||||
QObject::connect(UndoStack::instance(), &QUndoStack::indexChanged, this, &MainWindow::undoStackIndexChanged);
|
||||
QObject::connect(&settings, &Settings::changed, this, &MainWindow::updateStatus);
|
||||
QObject::connect(StreamNotifier::instance(), &StreamNotifier::changingStream, this, &MainWindow::changingStream);
|
||||
QObject::connect(StreamNotifier::instance(), &StreamNotifier::streamStarted, this, &MainWindow::streamStarted);
|
||||
}
|
||||
|
||||
void MainWindow::createActions() {
|
||||
QMenu *file_menu = menuBar()->addMenu(tr("&File"));
|
||||
if (!can->liveStreaming()) {
|
||||
file_menu->addAction(tr("Open Route..."), this, &MainWindow::openRoute);
|
||||
file_menu->addSeparator();
|
||||
}
|
||||
file_menu->addAction(tr("Open Stream..."), this, &MainWindow::openStream);
|
||||
file_menu->addSeparator();
|
||||
|
||||
file_menu->addAction(tr("New DBC File"), [this]() { newFile(); })->setShortcuts(QKeySequence::New);
|
||||
file_menu->addAction(tr("Open DBC File..."), [this]() { openFile(); })->setShortcuts(QKeySequence::Open);
|
||||
|
@ -151,14 +144,22 @@ void MainWindow::createActions() {
|
|||
}
|
||||
|
||||
void MainWindow::createDockWindows() {
|
||||
// left panel
|
||||
messages_dock = new QDockWidget(tr("MESSAGES"), this);
|
||||
messages_dock->setObjectName("MessagesPanel");
|
||||
messages_dock->setAllowedAreas(Qt::LeftDockWidgetArea | Qt::RightDockWidgetArea | Qt::TopDockWidgetArea | Qt::BottomDockWidgetArea);
|
||||
messages_dock->setFeatures(QDockWidget::DockWidgetMovable | QDockWidget::DockWidgetFloatable);
|
||||
addDockWidget(Qt::LeftDockWidgetArea, messages_dock);
|
||||
|
||||
video_dock = new QDockWidget("", this);
|
||||
video_dock->setObjectName(tr("VideoPanel"));
|
||||
video_dock->setAllowedAreas(Qt::LeftDockWidgetArea | Qt::RightDockWidgetArea);
|
||||
video_dock->setFeatures(QDockWidget::DockWidgetMovable | QDockWidget::DockWidgetFloatable);
|
||||
addDockWidget(Qt::RightDockWidgetArea, video_dock);
|
||||
}
|
||||
|
||||
void MainWindow::createDockWidgets() {
|
||||
messages_widget = new MessagesWidget(this);
|
||||
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_widget);
|
||||
addDockWidget(Qt::LeftDockWidgetArea, dock);
|
||||
messages_dock->setWidget(messages_widget);
|
||||
|
||||
// right panel
|
||||
charts_widget = new ChartsWidget(this);
|
||||
|
@ -176,17 +177,8 @@ void MainWindow::createDockWindows() {
|
|||
video_splitter->addWidget(charts_container);
|
||||
video_splitter->setStretchFactor(1, 1);
|
||||
video_splitter->restoreState(settings.video_splitter_state);
|
||||
if (can->liveStreaming() || video_splitter->sizes()[0] == 0) {
|
||||
// display video at minimum size.
|
||||
video_splitter->setSizes({1, 1});
|
||||
}
|
||||
|
||||
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(video_splitter);
|
||||
addDockWidget(Qt::RightDockWidgetArea, video_dock);
|
||||
QObject::connect(charts_widget, &ChartsWidget::dock, this, &MainWindow::dockCharts);
|
||||
}
|
||||
|
||||
void MainWindow::createStatusBar() {
|
||||
|
@ -242,15 +234,15 @@ void MainWindow::DBCFileChanged() {
|
|||
updateLoadSaveMenus();
|
||||
}
|
||||
|
||||
void MainWindow::openRoute() {
|
||||
StreamSelector dlg(this);
|
||||
dlg.addStreamWidget(ReplayStream::widget(&can));
|
||||
void MainWindow::openStream() {
|
||||
AbstractStream *stream = nullptr;
|
||||
StreamSelector dlg(&stream, this);
|
||||
if (dlg.exec()) {
|
||||
center_widget->clear();
|
||||
charts_widget->removeAll();
|
||||
if (!dlg.dbcFile().isEmpty()) {
|
||||
loadFile(dlg.dbcFile());
|
||||
}
|
||||
stream->start();
|
||||
statusBar()->showMessage(tr("Route %1 loaded").arg(can->routeName()), 2000);
|
||||
} else if (dlg.failed()) {
|
||||
close();
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -319,24 +311,42 @@ void MainWindow::loadFromClipboard(SourceSet s, bool close_all) {
|
|||
}
|
||||
}
|
||||
|
||||
void MainWindow::streamStarted() {
|
||||
auto fingerprint = can->carFingerprint();
|
||||
if (can->liveStreaming()) {
|
||||
video_dock->setWindowTitle(can->routeName());
|
||||
} else {
|
||||
video_dock->setWindowTitle(tr("ROUTE: %1 FINGERPRINT: %2").arg(can->routeName()).arg(fingerprint.isEmpty() ? tr("Unknown Car") : fingerprint));
|
||||
}
|
||||
void MainWindow::changingStream() {
|
||||
center_widget->clear();
|
||||
delete messages_widget;
|
||||
delete video_splitter;
|
||||
}
|
||||
|
||||
void MainWindow::streamStarted() {
|
||||
createDockWidgets();
|
||||
|
||||
video_dock->setWindowTitle(can->routeName());
|
||||
if (can->liveStreaming() || video_splitter->sizes()[0] == 0) {
|
||||
// display video at minimum size.
|
||||
video_splitter->setSizes({1, 1});
|
||||
}
|
||||
// Don't overwrite already loaded DBC
|
||||
if (!dbc()->msgCount()) {
|
||||
if (!fingerprint.isEmpty()) {
|
||||
newFile();
|
||||
}
|
||||
|
||||
QObject::connect(messages_widget, &MessagesWidget::msgSelectionChanged, center_widget, &CenterWidget::setMessage);
|
||||
QObject::connect(can, &AbstractStream::eventsMerged, this, &MainWindow::eventsMerged);
|
||||
QObject::connect(can, &AbstractStream::sourcesUpdated, dbc(), &DBCManager::updateSources);
|
||||
QObject::connect(can, &AbstractStream::sourcesUpdated, this, &MainWindow::updateLoadSaveMenus);
|
||||
}
|
||||
|
||||
void MainWindow::eventsMerged() {
|
||||
if (!can->liveStreaming()) {
|
||||
auto fingerprint = can->carFingerprint();
|
||||
video_dock->setWindowTitle(tr("ROUTE: %1 FINGERPRINT: %2").arg(can->routeName()).arg(fingerprint.isEmpty() ? tr("Unknown Car") : fingerprint));
|
||||
// Don't overwrite already loaded DBC
|
||||
if (!dbc()->msgCount() && !fingerprint.isEmpty()) {
|
||||
auto dbc_name = fingerprint_to_dbc[fingerprint];
|
||||
if (dbc_name != QJsonValue::Undefined) {
|
||||
loadDBCFromOpendbc(dbc_name.toString());
|
||||
return;
|
||||
}
|
||||
}
|
||||
newFile();
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -22,14 +22,17 @@ public:
|
|||
void dockCharts(bool dock);
|
||||
void showStatusMessage(const QString &msg, int timeout = 0) { statusBar()->showMessage(msg, timeout); }
|
||||
void loadFile(const QString &fn, SourceSet s = SOURCE_ALL);
|
||||
ChartsWidget *charts_widget = nullptr;
|
||||
|
||||
public slots:
|
||||
void openRoute();
|
||||
void openStream();
|
||||
void changingStream();
|
||||
void streamStarted();
|
||||
|
||||
void newFile(SourceSet s = SOURCE_ALL);
|
||||
void openFile(SourceSet s = SOURCE_ALL);
|
||||
void openRecentFile();
|
||||
void loadDBCFromOpendbc(const QString &name);
|
||||
void streamStarted();
|
||||
void save();
|
||||
void saveAs();
|
||||
void saveToClipboard();
|
||||
|
@ -67,18 +70,20 @@ protected:
|
|||
void toggleFullScreen();
|
||||
void updateStatus();
|
||||
void updateLoadSaveMenus();
|
||||
void createDockWidgets();
|
||||
void eventsMerged();
|
||||
|
||||
VideoWidget *video_widget = nullptr;
|
||||
QDockWidget *video_dock;
|
||||
MessagesWidget *messages_widget;
|
||||
QDockWidget *messages_dock;
|
||||
MessagesWidget *messages_widget = nullptr;
|
||||
CenterWidget *center_widget;
|
||||
ChartsWidget *charts_widget;
|
||||
QWidget *floating_window = nullptr;
|
||||
QVBoxLayout *charts_layout;
|
||||
QProgressBar *progress_bar;
|
||||
QLabel *status_label;
|
||||
QJsonDocument fingerprint_to_dbc;
|
||||
QSplitter *video_splitter;;
|
||||
QSplitter *video_splitter = nullptr;
|
||||
enum { MAX_RECENT_FILES = 15 };
|
||||
QAction *recent_files_acts[MAX_RECENT_FILES] = {};
|
||||
QMenu *open_recent_menu = nullptr;
|
||||
|
|
|
@ -81,7 +81,6 @@ MessagesWidget::MessagesWidget(QWidget *parent) : QWidget(parent) {
|
|||
settings.suppress_defined_signals = (state == Qt::Checked);
|
||||
});
|
||||
QObject::connect(can, &AbstractStream::msgsReceived, model, &MessageListModel::msgsReceived);
|
||||
QObject::connect(can, &AbstractStream::streamStarted, this, &MessagesWidget::reset);
|
||||
QObject::connect(dbc(), &DBCManager::DBCFileChanged, this, &MessagesWidget::dbcModified);
|
||||
QObject::connect(dbc(), &DBCManager::msgUpdated, this, &MessagesWidget::dbcModified);
|
||||
QObject::connect(dbc(), &DBCManager::msgRemoved, this, &MessagesWidget::dbcModified);
|
||||
|
@ -146,14 +145,6 @@ void MessagesWidget::updateSuppressedButtons() {
|
|||
}
|
||||
}
|
||||
|
||||
void MessagesWidget::reset() {
|
||||
current_msg_id = std::nullopt;
|
||||
view->selectionModel()->clear();
|
||||
model->reset();
|
||||
updateSuppressedButtons();
|
||||
}
|
||||
|
||||
|
||||
// MessageListModel
|
||||
|
||||
QVariant MessageListModel::headerData(int section, Qt::Orientation orientation, int role) const {
|
||||
|
@ -419,14 +410,6 @@ void MessageListModel::clearSuppress() {
|
|||
suppressed_bytes.clear();
|
||||
}
|
||||
|
||||
void MessageListModel::reset() {
|
||||
beginResetModel();
|
||||
filter_str.clear();
|
||||
msgs.clear();
|
||||
clearSuppress();
|
||||
endResetModel();
|
||||
}
|
||||
|
||||
void MessageListModel::forceResetModel() {
|
||||
beginResetModel();
|
||||
endResetModel();
|
||||
|
|
|
@ -38,7 +38,6 @@ public:
|
|||
void fetchData();
|
||||
void suppress();
|
||||
void clearSuppress();
|
||||
void reset();
|
||||
void forceResetModel();
|
||||
void dbcModified();
|
||||
std::vector<MessageId> msgs;
|
||||
|
@ -100,7 +99,6 @@ public:
|
|||
QByteArray saveHeaderState() const { return view->header()->saveState(); }
|
||||
bool restoreHeaderState(const QByteArray &state) const { return view->header()->restoreState(state); }
|
||||
void updateSuppressedButtons();
|
||||
void reset();
|
||||
|
||||
public slots:
|
||||
void dbcModified();
|
||||
|
|
|
@ -481,10 +481,10 @@ SignalView::SignalView(ChartsWidget *charts, QWidget *parent) : charts(charts),
|
|||
QObject::connect(model, &QAbstractItemModel::modelReset, this, &SignalView::rowsChanged);
|
||||
QObject::connect(model, &QAbstractItemModel::rowsRemoved, this, &SignalView::rowsChanged);
|
||||
QObject::connect(dbc(), &DBCManager::signalAdded, [this](MessageId id, const cabana::Signal *sig) { selectSignal(sig); });
|
||||
QObject::connect(can, &AbstractStream::msgsReceived, this, &SignalView::updateState);
|
||||
QObject::connect(dbc(), &DBCManager::signalUpdated, this, &SignalView::handleSignalUpdated);
|
||||
QObject::connect(tree->verticalScrollBar(), &QScrollBar::valueChanged, [this]() { updateState(); });
|
||||
QObject::connect(tree->verticalScrollBar(), &QScrollBar::rangeChanged, [this]() { updateState(); });
|
||||
QObject::connect(can, &AbstractStream::msgsReceived, this, &SignalView::updateState);
|
||||
|
||||
setWhatsThis(tr(R"(
|
||||
<b>Signal view</b><br />
|
||||
|
|
|
@ -4,10 +4,20 @@
|
|||
|
||||
AbstractStream *can = nullptr;
|
||||
|
||||
AbstractStream::AbstractStream(QObject *parent) : QObject(parent) {
|
||||
can = this;
|
||||
new_msgs = std::make_unique<QHash<MessageId, CanData>>();
|
||||
StreamNotifier *StreamNotifier::instance() {
|
||||
static StreamNotifier notifier;
|
||||
return ¬ifier;
|
||||
}
|
||||
|
||||
AbstractStream::AbstractStream(QObject *parent) : new_msgs(new QHash<MessageId, CanData>()), QObject(parent) {
|
||||
assert(parent != nullptr);
|
||||
QObject::connect(this, &AbstractStream::seekedTo, this, &AbstractStream::updateLastMsgsTo);
|
||||
QObject::connect(this, &AbstractStream::streamStarted, [this]() {
|
||||
emit StreamNotifier::instance()->changingStream();
|
||||
delete can;
|
||||
can = this;
|
||||
emit StreamNotifier::instance()->streamStarted();
|
||||
});
|
||||
}
|
||||
|
||||
void AbstractStream::updateMessages(QHash<MessageId, CanData> *messages) {
|
||||
|
@ -37,8 +47,7 @@ void AbstractStream::updateEvent(const MessageId &id, double sec, const uint8_t
|
|||
|
||||
bool AbstractStream::postEvents() {
|
||||
// delay posting CAN message if UI thread is busy
|
||||
if (!processing) {
|
||||
processing = true;
|
||||
if (processing.exchange(true) == false) {
|
||||
for (auto it = new_msgs->begin(); it != new_msgs->end(); ++it) {
|
||||
it.value() = all_msgs[it.key()];
|
||||
}
|
||||
|
|
|
@ -40,6 +40,7 @@ class AbstractStream : public QObject {
|
|||
public:
|
||||
AbstractStream(QObject *parent);
|
||||
virtual ~AbstractStream() {};
|
||||
virtual void start() = 0;
|
||||
inline bool liveStreaming() const { return route() == nullptr; }
|
||||
virtual void seekTo(double ts) {}
|
||||
virtual QString routeName() const = 0;
|
||||
|
@ -90,7 +91,6 @@ protected:
|
|||
};
|
||||
|
||||
class AbstractOpenStreamWidget : public QWidget {
|
||||
Q_OBJECT
|
||||
public:
|
||||
AbstractOpenStreamWidget(AbstractStream **stream, QWidget *parent = nullptr) : stream(stream), QWidget(parent) {}
|
||||
virtual bool open() = 0;
|
||||
|
@ -100,5 +100,15 @@ protected:
|
|||
AbstractStream **stream = nullptr;
|
||||
};
|
||||
|
||||
class StreamNotifier : public QObject {
|
||||
Q_OBJECT
|
||||
public:
|
||||
StreamNotifier(QObject *parent = nullptr) : QObject(parent) {}
|
||||
static StreamNotifier* instance();
|
||||
signals:
|
||||
void streamStarted();
|
||||
void changingStream();
|
||||
};
|
||||
|
||||
// A global pointer referring to the unique AbstractStream object
|
||||
extern AbstractStream *can;
|
||||
|
|
|
@ -9,13 +9,10 @@
|
|||
// DeviceStream
|
||||
|
||||
DeviceStream::DeviceStream(QObject *parent, QString address) : zmq_address(address), LiveStream(parent) {
|
||||
startStreamThread();
|
||||
}
|
||||
|
||||
void DeviceStream::streamThread() {
|
||||
if (!zmq_address.isEmpty()) {
|
||||
setenv("ZMQ", "1", 1);
|
||||
}
|
||||
zmq_address.isEmpty() ? unsetenv("ZMQ") : setenv("ZMQ", "1", 1);
|
||||
|
||||
std::unique_ptr<Context> context(Context::create());
|
||||
std::string address = zmq_address.isEmpty() ? "127.0.0.1" : zmq_address.toStdString();
|
||||
|
|
|
@ -1,7 +1,5 @@
|
|||
#include "tools/cabana/streams/livestream.h"
|
||||
|
||||
#include <QTimer>
|
||||
|
||||
LiveStream::LiveStream(QObject *parent) : AbstractStream(parent) {
|
||||
if (settings.log_livestream) {
|
||||
std::string path = (settings.log_path + "/" + QDateTime::currentDateTime().toString("yyyy-MM-dd--hh-mm-ss") + "--0").toStdString();
|
||||
|
@ -21,11 +19,9 @@ void LiveStream::startUpdateTimer() {
|
|||
timer_id = update_timer.timerId();
|
||||
}
|
||||
|
||||
void LiveStream::startStreamThread() {
|
||||
// delay the start of the thread to avoid calling startStreamThread
|
||||
// in the constructor when other classes' slots have not been connected to
|
||||
// the signals of the livestream.
|
||||
QTimer::singleShot(0, [this]() { stream_thread->start(); });
|
||||
void LiveStream::start() {
|
||||
emit streamStarted();
|
||||
stream_thread->start();
|
||||
startUpdateTimer();
|
||||
}
|
||||
|
||||
|
@ -71,7 +67,6 @@ void LiveStream::updateEvents() {
|
|||
if (first_update_ts == 0) {
|
||||
first_update_ts = nanos_since_boot();
|
||||
first_event_ts = current_event_ts = all_events_.back()->mono_time;
|
||||
emit streamStarted();
|
||||
}
|
||||
|
||||
if (paused_ || prev_speed != speed_) {
|
||||
|
|
|
@ -10,6 +10,7 @@ class LiveStream : public AbstractStream {
|
|||
public:
|
||||
LiveStream(QObject *parent);
|
||||
virtual ~LiveStream();
|
||||
void start() override;
|
||||
inline double routeStartTime() const override { return begin_event_ts / 1e9; }
|
||||
inline double currentSec() const override { return (current_event_ts - begin_event_ts) / 1e9; }
|
||||
void setSpeed(float speed) override { speed_ = speed; }
|
||||
|
@ -20,7 +21,6 @@ public:
|
|||
|
||||
protected:
|
||||
virtual void streamThread() = 0;
|
||||
void startStreamThread();
|
||||
void handleEvent(const char *data, const size_t size);
|
||||
|
||||
private:
|
||||
|
|
|
@ -20,7 +20,6 @@ PandaStream::PandaStream(QObject *parent, PandaStreamConfig config_) : config(co
|
|||
if (!connect()) {
|
||||
throw std::runtime_error("Failed to connect to panda");
|
||||
}
|
||||
startStreamThread();
|
||||
}
|
||||
|
||||
bool PandaStream::connect() {
|
||||
|
|
|
@ -6,18 +6,17 @@
|
|||
#include <QMessageBox>
|
||||
#include <QPushButton>
|
||||
|
||||
#include "common/prefix.h"
|
||||
|
||||
ReplayStream::ReplayStream(QObject *parent) : AbstractStream(parent) {
|
||||
unsetenv("ZMQ");
|
||||
// TODO: Remove when OpenpilotPrefix supports ZMQ
|
||||
#ifndef __APPLE__
|
||||
op_prefix = std::make_unique<OpenpilotPrefix>();
|
||||
#endif
|
||||
QObject::connect(&settings, &Settings::changed, [this]() {
|
||||
if (replay) replay->setSegmentCacheLimit(settings.max_cached_minutes);
|
||||
});
|
||||
}
|
||||
|
||||
ReplayStream::~ReplayStream() {
|
||||
if (replay) replay->stop();
|
||||
}
|
||||
|
||||
static bool event_filter(const Event *e, void *opaque) {
|
||||
return ((ReplayStream *)opaque)->eventFilter(e);
|
||||
}
|
||||
|
@ -37,13 +36,13 @@ bool ReplayStream::loadRoute(const QString &route, const QString &data_dir, uint
|
|||
replay->setSegmentCacheLimit(settings.max_cached_minutes);
|
||||
replay->installEventFilter(event_filter, this);
|
||||
QObject::connect(replay.get(), &Replay::seekedTo, this, &AbstractStream::seekedTo);
|
||||
QObject::connect(replay.get(), &Replay::streamStarted, this, &AbstractStream::streamStarted);
|
||||
QObject::connect(replay.get(), &Replay::segmentsMerged, this, &ReplayStream::mergeSegments);
|
||||
if (replay->load()) {
|
||||
replay->start();
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
return replay->load();
|
||||
}
|
||||
|
||||
void ReplayStream::start() {
|
||||
emit streamStarted();
|
||||
replay->start();
|
||||
}
|
||||
|
||||
bool ReplayStream::eventFilter(const Event *event) {
|
||||
|
@ -78,8 +77,6 @@ AbstractOpenStreamWidget *ReplayStream::widget(AbstractStream **stream) {
|
|||
|
||||
// OpenReplayWidget
|
||||
|
||||
static std::unique_ptr<OpenpilotPrefix> op_prefix;
|
||||
|
||||
OpenReplayWidget::OpenReplayWidget(AbstractStream **stream) : AbstractOpenStreamWidget(stream) {
|
||||
// TODO: get route list from api.comma.ai
|
||||
QGridLayout *grid_layout = new QGridLayout();
|
||||
|
@ -118,26 +115,17 @@ bool OpenReplayWidget::open() {
|
|||
route = route.mid(idx + 1);
|
||||
}
|
||||
|
||||
bool ret = false;
|
||||
bool is_valid_format = Route::parseRoute(route).str.size() > 0;
|
||||
if (!is_valid_format) {
|
||||
QMessageBox::warning(nullptr, tr("Warning"), tr("Invalid route format: '%1'").arg(route));
|
||||
} else {
|
||||
// TODO: Remove when OpenpilotPrefix supports ZMQ
|
||||
#ifndef __APPLE__
|
||||
op_prefix.reset(new OpenpilotPrefix());
|
||||
#endif
|
||||
uint32_t flags[] = {REPLAY_FLAG_NO_VIPC, REPLAY_FLAG_NONE, REPLAY_FLAG_ECAM, REPLAY_FLAG_DCAM, REPLAY_FLAG_QCAMERA};
|
||||
ReplayStream *replay_stream = *stream ? (ReplayStream *)*stream : new ReplayStream(qApp);
|
||||
ret = replay_stream->loadRoute(route, data_dir, flags[choose_video_cb->currentIndex()]);
|
||||
if (!ret) {
|
||||
if (replay_stream != *stream) {
|
||||
delete replay_stream;
|
||||
}
|
||||
QMessageBox::warning(nullptr, tr("Warning"), tr("Failed to load route: '%1'").arg(route));
|
||||
auto replay_stream = std::make_unique<ReplayStream>(qApp);
|
||||
if (replay_stream->loadRoute(route, data_dir, flags[choose_video_cb->currentIndex()])) {
|
||||
*stream = replay_stream.release();
|
||||
} else {
|
||||
*stream = replay_stream;
|
||||
QMessageBox::warning(nullptr, tr("Warning"), tr("Failed to load route: '%1'").arg(route));
|
||||
}
|
||||
}
|
||||
return ret;
|
||||
return *stream != nullptr;
|
||||
}
|
||||
|
|
|
@ -1,5 +1,6 @@
|
|||
#pragma once
|
||||
|
||||
#include "common/prefix.h"
|
||||
#include "tools/cabana/streams/abstractstream.h"
|
||||
|
||||
class ReplayStream : public AbstractStream {
|
||||
|
@ -7,7 +8,7 @@ class ReplayStream : public AbstractStream {
|
|||
|
||||
public:
|
||||
ReplayStream(QObject *parent);
|
||||
~ReplayStream();
|
||||
void start() override;
|
||||
bool loadRoute(const QString &route, const QString &data_dir, uint32_t replay_flags = REPLAY_FLAG_NONE);
|
||||
bool eventFilter(const Event *event);
|
||||
void seekTo(double ts) override { replay->seekTo(std::max(double(0), ts), false); };
|
||||
|
@ -29,6 +30,7 @@ private:
|
|||
void mergeSegments();
|
||||
std::unique_ptr<Replay> replay = nullptr;
|
||||
std::set<int> processed_segments;
|
||||
std::unique_ptr<OpenpilotPrefix> op_prefix;
|
||||
};
|
||||
|
||||
class OpenReplayWidget : public AbstractOpenStreamWidget {
|
||||
|
|
|
@ -6,13 +6,19 @@
|
|||
#include <QLabel>
|
||||
#include <QPushButton>
|
||||
|
||||
StreamSelector::StreamSelector(QWidget *parent) : QDialog(parent) {
|
||||
#include "tools/cabana/streams/devicestream.h"
|
||||
#include "tools/cabana/streams/pandastream.h"
|
||||
#include "tools/cabana/streams/replaystream.h"
|
||||
|
||||
StreamSelector::StreamSelector(AbstractStream **stream, QWidget *parent) : QDialog(parent) {
|
||||
setWindowTitle(tr("Open stream"));
|
||||
QVBoxLayout *main_layout = new QVBoxLayout(this);
|
||||
|
||||
QWidget *w = new QWidget(this);
|
||||
QVBoxLayout *layout = new QVBoxLayout(w);
|
||||
tab = new QTabWidget(this);
|
||||
tab->setTabBarAutoHide(true);
|
||||
main_layout->addWidget(tab);
|
||||
layout->addWidget(tab);
|
||||
|
||||
QHBoxLayout *dbc_layout = new QHBoxLayout();
|
||||
dbc_file = new QLineEdit(this);
|
||||
|
@ -22,20 +28,29 @@ StreamSelector::StreamSelector(QWidget *parent) : QDialog(parent) {
|
|||
dbc_layout->addWidget(new QLabel(tr("dbc File")));
|
||||
dbc_layout->addWidget(dbc_file);
|
||||
dbc_layout->addWidget(file_btn);
|
||||
main_layout->addLayout(dbc_layout);
|
||||
layout->addLayout(dbc_layout);
|
||||
|
||||
QFrame *line = new QFrame(this);
|
||||
line->setFrameStyle(QFrame::HLine | QFrame::Sunken);
|
||||
main_layout->addWidget(line);
|
||||
layout->addWidget(line);
|
||||
|
||||
main_layout->addWidget(w);
|
||||
auto btn_box = new QDialogButtonBox(QDialogButtonBox::Open | QDialogButtonBox::Cancel);
|
||||
main_layout->addWidget(btn_box);
|
||||
|
||||
addStreamWidget(ReplayStream::widget(stream));
|
||||
addStreamWidget(PandaStream::widget(stream));
|
||||
addStreamWidget(DeviceStream::widget(stream));
|
||||
|
||||
QObject::connect(btn_box, &QDialogButtonBox::rejected, this, &QDialog::reject);
|
||||
QObject::connect(btn_box, &QDialogButtonBox::accepted, [=]() {
|
||||
success = ((AbstractOpenStreamWidget *)tab->currentWidget())->open();
|
||||
if (success) {
|
||||
btn_box->button(QDialogButtonBox::Open)->setEnabled(false);
|
||||
w->setEnabled(false);
|
||||
if (((AbstractOpenStreamWidget *)tab->currentWidget())->open()) {
|
||||
accept();
|
||||
} else {
|
||||
btn_box->button(QDialogButtonBox::Open)->setEnabled(true);
|
||||
w->setEnabled(true);
|
||||
}
|
||||
});
|
||||
QObject::connect(file_btn, &QPushButton::clicked, [this]() {
|
||||
|
|
|
@ -10,13 +10,11 @@ class StreamSelector : public QDialog {
|
|||
Q_OBJECT
|
||||
|
||||
public:
|
||||
StreamSelector(QWidget *parent = nullptr);
|
||||
StreamSelector(AbstractStream **stream, QWidget *parent = nullptr);
|
||||
void addStreamWidget(AbstractOpenStreamWidget *w);
|
||||
QString dbcFile() const { return dbc_file->text(); }
|
||||
inline bool failed() const { return !success; }
|
||||
|
||||
private:
|
||||
QLineEdit *dbc_file;
|
||||
QTabWidget *tab;
|
||||
bool success = true;
|
||||
};
|
||||
|
|
|
@ -1,10 +1,12 @@
|
|||
#include "tools/cabana/videowidget.h"
|
||||
|
||||
#include <QButtonGroup>
|
||||
#include <QHBoxLayout>
|
||||
#include <QMouseEvent>
|
||||
#include <QPainter>
|
||||
#include <QStackedLayout>
|
||||
#include <QStyleOptionSlider>
|
||||
#include <QTimer>
|
||||
#include <QVBoxLayout>
|
||||
#include <QtConcurrent>
|
||||
|
||||
|
@ -20,18 +22,6 @@ static const QColor timeline_colors[] = {
|
|||
[(int)TimelineType::AlertCritical] = QColor(199, 0, 57),
|
||||
};
|
||||
|
||||
bool sortTimelineBasedOnEventPriority(const std::tuple<int, int, TimelineType> &left, const std::tuple<int, int, TimelineType> &right){
|
||||
const static std::map<TimelineType, int> timelinePriority = {
|
||||
{ TimelineType::None, 0 },
|
||||
{ TimelineType::Engaged, 10 },
|
||||
{ TimelineType::AlertInfo, 20 },
|
||||
{ TimelineType::AlertWarning, 30 },
|
||||
{ TimelineType::AlertCritical, 40 },
|
||||
{ TimelineType::UserFlag, 35 }
|
||||
};
|
||||
return timelinePriority.at(std::get<2>(left)) < timelinePriority.at(std::get<2>(right));
|
||||
}
|
||||
|
||||
VideoWidget::VideoWidget(QWidget *parent) : QFrame(parent) {
|
||||
setFrameStyle(QFrame::StyledPanel | QFrame::Plain);
|
||||
auto main_layout = new QVBoxLayout(this);
|
||||
|
@ -100,7 +90,7 @@ QWidget *VideoWidget::createCameraWidget() {
|
|||
l->addLayout(stacked);
|
||||
|
||||
// slider controls
|
||||
slider_layout = new QHBoxLayout();
|
||||
auto slider_layout = new QHBoxLayout();
|
||||
time_label = new QLabel("00:00");
|
||||
slider_layout->addWidget(time_label);
|
||||
|
||||
|
@ -111,12 +101,13 @@ QWidget *VideoWidget::createCameraWidget() {
|
|||
end_time_label = new QLabel(this);
|
||||
slider_layout->addWidget(end_time_label);
|
||||
l->addLayout(slider_layout);
|
||||
|
||||
setMaximumTime(can->totalSeconds());
|
||||
QObject::connect(slider, &QSlider::sliderReleased, [this]() { can->seekTo(slider->value() / 1000.0); });
|
||||
QObject::connect(slider, &QSlider::valueChanged, [=](int value) { time_label->setText(utils::formatSeconds(value / 1000)); });
|
||||
QObject::connect(slider, &Slider::updateMaximumTime, this, &VideoWidget::setMaximumTime);
|
||||
QObject::connect(cam_widget, &CameraWidget::clicked, []() { can->pause(!can->isPaused()); });
|
||||
QObject::connect(can, &AbstractStream::updated, this, &VideoWidget::updateState);
|
||||
QObject::connect(can, &AbstractStream::streamStarted, [this]() { setMaximumTime(can->totalSeconds()); });
|
||||
return w;
|
||||
}
|
||||
|
||||
|
@ -157,14 +148,16 @@ void VideoWidget::updatePlayBtnState() {
|
|||
}
|
||||
|
||||
// Slider
|
||||
Slider::Slider(QWidget *parent) : timer(this), thumbnail_label(parent), QSlider(Qt::Horizontal, parent) {
|
||||
timer.callOnTimeout([this]() {
|
||||
Slider::Slider(QWidget *parent) : thumbnail_label(parent), QSlider(Qt::Horizontal, parent) {
|
||||
setMouseTracking(true);
|
||||
auto timer = new QTimer(this);
|
||||
timer->callOnTimeout([this]() {
|
||||
timeline = can->getTimeline();
|
||||
std::sort(timeline.begin(), timeline.end(), sortTimelineBasedOnEventPriority);
|
||||
std::sort(timeline.begin(), timeline.end(), [](auto &l, auto &r) { return std::get<2>(l) < std::get<2>(r); });
|
||||
update();
|
||||
});
|
||||
setMouseTracking(true);
|
||||
QObject::connect(can, &AbstractStream::streamStarted, this, &Slider::streamStarted);
|
||||
timer->start(2000);
|
||||
thumnail_future = QtConcurrent::run(this, &Slider::loadThumbnails);
|
||||
}
|
||||
|
||||
Slider::~Slider() {
|
||||
|
@ -172,16 +165,6 @@ Slider::~Slider() {
|
|||
thumnail_future.waitForFinished();
|
||||
}
|
||||
|
||||
void Slider::streamStarted() {
|
||||
abort_load_thumbnail = true;
|
||||
thumnail_future.waitForFinished();
|
||||
abort_load_thumbnail = false;
|
||||
thumbnails.clear();
|
||||
timeline.clear();
|
||||
timer.start(2000);
|
||||
thumnail_future = QtConcurrent::run(this, &Slider::loadThumbnails);
|
||||
}
|
||||
|
||||
void Slider::loadThumbnails() {
|
||||
const auto &segments = can->route()->segments();
|
||||
double max_time = 0;
|
||||
|
@ -318,9 +301,7 @@ void InfoLabel::showAlert(const AlertInfo &alert) {
|
|||
alert_info = alert;
|
||||
pixmap = {};
|
||||
setVisible(!alert_info.text1.isEmpty());
|
||||
if (isVisible()) {
|
||||
update();
|
||||
}
|
||||
update();
|
||||
}
|
||||
|
||||
void InfoLabel::paintEvent(QPaintEvent *event) {
|
||||
|
|
|
@ -3,12 +3,10 @@
|
|||
#include <atomic>
|
||||
#include <mutex>
|
||||
|
||||
#include <QHBoxLayout>
|
||||
#include <QFuture>
|
||||
#include <QLabel>
|
||||
#include <QPushButton>
|
||||
#include <QSlider>
|
||||
#include <QTimer>
|
||||
|
||||
#include "selfdrive/ui/qt/widgets/cameraview.h"
|
||||
#include "tools/cabana/streams/abstractstream.h"
|
||||
|
@ -46,7 +44,6 @@ private:
|
|||
bool event(QEvent *event) override;
|
||||
void sliderChange(QAbstractSlider::SliderChange change) override;
|
||||
void paintEvent(QPaintEvent *ev) override;
|
||||
void streamStarted();
|
||||
void loadThumbnails();
|
||||
|
||||
double max_sec = 0;
|
||||
|
@ -58,7 +55,6 @@ private:
|
|||
std::map<uint64_t, AlertInfo> alerts;
|
||||
QFuture<void> thumnail_future;
|
||||
InfoLabel thumbnail_label;
|
||||
QTimer timer;
|
||||
friend class VideoWidget;
|
||||
};
|
||||
|
||||
|
@ -79,7 +75,6 @@ protected:
|
|||
double maximum_time = 0;
|
||||
QLabel *end_time_label;
|
||||
QLabel *time_label;
|
||||
QHBoxLayout *slider_layout;
|
||||
QPushButton *play_btn;
|
||||
InfoLabel *alert_label;
|
||||
Slider *slider;
|
||||
|
|
Loading…
Reference in New Issue