diff --git a/src/uas/UASWaypointManager.cc b/src/uas/UASWaypointManager.cc
index 4a274b4..5e87809 100644
--- a/src/uas/UASWaypointManager.cc
+++ b/src/uas/UASWaypointManager.cc
@@ -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)
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)
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)
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);
diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc
index dc29bfe..35705ae 100644
--- a/src/ui/MainWindow.cc
+++ b/src/ui/MainWindow.cc
@@ -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)
}
}
- }
+ //}
if (!ui.menuConnected_Systems->isEnabled()) ui.menuConnected_Systems->setEnabled(true);
diff --git a/src/ui/WaypointEditableView.cc b/src/ui/WaypointEditableView.cc
index 378f69b..73fdfb0 100644
--- a/src/ui/WaypointEditableView.cc
+++ b/src/ui/WaypointEditableView.cc
@@ -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)
*/
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)
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)
}
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()
{
// Action ID known, update
m_ui->comboBox_action->setCurrentIndex(action_index);
- updateActionView(action);
+ updateActionView(action);
}
}
}
diff --git a/src/ui/WaypointEditableView.ui b/src/ui/WaypointEditableView.ui
index 13e1093..5ba5bb5 100644
--- a/src/ui/WaypointEditableView.ui
+++ b/src/ui/WaypointEditableView.ui
@@ -105,6 +105,18 @@ QPushButton:pressed {
-
+
+
+ 0
+ 0
+
+
+
+
+ 25
+ 0
+
+
Qt::TabFocus
@@ -127,9 +139,15 @@ QPushButton:pressed {
-
+
+
+ 0
+ 0
+
+
- 15
+ 25
0
@@ -471,6 +489,12 @@ QPushButton:pressed {
-
+
+
+ 0
+ 0
+
+
Uncertainty radius in meters
where to accept this waypoint as reached
@@ -488,6 +512,12 @@ where to accept this waypoint as reached
-
+
+
+ 0
+ 0
+
+
Rotaty wing and ground vehicles only:
Time to stay at this position before advancing
@@ -505,6 +535,12 @@ Time to stay at this position before advancing
-
+
+
+ 0
+ 0
+
+
Number of turns to loiter
@@ -581,6 +617,12 @@ Time to stay at this position before advancing
-
+
+
+ 0
+ 0
+
+
Automatically continue after this waypoint
diff --git a/src/ui/WaypointList.cc b/src/ui/WaypointList.cc
index a4f1cf1..eb59d36 100644
--- a/src/ui/WaypointList.cc
+++ b/src/ui/WaypointList.cc
@@ -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) :
if (uas)
{
WPM = uas->getWaypointManager();
- setUAS(uas);
+ //setUAS(uas);
}
else
{
@@ -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,
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()
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()
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()
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()
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"));
}
diff --git a/src/ui/WaypointList.h b/src/ui/WaypointList.h
index d773fa7..01f6a71 100644
--- a/src/ui/WaypointList.h
+++ b/src/ui/WaypointList.h
@@ -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:
QPointF centerMapCoordinate;
bool loadFileGlobalWP;
bool readGlobalWP;
+ bool showOfflineWarning;
private:
Ui::WaypointList *m_ui;
diff --git a/src/ui/WaypointList.ui b/src/ui/WaypointList.ui
index a3cacae..2773693 100644
--- a/src/ui/WaypointList.ui
+++ b/src/ui/WaypointList.ui
@@ -74,22 +74,7 @@
316
-
-
- 0
-
-
- 4
-
-
- 8
-
-
- 4
-
-
- 4
-
+
-
@@ -287,9 +272,6 @@
6
-
- 6
-
-
@@ -307,30 +289,31 @@
true
-
-
- 4
-
-
- 8
-
-
- 4
-
-
- 4
-
+
-
true
+
+
+ 16777215
+ 16777215
+
+
+ -
+
+
+
+
+
+
-
@@ -364,13 +347,6 @@
- -
-
-
-
-
-
-
diff --git a/src/ui/WaypointViewOnlyView.cc b/src/ui/WaypointViewOnlyView.cc
index 2980972..8e51ec2 100644
--- a/src/ui/WaypointViewOnlyView.cc
+++ b/src/ui/WaypointViewOnlyView.cc
@@ -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()
{
case MAV_CMD_NAV_WAYPOINT:
{
- if (wp->getParam1()>0)
+ switch (wp->getFrame())
{
- 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()));
+ case MAV_FRAME_GLOBAL_RELATIVE_ALT:
+ case MAV_FRAME_GLOBAL:
+ {
+ if (wp->getParam1()>0)
+ {
+ m_ui->displayBar->setText(QString("Go to (lat %1o, lon %2o, alt %3) 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 (lat %1o,lon %2o,alt %3); 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 (%1, %2, %3); 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 (%1, %2, %3) 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 (%1, %2, %3); 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 (lat %1o, lon %2o, alt %3) 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 (%1, %2, %3) 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 (lat %1o, lon %2o, alt %3); 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 (%1, %2, %3); 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()
}
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: (lat %1o, lon %2o) and (lat %3o, lon %4o); alt: %5; 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: (%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;
+ }
+ } //end Frame switch
break;
}
default:
diff --git a/src/ui/WaypointViewOnlyView.ui b/src/ui/WaypointViewOnlyView.ui
index eb35191..76ef552 100644
--- a/src/ui/WaypointViewOnlyView.ui
+++ b/src/ui/WaypointViewOnlyView.ui
@@ -6,43 +6,63 @@
0
0
- 381
- 40
+ 704
+ 31
-
+
0
0
+
+
+ 200
+ 30
+
+
Form
-
+ 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;
+ }
-
-
- 0
-
-
- 2
-
-
+
+
0
-
- 2
-
-
+
0
- -
+
-
true
+
+
+ 0
+ 0
+
+
+
+
+
@@ -55,24 +75,27 @@
false
-
+
- 6
-
-
2
-
- 0
-
-
- 2
-
-
- 0
+
+ 4
-
+
+
+ 0
+ 0
+
+
+
+
+ 25
+ 0
+
+
Currently executed waypoint
@@ -86,40 +109,94 @@
-
+
+
+ 0
+ 0
+
+
+
+
+ 25
+ 0
+
+
+
+ 1
+
ID
+
+ Qt::AlignCenter
+
-
-
+
-
+
0
0
-
+
+ Mission element description
+
+
+ Mission element description
+
+
+
+
+
+ Mission element description
+
+
+
+ -
+
+
+ Qt::Horizontal
+
+
+ QSizePolicy::Expanding
+
+
- 16777215
- 31
+ 79
+ 17
-
-
- 8
-
+
+
+ -
+
+
+ Coordinate Frame
+
+
+ Coordinate Frame
+
+
+
-
- QFrame::NoFrame
+
+ Frame
-
- QFrame::Sunken
+
+ Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter
-
+
+
+ 0
+ 0
+
+
Automatically continue after this waypoint