Browse Source

Merge pull request #98 from Trof/offline-wplist

Substantially improves waypoint interface.
QGC4.4
QGroundControl 14 years ago
parent
commit
4d41cb2052
  1. 17
      src/uas/UASWaypointManager.cc
  2. 6
      src/ui/MainWindow.cc
  3. 65
      src/ui/WaypointEditableView.cc
  4. 44
      src/ui/WaypointEditableView.ui
  5. 58
      src/ui/WaypointList.cc
  6. 2
      src/ui/WaypointList.h
  7. 54
      src/ui/WaypointList.ui
  8. 117
      src/ui/WaypointViewOnlyView.cc
  9. 161
      src/ui/WaypointViewOnlyView.ui

17
src/uas/UASWaypointManager.cc

@ -211,6 +211,7 @@ void UASWaypointManager::handleWaypointAck(quint8 systemId, quint8 compId, mavli @@ -211,6 +211,7 @@ void UASWaypointManager::handleWaypointAck(quint8 systemId, quint8 compId, mavli
//all waypoints sent and ack received
protocol_timer.stop();
current_state = WP_IDLE;
readWaypoints(false); //Update "Onboard Waypoints"-tab immidiately after the waypoint list has been sent.
emit updateStatusString("done.");
// // qDebug() << "sent all waypoints to ID " << systemId;
} else if(current_state == WP_CLEARLIST) {
@ -405,6 +406,19 @@ int UASWaypointManager::removeWaypoint(quint16 seq) @@ -405,6 +406,19 @@ int UASWaypointManager::removeWaypoint(quint16 seq)
if (seq < waypointsEditable.size())
{
Waypoint *t = waypointsEditable[seq];
if (t->getCurrent() == true) //trying to remove the current waypoint
{
if (seq+1 < waypointsEditable.size()) // setting the next waypoint as current
{
waypointsEditable[seq+1]->setCurrent(true);
}
else if (seq-1 >= 0) //if deleting the last on the list, then setting the previous waypoint as current
{
waypointsEditable[seq-1]->setCurrent(true);
}
}
waypointsEditable.remove(seq);
delete t;
t = NULL;
@ -430,6 +444,7 @@ void UASWaypointManager::moveWaypoint(quint16 cur_seq, quint16 new_seq) @@ -430,6 +444,7 @@ void UASWaypointManager::moveWaypoint(quint16 cur_seq, quint16 new_seq)
for (int i = cur_seq; i < new_seq; i++)
{
waypointsEditable[i] = waypointsEditable[i+1];
waypointsEditable[i]->setId(i);
}
}
else
@ -437,9 +452,11 @@ void UASWaypointManager::moveWaypoint(quint16 cur_seq, quint16 new_seq) @@ -437,9 +452,11 @@ void UASWaypointManager::moveWaypoint(quint16 cur_seq, quint16 new_seq)
for (int i = cur_seq; i > new_seq; i--)
{
waypointsEditable[i] = waypointsEditable[i-1];
waypointsEditable[i]->setId(i);
}
}
waypointsEditable[new_seq] = t;
waypointsEditable[new_seq]->setId(new_seq);
emit waypointEditableListChanged();
emit waypointEditableListChanged(uasid);

6
src/ui/MainWindow.cc

@ -1197,8 +1197,8 @@ void MainWindow::UASCreated(UASInterface* uas) @@ -1197,8 +1197,8 @@ void MainWindow::UASCreated(UASInterface* uas)
// Connect the UAS to the full user interface
if (uas != NULL)
{
//if (uas != NULL)
//{
// The pilot, operator and engineer views were not available on startup, enable them now
ui.actionPilotsView->setEnabled(true);
ui.actionOperatorsView->setEnabled(true);
@ -1346,7 +1346,7 @@ void MainWindow::UASCreated(UASInterface* uas) @@ -1346,7 +1346,7 @@ void MainWindow::UASCreated(UASInterface* uas)
}
}
}
//}
if (!ui.menuConnected_Systems->isEnabled()) ui.menuConnected_Systems->setEnabled(true);

