diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index 78445baa057bfbf4207878415af1a867f8899505..95d082db90d922d9413a6c2e9b219d1fb04fe1e3 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -172,8 +172,7 @@ FORMS += src/ui/MainWindow.ui \ src/ui/Linechart.ui \ src/ui/UASView.ui \ src/ui/ParameterInterface.ui \ - src/ui/WaypointList.ui \ - src/ui/WaypointView.ui \ + src/ui/WaypointList.ui \ src/ui/ObjectDetectionView.ui \ src/ui/JoystickWidget.ui \ src/ui/DebugConsole.ui \ @@ -210,8 +209,8 @@ FORMS += src/ui/MainWindow.ui \ src/ui/map/QGCMapTool.ui \ src/ui/map/QGCMapToolBar.ui \ src/ui/QGCMAVLinkInspector.ui \ - src/ui/WaypointViewOnlyView.ui \ - src/ui/WaypointViewOnlyView.ui + src/ui/WaypointViewOnlyView.ui \ + src/ui/WaypointEditableView.ui INCLUDEPATH += src \ src/ui \ src/ui/linechart \ @@ -258,8 +257,7 @@ HEADERS += src/MG.h \ src/comm/UDPLink.h \ src/ui/ParameterInterface.h \ src/ui/WaypointList.h \ - src/Waypoint.h \ - src/ui/WaypointView.h \ + src/Waypoint.h \ src/ui/ObjectDetectionView.h \ src/input/JoystickInput.h \ src/ui/JoystickWidget.h \ @@ -327,7 +325,8 @@ HEADERS += src/MG.h \ src/ui/QGCMAVLinkInspector.h \ src/ui/MAVLinkDecoder.h \ src/ui/WaypointViewOnlyView.h \ - src/ui/WaypointViewOnlyView.h + src/ui/WaypointViewOnlyView.h \ + src/ui/WaypointEditableView.h # Google Earth is only supported on Mac OS and Windows with Visual Studio Compiler macx|win32-msvc2008|win32-msvc2010::HEADERS += src/ui/map3D/QGCGoogleEarthView.h @@ -390,7 +389,6 @@ SOURCES += src/main.cc \ src/ui/ParameterInterface.cc \ src/ui/WaypointList.cc \ src/Waypoint.cc \ - src/ui/WaypointView.cc \ src/ui/ObjectDetectionView.cc \ src/input/JoystickInput.cc \ src/ui/JoystickWidget.cc \ @@ -454,7 +452,8 @@ SOURCES += src/main.cc \ src/ui/QGCToolBar.cc \ src/ui/QGCMAVLinkInspector.cc \ src/ui/MAVLinkDecoder.cc \ - src/ui/WaypointViewOnlyView.cc + src/ui/WaypointViewOnlyView.cc \ + src/ui/WaypointEditableView.cc # Enable Google Earth only on Mac OS and Windows with Visual Studio compiler macx|win32-msvc2008|win32-msvc2010::SOURCES += src/ui/map3D/QGCGoogleEarthView.cc diff --git a/src/ui/WaypointView.cc b/src/ui/WaypointEditableView.cc similarity index 94% rename from src/ui/WaypointView.cc rename to src/ui/WaypointEditableView.cc index db9eeb6ce3d27fd4066c2ae3fd2b978d2dcf059f..be3774c20dff28fb1c2eabdfdffa6f6586b280e4 100644 --- a/src/ui/WaypointView.cc +++ b/src/ui/WaypointEditableView.cc @@ -17,15 +17,15 @@ #include #include -#include "WaypointView.h" -#include "ui_WaypointView.h" +#include "WaypointEditableView.h" +#include "ui_WaypointEditableView.h" #include "ui_QGCCustomWaypointAction.h" -WaypointView::WaypointView(Waypoint* wp, QWidget* parent) : +WaypointEditableView::WaypointEditableView(Waypoint* wp, QWidget* parent) : QWidget(parent), customCommand(new Ui_QGCCustomWaypointAction), - viewMode(QGC_WAYPOINTVIEW_MODE_NAV), - m_ui(new Ui::WaypointView) + viewMode(QGC_WAYPOINTEDITABLEVIEW_MODE_NAV), + m_ui(new Ui::WaypointEditableView) { m_ui->setupUi(this); @@ -102,24 +102,24 @@ WaypointView::WaypointView(Waypoint* wp, QWidget* parent) : connect(customCommand->param7SpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setParam7(double))); } -void WaypointView::moveUp() +void WaypointEditableView::moveUp() { emit moveUpWaypoint(wp); } -void WaypointView::moveDown() +void WaypointEditableView::moveDown() { emit moveDownWaypoint(wp); } -void WaypointView::remove() +void WaypointEditableView::remove() { emit removeWaypoint(wp); deleteLater(); } -void WaypointView::changedAutoContinue(int state) +void WaypointEditableView::changedAutoContinue(int state) { if (state == 0) wp->setAutocontinue(false); @@ -127,7 +127,7 @@ void WaypointView::changedAutoContinue(int state) wp->setAutocontinue(true); } -void WaypointView::updateActionView(int action) +void WaypointEditableView::updateActionView(int action) { // Remove stretch item at index 17 (m_ui->removeSpacer) m_ui->horizontalLayout->takeAt(17); @@ -231,7 +231,7 @@ void WaypointView::updateActionView(int action) /** * @param index The index of the combo box of the action entry, NOT the action ID */ -void WaypointView::changedAction(int index) +void WaypointEditableView::changedAction(int index) { // set waypoint action int actionIndex = m_ui->comboBox_action->itemData(index).toUInt(); @@ -252,7 +252,7 @@ void WaypointView::changedAction(int index) case MAV_CMD_NAV_LOITER_UNLIM: case MAV_CMD_NAV_LOITER_TURNS: case MAV_CMD_NAV_LOITER_TIME: - changeViewMode(QGC_WAYPOINTVIEW_MODE_NAV); + changeViewMode(QGC_WAYPOINTEDITABLEVIEW_MODE_NAV); // Update frame view updateFrameView(m_ui->comboBox_frame->currentIndex()); // Update view @@ -261,23 +261,23 @@ void WaypointView::changedAction(int index) case MAV_CMD_ENUM_END: default: // Switch to mission frame - changeViewMode(QGC_WAYPOINTVIEW_MODE_DIRECT_EDITING); + changeViewMode(QGC_WAYPOINTEDITABLEVIEW_MODE_DIRECT_EDITING); break; } } -void WaypointView::changeViewMode(QGC_WAYPOINTVIEW_MODE mode) +void WaypointEditableView::changeViewMode(QGC_WAYPOINTEDITABLEVIEW_MODE mode) { viewMode = mode; switch (mode) { - case QGC_WAYPOINTVIEW_MODE_NAV: - case QGC_WAYPOINTVIEW_MODE_CONDITION: + case QGC_WAYPOINTEDITABLEVIEW_MODE_NAV: + case QGC_WAYPOINTEDITABLEVIEW_MODE_CONDITION: // Hide everything, show condition widget // TODO - case QGC_WAYPOINTVIEW_MODE_DO: + case QGC_WAYPOINTEDITABLEVIEW_MODE_DO: break; - case QGC_WAYPOINTVIEW_MODE_DIRECT_EDITING: + case QGC_WAYPOINTEDITABLEVIEW_MODE_DIRECT_EDITING: // Hide almost everything m_ui->orbitSpinBox->hide(); m_ui->takeOffAngleSpinBox->hide(); @@ -307,7 +307,7 @@ void WaypointView::changeViewMode(QGC_WAYPOINTVIEW_MODE mode) } -void WaypointView::updateFrameView(int frame) +void WaypointEditableView::updateFrameView(int frame) { switch(frame) { case MAV_FRAME_GLOBAL: @@ -338,7 +338,7 @@ void WaypointView::updateFrameView(int frame) } } -void WaypointView::deleted(QObject* waypoint) +void WaypointEditableView::deleted(QObject* waypoint) { Q_UNUSED(waypoint); // if (waypoint == this->wp) @@ -347,7 +347,7 @@ void WaypointView::deleted(QObject* waypoint) // } } -void WaypointView::changedFrame(int index) +void WaypointEditableView::changedFrame(int index) { // set waypoint action MAV_FRAME frame = (MAV_FRAME)m_ui->comboBox_frame->itemData(index).toUInt(); @@ -356,7 +356,7 @@ void WaypointView::changedFrame(int index) updateFrameView(frame); } -void WaypointView::changedCurrent(int state) +void WaypointEditableView::changedCurrent(int state) { if (state == 0) { m_ui->selectedBox->setChecked(true); @@ -368,7 +368,7 @@ void WaypointView::changedCurrent(int state) } } -void WaypointView::updateValues() +void WaypointEditableView::updateValues() { // Check if we just lost the wp, delete the widget // accordingly @@ -501,11 +501,11 @@ void WaypointView::updateValues() // If action is unknown, set direct editing mode if (wp->getAction() < 0 || wp->getAction() > MAV_CMD_NAV_TAKEOFF) { - changeViewMode(QGC_WAYPOINTVIEW_MODE_DIRECT_EDITING); + changeViewMode(QGC_WAYPOINTEDITABLEVIEW_MODE_DIRECT_EDITING); } else { - if (viewMode != QGC_WAYPOINTVIEW_MODE_DIRECT_EDITING) + if (viewMode != QGC_WAYPOINTEDITABLEVIEW_MODE_DIRECT_EDITING) { // Action ID known, update m_ui->comboBox_action->setCurrentIndex(action_index); @@ -696,19 +696,19 @@ void WaypointView::updateValues() // wp->blockSignals(false); } -void WaypointView::setCurrent(bool state) +void WaypointEditableView::setCurrent(bool state) { m_ui->selectedBox->blockSignals(true); m_ui->selectedBox->setChecked(state); m_ui->selectedBox->blockSignals(false); } -WaypointView::~WaypointView() +WaypointEditableView::~WaypointEditableView() { delete m_ui; } -void WaypointView::changeEvent(QEvent *e) +void WaypointEditableView::changeEvent(QEvent *e) { switch (e->type()) { case QEvent::LanguageChange: diff --git a/src/ui/WaypointView.h b/src/ui/WaypointEditableView.h similarity index 77% rename from src/ui/WaypointView.h rename to src/ui/WaypointEditableView.h index ab21e4da9cda37748b2795318c4f899430f03242..d2b6c3322b85251f5e788347d76ab51ede36c4b4 100644 --- a/src/ui/WaypointView.h +++ b/src/ui/WaypointEditableView.h @@ -30,33 +30,33 @@ This file is part of the QGROUNDCONTROL project * */ -#ifndef WAYPOINTVIEW_H -#define WAYPOINTVIEW_H +#ifndef WAYPOINTEDITABLEVIEW_H +#define WAYPOINTEDITABLEVIEW_H #include #include "Waypoint.h" #include -enum QGC_WAYPOINTVIEW_MODE { - QGC_WAYPOINTVIEW_MODE_NAV, - QGC_WAYPOINTVIEW_MODE_CONDITION, - QGC_WAYPOINTVIEW_MODE_DO, - QGC_WAYPOINTVIEW_MODE_DIRECT_EDITING +enum QGC_WAYPOINTEDITABLEVIEW_MODE { + QGC_WAYPOINTEDITABLEVIEW_MODE_NAV, + QGC_WAYPOINTEDITABLEVIEW_MODE_CONDITION, + QGC_WAYPOINTEDITABLEVIEW_MODE_DO, + QGC_WAYPOINTEDITABLEVIEW_MODE_DIRECT_EDITING }; namespace Ui { -class WaypointView; +class WaypointEditableView; } class Ui_QGCCustomWaypointAction; -class WaypointView : public QWidget +class WaypointEditableView : public QWidget { Q_OBJECT - Q_DISABLE_COPY(WaypointView) + Q_DISABLE_COPY(WaypointEditableView) public: - explicit WaypointView(Waypoint* wp, QWidget* parent); - virtual ~WaypointView(); + explicit WaypointEditableView(Waypoint* wp, QWidget* parent); + virtual ~WaypointEditableView(); public: void setCurrent(bool state); @@ -76,7 +76,7 @@ public slots: void updateValues(void); protected slots: - void changeViewMode(QGC_WAYPOINTVIEW_MODE mode); + void changeViewMode(QGC_WAYPOINTEDITABLEVIEW_MODE mode); protected: virtual void changeEvent(QEvent *e); @@ -84,10 +84,10 @@ protected: // Special widgets extendending the // waypoint view to mission capabilities Ui_QGCCustomWaypointAction* customCommand; - QGC_WAYPOINTVIEW_MODE viewMode; + QGC_WAYPOINTEDITABLEVIEW_MODE viewMode; private: - Ui::WaypointView *m_ui; + Ui::WaypointEditableView *m_ui; signals: void moveUpWaypoint(Waypoint*); @@ -98,4 +98,4 @@ signals: void setYaw(double); }; -#endif // WAYPOINTVIEW_H +#endif // WAYPOINTEDITABLEVIEW_H diff --git a/src/ui/WaypointView.ui b/src/ui/WaypointEditableView.ui similarity index 98% rename from src/ui/WaypointView.ui rename to src/ui/WaypointEditableView.ui index 7e19b7f4a67681feede5ba78a8402ac78884d7a1..99c564a07c911bdbd3ac978dc1d32634a66128ae 100644 --- a/src/ui/WaypointView.ui +++ b/src/ui/WaypointEditableView.ui @@ -1,7 +1,7 @@ - WaypointView - + WaypointEditableView + 0 @@ -604,7 +604,7 @@ Time to stay at this position before advancing - + :/images/actions/go-up.svg:/images/actions/go-up.svg @@ -630,7 +630,7 @@ Time to stay at this position before advancing - + :/images/actions/go-down.svg:/images/actions/go-down.svg @@ -653,7 +653,7 @@ Time to stay at this position before advancing - + :/images/actions/list-remove.svg:/images/actions/list-remove.svg @@ -664,7 +664,7 @@ Time to stay at this position before advancing - + diff --git a/src/ui/WaypointList.cc b/src/ui/WaypointList.cc index fab78fe3f49c0352b65faf8bc0952407944e34e4..8591b3ca3b0042404969603a2e734ee5c002ffe5 100644 --- a/src/ui/WaypointList.cc +++ b/src/ui/WaypointList.cc @@ -263,7 +263,7 @@ void WaypointList::currentWaypointChanged(quint16 seq) { for(int i = 0; i < waypoints.size(); i++) { - WaypointView* widget = wpViews.find(waypoints[i]).value(); + WaypointEditableView* widget = wpViews.find(waypoints[i]).value(); if (waypoints[i]->getId() == seq) { @@ -281,7 +281,7 @@ void WaypointList::currentWaypointChanged(quint16 seq) void WaypointList::updateWaypoint(int uas, Waypoint* wp) { Q_UNUSED(uas); - WaypointView *wpv = wpViews.value(wp); + WaypointEditableView *wpv = wpViews.value(wp); wpv->updateValues(); } @@ -293,7 +293,7 @@ void WaypointList::waypointListChanged() const QVector &waypoints = uas->getWaypointManager()->getWaypointList(); if (!wpViews.empty()) { - QMapIterator viewIt(wpViews); + QMapIterator viewIt(wpViews); viewIt.toFront(); while(viewIt.hasNext()) { viewIt.next(); @@ -305,7 +305,7 @@ void WaypointList::waypointListChanged() } } if (i == waypoints.size()) { - WaypointView* widget = wpViews.find(cur).value(); + WaypointEditableView* widget = wpViews.find(cur).value(); widget->hide(); listLayout->removeWidget(widget); wpViews.remove(cur); @@ -317,7 +317,7 @@ void WaypointList::waypointListChanged() for(int i = 0; i < waypoints.size(); i++) { Waypoint *wp = waypoints[i]; if (!wpViews.contains(wp)) { - WaypointView* wpview = new WaypointView(wp, this); + WaypointEditableView* wpview = new WaypointEditableView(wp, this); wpViews.insert(wp, wpview); connect(wpview, SIGNAL(moveDownWaypoint(Waypoint*)), this, SLOT(moveDown(Waypoint*))); connect(wpview, SIGNAL(moveUpWaypoint(Waypoint*)), this, SLOT(moveUp(Waypoint*))); @@ -326,7 +326,7 @@ void WaypointList::waypointListChanged() connect(wpview, SIGNAL(changeCurrentWaypoint(quint16)), this, SLOT(changeCurrentWaypoint(quint16))); listLayout->insertWidget(i, wpview); } - WaypointView *wpv = wpViews.value(wp); + WaypointEditableView *wpv = wpViews.value(wp); //check if ordering has changed if(listLayout->itemAt(i)->widget() != wpv) { @@ -356,11 +356,11 @@ void WaypointList::waypointListChanged() //// foreach (Waypoint* wp, waypoints) //// { -//// WaypointView* wpview; +//// WaypointEditableView* wpview; //// // Create any new waypoint //// if (!wpViews.contains(wp)) //// { -//// wpview = new WaypointView(wp, this); +//// wpview = new WaypointEditableView(wp, this); //// wpViews.insert(wp, wpview); //// connect(wpview, SIGNAL(moveDownWaypoint(Waypoint*)), this, SLOT(moveDown(Waypoint*))); //// connect(wpview, SIGNAL(moveUpWaypoint(Waypoint*)), this, SLOT(moveUp(Waypoint*))); @@ -386,7 +386,7 @@ void WaypointList::waypointListChanged() //// foreach (Waypoint* wp, oldWaypoints) //// { //// // Delete waypoint view and entry in list -//// WaypointView* wpv = wpViews.value(wp); +//// WaypointEditableView* wpv = wpViews.value(wp); //// if (wpv) //// { //// listLayout->removeWidget(wpv); @@ -397,7 +397,7 @@ void WaypointList::waypointListChanged() // if (!wpViews.empty()) // { -// QMapIterator viewIt(wpViews); +// QMapIterator viewIt(wpViews); // viewIt.toFront(); // while(viewIt.hasNext()) // { @@ -413,7 +413,7 @@ void WaypointList::waypointListChanged() // } // if (i == waypoints.size()) // { -// WaypointView* widget = wpViews.find(cur).value(); +// WaypointEditableView* widget = wpViews.find(cur).value(); // if (widget) // { // widget->hide(); @@ -430,7 +430,7 @@ void WaypointList::waypointListChanged() // Waypoint *wp = waypoints[i]; // if (!wpViews.contains(wp)) // { -// WaypointView* wpview = new WaypointView(wp, this); +// WaypointEditableView* wpview = new WaypointEditableView(wp, this); // wpViews.insert(wp, wpview); // connect(wpview, SIGNAL(moveDownWaypoint(Waypoint*)), this, SLOT(moveDown(Waypoint*))); // connect(wpview, SIGNAL(moveUpWaypoint(Waypoint*)), this, SLOT(moveUp(Waypoint*))); @@ -438,7 +438,7 @@ void WaypointList::waypointListChanged() // connect(wpview, SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointChanged(quint16))); // connect(wpview, SIGNAL(changeCurrentWaypoint(quint16)), this, SLOT(changeCurrentWaypoint(quint16))); // } -// WaypointView *wpv = wpViews.value(wp); +// WaypointEditableView *wpv = wpViews.value(wp); // wpv->updateValues(); // update the values of the ui elements in the view // listLayout->addWidget(wpv); @@ -514,7 +514,7 @@ void WaypointList::on_clearWPListButton_clicked() emit clearPathclicked(); const QVector &waypoints = uas->getWaypointManager()->getWaypointList(); while(!waypoints.isEmpty()) { //for(int i = 0; i <= waypoints.size(); i++) - WaypointView* widget = wpViews.find(waypoints[0]).value(); + WaypointEditableView* widget = wpViews.find(waypoints[0]).value(); widget->remove(); } } else { @@ -565,7 +565,7 @@ void WaypointList::clearWPWidget() if (uas) { const QVector &waypoints = uas->getWaypointManager()->getWaypointList(); while(!waypoints.isEmpty()) { //for(int i = 0; i <= waypoints.size(); i++) - WaypointView* widget = wpViews.find(waypoints[0]).value(); + WaypointEditableView* widget = wpViews.find(waypoints[0]).value(); widget->remove(); } } diff --git a/src/ui/WaypointList.h b/src/ui/WaypointList.h index c63d67d29f75b44e1a0ed3f4ee24a49bf4bd33c4..85a2bc6bc24338051bbf8615cd1032057370347e 100644 --- a/src/ui/WaypointList.h +++ b/src/ui/WaypointList.h @@ -40,8 +40,8 @@ This file is part of the QGROUNDCONTROL project #include #include "Waypoint.h" #include "UASInterface.h" -#include "WaypointView.h" - +#include "WaypointEditableView.h" +#include "WaypointViewOnlyView.h" namespace Ui { @@ -115,7 +115,7 @@ protected: virtual void changeEvent(QEvent *e); protected: - QMap wpViews; + QMap wpViews; QVBoxLayout* listLayout; UASInterface* uas; double mavX; diff --git a/src/ui/WaypointViewViewOnly.cc b/src/ui/WaypointViewViewOnly.cc deleted file mode 100644 index 3f9ddad155ed7bd7d31f8144c77a38f64cdd5706..0000000000000000000000000000000000000000 --- a/src/ui/WaypointViewViewOnly.cc +++ /dev/null @@ -1,158 +0,0 @@ -#include -#include "WaypointViewViewOnly.h" -#include "ui_WaypointViewViewOnly.h" - -WaypointViewViewOnly::WaypointViewViewOnly(Waypoint* wp, QWidget *parent) : - QWidget(parent), - m_ui(new Ui::WaypointViewViewOnly) -{ - m_ui->setupUi(this); - this->wp = wp; - updateValues(); - - connect(m_ui->current, SIGNAL(stateChanged(int)), this, SLOT(changedCurrent(int))); - connect(m_ui->autoContinue, SIGNAL(stateChanged(int)),this, SLOT(changedAutoContinue(int))); -} - -void WaypointViewViewOnly::changedAutoContinue(int state) -{ - bool new_value = false; - if (state != 0) - { - new_value = true; - } - m_ui->autoContinue->blockSignals(true); - m_ui->autoContinue->setChecked(state); - m_ui->autoContinue->blockSignals(false); - wp->setAutocontinue(new_value); - emit changeAutoContinue(wp->getId(),new_value); - } - -void WaypointViewViewOnly::changedCurrent(int state) -{ - qDebug() << "Trof: WaypointViewViewOnly::changedCurrent(" << state << ") ID:" << wp->getId(); - - if (state == 0) - { - if (wp->getCurrent() == true) //User clicked on the waypoint, that is already current - { - m_ui->current->setChecked(true); - m_ui->current->setCheckState(Qt::Checked); - } - else - { - m_ui->current->setChecked(false); - m_ui->current->setCheckState(Qt::Unchecked); - wp->setCurrent(false); - } - } - else - { - wp->setCurrent(true); - emit changeCurrentWaypoint(wp->getId()); //the slot changeCurrentWaypoint() in WaypointList sets all other current flags to false - } -} - -void WaypointViewViewOnly::setCurrent(bool state) -{ - m_ui->current->blockSignals(true); - m_ui->current->setChecked(state); - m_ui->current->blockSignals(false); -} - -void WaypointViewViewOnly::updateValues() -{ - qDebug() << "Trof: WaypointViewViewOnly::updateValues() ID:" << wp->getId(); - // Check if we just lost the wp, delete the widget - // accordingly - if (!wp) - { - deleteLater(); - return; - } - // Deactivate signals from the WP - wp->blockSignals(true); - // update frame - - m_ui->idLabel->setText(QString("%1").arg(wp->getId())); - - if (m_ui->current->isChecked() != wp->getCurrent()) - { - m_ui->current->setChecked(wp->getCurrent()); - } - if (m_ui->autoContinue->isChecked() != wp->getAutoContinue()) - { - m_ui->autoContinue->setChecked(wp->getAutoContinue()); - } - -switch (wp->getAction()) -{ -case MAV_CMD_NAV_WAYPOINT: - { - if (wp->getParam1()>0) - { - m_ui->displayBar->setText(QString("Go to (%1, %2, %3) and wait there for %4 sec; yaw: %5; rad: %6").arg(wp->getX()).arg(wp->getY()).arg(wp->getZ()).arg(wp->getParam1()).arg(wp->getParam4()).arg(wp->getParam2())); - } - else - { - m_ui->displayBar->setText(QString("Go to (%1, %2, %3); yaw: %4; rad: %5").arg(wp->getX()).arg(wp->getY()).arg(wp->getZ()).arg(wp->getParam4()).arg(wp->getParam2())); - } - break; - } -case MAV_CMD_NAV_LAND: - { - m_ui->displayBar->setText(QString("LAND. Go to (%1, %2, %3) and descent; yaw: %4").arg(wp->getX()).arg(wp->getY()).arg(wp->getZ()).arg(wp->getParam4())); - break; - } -case MAV_CMD_NAV_TAKEOFF: - { - m_ui->displayBar->setText(QString("TAKEOFF. Go to (%1, %2, %3); yaw: %4").arg(wp->getX()).arg(wp->getY()).arg(wp->getZ()).arg(wp->getParam4())); - break; - } -case MAV_CMD_DO_JUMP: - { - if (wp->getParam2()>0) - { - m_ui->displayBar->setText(QString("Jump to waypoint %1. Jumps left: %2").arg(wp->getParam1()).arg(wp->getParam2())); - } - else - { - m_ui->displayBar->setText(QString("No jumps left. Proceed to next waypoint.")); - } - break; - } -case MAV_CMD_CONDITION_DELAY: - { - m_ui->displayBar->setText(QString("Delay: %1 sec").arg(wp->getParam1())); - break; - } -case 237: //MAV_CMD_DO_START_SEARCH - { - m_ui->displayBar->setText(QString("Start searching for pattern. Success when got more than %2 detections with confidence %1").arg(wp->getParam1()).arg(wp->getParam2())); - break; - } -case 238: //MAV_CMD_DO_FINISH_SEARCH - { - m_ui->displayBar->setText(QString("Check if search was successful. yes -> jump to %1, no -> jump to %2. Jumps left: %3").arg(wp->getParam1()).arg(wp->getParam2()).arg(wp->getParam3())); - break; - } -case 240: //MAV_CMD_DO_SWEEP - { - m_ui->displayBar->setText(QString("Sweep. Corners: (%1,%2) and (%3,%4); z: %5; scan radius: %6").arg(wp->getParam3()).arg(wp->getParam4()).arg(wp->getParam5()).arg(wp->getParam6()).arg(wp->getParam7()).arg(wp->getParam1())); - break; - } -default: - { - m_ui->displayBar->setText(QString("Unknown Command ID (%1) : %2, %3, %4, %5, %6, %7, %8").arg(wp->getAction()).arg(wp->getParam1()).arg(wp->getParam2()).arg(wp->getParam3()).arg(wp->getParam4()).arg(wp->getParam5()).arg(wp->getParam6()).arg(wp->getParam7())); - break; - } -} - - - wp->blockSignals(false); -} - -WaypointViewViewOnly::~WaypointViewViewOnly() -{ - delete m_ui; -} diff --git a/src/ui/WaypointViewViewOnly.h b/src/ui/WaypointViewViewOnly.h deleted file mode 100644 index 36475f9c39198c8575333d1ab0e4a0bc83779cad..0000000000000000000000000000000000000000 --- a/src/ui/WaypointViewViewOnly.h +++ /dev/null @@ -1,37 +0,0 @@ -#ifndef WAYPOINTVIEWVIEWONLY_H -#define WAYPOINTVIEWVIEWONLY_H - -#include -#include "Waypoint.h" -#include - -namespace Ui { - class WaypointViewViewOnly; -} - -class WaypointViewViewOnly : public QWidget -{ - Q_OBJECT - -public: - explicit WaypointViewViewOnly(Waypoint* wp, QWidget *parent = 0); - ~WaypointViewViewOnly(); - -public slots: -void changedCurrent(int state); -void changedAutoContinue(int state); -void updateValues(void); -void setCurrent(bool state); - -signals: - void changeCurrentWaypoint(quint16); - void changeAutoContinue(quint16, bool); - -protected: -Waypoint* wp; - -private: - Ui::WaypointViewViewOnly *m_ui; -}; - -#endif // WAYPOINTVIEWVIEWONLY_H diff --git a/src/ui/WaypointViewViewOnly.ui b/src/ui/WaypointViewViewOnly.ui deleted file mode 100644 index b3cc426429f4adf33f40077960f8237f90323301..0000000000000000000000000000000000000000 --- a/src/ui/WaypointViewViewOnly.ui +++ /dev/null @@ -1,244 +0,0 @@ - - - WaypointViewViewOnly - - - - 0 - 0 - 381 - 55 - - - - - 0 - 0 - - - - Form - - - QWidget#colorIcon {} - -QWidget { -background-color: #252528; -color: #DDDDDF; -border-color: #EEEEEE; -background-clip: border; -} - -QCheckBox { -background-color: #252528; -color: #454545; -} - -QGroupBox { - border: 1px solid #EEEEEE; - border-radius: 5px; - padding: 0px 0px 0px 0px; -margin-top: 1ex; /* leave space at the top for the title */ - margin: 0px; -} - - QGroupBox::title { - subcontrol-origin: margin; - subcontrol-position: top center; /* position at the top center */ - margin: 0 3px 0px 3px; - padding: 0 3px 0px 0px; - font: bold 8px; - } - -QGroupBox#heartbeatIcon { - background-color: red; -} - - QDockWidget { - font: bold; - border: 1px solid #32345E; -} - -QPushButton { - font-weight: bold; - font-size: 12px; - border: 1px solid #999999; - border-radius: 10px; - min-width:22px; - max-width: 36px; - min-height: 16px; - max-height: 16px; - padding: 2px; - background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #777777, stop: 1 #555555); -} - -QPushButton:pressed { - background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #444444, stop: 1 #555555); -} - -QPushButton#landButton { - color: #000000; - background: qlineargradient(x1:0, y1:0, x2:0, y2:1, - stop:0 #ffee01, stop:1 #ae8f00) url("ICONDIR/control/emergency-button.png"); -} - -QPushButton:pressed#landButton { - color: #000000; - background: qlineargradient(x1:0, y1:0, x2:0, y2:1, - stop:0 #bbaa00, stop:1 #a05b00) url("ICONDIR/control/emergency-button.png"); -} - -QPushButton#killButton { - color: #000000; - background: qlineargradient(x1:0, y1:0, x2:0, y2:1, - stop:0 #ffb917, stop:1 #b37300) url("ICONDIR/control/emergency-button.png"); -} - -QPushButton:pressed#killButton { - color: #000000; - background: qlineargradient(x1:0, y1:0, x2:0, y2:1, - stop:0 #bb8500, stop:1 #903000) url("ICONDIR/control/emergency-button.png"); -} - -QProgressBar { - border: 1px solid white; - border-radius: 4px; - text-align: center; - padding: 2px; - color: white; - background-color: #111111; -} - -QProgressBar:horizontal { - height: 12px; -} - -QProgressBar QLabel { - font-size: 8px; -} - -QProgressBar:vertical { - width: 12px; -} - -QProgressBar::chunk { - background-color: #656565; -} - -QProgressBar::chunk#batteryBar { - background-color: green; -} - -QProgressBar::chunk#speedBar { - background-color: yellow; -} - -QProgressBar::chunk#thrustBar { - background-color: orange; -} - - - - 2 - - - 0 - - - 2 - - - 0 - - - - - true - - - - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - false - - - false - - - - 2 - - - 2 - - - - - Currently executed waypoint - - - Currently executed waypoint - - - - - - - - - - ID - - - - - - - - 0 - 0 - - - - - 16777215 - 31 - - - - - 8 - - - - QFrame::NoFrame - - - QFrame::Sunken - - - - - - - Automatically continue after this waypoint - - - Automatically continue after this waypoint - - - - - - - - - - - - - -