7 changed files with 447 additions and 6 deletions
@ -0,0 +1,158 @@ |
|||||||
|
#include <QDebug> |
||||||
|
#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; |
||||||
|
} |
@ -0,0 +1,37 @@ |
|||||||
|
#ifndef WAYPOINTVIEWONLYVIEW_H |
||||||
|
#define WAYPOINTVIEWONLYVIEW_H |
||||||
|
|
||||||
|
#include <QtGui/QWidget> |
||||||
|
#include "Waypoint.h" |
||||||
|
#include <iostream> |
||||||
|
|
||||||
|
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
|
@ -0,0 +1,244 @@ |
|||||||
|
<?xml version="1.0" encoding="UTF-8"?> |
||||||
|
<ui version="4.0"> |
||||||
|
<class>WaypointViewOnlyView</class> |
||||||
|
<widget class="QWidget" name="WaypointViewOnlyView"> |
||||||
|
<property name="geometry"> |
||||||
|
<rect> |
||||||
|
<x>0</x> |
||||||
|
<y>0</y> |
||||||
|
<width>381</width> |
||||||
|
<height>55</height> |
||||||
|
</rect> |
||||||
|
</property> |
||||||
|
<property name="sizePolicy"> |
||||||
|
<sizepolicy hsizetype="Preferred" vsizetype="Fixed"> |
||||||
|
<horstretch>0</horstretch> |
||||||
|
<verstretch>0</verstretch> |
||||||
|
</sizepolicy> |
||||||
|
</property> |
||||||
|
<property name="windowTitle"> |
||||||
|
<string>Form</string> |
||||||
|
</property> |
||||||
|
<property name="styleSheet"> |
||||||
|
<string notr="true">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; |
||||||
|
}</string> |
||||||
|
</property> |
||||||
|
<layout class="QHBoxLayout" name="horizontalLayout_2"> |
||||||
|
<property name="leftMargin"> |
||||||
|
<number>2</number> |
||||||
|
</property> |
||||||
|
<property name="topMargin"> |
||||||
|
<number>0</number> |
||||||
|
</property> |
||||||
|
<property name="rightMargin"> |
||||||
|
<number>2</number> |
||||||
|
</property> |
||||||
|
<property name="bottomMargin"> |
||||||
|
<number>0</number> |
||||||
|
</property> |
||||||
|
<item> |
||||||
|
<widget class="QGroupBox" name="groupBox"> |
||||||
|
<property name="enabled"> |
||||||
|
<bool>true</bool> |
||||||
|
</property> |
||||||
|
<property name="title"> |
||||||
|
<string/> |
||||||
|
</property> |
||||||
|
<property name="alignment"> |
||||||
|
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set> |
||||||
|
</property> |
||||||
|
<property name="flat"> |
||||||
|
<bool>false</bool> |
||||||
|
</property> |
||||||
|
<property name="checkable"> |
||||||
|
<bool>false</bool> |
||||||
|
</property> |
||||||
|
<layout class="QHBoxLayout" name="horizontalLayout"> |
||||||
|
<property name="spacing"> |
||||||
|
<number>2</number> |
||||||
|
</property> |
||||||
|
<property name="margin"> |
||||||
|
<number>2</number> |
||||||
|
</property> |
||||||
|
<item> |
||||||
|
<widget class="QCheckBox" name="current"> |
||||||
|
<property name="toolTip"> |
||||||
|
<string>Currently executed waypoint</string> |
||||||
|
</property> |
||||||
|
<property name="statusTip"> |
||||||
|
<string>Currently executed waypoint</string> |
||||||
|
</property> |
||||||
|
<property name="text"> |
||||||
|
<string/> |
||||||
|
</property> |
||||||
|
</widget> |
||||||
|
</item> |
||||||
|
<item> |
||||||
|
<widget class="QLabel" name="idLabel"> |
||||||
|
<property name="text"> |
||||||
|
<string>ID</string> |
||||||
|
</property> |
||||||
|
</widget> |
||||||
|
</item> |
||||||
|
<item> |
||||||
|
<widget class="QTextBrowser" name="displayBar"> |
||||||
|
<property name="sizePolicy"> |
||||||
|
<sizepolicy hsizetype="Expanding" vsizetype="Expanding"> |
||||||
|
<horstretch>0</horstretch> |
||||||
|
<verstretch>0</verstretch> |
||||||
|
</sizepolicy> |
||||||
|
</property> |
||||||
|
<property name="maximumSize"> |
||||||
|
<size> |
||||||
|
<width>16777215</width> |
||||||
|
<height>31</height> |
||||||
|
</size> |
||||||
|
</property> |
||||||
|
<property name="font"> |
||||||
|
<font> |
||||||
|
<pointsize>8</pointsize> |
||||||
|
</font> |
||||||
|
</property> |
||||||
|
<property name="frameShape"> |
||||||
|
<enum>QFrame::NoFrame</enum> |
||||||
|
</property> |
||||||
|
<property name="frameShadow"> |
||||||
|
<enum>QFrame::Sunken</enum> |
||||||
|
</property> |
||||||
|
</widget> |
||||||
|
</item> |
||||||
|
<item> |
||||||
|
<widget class="QCheckBox" name="autoContinue"> |
||||||
|
<property name="toolTip"> |
||||||
|
<string>Automatically continue after this waypoint</string> |
||||||
|
</property> |
||||||
|
<property name="statusTip"> |
||||||
|
<string>Automatically continue after this waypoint</string> |
||||||
|
</property> |
||||||
|
<property name="text"> |
||||||
|
<string/> |
||||||
|
</property> |
||||||
|
</widget> |
||||||
|
</item> |
||||||
|
</layout> |
||||||
|
</widget> |
||||||
|
</item> |
||||||
|
</layout> |
||||||
|
</widget> |
||||||
|
<resources/> |
||||||
|
<connections/> |
||||||
|
</ui> |
Loading…
Reference in new issue