65
src/ui/WaypointEditableView.cc

@ -50,9 +50,9 @@ WaypointEditableView::WaypointEditableView(Waypoint* wp, QWidget* parent) : @@ -50,9 +50,9 @@ WaypointEditableView::WaypointEditableView(Waypoint* wp, QWidget* parent) :
m_ui->comboBox_action->addItem(tr("Other"), MAV_CMD_ENUM_END);
// add frames
m_ui->comboBox_frame->addItem("Abs. Alt/Global",MAV_FRAME_GLOBAL);
m_ui->comboBox_frame->addItem("Rel. Alt/Global", MAV_FRAME_GLOBAL_RELATIVE_ALT);
m_ui->comboBox_frame->addItem("Local/Abs. Alt.",MAV_FRAME_LOCAL_NED);
m_ui->comboBox_frame->addItem("Global/Abs. Alt",MAV_FRAME_GLOBAL);
m_ui->comboBox_frame->addItem("Global/Rel. Alt", MAV_FRAME_GLOBAL_RELATIVE_ALT);
m_ui->comboBox_frame->addItem("Local(NED)",MAV_FRAME_LOCAL_NED);
m_ui->comboBox_frame->addItem("Mission",MAV_FRAME_MISSION);
// Initialize view correctly
@ -234,6 +234,7 @@ void WaypointEditableView::updateActionView(int action) @@ -234,6 +234,7 @@ void WaypointEditableView::updateActionView(int action)
*/
void WaypointEditableView::changedAction(int index)
{
MAV_FRAME cur_frame = (MAV_FRAME) m_ui->comboBox_frame->itemData(m_ui->comboBox_frame->currentIndex()).toUInt();
// set waypoint action
int actionIndex = m_ui->comboBox_action->itemData(index).toUInt();
if (actionIndex < MAV_CMD_ENUM_END && actionIndex >= 0) {
@ -254,8 +255,8 @@ void WaypointEditableView::changedAction(int index) @@ -254,8 +255,8 @@ void WaypointEditableView::changedAction(int index)
case MAV_CMD_NAV_LOITER_TURNS:
case MAV_CMD_NAV_LOITER_TIME:
changeViewMode(QGC_WAYPOINTEDITABLEVIEW_MODE_NAV);
// Update frame view
updateFrameView(m_ui->comboBox_frame->currentIndex());
// Update frame view
updateFrameView(cur_frame);
// Update view
updateActionView(actionIndex);
break;
@ -309,30 +310,44 @@ void WaypointEditableView::changeViewMode(QGC_WAYPOINTEDITABLEVIEW_MODE mode) @@ -309,30 +310,44 @@ void WaypointEditableView::changeViewMode(QGC_WAYPOINTEDITABLEVIEW_MODE mode)
}
void WaypointEditableView::updateFrameView(int frame)
{
{
switch(frame) {
case MAV_FRAME_GLOBAL:
case MAV_FRAME_GLOBAL_RELATIVE_ALT:
m_ui->posNSpinBox->hide();
m_ui->posESpinBox->hide();
m_ui->posDSpinBox->hide();
m_ui->lonSpinBox->show();
m_ui->latSpinBox->show();
m_ui->altSpinBox->show();
// Coordinate frame
m_ui->comboBox_frame->show();
m_ui->customActionWidget->hide();
if (viewMode != QGC_WAYPOINTEDITABLEVIEW_MODE_DIRECT_EDITING)
{
m_ui->posNSpinBox->hide();
m_ui->posESpinBox->hide();
m_ui->posDSpinBox->hide();
m_ui->lonSpinBox->show();
m_ui->latSpinBox->show();
m_ui->altSpinBox->show();
// Coordinate frame
m_ui->comboBox_frame->show();
m_ui->customActionWidget->hide();
}
else // do not hide customActionWidget if Command is set to "Other"
{
m_ui->customActionWidget->show();
}
break;
case MAV_FRAME_LOCAL_NED:
m_ui->lonSpinBox->hide();
m_ui->latSpinBox->hide();
m_ui->altSpinBox->hide();
m_ui->posNSpinBox->show();
m_ui->posESpinBox->show();
m_ui->posDSpinBox->show();
// Coordinate frame
m_ui->comboBox_frame->show();
m_ui->customActionWidget->hide();
if (viewMode != QGC_WAYPOINTEDITABLEVIEW_MODE_DIRECT_EDITING)
{
m_ui->lonSpinBox->hide();
m_ui->latSpinBox->hide();
m_ui->altSpinBox->hide();
m_ui->posNSpinBox->show();
m_ui->posESpinBox->show();
m_ui->posDSpinBox->show();
// Coordinate frame
m_ui->comboBox_frame->show();
m_ui->customActionWidget->hide();
}
else // do not hide customActionWidget if Command is set to "Other"
{
m_ui->customActionWidget->show();
}
break;
default:
std::cerr << "unknown frame" << std::endl;
@ -526,7 +541,7 @@ void WaypointEditableView::updateValues() @@ -526,7 +541,7 @@ void WaypointEditableView::updateValues()
{
// Action ID known, update
m_ui->comboBox_action->setCurrentIndex(action_index);
updateActionView(action);
updateActionView(action);
}
}
}

44
src/ui/WaypointEditableView.ui

@ -105,6 +105,18 @@ QPushButton:pressed { @@ -105,6 +105,18 @@ QPushButton:pressed {
</property>
<item>
<widget class="QCheckBox" name="selectedBox">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>25</width>
<height>0</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::TabFocus</enum>
</property>
@ -127,9 +139,15 @@ QPushButton:pressed { @@ -127,9 +139,15 @@ QPushButton:pressed {
</item>
<item>
<widget class="QLabel" name="idLabel">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>15</width>
<width>25</width>
<height>0</height>
</size>
</property>
@ -471,6 +489,12 @@ QPushButton:pressed { @@ -471,6 +489,12 @@ QPushButton:pressed {
</item>
<item>
<widget class="QDoubleSpinBox" name="acceptanceSpinBox">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="toolTip">
<string>Uncertainty radius in meters
where to accept this waypoint as reached</string>
@ -488,6 +512,12 @@ where to accept this waypoint as reached</string> @@ -488,6 +512,12 @@ where to accept this waypoint as reached</string>
</item>
<item>
<widget class="QDoubleSpinBox" name="holdTimeSpinBox">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="toolTip">
<string>Rotaty wing and ground vehicles only:
Time to stay at this position before advancing</string>
@ -505,6 +535,12 @@ Time to stay at this position before advancing</string> @@ -505,6 +535,12 @@ Time to stay at this position before advancing</string>
</item>
<item>
<widget class="QSpinBox" name="turnsSpinBox">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="toolTip">
<string>Number of turns to loiter</string>
</property>
@ -581,6 +617,12 @@ Time to stay at this position before advancing</string> @@ -581,6 +617,12 @@ Time to stay at this position before advancing</string>
</item>
<item>
<widget class="QCheckBox" name="autoContinue">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="toolTip">
<string>Automatically continue after this waypoint</string>
</property>

58
src/ui/WaypointList.cc

@ -47,6 +47,7 @@ WaypointList::WaypointList(QWidget *parent, UASInterface* uas) : @@ -47,6 +47,7 @@ WaypointList::WaypointList(QWidget *parent, UASInterface* uas) :
mavY(0.0),
mavZ(0.0),
mavYaw(0.0),
showOfflineWarning(false),
m_ui(new Ui::WaypointList)
{
@ -100,7 +101,7 @@ WaypointList::WaypointList(QWidget *parent, UASInterface* uas) : @@ -100,7 +101,7 @@ WaypointList::WaypointList(QWidget *parent, UASInterface* uas) :
if (uas)
{
WPM = uas->getWaypointManager();
setUAS(uas);
//setUAS(uas);
}
else
{
@ -108,13 +109,16 @@ WaypointList::WaypointList(QWidget *parent, UASInterface* uas) : @@ -108,13 +109,16 @@ WaypointList::WaypointList(QWidget *parent, UASInterface* uas) :
m_ui->positionAddButton->hide();
m_ui->transmitButton->hide();
m_ui->readButton->hide();
//FIXME: The whole "Onboard Waypoints"-tab should be hidden, instead of "refresh" button
m_ui->refreshButton->hide();
//FIXME: The whole "Onboard Waypoints"-tab should be hidden, instead of "refresh" button
UnconnectedUASInfoWidget* inf = new UnconnectedUASInfoWidget(this);
viewOnlyListLayout->insertWidget(0, inf);
viewOnlyListLayout->insertWidget(0, inf); //insert a "NO UAV" info into the Onboard Tab
showOfflineWarning = true;
WPM = new UASWaypointManager(NULL);
}
setUAS(uas);
// STATUS LABEL
updateStatusLabel("");
@ -151,21 +155,21 @@ void WaypointList::updateAttitude(UASInterface* uas, double roll, double pitch, @@ -151,21 +155,21 @@ void WaypointList::updateAttitude(UASInterface* uas, double roll, double pitch,
void WaypointList::setUAS(UASInterface* uas)
{
if (this->uas == NULL && uas != NULL)
//if (this->uas == NULL && uas != NULL)
if (this->uas == NULL)
{
this->uas = uas;
if(uas != NULL)
{
connect(uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updatePosition(UASInterface*,double,double,double,quint64)));
connect(uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,double,double,double,quint64)));
}
connect(WPM, SIGNAL(updateStatusString(const QString &)), this, SLOT(updateStatusLabel(const QString &)));
connect(WPM, SIGNAL(waypointEditableListChanged(void)), this, SLOT(waypointEditableListChanged(void)));
connect(WPM, SIGNAL(waypointEditableChanged(int,Waypoint*)), this, SLOT(updateWaypointEditable(int,Waypoint*)));
connect(WPM, SIGNAL(waypointViewOnlyListChanged(void)), this, SLOT(waypointViewOnlyListChanged(void)));
connect(WPM, SIGNAL(waypointViewOnlyChanged(int,Waypoint*)), this, SLOT(updateWaypointViewOnly(int,Waypoint*)));
connect(WPM, SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointViewOnlyChanged(quint16)));
if (uas != NULL)
{
connect(uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updatePosition(UASInterface*,double,double,double,quint64)));
connect(uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,double,double,double,quint64)));
}
//connect(WPM,SIGNAL(loadWPFile()),this,SLOT(setIsLoadFileWP()));
//connect(WPM,SIGNAL(readGlobalWPFromUAS(bool)),this,SLOT(setIsReadGlobalWP(bool)));
}
@ -181,10 +185,20 @@ void WaypointList::saveWaypoints() @@ -181,10 +185,20 @@ void WaypointList::saveWaypoints()
void WaypointList::loadWaypoints()
{
QString fileName = QFileDialog::getOpenFileName(this, tr("Load File"), ".", tr("Waypoint File (*.txt)"));
WPM->loadWaypoints(fileName);
//create a popup notifying the user about the limitations of offline editing
if (showOfflineWarning == true)
{
QMessageBox msgBox;
msgBox.setIcon(QMessageBox::Warning);
msgBox.setText("Offline editor!");
msgBox.setInformativeText("You are using the offline mission editor. Please don't forget to save your mission plan before connecting the UAV, otherwise it will be lost.");
msgBox.setStandardButtons(QMessageBox::Ok);
msgBox.setDefaultButton(QMessageBox::Ok);
int ret = msgBox.exec();
showOfflineWarning = false;
}
QString fileName = QFileDialog::getOpenFileName(this, tr("Load File"), ".", tr("Waypoint File (*.txt)"));
WPM->loadWaypoints(fileName);
}
void WaypointList::transmit()
@ -237,6 +251,18 @@ void WaypointList::addEditable() @@ -237,6 +251,18 @@ void WaypointList::addEditable()
updateStatusLabel(tr("No UAV. Added default LOCAL (NED) waypoint"));
wp = new Waypoint(0, 0, 0, -0.50, 0, 0.20, 0, 0,true, true, MAV_FRAME_LOCAL_NED, MAV_CMD_NAV_WAYPOINT);
WPM->addWaypointEditable(wp);
//create a popup notifying the user about the limitations of offline editing
if (showOfflineWarning == true)
{
QMessageBox msgBox;
msgBox.setIcon(QMessageBox::Warning);
msgBox.setText("Offline editor!");
msgBox.setInformativeText("You are using the offline mission editor. Please don't forget to save your mission plan before connecting the UAV, otherwise it will be lost.");
msgBox.setStandardButtons(QMessageBox::Ok);
msgBox.setDefaultButton(QMessageBox::Ok);
int ret = msgBox.exec();
showOfflineWarning = false;
}
}
}
@ -267,7 +293,7 @@ void WaypointList::addCurrentPositionWaypoint() @@ -267,7 +293,7 @@ void WaypointList::addCurrentPositionWaypoint()
yawGlobal = last->getYaw();
}
// Create global frame waypoint per default
wp = new Waypoint(0, uas->getLatitude(), uas->getLongitude(), uas->getAltitude(), 0, acceptanceRadiusGlobal, holdTime, yawGlobal, true, true, MAV_FRAME_GLOBAL_RELATIVE_ALT, MAV_CMD_NAV_WAYPOINT);
wp = new Waypoint(0, uas->getLatitude(), uas->getLongitude(), uas->getAltitude(), 0, acceptanceRadiusGlobal, holdTime, yawGlobal, true, false, MAV_FRAME_GLOBAL_RELATIVE_ALT, MAV_CMD_NAV_WAYPOINT);
WPM->addWaypointEditable(wp);
updateStatusLabel(tr("Added GLOBAL, ALTITUDE OVER GROUND waypoint"));
}
@ -281,7 +307,7 @@ void WaypointList::addCurrentPositionWaypoint() @@ -281,7 +307,7 @@ void WaypointList::addCurrentPositionWaypoint()
holdTime = last->getHoldTime();
}
// Create local frame waypoint as second option
wp = new Waypoint(0, uas->getLocalX(), uas->getLocalY(), uas->getLocalZ(), uas->getYaw(), acceptanceRadiusLocal, holdTime, 0.0, true, true, MAV_FRAME_LOCAL_NED, MAV_CMD_NAV_WAYPOINT);
wp = new Waypoint(0, uas->getLocalX(), uas->getLocalY(), uas->getLocalZ(), uas->getYaw(), acceptanceRadiusLocal, holdTime, 0.0, true, false, MAV_FRAME_LOCAL_NED, MAV_CMD_NAV_WAYPOINT);
WPM->addWaypointEditable(wp);
updateStatusLabel(tr("Added LOCAL (NED) waypoint"));
}

