diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index 7891961..78445ba 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -210,7 +210,8 @@ FORMS += src/ui/MainWindow.ui \ src/ui/map/QGCMapTool.ui \ src/ui/map/QGCMapToolBar.ui \ src/ui/QGCMAVLinkInspector.ui \ - src/ui/WaypointViewViewOnly.ui + src/ui/WaypointViewOnlyView.ui \ + src/ui/WaypointViewOnlyView.ui INCLUDEPATH += src \ src/ui \ src/ui/linechart \ @@ -325,7 +326,8 @@ HEADERS += src/MG.h \ src/ui/QGCToolBar.h \ src/ui/QGCMAVLinkInspector.h \ src/ui/MAVLinkDecoder.h \ - src/ui/WaypointViewViewOnly.h + src/ui/WaypointViewOnlyView.h \ + src/ui/WaypointViewOnlyView.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 @@ -452,7 +454,7 @@ SOURCES += src/main.cc \ src/ui/QGCToolBar.cc \ src/ui/QGCMAVLinkInspector.cc \ src/ui/MAVLinkDecoder.cc \ - src/ui/WaypointViewViewOnly.cc + src/ui/WaypointViewOnlyView.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/WaypointList.cc b/src/ui/WaypointList.cc index 4eee0d1..fab78fe 100644 --- a/src/ui/WaypointList.cc +++ b/src/ui/WaypointList.cc @@ -322,7 +322,7 @@ void WaypointList::waypointListChanged() connect(wpview, SIGNAL(moveDownWaypoint(Waypoint*)), this, SLOT(moveDown(Waypoint*))); connect(wpview, SIGNAL(moveUpWaypoint(Waypoint*)), this, SLOT(moveUp(Waypoint*))); connect(wpview, SIGNAL(removeWaypoint(Waypoint*)), this, SLOT(removeWaypoint(Waypoint*))); - connect(wpview, SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointChanged(quint16))); + //connect(wpview, SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointChanged(quint16))); commented, because unused connect(wpview, SIGNAL(changeCurrentWaypoint(quint16)), this, SLOT(changeCurrentWaypoint(quint16))); listLayout->insertWidget(i, wpview); } diff --git a/src/ui/WaypointView.cc b/src/ui/WaypointView.cc index b0ed2cc..db9eeb6 100644 --- a/src/ui/WaypointView.cc +++ b/src/ui/WaypointView.cc @@ -361,7 +361,7 @@ void WaypointView::changedCurrent(int state) if (state == 0) { m_ui->selectedBox->setChecked(true); m_ui->selectedBox->setCheckState(Qt::Checked); - wp->setCurrent(false); + //wp->setCurrent(false); //FIXME: Is this line needed? } else { wp->setCurrent(true); emit changeCurrentWaypoint(wp->getId()); //the slot changeCurrentWaypoint() in WaypointList sets all other current flags to false diff --git a/src/ui/WaypointView.h b/src/ui/WaypointView.h index 21de924..ab21e4d 100644 --- a/src/ui/WaypointView.h +++ b/src/ui/WaypointView.h @@ -93,7 +93,7 @@ signals: void moveUpWaypoint(Waypoint*); void moveDownWaypoint(Waypoint*); void removeWaypoint(Waypoint*); - void currentWaypointChanged(quint16); + //void currentWaypointChanged(quint16); //unused void changeCurrentWaypoint(quint16); void setYaw(double); }; diff --git a/src/ui/WaypointViewOnlyView.cc b/src/ui/WaypointViewOnlyView.cc new file mode 100644 index 0000000..0a0ffcb --- /dev/null +++ b/src/ui/WaypointViewOnlyView.cc @@ -0,0 +1,158 @@ +#include +#include "WaypointViewOnlyView.h" +#include "ui_WaypointViewOnlyView.h" + +WaypointViewOnlyView::WaypointViewOnlyView(Waypoint* wp, QWidget *parent) : + QWidget(parent), + m_ui(new Ui::WaypointViewOnlyView) +{ + 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 WaypointViewOnlyView::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 WaypointViewOnlyView::changedCurrent(int state) +{ + qDebug() << "Trof: WaypointViewOnlyView::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 WaypointViewOnlyView::setCurrent(bool state) +{ + m_ui->current->blockSignals(true); + m_ui->current->setChecked(state); + m_ui->current->blockSignals(false); +} + +void WaypointViewOnlyView::updateValues() +{ + qDebug() << "Trof: WaypointViewOnlyView::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); +} + +WaypointViewOnlyView::~WaypointViewOnlyView() +{ + delete m_ui; +} diff --git a/src/ui/WaypointViewOnlyView.h b/src/ui/WaypointViewOnlyView.h new file mode 100644 index 0000000..099a3d8 --- /dev/null +++ b/src/ui/WaypointViewOnlyView.h @@ -0,0 +1,37 @@ +#ifndef WAYPOINTVIEWONLYVIEW_H +#define WAYPOINTVIEWONLYVIEW_H + +#include +#include "Waypoint.h" +#include + +namespace Ui { + class WaypointViewOnlyView; +} + +class WaypointViewOnlyView : public QWidget +{ + Q_OBJECT + +public: + explicit WaypointViewOnlyView(Waypoint* wp, QWidget *parent = 0); + ~WaypointViewOnlyView(); + +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::WaypointViewOnlyView *m_ui; +}; + +#endif // WAYPOINTVIEWONLYVIEW_H diff --git a/src/ui/WaypointViewOnlyView.ui b/src/ui/WaypointViewOnlyView.ui new file mode 100644 index 0000000..b2c7991 --- /dev/null +++ b/src/ui/WaypointViewOnlyView.ui @@ -0,0 +1,244 @@ + + + WaypointViewOnlyView + + + + 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 + + + + + + + + + + + + + +