diff --git a/groundStation/gui/MicroCART/MicroCART.pro b/groundStation/gui/MicroCART/MicroCART.pro index f5bb8ea5069cd4d1a8c4c451e005f03e383ac737..811433dab205a3e207bfc5af4ceed1f71f5d38a4 100644 --- a/groundStation/gui/MicroCART/MicroCART.pro +++ b/groundStation/gui/MicroCART/MicroCART.pro @@ -1,58 +1,59 @@ -#------------------------------------------------- -# -# Project created by QtCreator 2017-02-23T15:03:45 -# -#------------------------------------------------- - -QT += core gui - -greaterThan(QT_MAJOR_VERSION, 4): QT += widgets - -TARGET = MicroCART -TEMPLATE = app - -LIBS += ../../frontend.a -INCLUDEPATH += ../../src/frontend/ - -SOURCES += main.cpp\ - mainwindow.cpp \ - trackerworker.cpp \ - controlworker.cpp \ - quaditem.cpp \ - slotprocess.cpp \ - qFlightInstruments.cpp - -HEADERS += mainwindow.h \ - trackerworker.h \ - controlworker.h \ - quaditem.h \ - slotprocess.h \ - qFlightInstruments.h - -FORMS += mainwindow.ui - -INCLUDEPATH += $$PWD/../../../quad/inc -DEPENDPATH += $$PWD/../../../quad/inc - -win32:CONFIG(release, debug|release): LIBS += -L$$PWD/../../../quad/lib/release/ -lgraph_blocks -else:win32:CONFIG(debug, debug|release): LIBS += -L$$PWD/../../../quad/lib/debug/ -lgraph_blocks -else:unix: LIBS += -L$$PWD/../../../quad/lib/ -lgraph_blocks - -win32-g++:CONFIG(release, debug|release): PRE_TARGETDEPS += $$PWD/../../../quad/lib/release/libgraph_blocks.a -else:win32-g++:CONFIG(debug, debug|release): PRE_TARGETDEPS += $$PWD/../../../quad/lib/debug/libgraph_blocks.a -else:win32:!win32-g++:CONFIG(release, debug|release): PRE_TARGETDEPS += $$PWD/../../../quad/lib/release/graph_blocks.lib -else:win32:!win32-g++:CONFIG(debug, debug|release): PRE_TARGETDEPS += $$PWD/../../../quad/lib/debug/graph_blocks.lib -else:unix: PRE_TARGETDEPS += $$PWD/../../../quad/lib/libgraph_blocks.a - -win32:CONFIG(release, debug|release): LIBS += -L$$PWD/../../../quad/lib/release/ -lcomputation_graph -else:win32:CONFIG(debug, debug|release): LIBS += -L$$PWD/../../../quad/lib/debug/ -lcomputation_graph -else:unix: LIBS += -L$$PWD/../../../quad/lib/ -lcomputation_graph - -win32-g++:CONFIG(release, debug|release): PRE_TARGETDEPS += $$PWD/../../../quad/lib/release/libcomputation_graph.a -else:win32-g++:CONFIG(debug, debug|release): PRE_TARGETDEPS += $$PWD/../../../quad/lib/debug/libcomputation_graph.a -else:win32:!win32-g++:CONFIG(release, debug|release): PRE_TARGETDEPS += $$PWD/../../../quad/lib/release/computation_graph.lib -else:win32:!win32-g++:CONFIG(debug, debug|release): PRE_TARGETDEPS += $$PWD/../../../quad/lib/debug/computation_graph.lib -else:unix: PRE_TARGETDEPS += $$PWD/../../../quad/lib/libcomputation_graph.a - -RESOURCES += \ - resources.qrc +#------------------------------------------------- +# +# Project created by QtCreator 2017-02-23T15:03:45 +# +#------------------------------------------------- + +QT += core gui + +greaterThan(QT_MAJOR_VERSION, 4): QT += widgets + +TARGET = MicroCART +TEMPLATE = app + +LIBS += ../../frontend.a +INCLUDEPATH += ../../src/frontend/ + +SOURCES += main.cpp\ + mainwindow.cpp \ + trackerworker.cpp \ + controlworker.cpp \ + quaditem.cpp \ + slotprocess.cpp \ + qFlightInstruments.cpp + +HEADERS += mainwindow.h \ + trackerworker.h \ + controlworker.h \ + quaditem.h \ + slotprocess.h \ + graph_blocks.h \ + qFlightInstruments.h + +FORMS += mainwindow.ui + +INCLUDEPATH += $$PWD/../../../quad/inc +DEPENDPATH += $$PWD/../../../quad/inc + +win32:CONFIG(release, debug|release): LIBS += -L$$PWD/../../../quad/lib/release/ -lgraph_blocks +else:win32:CONFIG(debug, debug|release): LIBS += -L$$PWD/../../../quad/lib/debug/ -lgraph_blocks +else:unix: LIBS += -L$$PWD/../../../quad/lib/ -lgraph_blocks + +win32-g++:CONFIG(release, debug|release): PRE_TARGETDEPS += $$PWD/../../../quad/lib/release/libgraph_blocks.a +else:win32-g++:CONFIG(debug, debug|release): PRE_TARGETDEPS += $$PWD/../../../quad/lib/debug/libgraph_blocks.a +else:win32:!win32-g++:CONFIG(release, debug|release): PRE_TARGETDEPS += $$PWD/../../../quad/lib/release/graph_blocks.lib +else:win32:!win32-g++:CONFIG(debug, debug|release): PRE_TARGETDEPS += $$PWD/../../../quad/lib/debug/graph_blocks.lib +else:unix: PRE_TARGETDEPS += $$PWD/../../../quad/lib/libgraph_blocks.a + +win32:CONFIG(release, debug|release): LIBS += -L$$PWD/../../../quad/lib/release/ -lcomputation_graph +else:win32:CONFIG(debug, debug|release): LIBS += -L$$PWD/../../../quad/lib/debug/ -lcomputation_graph +else:unix: LIBS += -L$$PWD/../../../quad/lib/ -lcomputation_graph + +win32-g++:CONFIG(release, debug|release): PRE_TARGETDEPS += $$PWD/../../../quad/lib/release/libcomputation_graph.a +else:win32-g++:CONFIG(debug, debug|release): PRE_TARGETDEPS += $$PWD/../../../quad/lib/debug/libcomputation_graph.a +else:win32:!win32-g++:CONFIG(release, debug|release): PRE_TARGETDEPS += $$PWD/../../../quad/lib/release/computation_graph.lib +else:win32:!win32-g++:CONFIG(debug, debug|release): PRE_TARGETDEPS += $$PWD/../../../quad/lib/debug/computation_graph.lib +else:unix: PRE_TARGETDEPS += $$PWD/../../../quad/lib/libcomputation_graph.a + +RESOURCES += \ + resources.qrc diff --git a/groundStation/gui/MicroCART/mainwindow.cpp b/groundStation/gui/MicroCART/mainwindow.cpp index d91ea12c1552ad33a470770fcf5d147a40605afc..ca0d2ee6f8bbedbe5d8950b8b110873477cdecd7 100644 --- a/groundStation/gui/MicroCART/mainwindow.cpp +++ b/groundStation/gui/MicroCART/mainwindow.cpp @@ -1,601 +1,612 @@ -#include "mainwindow.h" -#include "ui_mainwindow.h" - -#include <QFileDialog> -#include <QThread> -#include <QTimer> -#include <QRegExp> -#include <QProcessEnvironment> -#include <QPixmap> -#include <QProcess> - -#include "trackerworker.h" -#include "controlworker.h" -#include "graph_blocks.h" -#include "quaditem.h" -#include "slotprocess.h" -#include "qFlightInstruments.h" - -#include <iostream> -MainWindow::MainWindow(QWidget *parent) : - QMainWindow(parent), - ui(new Ui::MainWindow), - setpointList(new QStandardItemModel(this)), - nextSpTimer(new QTimer(this)), - sp_x(0.0f), - sp_y(0.0f), - sp_z(0.0f), - trackerTimer(new QTimer(this)), - workerStartTimer(new QTimer(this)), - backendProcess(new QProcess(this)), - connectedWorkers(0) -{ - ui->setupUi(this); - - QGraphicsScene *posScene = new QGraphicsScene(this); - ui->posView->setScene(posScene); - QuadItem * posIndicator = new QuadItem(); - posScene->addItem(posIndicator); - - QGraphicsScene *attScene = new QGraphicsScene(this); - ui->attView->setScene(attScene); - QADI * attIndicator = new QADI(); - attScene->addWidget(attIndicator); - - - workerStartTimer->setSingleShot(true); - - /* Create a thread for workers */ - QThread* workerThread = new QThread(this); - - /* Create a worker to update the tracker */ - TrackerWorker * trackerWorker = new TrackerWorker(); - - /* Move it to the worker thread. This means that slots of this worker - * will run in the worker thread, and not block the UI */ - trackerWorker->moveToThread(workerThread); - - /* Connect tracker worker */ - connect(trackerWorker, SIGNAL (finished(float, float, float, float, float, float)), - this, SLOT (updateTracker(float, float, float, float, float, float))); - - connect(trackerWorker, SIGNAL (finished(float, float, float, float, float, float)), - posIndicator, SLOT(updatePos(float,float,float,float,float,float))); - - connect(trackerWorker, SIGNAL (finished(float, float, float, float, float, float)), - attIndicator, SLOT(updateAttitude(float, float, float, float, float, float))); - - backendProcess->setProcessChannelMode(QProcess::MergedChannels); - - /* Create another worker for the control graph */ - QThread * cwThread = new QThread(this); - ControlWorker * controlWorker = new ControlWorker(); - controlWorker->moveToThread(cwThread); - - /* Connect signals from control worker */ - connect(controlWorker, SIGNAL (gotNodes(QStringList)), this, SLOT (newNodes(QStringList))); - connect(controlWorker, SIGNAL (gotParams(QStringList)), this, SLOT (newParams(QStringList))); - connect(controlWorker, SIGNAL (gotParamValue(QString, QString, float)), this, SLOT (newParamValue(QString, QString, float))); - connect(controlWorker, SIGNAL (gotNodeOutput(QString, float)), this, SLOT (newNodeOutput(QString, float))); - connect(controlWorker, SIGNAL (gotConstantBlocks(QStringList)), this, SLOT (newConstantBlocks(QStringList))); - connect(controlWorker, SIGNAL (graphRendered(QString)), this, SLOT (newControlGraph(QString))); - connect(controlWorker, SIGNAL (paramSet(QString, QString)), controlWorker, SLOT (getParamValue(QString, QString))); - - /* Signals to control worker */ - connect(ui->pbControlRefresh, SIGNAL (clicked()), controlWorker, SLOT (getNodes())); - connect(ui->nodeSelect, SIGNAL (currentIndexChanged(QString)), controlWorker, SLOT (getParams(QString))); - connect(this, SIGNAL (getParamValue(QString, QString)), controlWorker, SLOT (getParamValue(QString, QString))); - connect(this, SIGNAL (setParamValue(QString, QString, float)), controlWorker, SLOT (setParamValue(QString, QString, float))); - connect(this, SIGNAL (getNodeOutput(QString)), controlWorker, SLOT (getNodeOutput(QString))); - - /* Connect and disconnect from backend when signals emitted */ - connect(workerStartTimer, SIGNAL (timeout()), trackerWorker, SLOT (connectBackend())); - connect(workerStartTimer, SIGNAL (timeout()), controlWorker, SLOT (connectBackend())); - connect(this, SIGNAL (connectWorkers()), trackerWorker, SLOT (connectBackend())); - connect(this, SIGNAL (connectWorkers()), controlWorker, SLOT (connectBackend())); - connect(this, SIGNAL (disconnectWorkers()), trackerWorker, SLOT (disconnectBackend())); - connect(this, SIGNAL (disconnectWorkers()), controlWorker, SLOT (disconnectBackend())); - - connect(backendProcess, SIGNAL (started()), this, SLOT (backendStarted())); - connect(backendProcess, SIGNAL (errorOccurred(QProcess::ProcessError)), this, SLOT (backendError(QProcess::ProcessError))); - connect(backendProcess, SIGNAL (finished(int, QProcess::ExitStatus)), this, SLOT (backendFinished(int, QProcess::ExitStatus))); - connect(backendProcess, SIGNAL (readyReadStandardOutput()), this, SLOT (backendRead())); - connect(backendProcess, SIGNAL (readyReadStandardError()), this, SLOT (backendRead())); - - connect(controlWorker, SIGNAL (connected()), this, SLOT (workerConnected())); - connect(controlWorker, SIGNAL (disconnected()), this, SLOT (workerDisconnected())); - - connect(trackerWorker, SIGNAL (connected()), this, SLOT (workerConnected())); - connect(trackerWorker, SIGNAL (disconnected()), this, SLOT (workerDisconnected())); - - /* Connect refresh button and refresh timer to tracker worker */ - connect(trackerTimer, SIGNAL(timeout()), this, SLOT(updatePosAtt())); - connect(ui->pbRefresh, SIGNAL (clicked()), this, SLOT (updatePosAtt())); - - connect(this, SIGNAL(getPosAttFromBackend()), trackerWorker, SLOT(process())); - - /* Timer used for next setpoint */ - nextSpTimer->setSingleShot(true); - connect(nextSpTimer, SIGNAL (timeout()), this, SLOT (on_pbNextSetpoint_clicked())); - - /* Start the things */ - trackerTimer->start(100); - workerThread->start(); - cwThread->start(); - - /* Connect the setpointlist to the model */ - ui->setpointList->setModel(setpointList); - - /* Connect various things that can result in sending setpoints */ - connect(ui->pbSendSetpoint, SIGNAL (clicked()), this, SLOT (sendSetpoints())); - connect(ui->setpointList, SIGNAL (doubleClicked(QModelIndex)), this, SLOT (sendSelectedSetpoint())); - - /* Populate scripts list */ - QDir scriptsDir("scripts/"); - QStringList scripts = scriptsDir.entryList(); - for (int i = 0; i < scripts.size(); i++) { - QAction * action = ui->menuScripts->addAction(scripts[i]); - SlotProcess * scriptProcess = new SlotProcess(action); - scriptProcess->setProgram(scriptsDir.filePath(scripts[i])); - connect(action, SIGNAL (triggered()), scriptProcess, SLOT (startProcess())); - } -} - -MainWindow::~MainWindow() -{ - delete ui; -} - -void MainWindow::updatePosAtt() -{ - if (ui->posattSrcVrpn->isChecked()) { - emit(getPosAttFromBackend()); - } else if (ui->posattSrcQuad->isChecked()) { - emit(getNodeOutput(ui->xPositionSelect->currentText())); - emit(getNodeOutput(ui->yPositionSelect->currentText())); - emit(getNodeOutput(ui->zPositionSelect->currentText())); - emit(getNodeOutput(ui->pAttitudeSelect->currentText())); - emit(getNodeOutput(ui->rAttitudeSelect->currentText())); - emit(getNodeOutput(ui->yAttitudeSelect->currentText())); - } -} - -void MainWindow::updateTracker(float x, float y, float z, float p, float r, float yaw) -{ - ui->xActual->setText(QString::number(x)); - ui->yActual->setText(QString::number(y)); - ui->zActual->setText(QString::number(z)); - ui->pitchActual->setText(QString::number(p)); - ui->rollActual->setText(QString::number(r)); - ui->yawActual->setText(QString::number(yaw)); - - float dist = sqrt(pow(x - sp_x, 2.0) + pow(y - sp_y, 2.0) + pow(z - sp_z, 2.0)); - - ui->dist->setText(QString::number(dist)); - - if (!nextSpTimer->isActive() && ui->autonavEnabled->isChecked() && - (dist < ui->autonavThreshold->text().toFloat())) { - nextSpTimer->start(ui->autonavDelay->text().toInt()); - } -} - -void MainWindow::on_pbStart_clicked() -{ - backendProcess->setProgram(ui->backendPath->text()); - - backendProcess->start(); -} - -void MainWindow::backendStarted() -{ - ui->pbStart->setEnabled(false); - ui->pbStop->setEnabled(true); - workerStartTimer->start(750); -} - -void MainWindow::backendError(QProcess::ProcessError error) -{ - ui->vConsole->append(backendProcess->errorString()); -} - -void MainWindow::backendRead() -{ - ui->vConsole->append(backendProcess->readAll()); -} - -void MainWindow::workerConnected() -{ - connectedWorkers++; - if (connectedWorkers == 2) { - ui->pbStart->setEnabled(false); - ui->pbConnect->setEnabled(false); - ui->pbStop->setEnabled(true); - } -} - -void MainWindow::workerDisconnected() -{ - connectedWorkers--; - if (( connectedWorkers == 0) && (backendProcess->state() == QProcess::Running)) { - backendProcess->terminate(); - } else if (connectedWorkers == 0) { - ui->pbStart->setEnabled(true); - ui->pbConnect->setEnabled(true); - ui->pbStop->setEnabled(false); - } -} - -void MainWindow::backendFinished(int exitCode, QProcess::ExitStatus exitStatus) -{ - ui->pbStart->setEnabled(true); - ui->pbConnect->setEnabled(true); - ui->pbStop->setEnabled(false); -} - -void MainWindow::on_pbConnect_clicked() -{ - emit(connectWorkers()); -} - -void MainWindow::on_pbStop_clicked() -{ - emit(disconnectWorkers()); -} - -void MainWindow::on_chooseBackend_clicked() -{ - QString backendPath = QFileDialog::getOpenFileName(this, - tr("Path to Backend Executable")); - ui->backendPath->setText(backendPath); -} - - -void MainWindow::newNodes(QStringList blocks) -{ - QComboBox * select = ui->nodeSelect; - select->clear(); - select->addItems(blocks); - - this->ui->noGraphWarning1->setVisible(false); - this->ui->noGraphWarning2->setVisible(false); - this->ui->noGraphWarningLine->setVisible(false); -} - -void MainWindow::newConstantBlocks(QStringList blocks) -{ - ui->xSetpointSelect->clear(); - ui->xSetpointSelect->addItems(blocks); - - ui->ySetpointSelect->clear(); - ui->ySetpointSelect->addItems(blocks); - - ui->zSetpointSelect->clear(); - ui->zSetpointSelect->addItems(blocks); - - ui->yawSetpointSelect->clear(); - ui->yawSetpointSelect->addItems(blocks); - - ui->xPositionSelect->clear(); - ui->xPositionSelect->addItems(blocks); - - ui->yPositionSelect->clear(); - ui->yPositionSelect->addItems(blocks); - - ui->zPositionSelect->clear(); - ui->zPositionSelect->addItems(blocks); - - ui->pAttitudeSelect->clear(); - ui->pAttitudeSelect->addItems(blocks); - - ui->rAttitudeSelect->clear(); - ui->rAttitudeSelect->addItems(blocks); - - ui->yAttitudeSelect->clear(); - ui->yAttitudeSelect->addItems(blocks); - - for (ssize_t i = 0; i < blocks.size(); i++) { - if (blocks[i].contains("setpoint", Qt::CaseInsensitive) || blocks[i].contains("sp", Qt::CaseInsensitive)) { - if (blocks[i].contains("x ", Qt::CaseInsensitive)) { - ui->xSetpointSelect->setCurrentIndex(i); - } - if (blocks[i].contains("y ", Qt::CaseInsensitive)) { - ui->ySetpointSelect->setCurrentIndex(i); - } - if (blocks[i].contains("z ", Qt::CaseInsensitive) || blocks[i].contains("alt", Qt::CaseInsensitive)) { - ui->zSetpointSelect->setCurrentIndex(i); - } - if (blocks[i].contains("yaw", Qt::CaseInsensitive) || blocks[i].contains("alt", Qt::CaseInsensitive)) { - ui->yawSetpointSelect->setCurrentIndex(i); - } - } - - if (blocks[i] == QString("Pitch")) { - ui->pAttitudeSelect->setCurrentIndex(i); - } - - if (blocks[i] == QString("Roll")) { - ui->rAttitudeSelect->setCurrentIndex(i); - } - - if (blocks[i] == QString("Yaw")) { - ui->yAttitudeSelect->setCurrentIndex(i); - } - - if (blocks[i] == QString("Lidar")) { - ui->zPositionSelect->setCurrentIndex(i); - } - - if (blocks[i] == QString("OF X Trim Add")) { - ui->xPositionSelect->setCurrentIndex(i); - } - - if (blocks[i] == QString("OF Y Trim Add")) { - ui->yPositionSelect->setCurrentIndex(i); - } - } -} - -void MainWindow::newNodeOutput(QString node, float val) -{ - /* Update the nav page if quad is set as the source for pos/att */ - if (node == ui->xPositionSelect->currentText()) { - ui->xActual->setText(QString::number(val)); - } else if (node == ui->yPositionSelect->currentText()) { - ui->yActual->setText(QString::number(val)); - } else if (node == ui->zPositionSelect->currentText()) { - ui->zActual->setText(QString::number(val)); - } else if (node == ui->pAttitudeSelect->currentText()) { - ui->pitchActual->setText(QString::number(val)); - } else if (node == ui->rAttitudeSelect->currentText()) { - ui->rollActual->setText(QString::number(val)); - } else if (node == ui->yAttitudeSelect->currentText()) { - ui->yawActual->setText(QString::number(val)); - } -} - -void MainWindow::newParams(QStringList params) -{ - QComboBox * select = ui->paramSelect; - select->clear(); - select->addItems(params); -} - -void MainWindow::newParamValue(QString node, QString param, float val) -{ - ui->paramValue->setText(QString::number(val)); - - /* Update the nav page setpoints if it's a setpoint paramvalue */ - if (node == ui->xSetpointSelect->currentText()) { - ui->xSetpoint->setText(QString::number(val)); - } else if (node == ui->ySetpointSelect->currentText()) { - ui->ySetpoint->setText(QString::number(val)); - } else if (node == ui->zSetpointSelect->currentText()) { - ui->zSetpoint->setText(QString::number(val)); - } -} - -void MainWindow::on_paramSelect_currentIndexChanged(const QString &arg1) -{ - emit(getParamValue(ui->nodeSelect->currentText(), arg1)); -} - -void MainWindow::on_paramValue_returnPressed() -{ - emit (setParamValue(ui->nodeSelect->currentText(), - ui->paramSelect->currentText(), - ui->paramValue->text().toFloat())); -} - -void MainWindow::sendSetpoints() -{ - if (ui->sendX->isChecked()) { - sp_x = ui->xSetpoint->text().toFloat(); - emit (setParamValue(ui->xSetpointSelect->currentText(), - blockDefs[BLOCK_CONSTANT]->param_names[0], sp_x)); - } - - if (ui->sendY->isChecked()) { - sp_y = ui->ySetpoint->text().toFloat(); - emit (setParamValue(ui->ySetpointSelect->currentText(), - blockDefs[BLOCK_CONSTANT]->param_names[0], sp_y)); - } - - if (ui->sendZ->isChecked()) { - sp_z = ui->zSetpoint->text().toFloat(); - emit (setParamValue(ui->zSetpointSelect->currentText(), - blockDefs[BLOCK_CONSTANT]->param_names[0], sp_z)); - } - - if (ui->sendYaw->isChecked()) { - emit (setParamValue(ui->yawSetpointSelect->currentText(), - blockDefs[BLOCK_CONSTANT]->param_names[0], - ui->yawSetpoint->text().toFloat())); - } -} - -void MainWindow::on_pbAppendSetpoint_clicked() -{ - QString str("[" + ui->xSetpoint->text() + ", "+ - ui->ySetpoint->text() + ", " + - ui->zSetpoint->text() + ", " + - ui->yawSetpoint->text() + "]"); - - setpointList->appendRow(new QStandardItem(str)); -} - -void MainWindow::on_pbNextSetpoint_clicked() -{ - QListView * listView = ui->setpointList; - if (listView->currentIndex().isValid() && setpointList->index(listView->currentIndex().row() + 1, 0).isValid()) { - listView->setCurrentIndex(setpointList->index(listView->currentIndex().row() + 1, 0)); - } else { - listView->setCurrentIndex(setpointList->index(0, 0)); - } - sendSelectedSetpoint(); -} - - -void MainWindow::sendSelectedSetpoint() -{ - if (ui->setpointList->currentIndex().isValid()) { - QRegExp regex("\\[(.*), (.*), (.*), (.*)\\]"); - int row = ui->setpointList->currentIndex().row(); - - regex.indexIn(setpointList->item(row)->text()); - ui->xSetpoint->setText(regex.cap(1)); - ui->ySetpoint->setText(regex.cap(2)); - ui->zSetpoint->setText(regex.cap(3)); - ui->yawSetpoint->setText(regex.cap(4)); - - sendSetpoints(); - } -} - -void MainWindow::on_pbActualToSetpoint_clicked() -{ - ui->xSetpoint->setText(ui->xActual->text()); - ui->ySetpoint->setText(ui->yActual->text()); - ui->zSetpoint->setText(ui->zActual->text()); - ui->yawSetpoint->setText(ui->yawActual->text()); -} - -void MainWindow::on_pbDeleteSetpoint_clicked() -{ - if (ui->setpointList->currentIndex().isValid()) { - setpointList->removeRow(ui->setpointList->currentIndex().row()); - } -} - -void MainWindow::newControlGraph(QString graph) -{ - ui->graphImage->setPixmap(QPixmap(graph)); -} - -void MainWindow::on_pbActualToWaypoint_clicked() -{ - QString str("[" + ui->xActual->text() + ", "+ - ui->yActual->text() + ", " + - ui->zActual->text() + ", " + - ui->yawActual->text() + "]"); - - setpointList->appendRow(new QStandardItem(str)); -} - -void MainWindow::on_pbMoveUp_clicked() -{ - if (ui->setpointList->currentIndex().isValid()) { - int current = ui->setpointList->currentIndex().row(); - if (current > 0) { - setpointList->insertRow(current - 1, setpointList->takeItem(current)); - setpointList->removeRow(current + 1); - } - } -} - -void MainWindow::on_pbMoveDown_clicked() -{ - if (ui->setpointList->currentIndex().isValid()) { - int current = ui->setpointList->currentIndex().row(); - if (current < (setpointList->rowCount() - 1)) { - setpointList->insertRow(current + 2, setpointList->takeItem(current)); - setpointList->removeRow(current); - } - } -} - -void MainWindow::on_pbInsertSetpoint_clicked() -{ - int current = 0; - if (ui->setpointList->currentIndex().isValid()) { - current = ui->setpointList->currentIndex().row(); - } - - QString str("[" + ui->xSetpoint->text() + ", "+ - ui->ySetpoint->text() + ", " + - ui->zSetpoint->text() + ", " + - ui->yawSetpoint->text() + "]"); - setpointList->insertRow(current, new QStandardItem(str)); -} - -void MainWindow::on_pbSaveWaypoints_clicked() -{ - QString filter = "Waypoints (*.wpt)"; - QString savePath = QFileDialog::getSaveFileName(this, tr("Save waypoint"), QString(), filter, &filter, QFileDialog::DontUseNativeDialog); - - if (!savePath.isEmpty()) { - QFileInfo finfo(savePath); - if (finfo.suffix().isNull()) - savePath.append(".wpt"); - QFile f(savePath); - f.open(QIODevice::WriteOnly | QIODevice::Text); - for (int i= 0; i < setpointList->rowCount(); i++) { - f.write(setpointList->item(i)->text().toStdString().c_str()); - f.write("\n"); - } - f.close(); - } -} - -void MainWindow::on_pbLoadWaypoints_clicked() -{ - - QString filter = "Waypoints (*.wpt)"; - QString openPath = QFileDialog::getOpenFileName(this, tr("Open Waypoint File"), QString(),filter); - - if (!openPath.isEmpty()) { - QFile f(openPath); - f.open(QIODevice::ReadOnly | QIODevice::Text); - - setpointList->clear(); - while (!f.atEnd()) { - QString line = f.readLine(); - line.chop(1); - setpointList->appendRow(new QStandardItem(line)); - } - f.close(); - } -} - -void Mainwindow::on_update_data_request_params_button_clicked() -{ - QString text = "testing button pressing"; - ui->flight_data_labelsetText(text); -} - -void MainWindow::on_xSetpoint_returnPressed() -{ - sp_x = ui->xSetpoint->text().toFloat(); - emit (setParamValue(ui->xSetpointSelect->currentText(), - blockDefs[BLOCK_CONSTANT]->param_names[0], sp_x)); -} - -void MainWindow::on_ySetpoint_returnPressed() -{ - sp_y = ui->ySetpoint->text().toFloat(); - emit (setParamValue(ui->ySetpointSelect->currentText(), - blockDefs[BLOCK_CONSTANT]->param_names[0], sp_y)); -} - -void MainWindow::on_zSetpoint_returnPressed() -{ - sp_z = ui->zSetpoint->text().toFloat(); - emit (setParamValue(ui->zSetpointSelect->currentText(), - blockDefs[BLOCK_CONSTANT]->param_names[0], sp_z)); -} - -void MainWindow::on_yawSetpoint_returnPressed() -{ - emit (setParamValue(ui->yawSetpointSelect->currentText(), - blockDefs[BLOCK_CONSTANT]->param_names[0], - ui->yawSetpoint->text().toFloat())); -} - -void MainWindow::on_posattSrcVrpn_clicked() -{ - trackerTimer->setInterval(100); -} - -void MainWindow::on_posattSrcQuad_clicked() -{ - trackerTimer->setInterval(750); -} +#include "mainwindow.h" +#include "ui_mainwindow.h" + +#include <QFileDialog> +#include <QDesktopServices> +#include <QMessageBox> +#include <QThread> +#include <QTimer> +#include <QRegExp> +#include <QProcessEnvironment> +#include <QPixmap> +#include <QProcess> + +#include "trackerworker.h" +#include "controlworker.h" +#include "quaditem.h" +#include "slotprocess.h" +#include "qFlightInstruments.h" +#include "graph_blocks.h" + +#include <iostream> +MainWindow::MainWindow(QWidget *parent) : + QMainWindow(parent), + ui(new Ui::MainWindow), + setpointList(new QStandardItemModel(this)), + nextSpTimer(new QTimer(this)), + sp_x(0.0f), + sp_y(0.0f), + sp_z(0.0f), + trackerTimer(new QTimer(this)), + workerStartTimer(new QTimer(this)), + backendProcess(new QProcess(this)), + matlabProcess(new QProcess(this)), + connectedWorkers(0) +{ + ui->setupUi(this); + + QGraphicsScene *posScene = new QGraphicsScene(this); + ui->posView->setScene(posScene); + QuadItem * posIndicator = new QuadItem(); + posScene->addItem(posIndicator); + + QGraphicsScene *attScene = new QGraphicsScene(this); + ui->attView->setScene(attScene); + QADI * attIndicator = new QADI(); + attScene->addWidget(attIndicator); + + + workerStartTimer->setSingleShot(true); + + /* Create a thread for workers */ + QThread* workerThread = new QThread(this); + + /* Create a worker to update the tracker */ + TrackerWorker * trackerWorker = new TrackerWorker(); + + /* Move it to the worker thread. This means that slots of this worker + * will run in the worker thread, and not block the UI */ + trackerWorker->moveToThread(workerThread); + + /* Connect tracker worker */ + connect(trackerWorker, SIGNAL (finished(float, float, float, float, float, float)), + this, SLOT (updateTracker(float, float, float, float, float, float))); + + connect(trackerWorker, SIGNAL (finished(float, float, float, float, float, float)), + posIndicator, SLOT(updatePos(float,float,float,float,float,float))); + + connect(trackerWorker, SIGNAL (finished(float, float, float, float, float, float)), + attIndicator, SLOT(updateAttitude(float, float, float, float, float, float))); + + backendProcess->setProcessChannelMode(QProcess::MergedChannels); + + /* Create another worker for the control graph */ + QThread * cwThread = new QThread(this); + ControlWorker * controlWorker = new ControlWorker(); + controlWorker->moveToThread(cwThread); + + /* Connect signals from control worker */ + connect(controlWorker, SIGNAL (gotNodes(QStringList)), this, SLOT (newNodes(QStringList))); + connect(controlWorker, SIGNAL (gotParams(QStringList)), this, SLOT (newParams(QStringList))); + connect(controlWorker, SIGNAL (gotParamValue(QString, QString, float)), this, SLOT (newParamValue(QString, QString, float))); + connect(controlWorker, SIGNAL (gotNodeOutput(QString, float)), this, SLOT (newNodeOutput(QString, float))); + connect(controlWorker, SIGNAL (gotConstantBlocks(QStringList)), this, SLOT (newConstantBlocks(QStringList))); + connect(controlWorker, SIGNAL (graphRendered(QString)), this, SLOT (newControlGraph(QString))); + connect(controlWorker, SIGNAL (paramSet(QString, QString)), controlWorker, SLOT (getParamValue(QString, QString))); + + /* Signals to control worker */ + connect(ui->pbControlRefresh, SIGNAL (clicked()), controlWorker, SLOT (getNodes())); + connect(ui->nodeSelect, SIGNAL (currentIndexChanged(QString)), controlWorker, SLOT (getParams(QString))); + connect(this, SIGNAL (getParamValue(QString, QString)), controlWorker, SLOT (getParamValue(QString, QString))); + connect(this, SIGNAL (setParamValue(QString, QString, float)), controlWorker, SLOT (setParamValue(QString, QString, float))); + connect(this, SIGNAL (getNodeOutput(QString)), controlWorker, SLOT (getNodeOutput(QString))); + + /* Connect and disconnect from backend when signals emitted */ + connect(workerStartTimer, SIGNAL (timeout()), trackerWorker, SLOT (connectBackend())); + connect(workerStartTimer, SIGNAL (timeout()), controlWorker, SLOT (connectBackend())); + connect(this, SIGNAL (connectWorkers()), trackerWorker, SLOT (connectBackend())); + connect(this, SIGNAL (connectWorkers()), controlWorker, SLOT (connectBackend())); + connect(this, SIGNAL (disconnectWorkers()), trackerWorker, SLOT (disconnectBackend())); + connect(this, SIGNAL (disconnectWorkers()), controlWorker, SLOT (disconnectBackend())); + + connect(backendProcess, SIGNAL (started()), this, SLOT (backendStarted())); + connect(backendProcess, SIGNAL (errorOccurred(QProcess::ProcessError)), this, SLOT (backendError(QProcess::ProcessError))); + connect(backendProcess, SIGNAL (finished(int, QProcess::ExitStatus)), this, SLOT (backendFinished(int, QProcess::ExitStatus))); + connect(backendProcess, SIGNAL (readyReadStandardOutput()), this, SLOT (backendRead())); + connect(backendProcess, SIGNAL (readyReadStandardError()), this, SLOT (backendRead())); + + connect(controlWorker, SIGNAL (connected()), this, SLOT (workerConnected())); + connect(controlWorker, SIGNAL (disconnected()), this, SLOT (workerDisconnected())); + + connect(trackerWorker, SIGNAL (connected()), this, SLOT (workerConnected())); + connect(trackerWorker, SIGNAL (disconnected()), this, SLOT (workerDisconnected())); + + /* Connect refresh button and refresh timer to tracker worker */ + connect(trackerTimer, SIGNAL(timeout()), this, SLOT(updatePosAtt())); + connect(ui->pbRefresh, SIGNAL (clicked()), this, SLOT (updatePosAtt())); + + connect(this, SIGNAL(getPosAttFromBackend()), trackerWorker, SLOT(process())); + + /* Timer used for next setpoint */ + nextSpTimer->setSingleShot(true); + connect(nextSpTimer, SIGNAL (timeout()), this, SLOT (on_pbNextSetpoint_clicked())); + + /* Start the things */ + trackerTimer->start(100); + workerThread->start(); + cwThread->start(); + matlabProcess->start(); + + /* Connect the setpointlist to the model */ + ui->setpointList->setModel(setpointList); + + /* Connect various things that can result in sending setpoints */ + connect(ui->pbSendSetpoint, SIGNAL (clicked()), this, SLOT (sendSetpoints())); + connect(ui->setpointList, SIGNAL (doubleClicked(QModelIndex)), this, SLOT (sendSelectedSetpoint())); + + /* Populate scripts list */ + QDir scriptsDir("scripts/"); + QStringList scripts = scriptsDir.entryList(); + for (int i = 0; i < scripts.size(); i++) { + QAction * action = ui->menuScripts->addAction(scripts[i]); + SlotProcess * scriptProcess = new SlotProcess(action); + scriptProcess->setProgram(scriptsDir.filePath(scripts[i])); + connect(action, SIGNAL (triggered()), scriptProcess, SLOT (startProcess())); + } + +} + +MainWindow::~MainWindow() +{ + delete ui; +} + +void MainWindow::connectMatlab() +{ + +} + +void MainWindow::on_run_data_analysis_button_clicked() +{ + QProcess * matProcess = new QProcess(this); + QString matlab = "/usr/local/bin/matlab"; + matProcess->start(matlab, QStringList() << QString("-nodesktop")<< QString("-nosplash")<<QString("-r")<<QString("run('../../../controls/DataAnalysisTool/Tool/GUI.m');")); +} + +void MainWindow::updatePosAtt() +{ + if (ui->posattSrcVrpn->isChecked()) { + emit(getPosAttFromBackend()); + } else if (ui->posattSrcQuad->isChecked()) { + emit(getNodeOutput(ui->xPositionSelect->currentText())); + emit(getNodeOutput(ui->yPositionSelect->currentText())); + emit(getNodeOutput(ui->zPositionSelect->currentText())); + emit(getNodeOutput(ui->pAttitudeSelect->currentText())); + emit(getNodeOutput(ui->rAttitudeSelect->currentText())); + emit(getNodeOutput(ui->yAttitudeSelect->currentText())); + } +} + +void MainWindow::updateTracker(float x, float y, float z, float p, float r, float yaw) +{ + ui->xActual->setText(QString::number(x)); + ui->yActual->setText(QString::number(y)); + ui->zActual->setText(QString::number(z)); + ui->pitchActual->setText(QString::number(p)); + ui->rollActual->setText(QString::number(r)); + ui->yawActual->setText(QString::number(yaw)); + + float dist = sqrt(pow(x - sp_x, 2.0) + pow(y - sp_y, 2.0) + pow(z - sp_z, 2.0)); + + ui->dist->setText(QString::number(dist)); + + if (!nextSpTimer->isActive() && ui->autonavEnabled->isChecked() && + (dist < ui->autonavThreshold->text().toFloat())) { + nextSpTimer->start(ui->autonavDelay->text().toInt()); + } +} + +void MainWindow::on_pbStart_clicked() +{ + backendProcess->setProgram(ui->backendPath->text()); + + backendProcess->start(); +} + +void MainWindow::backendStarted() +{ + ui->pbStart->setEnabled(false); + ui->pbStop->setEnabled(true); + workerStartTimer->start(750); +} + +void MainWindow::backendError(QProcess::ProcessError error) +{ + ui->vConsole->append(backendProcess->errorString()); +} + +void MainWindow::backendRead() +{ + ui->vConsole->append(backendProcess->readAll()); +} + +void MainWindow::workerConnected() +{ + connectedWorkers++; + if (connectedWorkers == 2) { + ui->pbStart->setEnabled(false); + ui->pbConnect->setEnabled(false); + ui->pbStop->setEnabled(true); + } +} + +void MainWindow::workerDisconnected() +{ + connectedWorkers--; + if (( connectedWorkers == 0) && (backendProcess->state() == QProcess::Running)) { + backendProcess->terminate(); + } else if (connectedWorkers == 0) { + ui->pbStart->setEnabled(true); + ui->pbConnect->setEnabled(true); + ui->pbStop->setEnabled(false); + } +} + +void MainWindow::backendFinished(int exitCode, QProcess::ExitStatus exitStatus) +{ + ui->pbStart->setEnabled(true); + ui->pbConnect->setEnabled(true); + ui->pbStop->setEnabled(false); +} + +void MainWindow::on_pbConnect_clicked() +{ + emit(connectWorkers()); +} + +void MainWindow::on_pbStop_clicked() +{ + emit(disconnectWorkers()); +} + +void MainWindow::on_chooseBackend_clicked() +{ + QString backendPath = QFileDialog::getOpenFileName(this, + tr("Path to Backend Executable")); + ui->backendPath->setText(backendPath); +} + + +void MainWindow::newNodes(QStringList blocks) +{ + QComboBox * select = ui->nodeSelect; + select->clear(); + select->addItems(blocks); + + this->ui->noGraphWarning1->setVisible(false); + this->ui->noGraphWarning2->setVisible(false); + this->ui->noGraphWarningLine->setVisible(false); +} + +void MainWindow::newConstantBlocks(QStringList blocks) +{ + ui->xSetpointSelect->clear(); + ui->xSetpointSelect->addItems(blocks); + + ui->ySetpointSelect->clear(); + ui->ySetpointSelect->addItems(blocks); + + ui->zSetpointSelect->clear(); + ui->zSetpointSelect->addItems(blocks); + + ui->yawSetpointSelect->clear(); + ui->yawSetpointSelect->addItems(blocks); + + ui->xPositionSelect->clear(); + ui->xPositionSelect->addItems(blocks); + + ui->yPositionSelect->clear(); + ui->yPositionSelect->addItems(blocks); + + ui->zPositionSelect->clear(); + ui->zPositionSelect->addItems(blocks); + + ui->pAttitudeSelect->clear(); + ui->pAttitudeSelect->addItems(blocks); + + ui->rAttitudeSelect->clear(); + ui->rAttitudeSelect->addItems(blocks); + + ui->yAttitudeSelect->clear(); + ui->yAttitudeSelect->addItems(blocks); + + for (ssize_t i = 0; i < blocks.size(); i++) { + if (blocks[i].contains("setpoint", Qt::CaseInsensitive) || blocks[i].contains("sp", Qt::CaseInsensitive)) { + if (blocks[i].contains("x ", Qt::CaseInsensitive)) { + ui->xSetpointSelect->setCurrentIndex(i); + } + if (blocks[i].contains("y ", Qt::CaseInsensitive)) { + ui->ySetpointSelect->setCurrentIndex(i); + } + if (blocks[i].contains("z ", Qt::CaseInsensitive) || blocks[i].contains("alt", Qt::CaseInsensitive)) { + ui->zSetpointSelect->setCurrentIndex(i); + } + if (blocks[i].contains("yaw", Qt::CaseInsensitive) || blocks[i].contains("alt", Qt::CaseInsensitive)) { + ui->yawSetpointSelect->setCurrentIndex(i); + } + } + + if (blocks[i] == QString("Pitch")) { + ui->pAttitudeSelect->setCurrentIndex(i); + } + + if (blocks[i] == QString("Roll")) { + ui->rAttitudeSelect->setCurrentIndex(i); + } + + if (blocks[i] == QString("Yaw")) { + ui->yAttitudeSelect->setCurrentIndex(i); + } + + if (blocks[i] == QString("Lidar")) { + ui->zPositionSelect->setCurrentIndex(i); + } + + if (blocks[i] == QString("OF X Trim Add")) { + ui->xPositionSelect->setCurrentIndex(i); + } + + if (blocks[i] == QString("OF Y Trim Add")) { + ui->yPositionSelect->setCurrentIndex(i); + } + } +} + +void MainWindow::newNodeOutput(QString node, float val) +{ + /* Update the nav page if quad is set as the source for pos/att */ + if (node == ui->xPositionSelect->currentText()) { + ui->xActual->setText(QString::number(val)); + } else if (node == ui->yPositionSelect->currentText()) { + ui->yActual->setText(QString::number(val)); + } else if (node == ui->zPositionSelect->currentText()) { + ui->zActual->setText(QString::number(val)); + } else if (node == ui->pAttitudeSelect->currentText()) { + ui->pitchActual->setText(QString::number(val)); + } else if (node == ui->rAttitudeSelect->currentText()) { + ui->rollActual->setText(QString::number(val)); + } else if (node == ui->yAttitudeSelect->currentText()) { + ui->yawActual->setText(QString::number(val)); + } +} + +void MainWindow::newParams(QStringList params) +{ + QComboBox * select = ui->paramSelect; + select->clear(); + select->addItems(params); +} + +void MainWindow::newParamValue(QString node, QString param, float val) +{ + ui->paramValue->setText(QString::number(val)); + + /* Update the nav page setpoints if it's a setpoint paramvalue */ + if (node == ui->xSetpointSelect->currentText()) { + ui->xSetpoint->setText(QString::number(val)); + } else if (node == ui->ySetpointSelect->currentText()) { + ui->ySetpoint->setText(QString::number(val)); + } else if (node == ui->zSetpointSelect->currentText()) { + ui->zSetpoint->setText(QString::number(val)); + } +} + +void MainWindow::on_paramSelect_currentIndexChanged(const QString &arg1) +{ + emit(getParamValue(ui->nodeSelect->currentText(), arg1)); +} + +void MainWindow::on_paramValue_returnPressed() +{ + emit (setParamValue(ui->nodeSelect->currentText(), + ui->paramSelect->currentText(), + ui->paramValue->text().toFloat())); +} + +void MainWindow::sendSetpoints() +{ + if (ui->sendX->isChecked()) { + sp_x = ui->xSetpoint->text().toFloat(); + emit (setParamValue(ui->xSetpointSelect->currentText(), + blockDefs[BLOCK_CONSTANT]->param_names[0], sp_x)); + } + + if (ui->sendY->isChecked()) { + sp_y = ui->ySetpoint->text().toFloat(); + emit (setParamValue(ui->ySetpointSelect->currentText(), + blockDefs[BLOCK_CONSTANT]->param_names[0], sp_y)); + } + + if (ui->sendZ->isChecked()) { + sp_z = ui->zSetpoint->text().toFloat(); + emit (setParamValue(ui->zSetpointSelect->currentText(), + blockDefs[BLOCK_CONSTANT]->param_names[0], sp_z)); + } + + if (ui->sendYaw->isChecked()) { + emit (setParamValue(ui->yawSetpointSelect->currentText(), + blockDefs[BLOCK_CONSTANT]->param_names[0], + ui->yawSetpoint->text().toFloat())); + } +} + +void MainWindow::on_pbAppendSetpoint_clicked() +{ + QString str("[" + ui->xSetpoint->text() + ", "+ + ui->ySetpoint->text() + ", " + + ui->zSetpoint->text() + ", " + + ui->yawSetpoint->text() + "]"); + + setpointList->appendRow(new QStandardItem(str)); +} + +void MainWindow::on_pbNextSetpoint_clicked() +{ + QListView * listView = ui->setpointList; + if (listView->currentIndex().isValid() && setpointList->index(listView->currentIndex().row() + 1, 0).isValid()) { + listView->setCurrentIndex(setpointList->index(listView->currentIndex().row() + 1, 0)); + } else { + listView->setCurrentIndex(setpointList->index(0, 0)); + } + sendSelectedSetpoint(); +} + + +void MainWindow::sendSelectedSetpoint() +{ + if (ui->setpointList->currentIndex().isValid()) { + QRegExp regex("\\[(.*), (.*), (.*), (.*)\\]"); + int row = ui->setpointList->currentIndex().row(); + + regex.indexIn(setpointList->item(row)->text()); + ui->xSetpoint->setText(regex.cap(1)); + ui->ySetpoint->setText(regex.cap(2)); + ui->zSetpoint->setText(regex.cap(3)); + ui->yawSetpoint->setText(regex.cap(4)); + + sendSetpoints(); + } +} + +void MainWindow::on_pbActualToSetpoint_clicked() +{ + ui->xSetpoint->setText(ui->xActual->text()); + ui->ySetpoint->setText(ui->yActual->text()); + ui->zSetpoint->setText(ui->zActual->text()); + ui->yawSetpoint->setText(ui->yawActual->text()); +} + +void MainWindow::on_pbDeleteSetpoint_clicked() +{ + if (ui->setpointList->currentIndex().isValid()) { + setpointList->removeRow(ui->setpointList->currentIndex().row()); + } +} + +void MainWindow::newControlGraph(QString graph) +{ + ui->graphImage->setPixmap(QPixmap(graph)); +} + +void MainWindow::on_pbActualToWaypoint_clicked() +{ + QString str("[" + ui->xActual->text() + ", "+ + ui->yActual->text() + ", " + + ui->zActual->text() + ", " + + ui->yawActual->text() + "]"); + + setpointList->appendRow(new QStandardItem(str)); +} + +void MainWindow::on_pbMoveUp_clicked() +{ + if (ui->setpointList->currentIndex().isValid()) { + int current = ui->setpointList->currentIndex().row(); + if (current > 0) { + setpointList->insertRow(current - 1, setpointList->takeItem(current)); + setpointList->removeRow(current + 1); + } + } +} + +void MainWindow::on_pbMoveDown_clicked() +{ + if (ui->setpointList->currentIndex().isValid()) { + int current = ui->setpointList->currentIndex().row(); + if (current < (setpointList->rowCount() - 1)) { + setpointList->insertRow(current + 2, setpointList->takeItem(current)); + setpointList->removeRow(current); + } + } +} + +void MainWindow::on_pbInsertSetpoint_clicked() +{ + int current = 0; + if (ui->setpointList->currentIndex().isValid()) { + current = ui->setpointList->currentIndex().row(); + } + + QString str("[" + ui->xSetpoint->text() + ", "+ + ui->ySetpoint->text() + ", " + + ui->zSetpoint->text() + ", " + + ui->yawSetpoint->text() + "]"); + setpointList->insertRow(current, new QStandardItem(str)); +} + +void MainWindow::on_pbSaveWaypoints_clicked() +{ + QString filter = "Waypoints (*.wpt)"; + QString savePath = QFileDialog::getSaveFileName(this, tr("Save waypoint"), QString(), filter, &filter, QFileDialog::DontUseNativeDialog); + + if (!savePath.isEmpty()) { + QFileInfo finfo(savePath); + if (finfo.suffix().isNull()) + savePath.append(".wpt"); + QFile f(savePath); + f.open(QIODevice::WriteOnly | QIODevice::Text); + for (int i= 0; i < setpointList->rowCount(); i++) { + f.write(setpointList->item(i)->text().toStdString().c_str()); + f.write("\n"); + } + f.close(); + } +} + +void MainWindow::on_pbLoadWaypoints_clicked() +{ + + QString filter = "Waypoints (*.wpt)"; + QString openPath = QFileDialog::getOpenFileName(this, tr("Open Waypoint File"), QString(),filter); + + if (!openPath.isEmpty()) { + QFile f(openPath); + f.open(QIODevice::ReadOnly | QIODevice::Text); + + setpointList->clear(); + while (!f.atEnd()) { + QString line = f.readLine(); + line.chop(1); + setpointList->appendRow(new QStandardItem(line)); + } + f.close(); + } +} + +void MainWindow::on_xSetpoint_returnPressed() +{ + sp_x = ui->xSetpoint->text().toFloat(); + emit (setParamValue(ui->xSetpointSelect->currentText(), + blockDefs[BLOCK_CONSTANT]->param_names[0], sp_x)); +} + +void MainWindow::on_ySetpoint_returnPressed() +{ + sp_y = ui->ySetpoint->text().toFloat(); + emit (setParamValue(ui->ySetpointSelect->currentText(), + blockDefs[BLOCK_CONSTANT]->param_names[0], sp_y)); +} + +void MainWindow::on_zSetpoint_returnPressed() +{ + sp_z = ui->zSetpoint->text().toFloat(); + emit (setParamValue(ui->zSetpointSelect->currentText(), + blockDefs[BLOCK_CONSTANT]->param_names[0], sp_z)); +} + +void MainWindow::on_yawSetpoint_returnPressed() +{ + emit (setParamValue(ui->yawSetpointSelect->currentText(), + blockDefs[BLOCK_CONSTANT]->param_names[0], + ui->yawSetpoint->text().toFloat())); +} + +void MainWindow::on_posattSrcVrpn_clicked() +{ + trackerTimer->setInterval(100); +} + +void MainWindow::on_posattSrcQuad_clicked() +{ + trackerTimer->setInterval(750); +} diff --git a/groundStation/gui/MicroCART/mainwindow.h b/groundStation/gui/MicroCART/mainwindow.h index db5534abe83d6d4301fe593f7db2531a591c469b..3ad5ed1da5fd958ad1f1b1a7f4c534e0ed7763d6 100644 --- a/groundStation/gui/MicroCART/mainwindow.h +++ b/groundStation/gui/MicroCART/mainwindow.h @@ -1,109 +1,113 @@ -#ifndef MAINWINDOW_H -#define MAINWINDOW_H - -#include <QMainWindow> -#include <QStringList> -#include <QStandardItemModel> -#include <QGraphicsScene> -#include "quaditem.h" - -namespace Ui { -class MainWindow; -} - -class MainWindow : public QMainWindow -{ - Q_OBJECT - -public: - explicit MainWindow(QWidget *parent = 0); - ~MainWindow(); - -signals: - void connectWorkers(); - void disconnectWorkers(); - void getParamValue(QString node, QString param); - void getNodeOutput(QString node); - void setParamValue(QString node, QString param, float value); - void getPosAttFromBackend(); - -private slots: - void on_pbStart_clicked(); - - void on_pbConnect_clicked(); - - void on_pbStop_clicked(); - - void on_chooseBackend_clicked(); - - void updateTracker(float x, float y, float z, float p, float r, float yaw); - - void updatePosAtt(); - - void newNodes(QStringList blocks); - void newParams(QStringList params); - void newParamValue(QString node, QString param, float val); - void newNodeOutput(QString node, float output); - void newConstantBlocks(QStringList blocks); - void newControlGraph(QString graph); - - void on_paramSelect_currentIndexChanged(const QString &arg1); - - void on_paramValue_returnPressed(); - - void on_pbAppendSetpoint_clicked(); - - void on_pbNextSetpoint_clicked(); - - void sendSetpoints(); - void sendSelectedSetpoint(); - - void on_pbActualToSetpoint_clicked(); - - void on_pbDeleteSetpoint_clicked(); - - void on_pbActualToWaypoint_clicked(); - - void on_pbMoveUp_clicked(); - - void on_pbMoveDown_clicked(); - - void on_pbInsertSetpoint_clicked(); - - void on_pbSaveWaypoints_clicked(); - - void on_pbLoadWaypoints_clicked(); - - void on_xSetpoint_returnPressed(); - - void on_ySetpoint_returnPressed(); - - void on_zSetpoint_returnPressed(); - - void on_posattSrcVrpn_clicked(); - - void on_posattSrcQuad_clicked(); - - void on_yawSetpoint_returnPressed(); - - void backendStarted(); - void backendFinished(int exitCode, QProcess::ExitStatus exitStatus); - void backendError(QProcess::ProcessError error); - void backendRead(); - void workerConnected(); - void workerDisconnected(); - -private: - Ui::MainWindow *ui; - QStandardItemModel * setpointList; - QTimer * nextSpTimer; - float sp_x; - float sp_y; - float sp_z; - QTimer * trackerTimer; - QTimer * workerStartTimer; - QProcess * backendProcess; - int connectedWorkers; -}; - -#endif // MAINWINDOW_H +#ifndef MAINWINDOW_H +#define MAINWINDOW_H + +#include <QMainWindow> +#include <QStringList> +#include <QStandardItemModel> +#include <QGraphicsScene> +#include "quaditem.h" + +namespace Ui { +class MainWindow; +} + +class MainWindow : public QMainWindow +{ + Q_OBJECT + +public: + explicit MainWindow(QWidget *parent = 0); + ~MainWindow(); + +signals: + void connectWorkers(); + void disconnectWorkers(); + void getParamValue(QString node, QString param); + void getNodeOutput(QString node); + void setParamValue(QString node, QString param, float value); + void getPosAttFromBackend(); + +private slots: + void on_pbStart_clicked(); + + void on_pbConnect_clicked(); + + void on_pbStop_clicked(); + + void on_chooseBackend_clicked(); + + void updateTracker(float x, float y, float z, float p, float r, float yaw); + + void updatePosAtt(); + + void newNodes(QStringList blocks); + void newParams(QStringList params); + void newParamValue(QString node, QString param, float val); + void newNodeOutput(QString node, float output); + void newConstantBlocks(QStringList blocks); + void newControlGraph(QString graph); + + void on_paramSelect_currentIndexChanged(const QString &arg1); + + void on_paramValue_returnPressed(); + + void on_pbAppendSetpoint_clicked(); + + void on_pbNextSetpoint_clicked(); + + void sendSetpoints(); + void sendSelectedSetpoint(); + + void on_pbActualToSetpoint_clicked(); + + void on_pbDeleteSetpoint_clicked(); + + void on_pbActualToWaypoint_clicked(); + + void on_pbMoveUp_clicked(); + + void on_pbMoveDown_clicked(); + + void on_pbInsertSetpoint_clicked(); + + void on_pbSaveWaypoints_clicked(); + + void on_pbLoadWaypoints_clicked(); + + void on_xSetpoint_returnPressed(); + + void on_run_data_analysis_button_clicked(); + + void on_ySetpoint_returnPressed(); + + void on_zSetpoint_returnPressed(); + + void on_posattSrcVrpn_clicked(); + + void on_posattSrcQuad_clicked(); + + void on_yawSetpoint_returnPressed(); + + void backendStarted(); + void connectMatlab(); + void backendFinished(int exitCode, QProcess::ExitStatus exitStatus); + void backendError(QProcess::ProcessError error); + void backendRead(); + void workerConnected(); + void workerDisconnected(); + +private: + Ui::MainWindow *ui; + QStandardItemModel * setpointList; + QTimer * nextSpTimer; + float sp_x; + float sp_y; + float sp_z; + QTimer * trackerTimer; + QTimer * workerStartTimer; + QProcess * backendProcess; + QProcess * matlabProcess; + int connectedWorkers; +}; + +#endif // MAINWINDOW_H diff --git a/groundStation/gui/MicroCART/mainwindow.ui b/groundStation/gui/MicroCART/mainwindow.ui index 94d275d7031b022b7e0c907e4367cb97addf630c..a857eb3f830e1af472e52cbc99faa7c8d80f5df7 100644 --- a/groundStation/gui/MicroCART/mainwindow.ui +++ b/groundStation/gui/MicroCART/mainwindow.ui @@ -1,1259 +1,1148 @@ -<?xml version="1.0" encoding="UTF-8"?> -<ui version="4.0"> - <class>MainWindow</class> - <widget class="QMainWindow" name="MainWindow"> - <property name="geometry"> - <rect> - <x>0</x> - <y>0</y> - <width>1186</width> - <height>1034</height> - </rect> - </property> - <property name="windowTitle"> - <string>MainWindow</string> - </property> - <widget class="QWidget" name="centralWidget"> - <layout class="QVBoxLayout" name="verticalLayout_4"> - <item> - <widget class="QTabWidget" name="tabWidget"> - <property name="currentIndex"> - <number>3</number> - </property> - <widget class="QWidget" name="backend"> - <attribute name="title"> - <string>Backend</string> - </attribute> - <layout class="QVBoxLayout" name="verticalLayout"> - <item> - <layout class="QHBoxLayout" name="horizontalLayout_8"> - <item> - <widget class="QLineEdit" name="backendPath"> - <property name="enabled"> - <bool>true</bool> - </property> - <property name="text"> - <string>./BackEnd</string> - </property> - </widget> - </item> - <item> - <widget class="QPushButton" name="chooseBackend"> - <property name="enabled"> - <bool>true</bool> - </property> - <property name="text"> - <string>Choose...</string> - </property> - </widget> - </item> - </layout> - </item> - <item> - <layout class="QHBoxLayout" name="horizontalLayout_7"> - <item> - <widget class="QPushButton" name="pbStart"> - <property name="enabled"> - <bool>true</bool> - </property> - <property name="text"> - <string>Start</string> - </property> - </widget> - </item> - <item> - <widget class="QPushButton" name="pbConnect"> - <property name="enabled"> - <bool>true</bool> - </property> - <property name="text"> - <string>Connect</string> - </property> - </widget> - </item> - <item> - <spacer name="horizontalSpacer_2"> - <property name="orientation"> - <enum>Qt::Horizontal</enum> - </property> - <property name="sizeHint" stdset="0"> - <size> - <width>40</width> - <height>20</height> - </size> - </property> - </spacer> - </item> - <item> - <widget class="QPushButton" name="pbStop"> - <property name="enabled"> - <bool>false</bool> - </property> - <property name="text"> - <string>Stop/Disconnect</string> - </property> - </widget> - </item> - </layout> - </item> - <item> - <widget class="Line" name="line_7"> - <property name="orientation"> - <enum>Qt::Horizontal</enum> - </property> - </widget> - </item> - <item> - <widget class="QTextEdit" name="vConsole"> - <property name="enabled"> - <bool>true</bool> - </property> - <property name="readOnly"> - <bool>true</bool> - </property> - </widget> - </item> - </layout> - </widget> - <widget class="QWidget" name="controlGraph"> - <attribute name="title"> - <string>Controller Graph</string> - </attribute> - <layout class="QVBoxLayout" name="verticalLayout_2"> - <item> - <widget class="QScrollArea" name="scrollArea"> - <property name="widgetResizable"> - <bool>true</bool> - </property> - <widget class="QWidget" name="scrollAreaWidgetContents"> - <property name="geometry"> - <rect> - <x>0</x> - <y>0</y> - <width>1144</width> - <height>679</height> - </rect> - </property> - <layout class="QVBoxLayout" name="verticalLayout_8"> - <item> - <widget class="QLabel" name="graphImage"> - <property name="sizePolicy"> - <sizepolicy hsizetype="Preferred" vsizetype="MinimumExpanding"> - <horstretch>0</horstretch> - <verstretch>0</verstretch> - </sizepolicy> - </property> - <property name="font"> - <font> - <pointsize>32</pointsize> - </font> - </property> - <property name="text"> - <string/> - </property> - <property name="alignment"> - <set>Qt::AlignCenter</set> - </property> - </widget> - </item> - </layout> - </widget> - </widget> - </item> - <item> - <widget class="Line" name="line_2"> - <property name="orientation"> - <enum>Qt::Horizontal</enum> - </property> - </widget> - </item> - <item> - <widget class="QPushButton" name="pbControlRefresh"> - <property name="text"> - <string>Refresh Controller Graph</string> - </property> - </widget> - </item> - <item> - <widget class="Line" name="line"> - <property name="orientation"> - <enum>Qt::Horizontal</enum> - </property> - </widget> - </item> - <item> - <layout class="QHBoxLayout" name="horizontalLayout_6"> - <item> - <widget class="QLabel" name="label"> - <property name="sizePolicy"> - <sizepolicy hsizetype="Fixed" vsizetype="Minimum"> - <horstretch>0</horstretch> - <verstretch>0</verstretch> - </sizepolicy> - </property> - <property name="text"> - <string>Node:</string> - </property> - </widget> - </item> - <item> - <widget class="QComboBox" name="nodeSelect"> - <property name="sizePolicy"> - <sizepolicy hsizetype="Preferred" vsizetype="Fixed"> - <horstretch>0</horstretch> - <verstretch>0</verstretch> - </sizepolicy> - </property> - </widget> - </item> - <item> - <widget class="QLabel" name="label_2"> - <property name="sizePolicy"> - <sizepolicy hsizetype="Fixed" vsizetype="Preferred"> - <horstretch>0</horstretch> - <verstretch>0</verstretch> - </sizepolicy> - </property> - <property name="text"> - <string>Param:</string> - </property> - </widget> - </item> - <item> - <widget class="QComboBox" name="paramSelect"/> - </item> - <item> - <widget class="QLineEdit" name="paramValue"> - <property name="sizePolicy"> - <sizepolicy hsizetype="Preferred" vsizetype="Fixed"> - <horstretch>0</horstretch> - <verstretch>0</verstretch> - </sizepolicy> - </property> - </widget> - </item> - </layout> - </item> - <item> - <widget class="Line" name="line_5"> - <property name="orientation"> - <enum>Qt::Horizontal</enum> - </property> - </widget> - </item> - <item> - <layout class="QHBoxLayout" name="horizontalLayout_4"> - <item> - <widget class="QLabel" name="label_4"> - <property name="sizePolicy"> - <sizepolicy hsizetype="Fixed" vsizetype="Minimum"> - <horstretch>0</horstretch> - <verstretch>0</verstretch> - </sizepolicy> - </property> - <property name="text"> - <string>X Setpoint</string> - </property> - </widget> - </item> - <item> - <widget class="QComboBox" name="xSetpointSelect"> - <property name="sizePolicy"> - <sizepolicy hsizetype="Preferred" vsizetype="Fixed"> - <horstretch>0</horstretch> - <verstretch>0</verstretch> - </sizepolicy> - </property> - </widget> - </item> - <item> - <widget class="QLabel" name="label_5"> - <property name="sizePolicy"> - <sizepolicy hsizetype="Fixed" vsizetype="Preferred"> - <horstretch>0</horstretch> - <verstretch>0</verstretch> - </sizepolicy> - </property> - <property name="text"> - <string>Y Setpoint</string> - </property> - </widget> - </item> - <item> - <widget class="QComboBox" name="ySetpointSelect"/> - </item> - <item> - <widget class="QLabel" name="label_3"> - <property name="sizePolicy"> - <sizepolicy hsizetype="Fixed" vsizetype="Preferred"> - <horstretch>0</horstretch> - <verstretch>0</verstretch> - </sizepolicy> - </property> - <property name="text"> - <string>Z Setpoint</string> - </property> - </widget> - </item> - <item> - <widget class="QComboBox" name="zSetpointSelect"/> - </item> - <item> - <widget class="QLabel" name="label_18"> - <property name="sizePolicy"> - <sizepolicy hsizetype="Fixed" vsizetype="Preferred"> - <horstretch>0</horstretch> - <verstretch>0</verstretch> - </sizepolicy> - </property> - <property name="text"> - <string>Yaw Setpoint:</string> - </property> - </widget> - </item> - <item> - <widget class="QComboBox" name="yawSetpointSelect"/> - </item> - </layout> - </item> - <item> - <layout class="QHBoxLayout" name="horizontalLayout_10"> - <item> - <widget class="QLabel" name="label_11"> - <property name="sizePolicy"> - <sizepolicy hsizetype="Fixed" vsizetype="Preferred"> - <horstretch>0</horstretch> - <verstretch>0</verstretch> - </sizepolicy> - </property> - <property name="text"> - <string>X Position</string> - </property> - </widget> - </item> - <item> - <widget class="QComboBox" name="xPositionSelect"/> - </item> - <item> - <widget class="QLabel" name="label_13"> - <property name="sizePolicy"> - <sizepolicy hsizetype="Fixed" vsizetype="Preferred"> - <horstretch>0</horstretch> - <verstretch>0</verstretch> - </sizepolicy> - </property> - <property name="text"> - <string>Y Position </string> - </property> - </widget> - </item> - <item> - <widget class="QComboBox" name="yPositionSelect"/> - </item> - <item> - <widget class="QLabel" name="label_14"> - <property name="sizePolicy"> - <sizepolicy hsizetype="Fixed" vsizetype="Preferred"> - <horstretch>0</horstretch> - <verstretch>0</verstretch> - </sizepolicy> - </property> - <property name="text"> - <string>Z Position</string> - </property> - </widget> - </item> - <item> - <widget class="QComboBox" name="zPositionSelect"/> - </item> - </layout> - </item> - <item> - <layout class="QHBoxLayout" name="horizontalLayout_11"> - <item> - <widget class="QLabel" name="label_15"> - <property name="sizePolicy"> - <sizepolicy hsizetype="Fixed" vsizetype="Preferred"> - <horstretch>0</horstretch> - <verstretch>0</verstretch> - </sizepolicy> - </property> - <property name="text"> - <string>P Attitude</string> - </property> - </widget> - </item> - <item> - <widget class="QComboBox" name="pAttitudeSelect"/> - </item> - <item> - <widget class="QLabel" name="label_16"> - <property name="sizePolicy"> - <sizepolicy hsizetype="Fixed" vsizetype="Preferred"> - <horstretch>0</horstretch> - <verstretch>0</verstretch> - </sizepolicy> - </property> - <property name="text"> - <string>R Attitude</string> - </property> - </widget> - </item> - <item> - <widget class="QComboBox" name="rAttitudeSelect"/> - </item> - <item> - <widget class="QLabel" name="label_17"> - <property name="sizePolicy"> - <sizepolicy hsizetype="Fixed" vsizetype="Preferred"> - <horstretch>0</horstretch> - <verstretch>0</verstretch> - </sizepolicy> - </property> - <property name="text"> - <string>Y Attitude</string> - </property> - </widget> - </item> - <item> - <widget class="QComboBox" name="yAttitudeSelect"/> - </item> - </layout> - </item> - </layout> - </widget> - <widget class="QWidget" name="navigation"> - <attribute name="title"> - <string>Navigation</string> - </attribute> - <layout class="QVBoxLayout" name="verticalLayout_3"> - <item> - <widget class="QLabel" name="noGraphWarning1"> - <property name="font"> - <font> - <pointsize>32</pointsize> - <weight>75</weight> - <bold>true</bold> - <underline>true</underline> - </font> - </property> - <property name="styleSheet"> - <string notr="true">QLabel {color : red; }</string> - </property> - <property name="text"> - <string>NO CONTROL GRAPH LOADED!</string> - </property> - <property name="alignment"> - <set>Qt::AlignCenter</set> - </property> - </widget> - </item> - <item> - <widget class="QLabel" name="noGraphWarning2"> - <property name="text"> - <string>These controls won't work right unless the correct control graph is loaded.</string> - </property> - <property name="alignment"> - <set>Qt::AlignCenter</set> - </property> - </widget> - </item> - <item> - <widget class="Line" name="noGraphWarningLine"> - <property name="orientation"> - <enum>Qt::Horizontal</enum> - </property> - </widget> - </item> - <item> - <layout class="QHBoxLayout" name="horizontalLayout_9"> - <item> - <widget class="QLabel" name="label_12"> - <property name="sizePolicy"> - <sizepolicy hsizetype="Fixed" vsizetype="Preferred"> - <horstretch>0</horstretch> - <verstretch>0</verstretch> - </sizepolicy> - </property> - <property name="text"> - <string>Position/Attitude Source: </string> - </property> - </widget> - </item> - <item> - <widget class="QRadioButton" name="posattSrcVrpn"> - <property name="sizePolicy"> - <sizepolicy hsizetype="Fixed" vsizetype="Fixed"> - <horstretch>0</horstretch> - <verstretch>0</verstretch> - </sizepolicy> - </property> - <property name="text"> - <string>Backend Tracker (&VRPN)</string> - </property> - <property name="checked"> - <bool>true</bool> - </property> - </widget> - </item> - <item> - <widget class="QRadioButton" name="posattSrcQuad"> - <property name="sizePolicy"> - <sizepolicy hsizetype="Minimum" vsizetype="Fixed"> - <horstretch>0</horstretch> - <verstretch>0</verstretch> - </sizepolicy> - </property> - <property name="text"> - <string>From &Quad</string> - </property> - </widget> - </item> - </layout> - </item> - <item> - <layout class="QHBoxLayout" name="horizontalLayout_3"> - <item> - <layout class="QVBoxLayout" name="verticalLayout_7"> - <item> - <widget class="QLabel" name="label_6"> - <property name="sizePolicy"> - <sizepolicy hsizetype="Preferred" vsizetype="Preferred"> - <horstretch>0</horstretch> - <verstretch>0</verstretch> - </sizepolicy> - </property> - <property name="text"> - <string>Current Position</string> - </property> - </widget> - </item> - <item> - <layout class="QFormLayout" name="formLayout"> - <property name="fieldGrowthPolicy"> - <enum>QFormLayout::ExpandingFieldsGrow</enum> - </property> - <item row="0" column="0"> - <widget class="QLabel" name="xLabel"> - <property name="text"> - <string>X</string> - </property> - </widget> - </item> - <item row="0" column="1"> - <widget class="QLineEdit" name="xActual"> - <property name="enabled"> - <bool>false</bool> - </property> - <property name="sizePolicy"> - <sizepolicy hsizetype="Minimum" vsizetype="Fixed"> - <horstretch>0</horstretch> - <verstretch>0</verstretch> - </sizepolicy> - </property> - </widget> - </item> - <item row="1" column="0"> - <widget class="QLabel" name="yLabel"> - <property name="text"> - <string>Y</string> - </property> - </widget> - </item> - <item row="1" column="1"> - <widget class="QLineEdit" name="yActual"> - <property name="enabled"> - <bool>false</bool> - </property> - <property name="sizePolicy"> - <sizepolicy hsizetype="Minimum" vsizetype="Fixed"> - <horstretch>0</horstretch> - <verstretch>0</verstretch> - </sizepolicy> - </property> - </widget> - </item> - <item row="2" column="0"> - <widget class="QLabel" name="zLabel"> - <property name="text"> - <string>Z</string> - </property> - </widget> - </item> - <item row="2" column="1"> - <widget class="QLineEdit" name="zActual"> - <property name="enabled"> - <bool>false</bool> - </property> - <property name="sizePolicy"> - <sizepolicy hsizetype="Minimum" vsizetype="Fixed"> - <horstretch>0</horstretch> - <verstretch>0</verstretch> - </sizepolicy> - </property> - </widget> - </item> - <item row="3" column="0"> - <widget class="QLabel" name="pLabel"> - <property name="text"> - <string>P</string> - </property> - </widget> - </item> - <item row="3" column="1"> - <widget class="QLineEdit" name="pitchActual"> - <property name="enabled"> - <bool>false</bool> - </property> - <property name="sizePolicy"> - <sizepolicy hsizetype="Minimum" vsizetype="Fixed"> - <horstretch>0</horstretch> - <verstretch>0</verstretch> - </sizepolicy> - </property> - </widget> - </item> - <item row="4" column="0"> - <widget class="QLabel" name="rLabel"> - <property name="text"> - <string>R</string> - </property> - </widget> - </item> - <item row="4" column="1"> - <widget class="QLineEdit" name="rollActual"> - <property name="enabled"> - <bool>false</bool> - </property> - <property name="sizePolicy"> - <sizepolicy hsizetype="Minimum" vsizetype="Fixed"> - <horstretch>0</horstretch> - <verstretch>0</verstretch> - </sizepolicy> - </property> - </widget> - </item> - <item row="5" column="0"> - <widget class="QLabel" name="yLabel_2"> - <property name="text"> - <string>Y</string> - </property> - </widget> - </item> - <item row="5" column="1"> - <widget class="QLineEdit" name="yawActual"> - <property name="enabled"> - <bool>false</bool> - </property> - <property name="sizePolicy"> - <sizepolicy hsizetype="Minimum" vsizetype="Fixed"> - <horstretch>0</horstretch> - <verstretch>0</verstretch> - </sizepolicy> - </property> - </widget> - </item> - </layout> - </item> - <item> - <widget class="Line" name="line_6"> - <property name="orientation"> - <enum>Qt::Horizontal</enum> - </property> - </widget> - </item> - <item> - <layout class="QFormLayout" name="formLayout_5"> - <item row="0" column="1"> - <widget class="QLineEdit" name="dist"> - <property name="enabled"> - <bool>false</bool> - </property> - <property name="sizePolicy"> - <sizepolicy hsizetype="Minimum" vsizetype="Fixed"> - <horstretch>0</horstretch> - <verstretch>0</verstretch> - </sizepolicy> - </property> - </widget> - </item> - <item row="0" column="0"> - <widget class="QLabel" name="label_10"> - <property name="sizePolicy"> - <sizepolicy hsizetype="Fixed" vsizetype="Preferred"> - <horstretch>0</horstretch> - <verstretch>0</verstretch> - </sizepolicy> - </property> - <property name="text"> - <string>D</string> - </property> - </widget> - </item> - </layout> - </item> - <item> - <layout class="QHBoxLayout" name="horizontalLayout_5"/> - </item> - <item> - <widget class="QPushButton" name="pbActualToSetpoint"> - <property name="text"> - <string>To Setpoint</string> - </property> - </widget> - </item> - <item> - <widget class="QPushButton" name="pbActualToWaypoint"> - <property name="text"> - <string>To Waypoint</string> - </property> - </widget> - </item> - <item> - <spacer name="verticalSpacer_4"> - <property name="orientation"> - <enum>Qt::Vertical</enum> - </property> - <property name="sizeHint" stdset="0"> - <size> - <width>20</width> - <height>40</height> - </size> - </property> - </spacer> - </item> - </layout> - </item> - <item> - <layout class="QVBoxLayout" name="verticalLayout_5"> - <item> - <widget class="QLabel" name="label_7"> - <property name="text"> - <string>Position Setpoints</string> - </property> - </widget> - </item> - <item> - <layout class="QFormLayout" name="formLayout_2"> - <item row="0" column="0"> - <widget class="QLabel" name="setpointLabel"> - <property name="text"> - <string>X</string> - </property> - </widget> - </item> - <item row="2" column="0"> - <widget class="QLabel" name="setpointLabel_3"> - <property name="text"> - <string>Z</string> - </property> - </widget> - </item> - <item row="1" column="0"> - <widget class="QLabel" name="setpointLabel_2"> - <property name="text"> - <string>Y</string> - </property> - </widget> - </item> - <item row="3" column="0"> - <widget class="QLabel" name="yawLabel"> - <property name="text"> - <string>Yaw</string> - </property> - </widget> - </item> - <item row="0" column="1"> - <layout class="QHBoxLayout" name="horizontalLayout_12"> - <item> - <widget class="QLineEdit" name="xSetpoint"> - <property name="sizePolicy"> - <sizepolicy hsizetype="Minimum" vsizetype="Fixed"> - <horstretch>0</horstretch> - <verstretch>0</verstretch> - </sizepolicy> - </property> - </widget> - </item> - <item> - <widget class="QCheckBox" name="sendX"> - <property name="text"> - <string/> - </property> - <property name="checked"> - <bool>true</bool> - </property> - </widget> - </item> - </layout> - </item> - <item row="1" column="1"> - <layout class="QHBoxLayout" name="horizontalLayout_13"> - <item> - <widget class="QLineEdit" name="ySetpoint"> - <property name="sizePolicy"> - <sizepolicy hsizetype="Minimum" vsizetype="Fixed"> - <horstretch>0</horstretch> - <verstretch>0</verstretch> - </sizepolicy> - </property> - </widget> - </item> - <item> - <widget class="QCheckBox" name="sendY"> - <property name="text"> - <string/> - </property> - <property name="checked"> - <bool>true</bool> - </property> - </widget> - </item> - </layout> - </item> - <item row="2" column="1"> - <layout class="QHBoxLayout" name="horizontalLayout_14"> - <item> - <widget class="QLineEdit" name="zSetpoint"> - <property name="sizePolicy"> - <sizepolicy hsizetype="Minimum" vsizetype="Fixed"> - <horstretch>0</horstretch> - <verstretch>0</verstretch> - </sizepolicy> - </property> - </widget> - </item> - <item> - <widget class="QCheckBox" name="sendZ"> - <property name="text"> - <string/> - </property> - <property name="checked"> - <bool>true</bool> - </property> - </widget> - </item> - </layout> - </item> - <item row="3" column="1"> - <layout class="QHBoxLayout" name="horizontalLayout_15"> - <item> - <widget class="QLineEdit" name="yawSetpoint"> - <property name="sizePolicy"> - <sizepolicy hsizetype="Fixed" vsizetype="Fixed"> - <horstretch>0</horstretch> - <verstretch>0</verstretch> - </sizepolicy> - </property> - </widget> - </item> - <item> - <widget class="QCheckBox" name="sendYaw"> - <property name="text"> - <string/> - </property> - <property name="checked"> - <bool>false</bool> - </property> - </widget> - </item> - </layout> - </item> - </layout> - </item> - <item> - <widget class="QPushButton" name="pbSendSetpoint"> - <property name="text"> - <string>Send to Quad</string> - </property> - </widget> - </item> - <item> - <widget class="Line" name="line_3"> - <property name="orientation"> - <enum>Qt::Horizontal</enum> - </property> - </widget> - </item> - <item> - <widget class="QPushButton" name="pbAppendSetpoint"> - <property name="text"> - <string>Append</string> - </property> - </widget> - </item> - <item> - <widget class="QPushButton" name="pbInsertSetpoint"> - <property name="enabled"> - <bool>true</bool> - </property> - <property name="text"> - <string>Insert</string> - </property> - </widget> - </item> - <item> - <widget class="QPushButton" name="pbDeleteSetpoint"> - <property name="enabled"> - <bool>true</bool> - </property> - <property name="text"> - <string>Delete</string> - </property> - </widget> - </item> - <item> - <spacer name="verticalSpacer_3"> - <property name="orientation"> - <enum>Qt::Vertical</enum> - </property> - <property name="sizeHint" stdset="0"> - <size> - <width>20</width> - <height>40</height> - </size> - </property> - </spacer> - </item> - </layout> - </item> - <item> - <layout class="QVBoxLayout" name="verticalLayout_6"> - <item> - <widget class="QLabel" name="label_8"> - <property name="sizePolicy"> - <sizepolicy hsizetype="Minimum" vsizetype="Preferred"> - <horstretch>0</horstretch> - <verstretch>0</verstretch> - </sizepolicy> - </property> - <property name="text"> - <string>Waypoints</string> - </property> - </widget> - </item> - <item> - <widget class="QListView" name="setpointList"> - <property name="sizePolicy"> - <sizepolicy hsizetype="Minimum" vsizetype="Expanding"> - <horstretch>0</horstretch> - <verstretch>0</verstretch> - </sizepolicy> - </property> - <property name="editTriggers"> - <set>QAbstractItemView::NoEditTriggers</set> - </property> - <property name="dragEnabled"> - <bool>false</bool> - </property> - <property name="dragDropOverwriteMode"> - <bool>false</bool> - </property> - <property name="dragDropMode"> - <enum>QAbstractItemView::NoDragDrop</enum> - </property> - <property name="defaultDropAction"> - <enum>Qt::MoveAction</enum> - </property> - </widget> - </item> - <item> - <widget class="QPushButton" name="pbNextSetpoint"> - <property name="text"> - <string>Send Next</string> - </property> - </widget> - </item> - <item> - <layout class="QHBoxLayout" name="horizontalLayout_2"> - <item> - <widget class="QPushButton" name="pbMoveUp"> - <property name="text"> - <string>Move Up</string> - </property> - </widget> - </item> - <item> - <widget class="QPushButton" name="pbMoveDown"> - <property name="text"> - <string>Move Down</string> - </property> - </widget> - </item> - </layout> - </item> - <item> - <layout class="QHBoxLayout" name="horizontalLayout"> - <item> - <widget class="QPushButton" name="pbSaveWaypoints"> - <property name="text"> - <string>Save</string> - </property> - </widget> - </item> - <item> - <widget class="QPushButton" name="pbLoadWaypoints"> - <property name="text"> - <string>Load</string> - </property> - </widget> - </item> - </layout> - </item> - <item> - <widget class="Line" name="line_4"> - <property name="orientation"> - <enum>Qt::Horizontal</enum> - </property> - </widget> - </item> - <item> - <widget class="QCheckBox" name="autonavEnabled"> - <property name="text"> - <string>Enable Autonavigation</string> - </property> - </widget> - </item> - <item> - <layout class="QFormLayout" name="formLayout_6"> - <item row="0" column="0"> - <widget class="QLabel" name="label_9"> - <property name="sizePolicy"> - <sizepolicy hsizetype="Fixed" vsizetype="Preferred"> - <horstretch>0</horstretch> - <verstretch>0</verstretch> - </sizepolicy> - </property> - <property name="text"> - <string>Threshold</string> - </property> - </widget> - </item> - <item row="1" column="0"> - <widget class="QLabel" name="delayLabel"> - <property name="text"> - <string>Delay</string> - </property> - </widget> - </item> - <item row="0" column="1"> - <widget class="QLineEdit" name="autonavThreshold"> - <property name="sizePolicy"> - <sizepolicy hsizetype="Preferred" vsizetype="Fixed"> - <horstretch>0</horstretch> - <verstretch>0</verstretch> - </sizepolicy> - </property> - <property name="text"> - <string>0.1</string> - </property> - </widget> - </item> - <item row="1" column="1"> - <widget class="QLineEdit" name="autonavDelay"> - <property name="sizePolicy"> - <sizepolicy hsizetype="Preferred" vsizetype="Fixed"> - <horstretch>0</horstretch> - <verstretch>0</verstretch> - </sizepolicy> - </property> - <property name="text"> - <string>88</string> - </property> - </widget> - </item> - </layout> - </item> - </layout> - </item> - <item> - <layout class="QVBoxLayout" name="verticalLayout_9"> - <item> - <widget class="QGraphicsView" name="posView"> - <property name="verticalScrollBarPolicy"> - <enum>Qt::ScrollBarAlwaysOff</enum> - </property> - <property name="horizontalScrollBarPolicy"> - <enum>Qt::ScrollBarAlwaysOff</enum> - </property> - </widget> - </item> - <item> - <widget class="QGraphicsView" name="attView"/> - </item> - </layout> - </item> - </layout> - </item> - <item> - <widget class="QPushButton" name="pbRefresh"> - <property name="text"> - <string>Refresh</string> - </property> - </widget> - </item> - </layout> - </widget> - <widget class="QWidget" name="tab"> - <attribute name="title"> - <string>Flight Data</string> - </attribute> - <widget class="QWidget" name="horizontalLayoutWidget"> - <property name="geometry"> - <rect> - <x>10</x> - <y>10</y> - <width>1141</width> - <height>91</height> - </rect> - </property> - <layout class="QHBoxLayout" name="horizontalLayout_16"> - <item> - <layout class="QVBoxLayout" name="verticalLayout_12"> - <item> - <widget class="QRadioButton" name="camera_fd_button"> - <property name="text"> - <string>Camera Data</string> - </property> - </widget> - </item> - <item> - <widget class="QRadioButton" name="gyro_fd_button"> - <property name="text"> - <string>Gyro Data</string> - </property> - </widget> - </item> - <item> - <widget class="QRadioButton" name="accelerometer_fd_button"> - <property name="text"> - <string>Accelerometer Data</string> - </property> - </widget> - </item> - </layout> - </item> - <item> - <layout class="QVBoxLayout" name="verticalLayout_11"> - <item> - <widget class="QRadioButton" name="lidar_fd_button"> - <property name="text"> - <string>Lidar Data</string> - </property> - </widget> - </item> - <item> - <widget class="QRadioButton" name="opflow_fd_button"> - <property name="text"> - <string>Optical Flow Data</string> - </property> - </widget> - </item> - <item> - <widget class="QRadioButton" name="gps_data_button"> - <property name="text"> - <string>GPS Data</string> - </property> - </widget> - </item> - </layout> - </item> - <item> - <layout class="QVBoxLayout" name="verticalLayout_10"> - <item> - <widget class="QRadioButton" name="pid_fd_button"> - <property name="text"> - <string>PID Data</string> - </property> - </widget> - </item> - <item> - <widget class="QRadioButton" name="rctrans_fd_button"> - <property name="text"> - <string>RC TRANS Data</string> - </property> - </widget> - </item> - <item> - <widget class="QRadioButton" name="actuator_fd_button"> - <property name="text"> - <string>Actuator Data</string> - </property> - </widget> - </item> - </layout> - </item> - </layout> - </widget> - <widget class="QPushButton" name="update_data_request_params_button"> - <property name="geometry"> - <rect> - <x>10</x> - <y>100</y> - <width>1141</width> - <height>28</height> - </rect> - </property> - <property name="text"> - <string>Update Data Request Parameters</string> - </property> - </widget> - <widget class="QLabel" name="flight_data_label"> - <property name="geometry"> - <rect> - <x>10</x> - <y>140</y> - <width>1141</width> - <height>761</height> - </rect> - </property> - <property name="font"> - <font> - <pointsize>32</pointsize> - <weight>75</weight> - <bold>true</bold> - <underline>true</underline> - </font> - </property> - <property name="text"> - <string>INSERT FLIGHT DATA GRAPHS HERE</string> - </property> - <property name="alignment"> - <set>Qt::AlignCenter</set> - </property> - </widget> - </widget> - </widget> - </item> - </layout> - </widget> - <widget class="QMenuBar" name="menuBar"> - <property name="geometry"> - <rect> - <x>0</x> - <y>0</y> - <width>1186</width> - <height>28</height> - </rect> - </property> - <widget class="QMenu" name="menuScripts"> - <property name="title"> - <string>Scripts</string> - </property> - </widget> - <addaction name="menuScripts"/> - </widget> - <widget class="QToolBar" name="mainToolBar"> - <attribute name="toolBarArea"> - <enum>TopToolBarArea</enum> - </attribute> - <attribute name="toolBarBreak"> - <bool>false</bool> - </attribute> - </widget> - <widget class="QStatusBar" name="statusBar"/> - </widget> - <layoutdefault spacing="6" margin="11"/> - <resources/> - <connections/> -</ui> +<?xml version="1.0" encoding="UTF-8"?> +<ui version="4.0"> + <class>MainWindow</class> + <widget class="QMainWindow" name="MainWindow"> + <property name="geometry"> + <rect> + <x>0</x> + <y>0</y> + <width>1186</width> + <height>1034</height> + </rect> + </property> + <property name="windowTitle"> + <string>MainWindow</string> + </property> + <widget class="QWidget" name="centralWidget"> + <layout class="QVBoxLayout" name="verticalLayout_4"> + <item> + <widget class="QTabWidget" name="tabWidget"> + <property name="currentIndex"> + <number>3</number> + </property> + <widget class="QWidget" name="backend"> + <attribute name="title"> + <string>Backend</string> + </attribute> + <layout class="QVBoxLayout" name="verticalLayout"> + <item> + <layout class="QHBoxLayout" name="horizontalLayout_8"> + <item> + <widget class="QLineEdit" name="backendPath"> + <property name="enabled"> + <bool>true</bool> + </property> + <property name="text"> + <string>./BackEnd</string> + </property> + </widget> + </item> + <item> + <widget class="QPushButton" name="chooseBackend"> + <property name="enabled"> + <bool>true</bool> + </property> + <property name="text"> + <string>Choose...</string> + </property> + </widget> + </item> + </layout> + </item> + <item> + <layout class="QHBoxLayout" name="horizontalLayout_7"> + <item> + <widget class="QPushButton" name="pbStart"> + <property name="enabled"> + <bool>true</bool> + </property> + <property name="text"> + <string>Start</string> + </property> + </widget> + </item> + <item> + <widget class="QPushButton" name="pbConnect"> + <property name="enabled"> + <bool>true</bool> + </property> + <property name="text"> + <string>Connect</string> + </property> + </widget> + </item> + <item> + <spacer name="horizontalSpacer_2"> + <property name="orientation"> + <enum>Qt::Horizontal</enum> + </property> + <property name="sizeHint" stdset="0"> + <size> + <width>40</width> + <height>20</height> + </size> + </property> + </spacer> + </item> + <item> + <widget class="QPushButton" name="pbStop"> + <property name="enabled"> + <bool>false</bool> + </property> + <property name="text"> + <string>Stop/Disconnect</string> + </property> + </widget> + </item> + </layout> + </item> + <item> + <widget class="Line" name="line_7"> + <property name="orientation"> + <enum>Qt::Horizontal</enum> + </property> + </widget> + </item> + <item> + <widget class="QTextEdit" name="vConsole"> + <property name="enabled"> + <bool>true</bool> + </property> + <property name="readOnly"> + <bool>true</bool> + </property> + </widget> + </item> + </layout> + </widget> + <widget class="QWidget" name="controlGraph"> + <attribute name="title"> + <string>Controller Graph</string> + </attribute> + <layout class="QVBoxLayout" name="verticalLayout_2"> + <item> + <widget class="QScrollArea" name="scrollArea"> + <property name="widgetResizable"> + <bool>true</bool> + </property> + <widget class="QWidget" name="scrollAreaWidgetContents"> + <property name="geometry"> + <rect> + <x>0</x> + <y>0</y> + <width>1142</width> + <height>749</height> + </rect> + </property> + <layout class="QVBoxLayout" name="verticalLayout_8"> + <item> + <widget class="QLabel" name="graphImage"> + <property name="sizePolicy"> + <sizepolicy hsizetype="Preferred" vsizetype="MinimumExpanding"> + <horstretch>0</horstretch> + <verstretch>0</verstretch> + </sizepolicy> + </property> + <property name="font"> + <font> + <pointsize>32</pointsize> + </font> + </property> + <property name="text"> + <string/> + </property> + <property name="alignment"> + <set>Qt::AlignCenter</set> + </property> + </widget> + </item> + </layout> + </widget> + </widget> + </item> + <item> + <widget class="Line" name="line_2"> + <property name="orientation"> + <enum>Qt::Horizontal</enum> + </property> + </widget> + </item> + <item> + <widget class="QPushButton" name="pbControlRefresh"> + <property name="text"> + <string>Refresh Controller Graph</string> + </property> + </widget> + </item> + <item> + <widget class="Line" name="line"> + <property name="orientation"> + <enum>Qt::Horizontal</enum> + </property> + </widget> + </item> + <item> + <layout class="QHBoxLayout" name="horizontalLayout_6"> + <item> + <widget class="QLabel" name="label"> + <property name="sizePolicy"> + <sizepolicy hsizetype="Fixed" vsizetype="Minimum"> + <horstretch>0</horstretch> + <verstretch>0</verstretch> + </sizepolicy> + </property> + <property name="text"> + <string>Node:</string> + </property> + </widget> + </item> + <item> + <widget class="QComboBox" name="nodeSelect"> + <property name="sizePolicy"> + <sizepolicy hsizetype="Preferred" vsizetype="Fixed"> + <horstretch>0</horstretch> + <verstretch>0</verstretch> + </sizepolicy> + </property> + </widget> + </item> + <item> + <widget class="QLabel" name="label_2"> + <property name="sizePolicy"> + <sizepolicy hsizetype="Fixed" vsizetype="Preferred"> + <horstretch>0</horstretch> + <verstretch>0</verstretch> + </sizepolicy> + </property> + <property name="text"> + <string>Param:</string> + </property> + </widget> + </item> + <item> + <widget class="QComboBox" name="paramSelect"/> + </item> + <item> + <widget class="QLineEdit" name="paramValue"> + <property name="sizePolicy"> + <sizepolicy hsizetype="Preferred" vsizetype="Fixed"> + <horstretch>0</horstretch> + <verstretch>0</verstretch> + </sizepolicy> + </property> + </widget> + </item> + </layout> + </item> + <item> + <widget class="Line" name="line_5"> + <property name="orientation"> + <enum>Qt::Horizontal</enum> + </property> + </widget> + </item> + <item> + <layout class="QHBoxLayout" name="horizontalLayout_4"> + <item> + <widget class="QLabel" name="label_4"> + <property name="sizePolicy"> + <sizepolicy hsizetype="Fixed" vsizetype="Minimum"> + <horstretch>0</horstretch> + <verstretch>0</verstretch> + </sizepolicy> + </property> + <property name="text"> + <string>X Setpoint</string> + </property> + </widget> + </item> + <item> + <widget class="QComboBox" name="xSetpointSelect"> + <property name="sizePolicy"> + <sizepolicy hsizetype="Preferred" vsizetype="Fixed"> + <horstretch>0</horstretch> + <verstretch>0</verstretch> + </sizepolicy> + </property> + </widget> + </item> + <item> + <widget class="QLabel" name="label_5"> + <property name="sizePolicy"> + <sizepolicy hsizetype="Fixed" vsizetype="Preferred"> + <horstretch>0</horstretch> + <verstretch>0</verstretch> + </sizepolicy> + </property> + <property name="text"> + <string>Y Setpoint</string> + </property> + </widget> + </item> + <item> + <widget class="QComboBox" name="ySetpointSelect"/> + </item> + <item> + <widget class="QLabel" name="label_3"> + <property name="sizePolicy"> + <sizepolicy hsizetype="Fixed" vsizetype="Preferred"> + <horstretch>0</horstretch> + <verstretch>0</verstretch> + </sizepolicy> + </property> + <property name="text"> + <string>Z Setpoint</string> + </property> + </widget> + </item> + <item> + <widget class="QComboBox" name="zSetpointSelect"/> + </item> + <item> + <widget class="QLabel" name="label_18"> + <property name="sizePolicy"> + <sizepolicy hsizetype="Fixed" vsizetype="Preferred"> + <horstretch>0</horstretch> + <verstretch>0</verstretch> + </sizepolicy> + </property> + <property name="text"> + <string>Yaw Setpoint:</string> + </property> + </widget> + </item> + <item> + <widget class="QComboBox" name="yawSetpointSelect"/> + </item> + </layout> + </item> + <item> + <layout class="QHBoxLayout" name="horizontalLayout_10"> + <item> + <widget class="QLabel" name="label_11"> + <property name="sizePolicy"> + <sizepolicy hsizetype="Fixed" vsizetype="Preferred"> + <horstretch>0</horstretch> + <verstretch>0</verstretch> + </sizepolicy> + </property> + <property name="text"> + <string>X Position</string> + </property> + </widget> + </item> + <item> + <widget class="QComboBox" name="xPositionSelect"/> + </item> + <item> + <widget class="QLabel" name="label_13"> + <property name="sizePolicy"> + <sizepolicy hsizetype="Fixed" vsizetype="Preferred"> + <horstretch>0</horstretch> + <verstretch>0</verstretch> + </sizepolicy> + </property> + <property name="text"> + <string>Y Position </string> + </property> + </widget> + </item> + <item> + <widget class="QComboBox" name="yPositionSelect"/> + </item> + <item> + <widget class="QLabel" name="label_14"> + <property name="sizePolicy"> + <sizepolicy hsizetype="Fixed" vsizetype="Preferred"> + <horstretch>0</horstretch> + <verstretch>0</verstretch> + </sizepolicy> + </property> + <property name="text"> + <string>Z Position</string> + </property> + </widget> + </item> + <item> + <widget class="QComboBox" name="zPositionSelect"/> + </item> + </layout> + </item> + <item> + <layout class="QHBoxLayout" name="horizontalLayout_11"> + <item> + <widget class="QLabel" name="label_15"> + <property name="sizePolicy"> + <sizepolicy hsizetype="Fixed" vsizetype="Preferred"> + <horstretch>0</horstretch> + <verstretch>0</verstretch> + </sizepolicy> + </property> + <property name="text"> + <string>P Attitude</string> + </property> + </widget> + </item> + <item> + <widget class="QComboBox" name="pAttitudeSelect"/> + </item> + <item> + <widget class="QLabel" name="label_16"> + <property name="sizePolicy"> + <sizepolicy hsizetype="Fixed" vsizetype="Preferred"> + <horstretch>0</horstretch> + <verstretch>0</verstretch> + </sizepolicy> + </property> + <property name="text"> + <string>R Attitude</string> + </property> + </widget> + </item> + <item> + <widget class="QComboBox" name="rAttitudeSelect"/> + </item> + <item> + <widget class="QLabel" name="label_17"> + <property name="sizePolicy"> + <sizepolicy hsizetype="Fixed" vsizetype="Preferred"> + <horstretch>0</horstretch> + <verstretch>0</verstretch> + </sizepolicy> + </property> + <property name="text"> + <string>Y Attitude</string> + </property> + </widget> + </item> + <item> + <widget class="QComboBox" name="yAttitudeSelect"/> + </item> + </layout> + </item> + </layout> + </widget> + <widget class="QWidget" name="navigation"> + <attribute name="title"> + <string>Navigation</string> + </attribute> + <layout class="QVBoxLayout" name="verticalLayout_3"> + <item> + <widget class="QLabel" name="noGraphWarning1"> + <property name="font"> + <font> + <pointsize>32</pointsize> + <weight>75</weight> + <bold>true</bold> + <underline>true</underline> + </font> + </property> + <property name="styleSheet"> + <string notr="true">QLabel {color : red; }</string> + </property> + <property name="text"> + <string>NO CONTROL GRAPH LOADED!</string> + </property> + <property name="alignment"> + <set>Qt::AlignCenter</set> + </property> + </widget> + </item> + <item> + <widget class="QLabel" name="noGraphWarning2"> + <property name="text"> + <string>These controls won't work right unless the correct control graph is loaded.</string> + </property> + <property name="alignment"> + <set>Qt::AlignCenter</set> + </property> + </widget> + </item> + <item> + <widget class="Line" name="noGraphWarningLine"> + <property name="orientation"> + <enum>Qt::Horizontal</enum> + </property> + </widget> + </item> + <item> + <layout class="QHBoxLayout" name="horizontalLayout_9"> + <item> + <widget class="QLabel" name="label_12"> + <property name="sizePolicy"> + <sizepolicy hsizetype="Fixed" vsizetype="Preferred"> + <horstretch>0</horstretch> + <verstretch>0</verstretch> + </sizepolicy> + </property> + <property name="text"> + <string>Position/Attitude Source: </string> + </property> + </widget> + </item> + <item> + <widget class="QRadioButton" name="posattSrcVrpn"> + <property name="sizePolicy"> + <sizepolicy hsizetype="Fixed" vsizetype="Fixed"> + <horstretch>0</horstretch> + <verstretch>0</verstretch> + </sizepolicy> + </property> + <property name="text"> + <string>Backend Tracker (&VRPN)</string> + </property> + <property name="checked"> + <bool>true</bool> + </property> + </widget> + </item> + <item> + <widget class="QRadioButton" name="posattSrcQuad"> + <property name="sizePolicy"> + <sizepolicy hsizetype="Minimum" vsizetype="Fixed"> + <horstretch>0</horstretch> + <verstretch>0</verstretch> + </sizepolicy> + </property> + <property name="text"> + <string>From &Quad</string> + </property> + </widget> + </item> + </layout> + </item> + <item> + <layout class="QHBoxLayout" name="horizontalLayout_3"> + <item> + <layout class="QVBoxLayout" name="verticalLayout_7"> + <item> + <widget class="QLabel" name="label_6"> + <property name="sizePolicy"> + <sizepolicy hsizetype="Preferred" vsizetype="Preferred"> + <horstretch>0</horstretch> + <verstretch>0</verstretch> + </sizepolicy> + </property> + <property name="text"> + <string>Current Position</string> + </property> + </widget> + </item> + <item> + <layout class="QFormLayout" name="formLayout"> + <property name="fieldGrowthPolicy"> + <enum>QFormLayout::ExpandingFieldsGrow</enum> + </property> + <item row="0" column="0"> + <widget class="QLabel" name="xLabel"> + <property name="text"> + <string>X</string> + </property> + </widget> + </item> + <item row="0" column="1"> + <widget class="QLineEdit" name="xActual"> + <property name="enabled"> + <bool>false</bool> + </property> + <property name="sizePolicy"> + <sizepolicy hsizetype="Minimum" vsizetype="Fixed"> + <horstretch>0</horstretch> + <verstretch>0</verstretch> + </sizepolicy> + </property> + </widget> + </item> + <item row="1" column="0"> + <widget class="QLabel" name="yLabel"> + <property name="text"> + <string>Y</string> + </property> + </widget> + </item> + <item row="1" column="1"> + <widget class="QLineEdit" name="yActual"> + <property name="enabled"> + <bool>false</bool> + </property> + <property name="sizePolicy"> + <sizepolicy hsizetype="Minimum" vsizetype="Fixed"> + <horstretch>0</horstretch> + <verstretch>0</verstretch> + </sizepolicy> + </property> + </widget> + </item> + <item row="2" column="0"> + <widget class="QLabel" name="zLabel"> + <property name="text"> + <string>Z</string> + </property> + </widget> + </item> + <item row="2" column="1"> + <widget class="QLineEdit" name="zActual"> + <property name="enabled"> + <bool>false</bool> + </property> + <property name="sizePolicy"> + <sizepolicy hsizetype="Minimum" vsizetype="Fixed"> + <horstretch>0</horstretch> + <verstretch>0</verstretch> + </sizepolicy> + </property> + </widget> + </item> + <item row="3" column="0"> + <widget class="QLabel" name="pLabel"> + <property name="text"> + <string>P</string> + </property> + </widget> + </item> + <item row="3" column="1"> + <widget class="QLineEdit" name="pitchActual"> + <property name="enabled"> + <bool>false</bool> + </property> + <property name="sizePolicy"> + <sizepolicy hsizetype="Minimum" vsizetype="Fixed"> + <horstretch>0</horstretch> + <verstretch>0</verstretch> + </sizepolicy> + </property> + </widget> + </item> + <item row="4" column="0"> + <widget class="QLabel" name="rLabel"> + <property name="text"> + <string>R</string> + </property> + </widget> + </item> + <item row="4" column="1"> + <widget class="QLineEdit" name="rollActual"> + <property name="enabled"> + <bool>false</bool> + </property> + <property name="sizePolicy"> + <sizepolicy hsizetype="Minimum" vsizetype="Fixed"> + <horstretch>0</horstretch> + <verstretch>0</verstretch> + </sizepolicy> + </property> + </widget> + </item> + <item row="5" column="0"> + <widget class="QLabel" name="yLabel_2"> + <property name="text"> + <string>Y</string> + </property> + </widget> + </item> + <item row="5" column="1"> + <widget class="QLineEdit" name="yawActual"> + <property name="enabled"> + <bool>false</bool> + </property> + <property name="sizePolicy"> + <sizepolicy hsizetype="Minimum" vsizetype="Fixed"> + <horstretch>0</horstretch> + <verstretch>0</verstretch> + </sizepolicy> + </property> + </widget> + </item> + </layout> + </item> + <item> + <widget class="Line" name="line_6"> + <property name="orientation"> + <enum>Qt::Horizontal</enum> + </property> + </widget> + </item> + <item> + <layout class="QFormLayout" name="formLayout_5"> + <item row="0" column="1"> + <widget class="QLineEdit" name="dist"> + <property name="enabled"> + <bool>false</bool> + </property> + <property name="sizePolicy"> + <sizepolicy hsizetype="Minimum" vsizetype="Fixed"> + <horstretch>0</horstretch> + <verstretch>0</verstretch> + </sizepolicy> + </property> + </widget> + </item> + <item row="0" column="0"> + <widget class="QLabel" name="label_10"> + <property name="sizePolicy"> + <sizepolicy hsizetype="Fixed" vsizetype="Preferred"> + <horstretch>0</horstretch> + <verstretch>0</verstretch> + </sizepolicy> + </property> + <property name="text"> + <string>D</string> + </property> + </widget> + </item> + </layout> + </item> + <item> + <layout class="QHBoxLayout" name="horizontalLayout_5"/> + </item> + <item> + <widget class="QPushButton" name="pbActualToSetpoint"> + <property name="text"> + <string>To Setpoint</string> + </property> + </widget> + </item> + <item> + <widget class="QPushButton" name="pbActualToWaypoint"> + <property name="text"> + <string>To Waypoint</string> + </property> + </widget> + </item> + <item> + <spacer name="verticalSpacer_4"> + <property name="orientation"> + <enum>Qt::Vertical</enum> + </property> + <property name="sizeHint" stdset="0"> + <size> + <width>20</width> + <height>40</height> + </size> + </property> + </spacer> + </item> + </layout> + </item> + <item> + <layout class="QVBoxLayout" name="verticalLayout_5"> + <item> + <widget class="QLabel" name="label_7"> + <property name="text"> + <string>Position Setpoints</string> + </property> + </widget> + </item> + <item> + <layout class="QFormLayout" name="formLayout_2"> + <item row="0" column="0"> + <widget class="QLabel" name="setpointLabel"> + <property name="text"> + <string>X</string> + </property> + </widget> + </item> + <item row="2" column="0"> + <widget class="QLabel" name="setpointLabel_3"> + <property name="text"> + <string>Z</string> + </property> + </widget> + </item> + <item row="1" column="0"> + <widget class="QLabel" name="setpointLabel_2"> + <property name="text"> + <string>Y</string> + </property> + </widget> + </item> + <item row="3" column="0"> + <widget class="QLabel" name="yawLabel"> + <property name="text"> + <string>Yaw</string> + </property> + </widget> + </item> + <item row="0" column="1"> + <layout class="QHBoxLayout" name="horizontalLayout_12"> + <item> + <widget class="QLineEdit" name="xSetpoint"> + <property name="sizePolicy"> + <sizepolicy hsizetype="Minimum" vsizetype="Fixed"> + <horstretch>0</horstretch> + <verstretch>0</verstretch> + </sizepolicy> + </property> + </widget> + </item> + <item> + <widget class="QCheckBox" name="sendX"> + <property name="text"> + <string/> + </property> + <property name="checked"> + <bool>true</bool> + </property> + </widget> + </item> + </layout> + </item> + <item row="1" column="1"> + <layout class="QHBoxLayout" name="horizontalLayout_13"> + <item> + <widget class="QLineEdit" name="ySetpoint"> + <property name="sizePolicy"> + <sizepolicy hsizetype="Minimum" vsizetype="Fixed"> + <horstretch>0</horstretch> + <verstretch>0</verstretch> + </sizepolicy> + </property> + </widget> + </item> + <item> + <widget class="QCheckBox" name="sendY"> + <property name="text"> + <string/> + </property> + <property name="checked"> + <bool>true</bool> + </property> + </widget> + </item> + </layout> + </item> + <item row="2" column="1"> + <layout class="QHBoxLayout" name="horizontalLayout_14"> + <item> + <widget class="QLineEdit" name="zSetpoint"> + <property name="sizePolicy"> + <sizepolicy hsizetype="Minimum" vsizetype="Fixed"> + <horstretch>0</horstretch> + <verstretch>0</verstretch> + </sizepolicy> + </property> + </widget> + </item> + <item> + <widget class="QCheckBox" name="sendZ"> + <property name="text"> + <string/> + </property> + <property name="checked"> + <bool>true</bool> + </property> + </widget> + </item> + </layout> + </item> + <item row="3" column="1"> + <layout class="QHBoxLayout" name="horizontalLayout_15"> + <item> + <widget class="QLineEdit" name="yawSetpoint"> + <property name="sizePolicy"> + <sizepolicy hsizetype="Fixed" vsizetype="Fixed"> + <horstretch>0</horstretch> + <verstretch>0</verstretch> + </sizepolicy> + </property> + </widget> + </item> + <item> + <widget class="QCheckBox" name="sendYaw"> + <property name="text"> + <string/> + </property> + <property name="checked"> + <bool>false</bool> + </property> + </widget> + </item> + </layout> + </item> + </layout> + </item> + <item> + <widget class="QPushButton" name="pbSendSetpoint"> + <property name="text"> + <string>Send to Quad</string> + </property> + </widget> + </item> + <item> + <widget class="Line" name="line_3"> + <property name="orientation"> + <enum>Qt::Horizontal</enum> + </property> + </widget> + </item> + <item> + <widget class="QPushButton" name="pbAppendSetpoint"> + <property name="text"> + <string>Append</string> + </property> + </widget> + </item> + <item> + <widget class="QPushButton" name="pbInsertSetpoint"> + <property name="enabled"> + <bool>true</bool> + </property> + <property name="text"> + <string>Insert</string> + </property> + </widget> + </item> + <item> + <widget class="QPushButton" name="pbDeleteSetpoint"> + <property name="enabled"> + <bool>true</bool> + </property> + <property name="text"> + <string>Delete</string> + </property> + </widget> + </item> + <item> + <spacer name="verticalSpacer_3"> + <property name="orientation"> + <enum>Qt::Vertical</enum> + </property> + <property name="sizeHint" stdset="0"> + <size> + <width>20</width> + <height>40</height> + </size> + </property> + </spacer> + </item> + </layout> + </item> + <item> + <layout class="QVBoxLayout" name="verticalLayout_6"> + <item> + <widget class="QLabel" name="label_8"> + <property name="sizePolicy"> + <sizepolicy hsizetype="Minimum" vsizetype="Preferred"> + <horstretch>0</horstretch> + <verstretch>0</verstretch> + </sizepolicy> + </property> + <property name="text"> + <string>Waypoints</string> + </property> + </widget> + </item> + <item> + <widget class="QListView" name="setpointList"> + <property name="sizePolicy"> + <sizepolicy hsizetype="Minimum" vsizetype="Expanding"> + <horstretch>0</horstretch> + <verstretch>0</verstretch> + </sizepolicy> + </property> + <property name="editTriggers"> + <set>QAbstractItemView::NoEditTriggers</set> + </property> + <property name="dragEnabled"> + <bool>false</bool> + </property> + <property name="dragDropOverwriteMode"> + <bool>false</bool> + </property> + <property name="dragDropMode"> + <enum>QAbstractItemView::NoDragDrop</enum> + </property> + <property name="defaultDropAction"> + <enum>Qt::MoveAction</enum> + </property> + </widget> + </item> + <item> + <widget class="QPushButton" name="pbNextSetpoint"> + <property name="text"> + <string>Send Next</string> + </property> + </widget> + </item> + <item> + <layout class="QHBoxLayout" name="horizontalLayout_2"> + <item> + <widget class="QPushButton" name="pbMoveUp"> + <property name="text"> + <string>Move Up</string> + </property> + </widget> + </item> + <item> + <widget class="QPushButton" name="pbMoveDown"> + <property name="text"> + <string>Move Down</string> + </property> + </widget> + </item> + </layout> + </item> + <item> + <layout class="QHBoxLayout" name="horizontalLayout"> + <item> + <widget class="QPushButton" name="pbSaveWaypoints"> + <property name="text"> + <string>Save</string> + </property> + </widget> + </item> + <item> + <widget class="QPushButton" name="pbLoadWaypoints"> + <property name="text"> + <string>Load</string> + </property> + </widget> + </item> + </layout> + </item> + <item> + <widget class="Line" name="line_4"> + <property name="orientation"> + <enum>Qt::Horizontal</enum> + </property> + </widget> + </item> + <item> + <widget class="QCheckBox" name="autonavEnabled"> + <property name="text"> + <string>Enable Autonavigation</string> + </property> + </widget> + </item> + <item> + <layout class="QFormLayout" name="formLayout_6"> + <item row="0" column="0"> + <widget class="QLabel" name="label_9"> + <property name="sizePolicy"> + <sizepolicy hsizetype="Fixed" vsizetype="Preferred"> + <horstretch>0</horstretch> + <verstretch>0</verstretch> + </sizepolicy> + </property> + <property name="text"> + <string>Threshold</string> + </property> + </widget> + </item> + <item row="1" column="0"> + <widget class="QLabel" name="delayLabel"> + <property name="text"> + <string>Delay</string> + </property> + </widget> + </item> + <item row="0" column="1"> + <widget class="QLineEdit" name="autonavThreshold"> + <property name="sizePolicy"> + <sizepolicy hsizetype="Preferred" vsizetype="Fixed"> + <horstretch>0</horstretch> + <verstretch>0</verstretch> + </sizepolicy> + </property> + <property name="text"> + <string>0.1</string> + </property> + </widget> + </item> + <item row="1" column="1"> + <widget class="QLineEdit" name="autonavDelay"> + <property name="sizePolicy"> + <sizepolicy hsizetype="Preferred" vsizetype="Fixed"> + <horstretch>0</horstretch> + <verstretch>0</verstretch> + </sizepolicy> + </property> + <property name="text"> + <string>88</string> + </property> + </widget> + </item> + </layout> + </item> + </layout> + </item> + <item> + <layout class="QVBoxLayout" name="verticalLayout_9"> + <item> + <widget class="QGraphicsView" name="posView"> + <property name="verticalScrollBarPolicy"> + <enum>Qt::ScrollBarAlwaysOff</enum> + </property> + <property name="horizontalScrollBarPolicy"> + <enum>Qt::ScrollBarAlwaysOff</enum> + </property> + </widget> + </item> + <item> + <widget class="QGraphicsView" name="attView"/> + </item> + </layout> + </item> + </layout> + </item> + <item> + <widget class="QPushButton" name="pbRefresh"> + <property name="text"> + <string>Refresh</string> + </property> + </widget> + </item> + </layout> + </widget> + <widget class="QWidget" name="tab"> + <attribute name="title"> + <string>Flight Data</string> + </attribute> + <widget class="QPushButton" name="run_data_analysis_button"> + <property name="geometry"> + <rect> + <x>0</x> + <y>0</y> + <width>1141</width> + <height>28</height> + </rect> + </property> + <property name="text"> + <string>Run Data Analysis</string> + </property> + </widget> + </widget> + </widget> + </item> + </layout> + </widget> + <widget class="QMenuBar" name="menuBar"> + <property name="geometry"> + <rect> + <x>0</x> + <y>0</y> + <width>1186</width> + <height>21</height> + </rect> + </property> + <widget class="QMenu" name="menuScripts"> + <property name="title"> + <string>Scripts</string> + </property> + </widget> + <addaction name="menuScripts"/> + </widget> + <widget class="QToolBar" name="mainToolBar"> + <attribute name="toolBarArea"> + <enum>TopToolBarArea</enum> + </attribute> + <attribute name="toolBarBreak"> + <bool>false</bool> + </attribute> + </widget> + <widget class="QStatusBar" name="statusBar"/> + </widget> + <layoutdefault spacing="6" margin="11"/> + <resources/> + <connections/> +</ui>