2
src/ui/WaypointList.h

@ -43,6 +43,7 @@ This file is part of the QGROUNDCONTROL project @@ -43,6 +43,7 @@ This file is part of the QGROUNDCONTROL project
#include "WaypointEditableView.h"
#include "WaypointViewOnlyView.h"
#include "UnconnectedUASInfoWidget.h"
//#include "PopupMessage.h"
namespace Ui
@ -140,6 +141,7 @@ protected: @@ -140,6 +141,7 @@ protected:
QPointF centerMapCoordinate;
bool loadFileGlobalWP;
bool readGlobalWP;
bool showOfflineWarning;
private:
Ui::WaypointList *m_ui;

54
src/ui/WaypointList.ui

@ -74,22 +74,7 @@ @@ -74,22 +74,7 @@
<height>316</height>
</rect>
</property>
<layout class="QHBoxLayout" name="horizontalLayout">
<property name="spacing">
<number>0</number>
</property>
<property name="leftMargin">
<number>4</number>
</property>
<property name="topMargin">
<number>8</number>
</property>
<property name="rightMargin">
<number>4</number>
</property>
<property name="bottomMargin">
<number>4</number>
</property>
<layout class="QVBoxLayout" name="verticalLayout_2">
<item>
<widget class="QWidget" name="editableListWidget" native="true">
<property name="toolTip">
@ -287,9 +272,6 @@ @@ -287,9 +272,6 @@
<property name="bottomMargin">
<number>6</number>
</property>
<property name="spacing">
<number>6</number>
</property>
<item row="0" column="0" colspan="3">
<widget class="QScrollArea" name="readOnlyScrollArea">
<property name="widgetResizable">
@ -307,30 +289,31 @@ @@ -307,30 +289,31 @@
<property name="autoFillBackground">
<bool>true</bool>
</property>
<layout class="QHBoxLayout" name="horizontalLayout_3">
<property name="leftMargin">
<number>4</number>
</property>
<property name="topMargin">
<number>8</number>
</property>
<property name="rightMargin">
<number>4</number>
</property>
<property name="bottomMargin">
<number>4</number>
</property>
<layout class="QVBoxLayout" name="verticalLayout">
<item>
<widget class="QWidget" name="viewOnlyListWidget" native="true">
<property name="enabled">
<bool>true</bool>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
</widget>
</item>
</layout>
</widget>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="viewStatusLabel">
<property name="text">
<string/>
</property>
</widget>
</item>
<item row="1" column="1">
<spacer name="horizontalSpacer_2">
<property name="orientation">
@ -364,13 +347,6 @@ @@ -364,13 +347,6 @@
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="viewStatusLabel">
<property name="text">
<string/>
</property>
</widget>
</item>
</layout>
</widget>
</widget>

117
src/ui/WaypointViewOnlyView.cc

@ -125,6 +125,41 @@ void WaypointViewOnlyView::updateValues() @@ -125,6 +125,41 @@ void WaypointViewOnlyView::updateValues()
// update frame
m_ui->idLabel->setText(QString("%1").arg(wp->getId()));
switch (wp->getFrame())
{
case MAV_FRAME_GLOBAL:
{
m_ui->frameLabel->setText(QString("GAA"));
break;
}
case MAV_FRAME_LOCAL_NED:
{
m_ui->frameLabel->setText(QString("NED"));
break;
}
case MAV_FRAME_MISSION:
{
m_ui->frameLabel->setText(QString("MIS"));
break;
}
case MAV_FRAME_GLOBAL_RELATIVE_ALT:
{
m_ui->frameLabel->setText(QString("GRA"));
break;
}
case MAV_FRAME_LOCAL_ENU:
{
m_ui->frameLabel->setText(QString("ENU"));
break;
}
default:
{
m_ui->frameLabel->setText(QString(""));
break;
}
}
if (m_ui->current->isChecked() != wp->getCurrent())
{
@ -143,24 +178,74 @@ void WaypointViewOnlyView::updateValues() @@ -143,24 +178,74 @@ void WaypointViewOnlyView::updateValues()
{
case MAV_CMD_NAV_WAYPOINT:
{
if (wp->getParam1()>0)
switch (wp->getFrame())
{
m_ui->displayBar->setText(QString("Go to <b>(%1, %2, %3)</b> 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()));
case MAV_FRAME_GLOBAL_RELATIVE_ALT:
case MAV_FRAME_GLOBAL:
{
if (wp->getParam1()>0)
{
m_ui->displayBar->setText(QString("Go to <b>(</b>lat <b>%1<sup>o</sup></b>, lon <b>%2<sup>o</sup></b>, alt <b>%3)</b> and wait there for %4 sec; yaw: %5; rad: %6").arg(wp->getX(),0, 'f', 7).arg(wp->getY(),0, 'f', 7).arg(wp->getZ(),0, 'f', 2).arg(wp->getParam1()).arg(wp->getParam4()).arg(wp->getParam2()));
}
else
{
m_ui->displayBar->setText(QString("Go to <b>(</b>lat <b>%1<sup>o</sup></b>,lon <b>%2<sup>o</sup></b>,alt <b>%3)</b>; yaw: %4; rad: %5").arg(wp->getX(),0, 'f', 7).arg(wp->getY(),0, 'f', 7).arg(wp->getZ(),0, 'f', 2).arg(wp->getParam4()).arg(wp->getParam2()));
}
break;
}
else
case MAV_FRAME_LOCAL_NED:
default:
{
m_ui->displayBar->setText(QString("Go to <b>(%1, %2, %3)</b>; yaw: %4; rad: %5").arg(wp->getX()).arg(wp->getY()).arg(wp->getZ()).arg(wp->getParam4()).arg(wp->getParam2()));
if (wp->getParam1()>0)
{
m_ui->displayBar->setText(QString("Go to <b>(%1, %2, %3)</b> and wait there for %4 sec; yaw: %5; rad: %6").arg(wp->getX(),0, 'f', 2).arg(wp->getY(),0, 'f', 2).arg(wp->getZ(),0, 'f',2).arg(wp->getParam1()).arg(wp->getParam4()).arg(wp->getParam2()));
}
else
{
m_ui->displayBar->setText(QString("Go to <b>(%1, %2, %3)</b>; yaw: %4; rad: %5").arg(wp->getX(),0, 'f', 2).arg(wp->getY(),0, 'f', 2).arg(wp->getZ(),0, 'f', 2).arg(wp->getParam4()).arg(wp->getParam2()));
}
break;
}
} //end Frame switch
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()));
{
switch (wp->getFrame())
{
case MAV_FRAME_GLOBAL_RELATIVE_ALT:
case MAV_FRAME_GLOBAL:
{
m_ui->displayBar->setText(QString("LAND. Go to <b>(</b>lat <b>%1<sup>o</sup></b>, lon <b>%2<sup>o</sup></b>, alt <b>%3)</b> and descent; yaw: %4").arg(wp->getX(),0, 'f', 7).arg(wp->getY(),0, 'f', 7).arg(wp->getZ(),0, 'f', 2).arg(wp->getParam4()));
break;
}
case MAV_FRAME_LOCAL_NED:
default:
{
m_ui->displayBar->setText(QString("LAND. Go to <b>(%1, %2, %3)</b> and descent; yaw: %4").arg(wp->getX(),0, 'f', 2).arg(wp->getY(),0, 'f', 2).arg(wp->getZ(),0, 'f', 2).arg(wp->getParam4()));
break;
}
} //end Frame switch
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()));
{
switch (wp->getFrame())
{
case MAV_FRAME_GLOBAL_RELATIVE_ALT:
case MAV_FRAME_GLOBAL:
{
m_ui->displayBar->setText(QString("TAKEOFF. Go to <b>(</b>lat <b>%1<sup>o</sup></b>, lon <b>%2<sup>o</sup></b>, alt <b>%3)</b>; yaw: %4").arg(wp->getX(),0, 'f', 7).arg(wp->getY(),0, 'f', 7).arg(wp->getZ(),0, 'f', 2).arg(wp->getParam4()));
break;
}
case MAV_FRAME_LOCAL_NED:
default:
{
m_ui->displayBar->setText(QString("TAKEOFF. Go to <b>(%1, %2, %3)</b>; yaw: %4").arg(wp->getX(),0, 'f', 2).arg(wp->getY(),0, 'f', 2).arg(wp->getZ(),0, 'f', 2).arg(wp->getParam4()));
break;
}
} //end Frame switch
break;
break;
}
case MAV_CMD_DO_JUMP:
@ -192,7 +277,21 @@ void WaypointViewOnlyView::updateValues() @@ -192,7 +277,21 @@ void WaypointViewOnlyView::updateValues()
}
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()));
switch (wp->getFrame())
{
case MAV_FRAME_GLOBAL_RELATIVE_ALT:
case MAV_FRAME_GLOBAL:
{
m_ui->displayBar->setText(QString("Sweep. Corners: <b>(</b>lat <b>%1<sup>o</sup></b>, lon <b>%2<sup>o</sup>)</b> and <b>(</b>lat <b>%3<sup>o</sup></b>, lon <b>%4<sup>o</sup>)</b>; alt: <b>%5</b>; scan radius: %6").arg(wp->getParam3(),0, 'f', 7).arg(wp->getParam4(),0, 'f', 7).arg(wp->getParam5(),0, 'f', 7).arg(wp->getParam6(),0, 'f', 7).arg(wp->getParam7(),0, 'f', 2).arg(wp->getParam1()));
break;
}
case MAV_FRAME_LOCAL_NED:
default:
{
m_ui->displayBar->setText(QString("Sweep. Corners: <b>(%1, %2)</b> and <b>(%3, %4)</b>; z: <b>%5</b>; scan radius: %6").arg(wp->getParam3()).arg(wp->getParam4()).arg(wp->getParam5()).arg(wp->getParam6()).arg(wp->getParam7()).arg(wp->getParam1()));
break;
}
} //end Frame switch
break;
}
default:

161
src/ui/WaypointViewOnlyView.ui

@ -6,43 +6,63 @@ @@ -6,43 +6,63 @@
<rect>
<x>0</x>
<y>0</y>
<width>381</width>
<height>40</height>
<width>704</width>
<height>31</height>
</rect>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<sizepolicy hsizetype="Expanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>200</width>
<height>30</height>
</size>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<property name="styleSheet">
<string notr="true"/>
<string notr="true">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;
}</string>
</property>
<layout class="QHBoxLayout" name="horizontalLayout_2">
<property name="spacing">
<number>0</number>
</property>
<property name="leftMargin">
<number>2</number>
</property>
<property name="topMargin">
<layout class="QGridLayout" name="gridLayout">
<property name="margin">
<number>0</number>
</property>
<property name="rightMargin">
<number>2</number>
</property>
<property name="bottomMargin">
<property name="spacing">
<number>0</number>
</property>
<item>
<item row="0" column="0">
<widget class="QGroupBox" name="groupBox">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="styleSheet">
<string notr="true"/>
</property>
<property name="title">
<string/>
</property>
@ -55,24 +75,27 @@ @@ -55,24 +75,27 @@
<property name="checkable">
<bool>false</bool>
</property>
<layout class="QHBoxLayout" name="horizontalLayout" stretch="1,1,100,1">
<layout class="QHBoxLayout" name="horizontalLayout" stretch="0,2,100,10,5,1">
<property name="spacing">
<number>6</number>
</property>
<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 name="margin">
<number>4</number>
</property>
<item>
<widget class="QCheckBox" name="current">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>25</width>
<height>0</height>
</size>
</property>
<property name="toolTip">
<string>Currently executed waypoint</string>
</property>
@ -86,40 +109,94 @@ @@ -86,40 +109,94 @@
</item>
<item>
<widget class="QLabel" name="idLabel">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>25</width>
<height>0</height>
</size>
</property>
<property name="lineWidth">
<number>1</number>
</property>
<property name="text">
<string>ID</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QTextBrowser" name="displayBar">
<widget class="QLabel" name="displayBar">
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Expanding">
<sizepolicy hsizetype="Expanding" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<property name="toolTip">
<string>Mission element description</string>
</property>
<property name="statusTip">
<string>Mission element description</string>
</property>
<property name="whatsThis">
<string/>
</property>
<property name="text">
<string>Mission element description</string>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Expanding</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>16777215</width>
<height>31</height>
<width>79</width>
<height>17</height>
</size>
</property>
<property name="font">
<font>
<pointsize>8</pointsize>
</font>
</spacer>
</item>
<item>
<widget class="QLabel" name="frameLabel">
<property name="toolTip">
<string comment="Coordinate Frame" extracomment="Coordinate Frame">Coordinate Frame</string>
</property>
<property name="statusTip">
<string>Coordinate Frame</string>
</property>
<property name="whatsThis">
<string/>
</property>
<property name="frameShape">
<enum>QFrame::NoFrame</enum>
<property name="text">
<string>Frame</string>
</property>
<property name="frameShadow">
<enum>QFrame::Sunken</enum>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QCheckBox" name="autoContinue">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="toolTip">
<string>Automatically continue after this waypoint</string>
</property>

Loading…
Cancel
Save