Browse Source

Merge branch 'master' of https://github.com/mavlink/qgroundcontrol into restyling

Conflicts:
	src/ui/MainWindow.cc
QGC4.4
Bryant 12 years ago
parent
commit
19506a7acd
  1. 3
      src/comm/QGCHilLink.h
  2. 2
      src/comm/QGCXPlaneLink.cc
  3. 2
      src/configuration.h
  4. 109
      src/uas/UASWaypointManager.cc
  5. 31
      src/uas/UASWaypointManager.h
  6. 5
      src/ui/HSIDisplay.cc
  7. 358
      src/ui/MainWindow.cc
  8. 4
      src/ui/MainWindow.h
  9. 9
      src/ui/QGCHilConfiguration.cc
  10. 1
      src/ui/QGCHilConfiguration.h
  11. 7
      src/ui/QGCHilXPlaneConfiguration.cc
  12. 2
      src/ui/QGCHilXPlaneConfiguration.h
  13. 6
      src/ui/QGCHilXPlaneConfiguration.ui
  14. 17
      src/ui/QGCMAVLinkLogPlayer.cc
  15. 17
      src/ui/QGCToolBar.cc
  16. 4
      src/ui/QGCToolBar.h
  17. 3
      src/ui/QGCVehicleConfig.cc
  18. 4
      src/ui/QGCWaypointListMulti.cc
  19. 10
      src/ui/SerialConfigurationWindow.cc
  20. 395
      src/ui/WaypointList.cc
  21. 8
      src/ui/WaypointList.h
  22. 34
      src/ui/designer/QGCParamSlider.cc
  23. 162
      src/ui/map/QGCMapWidget.cc
  24. 8
      src/ui/map3D/Pixhawk3DWidget.cc
  25. 4
      src/ui/map3D/QGCGoogleEarthView.cc
  26. 13
      src/ui/map3D/WaypointGroupNode.cc

3
src/comm/QGCHilLink.h

@ -114,6 +114,9 @@ signals: @@ -114,6 +114,9 @@ signals:
/** @brief Selected sim version changed */
void versionChanged(const QString& version);
/** @brief Selected sim version changed */
void versionChanged(const int version);
/** @brief Sensor leve HIL state changed */
void sensorHilChanged(bool enabled);
};

2
src/comm/QGCXPlaneLink.cc

@ -54,7 +54,7 @@ QGCXPlaneLink::QGCXPlaneLink(UASInterface* mav, QString remoteHost, QHostAddress @@ -54,7 +54,7 @@ QGCXPlaneLink::QGCXPlaneLink(UASInterface* mav, QString remoteHost, QHostAddress
simUpdateLast(QGC::groundTimeMilliseconds()),
simUpdateLastText(QGC::groundTimeMilliseconds()),
simUpdateHz(0),
_sensorHilEnabled(true)
_sensorHilEnabled(false)
{
this->localHost = localHost;
this->localPort = localPort/*+mav->getUASID()*/;

2
src/configuration.h

@ -11,7 +11,7 @@ @@ -11,7 +11,7 @@
#define WITH_TEXT_TO_SPEECH 1
#define QGC_APPLICATION_NAME "QGroundControl"
#define QGC_APPLICATION_VERSION "v. 1.0.9 (beta)"
#define QGC_APPLICATION_VERSION "v. 1.0.9 (beta RC1)"
namespace QGC

109
src/uas/UASWaypointManager.cc

@ -32,6 +32,8 @@ This file is part of the QGROUNDCONTROL project @@ -32,6 +32,8 @@ This file is part of the QGROUNDCONTROL project
#include "UASWaypointManager.h"
#include "UAS.h"
#include "mavlink_types.h"
#include "UASManager.h"
#include "MainWindow.h"
#define PROTOCOL_TIMEOUT_MS 2000 ///< maximum time to wait for pending messages until timeout
#define PROTOCOL_DELAY_MS 20 ///< minimum delay between sent messages
@ -136,9 +138,9 @@ void UASWaypointManager::handleWaypointCount(quint8 systemId, quint8 compId, qui @@ -136,9 +138,9 @@ void UASWaypointManager::handleWaypointCount(quint8 systemId, quint8 compId, qui
//Clear the old edit-list before receiving the new one
if (read_to_edit == true){
while(waypointsEditable.size()>0) {
while(waypointsEditable.count()>0) {
Waypoint *t = waypointsEditable[0];
waypointsEditable.remove(0);
waypointsEditable.removeAt(0);
delete t;
}
emit waypointEditableListChanged();
@ -331,10 +333,10 @@ int UASWaypointManager::setCurrentWaypoint(quint16 seq) @@ -331,10 +333,10 @@ int UASWaypointManager::setCurrentWaypoint(quint16 seq)
int UASWaypointManager::setCurrentEditable(quint16 seq)
{
if (seq < waypointsEditable.size()) {
if (seq < waypointsEditable.count()) {
if(current_state == WP_IDLE) {
//update local main storage
for(int i = 0; i < waypointsEditable.size(); i++) {
for(int i = 0; i < waypointsEditable.count(); i++) {
if (waypointsEditable[i]->getId() == seq) {
waypointsEditable[i]->setCurrent(true);
} else {
@ -370,13 +372,17 @@ void UASWaypointManager::addWaypointEditable(Waypoint *wp, bool enforceFirstActi @@ -370,13 +372,17 @@ void UASWaypointManager::addWaypointEditable(Waypoint *wp, bool enforceFirstActi
{
if (wp)
{
wp->setId(waypointsEditable.size());
if (enforceFirstActive && waypointsEditable.size() == 0)
// Check if this is the first waypoint in an offline list
if (waypointsEditable.count() == 0 && uas == NULL)
MainWindow::instance()->showCriticalMessage(tr("OFFLINE Waypoint Editing Mode"), tr("You are in offline editing mode. Make sure to safe your mission to a file before connecting to a system - you will need to load the file into the system, the offline list will be cleared on connect."));
wp->setId(waypointsEditable.count());
if (enforceFirstActive && waypointsEditable.count() == 0)
{
wp->setCurrent(true);
currentWaypointEditable = wp;
}
waypointsEditable.insert(waypointsEditable.size(), wp);
waypointsEditable.insert(waypointsEditable.count(), wp);
connect(wp, SIGNAL(changed(Waypoint*)), this, SLOT(notifyOfChangeEditable(Waypoint*)));
emit waypointEditableListChanged();
@ -389,14 +395,21 @@ void UASWaypointManager::addWaypointEditable(Waypoint *wp, bool enforceFirstActi @@ -389,14 +395,21 @@ void UASWaypointManager::addWaypointEditable(Waypoint *wp, bool enforceFirstActi
*/
Waypoint* UASWaypointManager::createWaypoint(bool enforceFirstActive)
{
// Check if this is the first waypoint in an offline list
if (waypointsEditable.count() == 0 && uas == NULL)
MainWindow::instance()->showCriticalMessage(tr("OFFLINE Waypoint Editing Mode"), tr("You are in offline editing mode. Make sure to safe your mission to a file before connecting to a system - you will need to load the file into the system, the offline list will be cleared on connect."));
Waypoint* wp = new Waypoint();
wp->setId(waypointsEditable.size());
if (enforceFirstActive && waypointsEditable.size() == 0)
wp->setId(waypointsEditable.count());
wp->setFrame((MAV_FRAME)getFrameRecommendation());
wp->setAltitude(getAltitudeRecommendation());
wp->setAcceptanceRadius(getAcceptanceRadiusRecommendation());
if (enforceFirstActive && waypointsEditable.count() == 0)
{
wp->setCurrent(true);
currentWaypointEditable = wp;
}
waypointsEditable.insert(waypointsEditable.size(), wp);
waypointsEditable.append(wp);
connect(wp, SIGNAL(changed(Waypoint*)), this, SLOT(notifyOfChangeEditable(Waypoint*)));
emit waypointEditableListChanged();
@ -406,27 +419,27 @@ Waypoint* UASWaypointManager::createWaypoint(bool enforceFirstActive) @@ -406,27 +419,27 @@ Waypoint* UASWaypointManager::createWaypoint(bool enforceFirstActive)
int UASWaypointManager::removeWaypoint(quint16 seq)
{
if (seq < waypointsEditable.size())
if (seq < waypointsEditable.count())
{
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
if (seq+1 < waypointsEditable.count()) // 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
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);
waypointsEditable.removeAt(seq);
delete t;
t = NULL;
for(int i = seq; i < waypointsEditable.size(); i++)
for(int i = seq; i < waypointsEditable.count(); i++)
{
waypointsEditable[i]->setId(i);
}
@ -440,7 +453,7 @@ int UASWaypointManager::removeWaypoint(quint16 seq) @@ -440,7 +453,7 @@ int UASWaypointManager::removeWaypoint(quint16 seq)
void UASWaypointManager::moveWaypoint(quint16 cur_seq, quint16 new_seq)
{
if (cur_seq != new_seq && cur_seq < waypointsEditable.size() && new_seq < waypointsEditable.size())
if (cur_seq != new_seq && cur_seq < waypointsEditable.count() && new_seq < waypointsEditable.count())
{
Waypoint *t = waypointsEditable[cur_seq];
if (cur_seq < new_seq) {
@ -477,7 +490,7 @@ void UASWaypointManager::saveWaypoints(const QString &saveFile) @@ -477,7 +490,7 @@ void UASWaypointManager::saveWaypoints(const QString &saveFile)
//write the waypoint list version to the first line for compatibility check
out << "QGC WPL 120\r\n";
for (int i = 0; i < waypointsEditable.size(); i++)
for (int i = 0; i < waypointsEditable.count(); i++)
{
waypointsEditable[i]->setId(i);
waypointsEditable[i]->save(out);
@ -491,9 +504,9 @@ void UASWaypointManager::loadWaypoints(const QString &loadFile) @@ -491,9 +504,9 @@ void UASWaypointManager::loadWaypoints(const QString &loadFile)
if (!file.open(QIODevice::ReadOnly | QIODevice::Text))
return;
while(waypointsEditable.size()>0) {
while(waypointsEditable.count()>0) {
Waypoint *t = waypointsEditable[0];
waypointsEditable.remove(0);
waypointsEditable.removeAt(0);
delete t;
}
@ -512,8 +525,8 @@ void UASWaypointManager::loadWaypoints(const QString &loadFile) @@ -512,8 +525,8 @@ void UASWaypointManager::loadWaypoints(const QString &loadFile)
Waypoint *t = new Waypoint();
if(t->load(in))
{
t->setId(waypointsEditable.size());
waypointsEditable.insert(waypointsEditable.size(), t);
t->setId(waypointsEditable.count());
waypointsEditable.insert(waypointsEditable.count(), t);
}
else
{
@ -532,7 +545,7 @@ void UASWaypointManager::loadWaypoints(const QString &loadFile) @@ -532,7 +545,7 @@ void UASWaypointManager::loadWaypoints(const QString &loadFile)
void UASWaypointManager::clearWaypointList()
{
if(current_state == WP_IDLE)
if (current_state == WP_IDLE)
{
protocol_timer.start(PROTOCOL_TIMEOUT_MS);
current_retries = PROTOCOL_MAX_RETRIES;
@ -546,12 +559,12 @@ void UASWaypointManager::clearWaypointList() @@ -546,12 +559,12 @@ void UASWaypointManager::clearWaypointList()
}
}
const QVector<Waypoint *> UASWaypointManager::getGlobalFrameWaypointList()
const QList<Waypoint *> UASWaypointManager::getGlobalFrameWaypointList()
{
// TODO Keep this global frame list up to date
// with complete waypoint list
// instead of filtering on each request
QVector<Waypoint*> wps;
QList<Waypoint*> wps;
foreach (Waypoint* wp, waypointsEditable)
{
if (wp->getFrame() == MAV_FRAME_GLOBAL || wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT)
@ -562,12 +575,12 @@ const QVector<Waypoint *> UASWaypointManager::getGlobalFrameWaypointList() @@ -562,12 +575,12 @@ const QVector<Waypoint *> UASWaypointManager::getGlobalFrameWaypointList()
return wps;
}
const QVector<Waypoint *> UASWaypointManager::getGlobalFrameAndNavTypeWaypointList()
const QList<Waypoint *> UASWaypointManager::getGlobalFrameAndNavTypeWaypointList()
{
// TODO Keep this global frame list up to date
// with complete waypoint list
// instead of filtering on each request
QVector<Waypoint*> wps;
QList<Waypoint*> wps;
foreach (Waypoint* wp, waypointsEditable)
{
if ((wp->getFrame() == MAV_FRAME_GLOBAL || wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT) && wp->isNavigationType())
@ -578,12 +591,12 @@ const QVector<Waypoint *> UASWaypointManager::getGlobalFrameAndNavTypeWaypointLi @@ -578,12 +591,12 @@ const QVector<Waypoint *> UASWaypointManager::getGlobalFrameAndNavTypeWaypointLi
return wps;
}
const QVector<Waypoint *> UASWaypointManager::getNavTypeWaypointList()
const QList<Waypoint *> UASWaypointManager::getNavTypeWaypointList()
{
// TODO Keep this global frame list up to date
// with complete waypoint list
// instead of filtering on each request
QVector<Waypoint*> wps;
QList<Waypoint*> wps;
foreach (Waypoint* wp, waypointsEditable)
{
if (wp->isNavigationType())
@ -772,14 +785,14 @@ void UASWaypointManager::readWaypoints(bool readToEdit) @@ -772,14 +785,14 @@ void UASWaypointManager::readWaypoints(bool readToEdit)
//Clear the old view-list before receiving the new one
while(waypointsViewOnly.size()>0) {
Waypoint *t = waypointsViewOnly[0];
waypointsViewOnly.remove(0);
waypointsViewOnly.removeAt(0);
delete t;
}
emit waypointViewOnlyListChanged();
/* THIS PART WAS MOVED TO handleWaypointCount. THE EDIT-LIST SHOULD NOT BE CLEARED UNLESS THERE IS A RESPONSE FROM UAV.
//Clear the old edit-list before receiving the new one
if (read_to_edit == true){
while(waypointsEditable.size()>0) {
while(waypointsEditable.count()>0) {
Waypoint *t = waypointsEditable[0];
waypointsEditable.remove(0);
delete t;
@ -1023,3 +1036,39 @@ void UASWaypointManager::sendWaypointAck(quint8 type) @@ -1023,3 +1036,39 @@ void UASWaypointManager::sendWaypointAck(quint8 type)
uas->sendMessage(message);
QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
}
UAS* UASWaypointManager::getUAS() {
return this->uas; ///< Returns the owning UAS
}
float UASWaypointManager::getAltitudeRecommendation()
{
if (waypointsEditable.count() > 0) {
return waypointsEditable.last()->getAltitude();
} else {
return UASManager::instance()->getHomeAltitude() + getHomeAltitudeOffsetDefault();
}
}
int UASWaypointManager::getFrameRecommendation()
{
if (waypointsEditable.count() > 0) {
return static_cast<int>(waypointsEditable.last()->getFrame());
} else {
return MAV_FRAME_GLOBAL;
}
}
float UASWaypointManager::getAcceptanceRadiusRecommendation()
{
if (waypointsEditable.count() > 0) {
return waypointsEditable.last()->getAcceptanceRadius();
} else {
return 10.0f;
}
}
float UASWaypointManager::getHomeAltitudeOffsetDefault()
{
return defaultAltitudeHomeOffset;
}

31
src/uas/UASWaypointManager.h

@ -33,7 +33,7 @@ This file is part of the QGROUNDCONTROL project @@ -33,7 +33,7 @@ This file is part of the QGROUNDCONTROL project
#define UASWAYPOINTMANAGER_H
#include <QObject>
#include <QVector>
#include <QList>
#include <QTimer>
#include "Waypoint.h"
#include "QGCMAVLink.h"
@ -44,7 +44,7 @@ class UASInterface; @@ -44,7 +44,7 @@ class UASInterface;
* @brief Implementation of the MAVLINK waypoint protocol
*
* This class handles the communication with a waypoint manager on the MAV.
* All waypoints are stored in the QVector waypoints, modifications can be done with the WaypointList widget.
* All waypoints are stored in the QList waypoints, modifications can be done with the WaypointList widget.
* Notice that currently the access to the internal waypoint storage is not guarded nor thread-safe. This works as long as no other widget alters the data.
*
* See http://qgroundcontrol.org/waypoint_protocol for more information about the protocol and the states.
@ -91,15 +91,15 @@ public: @@ -91,15 +91,15 @@ public:
/** @name Waypoint list operations */
/*@{*/
const QVector<Waypoint *> &getWaypointEditableList(void) {
const QList<Waypoint *> &getWaypointEditableList(void) {
return waypointsEditable; ///< Returns a const reference to the waypoint list.
}
const QVector<Waypoint *> &getWaypointViewOnlyList(void) {
const QList<Waypoint *> &getWaypointViewOnlyList(void) {
return waypointsViewOnly; ///< Returns a const reference to the waypoint list.
}
const QVector<Waypoint *> getGlobalFrameWaypointList(); ///< Returns a global waypoint list
const QVector<Waypoint *> getGlobalFrameAndNavTypeWaypointList(); ///< Returns a global waypoint list containing only waypoints suitable for navigation. Actions and other mission items are filtered out.
const QVector<Waypoint *> getNavTypeWaypointList(); ///< Returns a waypoint list containing only waypoints suitable for navigation. Actions and other mission items are filtered out.
const QList<Waypoint *> getGlobalFrameWaypointList(); ///< Returns a global waypoint list
const QList<Waypoint *> getGlobalFrameAndNavTypeWaypointList(); ///< Returns a global waypoint list containing only waypoints suitable for navigation. Actions and other mission items are filtered out.
const QList<Waypoint *> getNavTypeWaypointList(); ///< Returns a waypoint list containing only waypoints suitable for navigation. Actions and other mission items are filtered out.
int getIndexOf(Waypoint* wp); ///< Get the index of a waypoint in the list
int getGlobalFrameIndexOf(Waypoint* wp); ///< Get the index of a waypoint in the list, counting only global waypoints
int getGlobalFrameAndNavTypeIndexOf(Waypoint* wp); ///< Get the index of a waypoint in the list, counting only global AND navigation mode waypoints
@ -112,9 +112,11 @@ public: @@ -112,9 +112,11 @@ public:
int getLocalFrameCount(); ///< Get the count of local waypoints in the list
/*@}*/
UAS* getUAS() {
return this->uas; ///< Returns the owning UAS
}
UAS* getUAS();
float getAltitudeRecommendation();
int getFrameRecommendation();
float getAcceptanceRadiusRecommendation();
float getHomeAltitudeOffsetDefault();
private:
/** @name Message send functions */
@ -169,13 +171,16 @@ private: @@ -169,13 +171,16 @@ private:
quint8 current_partner_compid; ///< The current protocol communication target component
bool read_to_edit; ///< If true, after readWaypoints() incoming waypoints will be copied both to "edit"-tab and "view"-tab. Otherwise, only to "view"-tab.
QVector<Waypoint *> waypointsViewOnly; ///< local copy of current waypoint list on MAV
QVector<Waypoint *> waypointsEditable; ///< local editable waypoint list
QList<Waypoint *> waypointsViewOnly; ///< local copy of current waypoint list on MAV
QList<Waypoint *> waypointsEditable; ///< local editable waypoint list
Waypoint* currentWaypointEditable; ///< The currently used waypoint
QVector<mavlink_mission_item_t *> waypoint_buffer; ///< buffer for waypoints during communication
QList<mavlink_mission_item_t *> waypoint_buffer; ///< buffer for waypoints during communication
QTimer protocol_timer; ///< Timer to catch timeouts
bool standalone; ///< If standalone is set, do not write to UAS
quint16 uasid;
// XXX export to settings
static const float defaultAltitudeHomeOffset = 30.0f; ///< Altitude offset in meters from home for new waypoints
};
#endif // UASWAYPOINTMANAGER_H

5
src/ui/HSIDisplay.cc

@ -854,6 +854,9 @@ void HSIDisplay::setMetricWidth(double width) @@ -854,6 +854,9 @@ void HSIDisplay::setMetricWidth(double width)
*/
void HSIDisplay::setActiveUAS(UASInterface* uas)
{
if (!uas)
return;
if (this->uas != NULL) {
disconnect(this->uas, SIGNAL(gpsSatelliteStatusChanged(int,int,float,float,float,bool)), this, SLOT(updateSatellite(int,int,float,float,float,bool)));
disconnect(this->uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateLocalPosition(UASInterface*,double,double,double,quint64)));
@ -1231,7 +1234,7 @@ void HSIDisplay::drawWaypoints(QPainter& painter) @@ -1231,7 +1234,7 @@ void HSIDisplay::drawWaypoints(QPainter& painter)
if (uas)
{
// Grab all waypoints.
const QVector<Waypoint*>& list = uas->getWaypointManager()->getWaypointEditableList();
const QList<Waypoint*>& list = uas->getWaypointManager()->getWaypointEditableList();
const int numWaypoints = list.size();
// Do not work on empty lists

358
src/ui/MainWindow.cc

@ -158,7 +158,7 @@ MainWindow::MainWindow(QWidget *parent): @@ -158,7 +158,7 @@ MainWindow::MainWindow(QWidget *parent):
hide();
// We only need this menu if we have more than one system
// ui.menuConnected_Systems->setEnabled(false);
// ui.menuConnected_Systems->setEnabled(false);
// Set dock options
setDockOptions(AnimatedDocks | AllowTabbedDocks | AllowNestedDocks);
@ -295,11 +295,11 @@ MainWindow::~MainWindow() @@ -295,11 +295,11 @@ MainWindow::~MainWindow()
delete mavlink;
mavlink = NULL;
}
// if (simulationLink)
// {
// simulationLink->deleteLater();
// simulationLink = NULL;
// }
// if (simulationLink)
// {
// simulationLink->deleteLater();
// simulationLink = NULL;
// }
if (joystick)
{
joystick->shutdown();
@ -356,7 +356,7 @@ QString MainWindow::getWindowStateKey() @@ -356,7 +356,7 @@ QString MainWindow::getWindowStateKey()
}
else
return QString::number(currentView)+"_windowstate";
return QString::number(currentView)+"_windowstate";
}
QString MainWindow::getWindowGeometryKey()
@ -410,7 +410,7 @@ void MainWindow::buildCustomWidget() @@ -410,7 +410,7 @@ void MainWindow::buildCustomWidget()
switch (view)
{
case VIEW_ENGINEER:
dock = createDockWidget(dataView,tool,tool->getTitle(),tool->objectName(),(VIEW_SECTIONS)view,location);
dock = createDockWidget(engineeringView,tool,tool->getTitle(),tool->objectName(),(VIEW_SECTIONS)view,location);
break;
case VIEW_FLIGHT:
dock = createDockWidget(pilotView,tool,tool->getTitle(),tool->objectName(),(VIEW_SECTIONS)view,location);
@ -421,6 +421,9 @@ void MainWindow::buildCustomWidget() @@ -421,6 +421,9 @@ void MainWindow::buildCustomWidget()
case VIEW_MISSION:
dock = createDockWidget(plannerView,tool,tool->getTitle(),tool->objectName(),(VIEW_SECTIONS)view,location);
break;
case VIEW_MAVLINK:
dock = createDockWidget(mavlinkView,tool,tool->getTitle(),tool->objectName(),(VIEW_SECTIONS)view,location);
break;
default:
dock = createDockWidget(centerStack->currentWidget(),tool,tool->getTitle(),tool->objectName(),(VIEW_SECTIONS)view,location);
break;
@ -480,15 +483,15 @@ void MainWindow::buildCommonWidgets() @@ -480,15 +483,15 @@ void MainWindow::buildCommonWidgets()
{
engineeringView = new SubMainWindow(this);
engineeringView->setObjectName("VIEW_ENGINEER");
engineeringView->setCentralWidget(new XMLCommProtocolWidget(this));
addCentralWidget(engineeringView,"Mavlink Generator");
engineeringView->setCentralWidget(new QGCDataPlot2D(this));
addCentralWidget(engineeringView,tr("Logfile Plot"));
}
if (!dataView)
if (!mavlinkView)
{
dataView = new SubMainWindow(this);
dataView->setObjectName("VIEW_DATA");
dataView->setCentralWidget(new QGCDataPlot2D(this));
addCentralWidget(dataView,tr("Logfile Plot"));
mavlinkView = new SubMainWindow(this);
mavlinkView->setObjectName("VIEW_MAVLINK");
mavlinkView->setCentralWidget(new XMLCommProtocolWidget(this));
addCentralWidget(mavlinkView,tr("Mavlink Generator"));
}
if (!simView)
{
@ -503,38 +506,38 @@ void MainWindow::buildCommonWidgets() @@ -503,38 +506,38 @@ void MainWindow::buildCommonWidgets()
tempAction->setCheckable(true);
connect(tempAction,SIGNAL(triggered(bool)),this, SLOT(showTool(bool)));
createDockWidget(simView,new UASControlWidget(this),tr("Control"),"UNMANNED_SYSTEM_CONTROL_DOCKWIDGET",VIEW_SIMULATION,Qt::LeftDockWidgetArea);
createDockWidget(simView,new UASControlWidget(this),tr("Control"),"UNMANNED_SYSTEM_CONTROL_DOCKWIDGET",VIEW_SIMULATION,Qt::LeftDockWidgetArea);
createDockWidget(plannerView,new UASListWidget(this),tr("Unmanned Systems"),"UNMANNED_SYSTEM_LIST_DOCKWIDGET",VIEW_MISSION,Qt::LeftDockWidgetArea);
createDockWidget(plannerView,new UASListWidget(this),tr("Unmanned Systems"),"UNMANNED_SYSTEM_LIST_DOCKWIDGET",VIEW_MISSION,Qt::LeftDockWidgetArea);
{
{
//createDockWidget(plannerView,new QGCWaypointListMulti(this),tr("Mission Plan"),"WAYPOINT_LIST_DOCKWIDGET",VIEW_MISSION,Qt::BottomDockWidgetArea);
QAction* tempAction = ui.menuTools->addAction(tr("Mission Plan"));
tempAction->setCheckable(true);
connect(tempAction,SIGNAL(triggered(bool)),this, SLOT(showTool(bool)));
menuToDockNameMap[tempAction] = "WAYPOINT_LIST_DOCKWIDGET";
}
}
createDockWidget(simView,new QGCWaypointListMulti(this),tr("Mission Plan"),"WAYPOINT_LIST_DOCKWIDGET",VIEW_SIMULATION,Qt::BottomDockWidgetArea);
createDockWidget(engineeringView,new QGCMAVLinkInspector(mavlink,this),tr("MAVLink Inspector"),"MAVLINK_INSPECTOR_DOCKWIDGET",VIEW_ENGINEER,Qt::RightDockWidgetArea);
createDockWidget(simView,new QGCWaypointListMulti(this),tr("Mission Plan"),"WAYPOINT_LIST_DOCKWIDGET",VIEW_SIMULATION,Qt::BottomDockWidgetArea);
createDockWidget(engineeringView,new QGCMAVLinkInspector(mavlink,this),tr("MAVLink Inspector"),"MAVLINK_INSPECTOR_DOCKWIDGET",VIEW_ENGINEER,Qt::RightDockWidgetArea);
createDockWidget(engineeringView,new ParameterInterface(this),tr("Onboard Parameters"),"PARAMETER_INTERFACE_DOCKWIDGET",VIEW_ENGINEER,Qt::RightDockWidgetArea);
createDockWidget(simView,new ParameterInterface(this),tr("Onboard Parameters"),"PARAMETER_INTERFACE_DOCKWIDGET",VIEW_SIMULATION,Qt::RightDockWidgetArea);
createDockWidget(engineeringView,new ParameterInterface(this),tr("Onboard Parameters"),"PARAMETER_INTERFACE_DOCKWIDGET",VIEW_ENGINEER,Qt::RightDockWidgetArea);
createDockWidget(simView,new ParameterInterface(this),tr("Onboard Parameters"),"PARAMETER_INTERFACE_DOCKWIDGET",VIEW_SIMULATION,Qt::RightDockWidgetArea);
{
{
QAction* tempAction = ui.menuTools->addAction(tr("Status Details"));
menuToDockNameMap[tempAction] = "UAS_STATUS_DETAILS_DOCKWIDGET";
tempAction->setCheckable(true);
connect(tempAction,SIGNAL(triggered(bool)),this, SLOT(showTool(bool)));
}
{
}
{
QAction* tempAction = ui.menuTools->addAction(tr("Communication Console"));
menuToDockNameMap[tempAction] = "COMMUNICATION_DEBUG_CONSOLE_DOCKWIDGET";
tempAction->setCheckable(true);
connect(tempAction,SIGNAL(triggered(bool)),this, SLOT(showTool(bool)));
}
createDockWidget(simView,new HSIDisplay(this),tr("Horizontal Situation"),"HORIZONTAL_SITUATION_INDICATOR_DOCKWIDGET",VIEW_SIMULATION,Qt::BottomDockWidgetArea);
}
createDockWidget(simView,new HSIDisplay(this),tr("Horizontal Situation"),"HORIZONTAL_SITUATION_INDICATOR_DOCKWIDGET",VIEW_SIMULATION,Qt::BottomDockWidgetArea);
@ -558,23 +561,23 @@ void MainWindow::buildCommonWidgets() @@ -558,23 +561,23 @@ void MainWindow::buildCommonWidgets()
//createDockWidget(pilotView,hdDisplay2,tr("Actuator Status"),"HEAD_DOWN_DISPLAY_2_DOCKWIDGET",VIEW_FLIGHT,Qt::RightDockWidgetArea);
{
QAction* tempAction = ui.menuTools->addAction(tr("Flight Display"));
tempAction->setCheckable(true);
connect(tempAction,SIGNAL(triggered(bool)),this, SLOT(showTool(bool)));
menuToDockNameMap[tempAction] = "HEAD_DOWN_DISPLAY_1_DOCKWIDGET";
QAction* tempAction = ui.menuTools->addAction(tr("Flight Display"));
tempAction->setCheckable(true);
connect(tempAction,SIGNAL(triggered(bool)),this, SLOT(showTool(bool)));
menuToDockNameMap[tempAction] = "HEAD_DOWN_DISPLAY_1_DOCKWIDGET";
}
{
QAction* tempAction = ui.menuTools->addAction(tr("Actuator Status"));
tempAction->setCheckable(true);
connect(tempAction,SIGNAL(triggered(bool)),this, SLOT(showTool(bool)));
menuToDockNameMap[tempAction] = "HEAD_DOWN_DISPLAY_2_DOCKWIDGET";
QAction* tempAction = ui.menuTools->addAction(tr("Actuator Status"));
tempAction->setCheckable(true);
connect(tempAction,SIGNAL(triggered(bool)),this, SLOT(showTool(bool)));
menuToDockNameMap[tempAction] = "HEAD_DOWN_DISPLAY_2_DOCKWIDGET";
}
{
QAction* tempAction = ui.menuTools->addAction(tr("Radio Control"));
tempAction->setCheckable(true);
connect(tempAction,SIGNAL(triggered(bool)),this, SLOT(showTool(bool)));
QAction* tempAction = ui.menuTools->addAction(tr("Radio Control"));
tempAction->setCheckable(true);
connect(tempAction,SIGNAL(triggered(bool)),this, SLOT(showTool(bool)));
}
@ -600,11 +603,11 @@ void MainWindow::buildCommonWidgets() @@ -600,11 +603,11 @@ void MainWindow::buildCommonWidgets()
}*/
// if (!firmwareUpdateWidget)
// {
// firmwareUpdateWidget = new QGCFirmwareUpdate(this);
// addCentralWidget(firmwareUpdateWidget, "Firmware Update");
// }
// if (!firmwareUpdateWidget)
// {
// firmwareUpdateWidget = new QGCFirmwareUpdate(this);
// addCentralWidget(firmwareUpdateWidget, "Firmware Update");
// }
/*if (!hudWidget)
{
@ -690,7 +693,7 @@ QDockWidget* MainWindow::createDockWidget(QWidget *parent,QWidget *child,QString @@ -690,7 +693,7 @@ QDockWidget* MainWindow::createDockWidget(QWidget *parent,QWidget *child,QString
{
//if (child->objectName() == "")
//{
child->setObjectName(objectname);
child->setObjectName(objectname);
//}
QDockWidget *widget = new QDockWidget(title,this);
if (!isAdvancedMode)
@ -862,16 +865,16 @@ void MainWindow::addCentralWidget(QWidget* widget, const QString& title) @@ -862,16 +865,16 @@ void MainWindow::addCentralWidget(QWidget* widget, const QString& title)
{
centerStack->addWidget(widget);
// QAction* tempAction = ui.menuMain->addAction(title);
// QAction* tempAction = ui.menuMain->addAction(title);
// tempAction->setCheckable(true);
// QVariant var;
// var.setValue((QWidget*)widget);
// tempAction->setData(var);
// centerStackActionGroup->addAction(tempAction);
// connect(tempAction,SIGNAL(triggered()),this, SLOT(showCentralWidget()));
// tempAction->setCheckable(true);
// QVariant var;
// var.setValue((QWidget*)widget);
// tempAction->setData(var);
// centerStackActionGroup->addAction(tempAction);
// connect(tempAction,SIGNAL(triggered()),this, SLOT(showCentralWidget()));
//connect(widget, SIGNAL(visibilityChanged(bool)), tempAction, SLOT(setChecked(bool)));
// tempAction->setChecked(widget->isVisible());
// tempAction->setChecked(widget->isVisible());
}
}
@ -891,17 +894,14 @@ void MainWindow::showHILConfigurationWidget(UASInterface* uas) @@ -891,17 +894,14 @@ void MainWindow::showHILConfigurationWidget(UASInterface* uas)
if (mav && !hilDocks.contains(mav->getUASID()))
{
QGCHilConfiguration* hconf = new QGCHilConfiguration(mav, this);
QString hilDockName = tr("HIL Config (%1)").arg(uas->getUASName());
QDockWidget* hilDock = new QDockWidget(hilDockName, this);
hilDock->setWidget(hconf);
hilDock->setObjectName(QString("HIL_CONFIG_%1").arg(uas->getUASID()));
//addTool(hilDock, hilDockName, Qt::LeftDockWidgetArea);
QString hilDockName = tr("HIL Config %1").arg(uas->getUASName());
QDockWidget* hilDock = createDockWidget(simView, hconf,hilDockName, hilDockName.toUpper().replace(" ", "_"),VIEW_SIMULATION,Qt::LeftDockWidgetArea);
hilDocks.insert(mav->getUASID(), hilDock);
if (currentView != VIEW_SIMULATION)
hilDock->hide();
else
hilDock->show();
// if (currentView != VIEW_SIMULATION)
// hilDock->hide();
// else
// hilDock->show();
}
}
@ -975,7 +975,7 @@ void MainWindow::loadCustomWidget(const QString& fileName, int view) @@ -975,7 +975,7 @@ void MainWindow::loadCustomWidget(const QString& fileName, int view)
switch ((VIEW_SECTIONS)view)
{
case VIEW_ENGINEER:
createDockWidget(dataView,tool,tool->getTitle(),tool->objectName()+"DOCK",(VIEW_SECTIONS)view,Qt::LeftDockWidgetArea);
createDockWidget(engineeringView,tool,tool->getTitle(),tool->objectName()+"DOCK",(VIEW_SECTIONS)view,Qt::LeftDockWidgetArea);
break;
case VIEW_FLIGHT:
createDockWidget(pilotView,tool,tool->getTitle(),tool->objectName()+"DOCK",(VIEW_SECTIONS)view,Qt::LeftDockWidgetArea);
@ -987,16 +987,16 @@ void MainWindow::loadCustomWidget(const QString& fileName, int view) @@ -987,16 +987,16 @@ void MainWindow::loadCustomWidget(const QString& fileName, int view)
createDockWidget(plannerView,tool,tool->getTitle(),tool->objectName()+"DOCK",(VIEW_SECTIONS)view,Qt::LeftDockWidgetArea);
break;
default:
{
//Delete tool, create menu item to tie it to.
customWidgetNameToFilenameMap[tool->objectName()+"DOCK"] = fileName;
QAction* tempAction = ui.menuTools->addAction(tool->getTitle());
menuToDockNameMap[tempAction] = tool->objectName()+"DOCK";
tempAction->setCheckable(true);
connect(tempAction,SIGNAL(triggered(bool)),this, SLOT(showTool(bool)));
tool->deleteLater();
//createDockWidget(centerStack->currentWidget(),tool,tool->getTitle(),tool->objectName()+"DOCK",(VIEW_SECTIONS)view,Qt::LeftDockWidgetArea);
}
{
//Delete tool, create menu item to tie it to.
customWidgetNameToFilenameMap[tool->objectName()+"DOCK"] = fileName;
QAction* tempAction = ui.menuTools->addAction(tool->getTitle());
menuToDockNameMap[tempAction] = tool->objectName()+"DOCK";
tempAction->setCheckable(true);
connect(tempAction,SIGNAL(triggered(bool)),this, SLOT(showTool(bool)));
tool->deleteLater();
//createDockWidget(centerStack->currentWidget(),tool,tool->getTitle(),tool->objectName()+"DOCK",(VIEW_SECTIONS)view,Qt::LeftDockWidgetArea);
}
break;
}
}
@ -1020,7 +1020,7 @@ void MainWindow::loadCustomWidget(const QString& fileName, bool singleinstance) @@ -1020,7 +1020,7 @@ void MainWindow::loadCustomWidget(const QString& fileName, bool singleinstance)
switch (view)
{
case VIEW_ENGINEER:
createDockWidget(dataView,tool,tool->getTitle(),tool->objectName()+"DOCK",(VIEW_SECTIONS)view,Qt::LeftDockWidgetArea);
createDockWidget(engineeringView,tool,tool->getTitle(),tool->objectName()+"DOCK",(VIEW_SECTIONS)view,Qt::LeftDockWidgetArea);
break;
case VIEW_FLIGHT:
createDockWidget(pilotView,tool,tool->getTitle(),tool->objectName()+"DOCK",(VIEW_SECTIONS)view,Qt::LeftDockWidgetArea);
@ -1032,16 +1032,16 @@ void MainWindow::loadCustomWidget(const QString& fileName, bool singleinstance) @@ -1032,16 +1032,16 @@ void MainWindow::loadCustomWidget(const QString& fileName, bool singleinstance)
createDockWidget(plannerView,tool,tool->getTitle(),tool->objectName()+"DOCK",(VIEW_SECTIONS)view,Qt::LeftDockWidgetArea);
break;
default:
{
//Delete tool, create menu item to tie it to.
customWidgetNameToFilenameMap[tool->objectName()+"DOCK"] = fileName;
QAction* tempAction = ui.menuTools->addAction(tool->getTitle());
menuToDockNameMap[tempAction] = tool->objectName()+"DOCK";
tempAction->setCheckable(true);
connect(tempAction,SIGNAL(triggered(bool)),this, SLOT(showTool(bool)));
tool->deleteLater();
//createDockWidget(centerStack->currentWidget(),tool,tool->getTitle(),tool->objectName()+"DOCK",(VIEW_SECTIONS)view,Qt::LeftDockWidgetArea);
}
{
//Delete tool, create menu item to tie it to.
customWidgetNameToFilenameMap[tool->objectName()+"DOCK"] = fileName;
QAction* tempAction = ui.menuTools->addAction(tool->getTitle());
menuToDockNameMap[tempAction] = tool->objectName()+"DOCK";
tempAction->setCheckable(true);
connect(tempAction,SIGNAL(triggered(bool)),this, SLOT(showTool(bool)));
tool->deleteLater();
//createDockWidget(centerStack->currentWidget(),tool,tool->getTitle(),tool->objectName()+"DOCK",(VIEW_SECTIONS)view,Qt::LeftDockWidgetArea);
}
break;
}
@ -1575,8 +1575,8 @@ void MainWindow::setActiveUAS(UASInterface* uas) @@ -1575,8 +1575,8 @@ void MainWindow::setActiveUAS(UASInterface* uas)
{
Q_UNUSED(uas);
// Enable and rename menu
// ui.menuUnmanned_System->setTitle(uas->getUASName());
// if (!ui.menuUnmanned_System->isEnabled()) ui.menuUnmanned_System->setEnabled(true);
// ui.menuUnmanned_System->setTitle(uas->getUASName());
// if (!ui.menuUnmanned_System->isEnabled()) ui.menuUnmanned_System->setEnabled(true);
if (settings.contains(getWindowStateKey()))
{
SubMainWindow *win = qobject_cast<SubMainWindow*>(centerStack->currentWidget());
@ -1593,14 +1593,14 @@ void MainWindow::UASSpecsChanged(int uas) @@ -1593,14 +1593,14 @@ void MainWindow::UASSpecsChanged(int uas)
{
if (activeUAS->getUASID() == uas)
{
// ui.menuUnmanned_System->setTitle(activeUAS->getUASName());
// ui.menuUnmanned_System->setTitle(activeUAS->getUASName());
}
}
else
{
// Last system deleted
// ui.menuUnmanned_System->setTitle(tr("No System"));
// ui.menuUnmanned_System->setEnabled(false);
// ui.menuUnmanned_System->setTitle(tr("No System"));
// ui.menuUnmanned_System->setEnabled(false);
}
}
@ -1609,12 +1609,12 @@ void MainWindow::UASCreated(UASInterface* uas) @@ -1609,12 +1609,12 @@ void MainWindow::UASCreated(UASInterface* uas)
// Check if this is the 2nd system and we need a switch menu
if (UASManager::instance()->getUASList().count() > 1)
// ui.menuConnected_Systems->setEnabled(true);
// ui.menuConnected_Systems->setEnabled(true);
// Connect the UAS to the full user interface
// 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.actionFlightView->setEnabled(true);
ui.actionMissionView->setEnabled(true);
@ -1689,69 +1689,69 @@ void MainWindow::UASCreated(UASInterface* uas) @@ -1689,69 +1689,69 @@ void MainWindow::UASCreated(UASInterface* uas)
break;
}
// XXX The multi-UAS selection menu has been disabled for now,
// its redundant with right-clicking the UAS in the list.
// this code piece might be removed later if this is the final
// conclusion (May 2013)
// QAction* uasAction = new QAction(icon, tr("Select %1 for control").arg(uas->getUASName()), ui.menuConnected_Systems);
// connect(uas, SIGNAL(systemRemoved()), uasAction, SLOT(deleteLater()));
// connect(uasAction, SIGNAL(triggered()), uas, SLOT(setSelected()));
// ui.menuConnected_Systems->addAction(uasAction);
// XXX The multi-UAS selection menu has been disabled for now,
// its redundant with right-clicking the UAS in the list.
// this code piece might be removed later if this is the final
// conclusion (May 2013)
// QAction* uasAction = new QAction(icon, tr("Select %1 for control").arg(uas->getUASName()), ui.menuConnected_Systems);
// connect(uas, SIGNAL(systemRemoved()), uasAction, SLOT(deleteLater()));
// connect(uasAction, SIGNAL(triggered()), uas, SLOT(setSelected()));
// ui.menuConnected_Systems->addAction(uasAction);
connect(uas, SIGNAL(systemSpecsChanged(int)), this, SLOT(UASSpecsChanged(int)));
connect(uas, SIGNAL(systemSpecsChanged(int)), this, SLOT(UASSpecsChanged(int)));
// HIL
showHILConfigurationWidget(uas);
// HIL
showHILConfigurationWidget(uas);
if (!linechartWidget)
{
linechartWidget = new Linecharts(this);
//linechartWidget->hide();
if (!linechartWidget)
{
linechartWidget = new Linecharts(this);
//linechartWidget->hide();
}
}
linechartWidget->addSource(mavlinkDecoder);
if (dataView->centralWidget() != linechartWidget)
{
dataView->setCentralWidget(linechartWidget);
linechartWidget->show();
}
linechartWidget->addSource(mavlinkDecoder);
if (engineeringView->centralWidget() != linechartWidget)
{
engineeringView->setCentralWidget(linechartWidget);
linechartWidget->show();
}
// Load default custom widgets for this autopilot type
loadCustomWidgetsFromDefaults(uas->getSystemTypeName(), uas->getAutopilotTypeName());
// Load default custom widgets for this autopilot type
loadCustomWidgetsFromDefaults(uas->getSystemTypeName(), uas->getAutopilotTypeName());
if (uas->getAutopilotType() == MAV_AUTOPILOT_PIXHAWK)
if (uas->getAutopilotType() == MAV_AUTOPILOT_PIXHAWK)
{
// Dock widgets
if (!detectionDockWidget)
{
// Dock widgets
if (!detectionDockWidget)
{
detectionDockWidget = new QDockWidget(tr("Object Recognition"), this);
detectionDockWidget->setWidget( new ObjectDetectionView("files/images/patterns", this) );
detectionDockWidget->setObjectName("OBJECT_DETECTION_DOCK_WIDGET");
//addTool(detectionDockWidget, tr("Object Recognition"), Qt::RightDockWidgetArea);
}
detectionDockWidget = new QDockWidget(tr("Object Recognition"), this);
detectionDockWidget->setWidget( new ObjectDetectionView("files/images/patterns", this) );
detectionDockWidget->setObjectName("OBJECT_DETECTION_DOCK_WIDGET");
//addTool(detectionDockWidget, tr("Object Recognition"), Qt::RightDockWidgetArea);
}
if (!watchdogControlDockWidget)
{
watchdogControlDockWidget = new QDockWidget(tr("Process Control"), this);
watchdogControlDockWidget->setWidget( new WatchdogControl(this) );
watchdogControlDockWidget->setObjectName("WATCHDOG_CONTROL_DOCKWIDGET");
//addTool(watchdogControlDockWidget, tr("Process Control"), Qt::BottomDockWidgetArea);
}
if (!watchdogControlDockWidget)
{
watchdogControlDockWidget = new QDockWidget(tr("Process Control"), this);
watchdogControlDockWidget->setWidget( new WatchdogControl(this) );
watchdogControlDockWidget->setObjectName("WATCHDOG_CONTROL_DOCKWIDGET");
//addTool(watchdogControlDockWidget, tr("Process Control"), Qt::BottomDockWidgetArea);
}
}
// Change the view only if this is the first UAS
// Change the view only if this is the first UAS
// If this is the first connected UAS, it is both created as well as
// the currently active UAS
if (UASManager::instance()->getUASList().size() == 1)
// If this is the first connected UAS, it is both created as well as
// the currently active UAS
if (UASManager::instance()->getUASList().size() == 1)
{
// Load last view if setting is present
if (settings.contains("CURRENT_VIEW_WITH_UAS_CONNECTED"))
{
// Load last view if setting is present
if (settings.contains("CURRENT_VIEW_WITH_UAS_CONNECTED"))
{
/*int view = settings.value("CURRENT_VIEW_WITH_UAS_CONNECTED").toInt();
/*int view = settings.value("CURRENT_VIEW_WITH_UAS_CONNECTED").toInt();
switch (view)
{
case VIEW_ENGINEER:
@ -1777,17 +1777,17 @@ void MainWindow::UASCreated(UASInterface* uas) @@ -1777,17 +1777,17 @@ void MainWindow::UASCreated(UASInterface* uas)
loadOperatorView();
break;
}*/
}
else
{
// loadOperatorView();
}
}
else
{
// loadOperatorView();
}
}
//}
// if (!ui.menuConnected_Systems->isEnabled()) ui.menuConnected_Systems->setEnabled(true);
// if (!ui.menuUnmanned_System->isEnabled()) ui.menuUnmanned_System->setEnabled(true);
// if (!ui.menuConnected_Systems->isEnabled()) ui.menuConnected_Systems->setEnabled(true);
// if (!ui.menuUnmanned_System->isEnabled()) ui.menuUnmanned_System->setEnabled(true);
// Reload view state in case new widgets were added
loadViewState();
@ -1799,18 +1799,18 @@ void MainWindow::UASDeleted(UASInterface* uas) @@ -1799,18 +1799,18 @@ void MainWindow::UASDeleted(UASInterface* uas)
if (UASManager::instance()->getUASList().count() == 0)
{
// Last system deleted
// ui.menuUnmanned_System->setTitle(tr("No System"));
// ui.menuUnmanned_System->setEnabled(false);
// ui.menuUnmanned_System->setTitle(tr("No System"));
// ui.menuUnmanned_System->setEnabled(false);
}
// QAction* act;
// QList<QAction*> actions = ui.menuConnected_Systems->actions();
// QAction* act;
// QList<QAction*> actions = ui.menuConnected_Systems->actions();
// foreach (act, actions)
// {
// if (act->text().contains(uas->getUASName()))
// ui.menuConnected_Systems->removeAction(act);
// }
// foreach (act, actions)
// {
// if (act->text().contains(uas->getUASName()))
// ui.menuConnected_Systems->removeAction(act);
// }
}
/**
@ -1846,7 +1846,7 @@ void MainWindow::loadViewState() @@ -1846,7 +1846,7 @@ void MainWindow::loadViewState()
// Restore center stack state
int index = settings.value(getWindowStateKey()+"CENTER_WIDGET", -1).toInt();
// The offline plot view is usually the consequence of a logging run, always show the realtime view first
if (centerStack->indexOf(dataView) == index)
if (centerStack->indexOf(engineeringView) == index)
{
// Rewrite to realtime plot
//index = centerStack->indexOf(linechartWidget);
@ -1869,13 +1869,13 @@ void MainWindow::loadViewState() @@ -1869,13 +1869,13 @@ void MainWindow::loadViewState()
centerStack->setCurrentWidget(configView);
break;
case VIEW_ENGINEER:
centerStack->setCurrentWidget(dataView);
centerStack->setCurrentWidget(engineeringView);
break;
case VIEW_FLIGHT:
centerStack->setCurrentWidget(pilotView);
break;
case VIEW_MAVLINK:
centerStack->setCurrentWidget(engineeringView);
centerStack->setCurrentWidget(mavlinkView);
break;
case VIEW_FIRMWAREUPDATE:
centerStack->setCurrentWidget(firmwareUpdateWidget);
@ -2043,25 +2043,25 @@ void MainWindow::loadFirmwareUpdateView() @@ -2043,25 +2043,25 @@ void MainWindow::loadFirmwareUpdateView()
}
}
void MainWindow::loadDataView(QString fileName)
{
// Plot is now selected, now load data from file
if (dataView)
{
//dataView->setCentralWidget(new QGCDataPlot2D(this));
QGCDataPlot2D *plot = qobject_cast<QGCDataPlot2D*>(dataView->centralWidget());
if (plot)
{
plot->loadFile(fileName);
}
}
/*QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
if (centerStack)
{
centerStack->setCurrentWidget(dataView);
dataplotWidget->loadFile(fileName);
}*/
}
//void MainWindow::loadDataView(QString fileName)
//{
// // Plot is now selected, now load data from file
// if (dataView)
// {
// //dataView->setCentralWidget(new QGCDataPlot2D(this));
// QGCDataPlot2D *plot = qobject_cast<QGCDataPlot2D*>(dataView->centralWidget());
// if (plot)
// {
// plot->loadFile(fileName);
// }
// }
// /*QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
// if (centerStack)
// {
// centerStack->setCurrentWidget(dataView);
// dataplotWidget->loadFile(fileName);
// }*/
//}
QList<QAction*> MainWindow::listLinkMenuActions(void)

4
src/ui/MainWindow.h

@ -233,7 +233,7 @@ public slots: @@ -233,7 +233,7 @@ public slots:
void closeEvent(QCloseEvent* event);
/** @brief Load data view, allowing to plot flight data */
void loadDataView(QString fileName);
// void loadDataView(QString fileName);
/**
* @brief Shows a Docked Widget based on the action sender
@ -354,7 +354,7 @@ protected: @@ -354,7 +354,7 @@ protected:
QPointer<SubMainWindow> plannerView;
QPointer<SubMainWindow> pilotView;
QPointer<SubMainWindow> configView;
QPointer<SubMainWindow> dataView;
QPointer<SubMainWindow> mavlinkView;
QPointer<SubMainWindow> engineeringView;
QPointer<SubMainWindow> simView;

9
src/ui/QGCHilConfiguration.cc

@ -22,9 +22,9 @@ QGCHilConfiguration::QGCHilConfiguration(UAS *mav, QWidget *parent) : @@ -22,9 +22,9 @@ QGCHilConfiguration::QGCHilConfiguration(UAS *mav, QWidget *parent) :
int i = settings.value("SIMULATOR_INDEX", -1).toInt();
if (i > 0) {
ui->simComboBox->blockSignals(true);
// ui->simComboBox->blockSignals(true);
ui->simComboBox->setCurrentIndex(i);
ui->simComboBox->blockSignals(false);
// ui->simComboBox->blockSignals(false);
on_simComboBox_currentIndexChanged(i);
}
@ -46,6 +46,11 @@ QGCHilConfiguration::~QGCHilConfiguration() @@ -46,6 +46,11 @@ QGCHilConfiguration::~QGCHilConfiguration()
delete ui;
}
void QGCHilConfiguration::setVersion(QString version)
{
}
void QGCHilConfiguration::on_simComboBox_currentIndexChanged(int index)
{
//clean up

1
src/ui/QGCHilConfiguration.h

@ -21,6 +21,7 @@ public: @@ -21,6 +21,7 @@ public:
public slots:
/** @brief Receive status message */
void receiveStatusMessage(const QString& message);
void setVersion(QString version);
protected:
UAS* mav;

7
src/ui/QGCHilXPlaneConfiguration.cc

@ -32,6 +32,8 @@ QGCHilXPlaneConfiguration::QGCHilXPlaneConfiguration(QGCHilLink* link, QWidget * @@ -32,6 +32,8 @@ QGCHilXPlaneConfiguration::QGCHilXPlaneConfiguration(QGCHilLink* link, QWidget *
ui->sensorHilCheckBox->setChecked(link->sensorHilEnabled());
connect(link, SIGNAL(sensorHilChanged(bool)), ui->sensorHilCheckBox, SLOT(setChecked(bool)));
connect(ui->sensorHilCheckBox, SIGNAL(clicked(bool)), link, SLOT(enableSensorHIL(bool)));
connect(link, SIGNAL(versionChanged(int)), this, SLOT(setVersion(int)));
}
ui->hostComboBox->clear();
@ -40,6 +42,11 @@ QGCHilXPlaneConfiguration::QGCHilXPlaneConfiguration(QGCHilLink* link, QWidget * @@ -40,6 +42,11 @@ QGCHilXPlaneConfiguration::QGCHilXPlaneConfiguration(QGCHilLink* link, QWidget *
}
void QGCHilXPlaneConfiguration::setVersion(int version)
{
}
void QGCHilXPlaneConfiguration::toggleSimulation(bool connect)
{
Q_UNUSED(connect);

2
src/ui/QGCHilXPlaneConfiguration.h

@ -20,6 +20,8 @@ public: @@ -20,6 +20,8 @@ public:
public slots:
/** @brief Start / stop simulation */
void toggleSimulation(bool connect);
/** @brief Set X-Plane version */
void setVersion(int version);
protected:
QGCHilLink* link;

6
src/ui/QGCHilXPlaneConfiguration.ui

@ -6,14 +6,14 @@ @@ -6,14 +6,14 @@
<rect>
<x>0</x>
<y>0</y>
<width>295</width>
<height>148</height>
<width>570</width>
<height>238</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QGridLayout" name="gridLayout" rowstretch="0,0,0,0,0,100" columnstretch="40,10,10,40">
<layout class="QGridLayout" name="gridLayout" rowstretch="0,0,0,0,0,100" columnstretch="20,40,40,20">
<property name="margin">
<number>0</number>
</property>

17
src/ui/QGCMAVLinkLogPlayer.cc

@ -3,6 +3,7 @@ @@ -3,6 +3,7 @@
#include <QDesktopServices>
#include "MainWindow.h"
#include "SerialLink.h"
#include "QGCMAVLinkLogPlayer.h"
#include "QGC.h"
#include "ui_QGCMAVLinkLogPlayer.h"
@ -361,6 +362,22 @@ bool QGCMAVLinkLogPlayer::loadLogFile(const QString& file) @@ -361,6 +362,22 @@ bool QGCMAVLinkLogPlayer::loadLogFile(const QString& file)
// Reset current state
reset(0);
// Check if a serial link is connected
bool linkWarning = false;
foreach (LinkInterface* link, LinkManager::instance()->getLinks())
{
SerialLink* s = dynamic_cast<SerialLink*>(link);
if (s && s->isConnected())
linkWarning = true;
}
if (linkWarning)
MainWindow::instance()->showInfoMessage(tr("Active MAVLink links found"), tr("Currently other links are connected. It is recommended to disconnect any active link before replaying a log."));
play();
return true;
}
}

17
src/ui/QGCToolBar.cc

@ -46,6 +46,16 @@ QGCToolBar::QGCToolBar(QWidget *parent) : @@ -46,6 +46,16 @@ QGCToolBar::QGCToolBar(QWidget *parent) :
// Do not load UI, wait for actions
}
void QGCToolBar::globalPositionChanged(UASInterface* uas, double lat, double lon, double alt, quint64 usec)
{
Q_UNUSED(uas);
Q_UNUSED(lat);
Q_UNUSED(lon);
Q_UNUSED(usec);
altitudeMSL = alt;
changed = true;
}
void QGCToolBar::heartbeatTimeout(bool timeout, unsigned int ms)
{
// set timeout label visible
@ -278,6 +288,7 @@ void QGCToolBar::setActiveUAS(UASInterface* active) @@ -278,6 +288,7 @@ void QGCToolBar::setActiveUAS(UASInterface* active)
disconnect(mav, SIGNAL(batteryChanged(UASInterface*,double,double,int)), this, SLOT(updateBatteryRemaining(UASInterface*,double,double,int)));
disconnect(mav, SIGNAL(armingChanged(bool)), this, SLOT(updateArmingState(bool)));
disconnect(mav, SIGNAL(heartbeatTimeout(bool, unsigned int)), this, SLOT(heartbeatTimeout(bool,unsigned int)));
disconnect(active, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(globalPositionChanged(UASInterface*,double,double,double,quint64)));
if (mav->getWaypointManager())
{
disconnect(mav->getWaypointManager(), SIGNAL(currentWaypointChanged(quint16)), this, SLOT(updateCurrentWaypoint(quint16)));
@ -295,6 +306,7 @@ void QGCToolBar::setActiveUAS(UASInterface* active) @@ -295,6 +306,7 @@ void QGCToolBar::setActiveUAS(UASInterface* active)
connect(active, SIGNAL(batteryChanged(UASInterface*,double,double,int)), this, SLOT(updateBatteryRemaining(UASInterface*,double,double,int)));
connect(active, SIGNAL(armingChanged(bool)), this, SLOT(updateArmingState(bool)));
connect(active, SIGNAL(heartbeatTimeout(bool, unsigned int)), this, SLOT(heartbeatTimeout(bool,unsigned int)));
connect(active, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(globalPositionChanged(UASInterface*,double,double,double,quint64)));
if (active->getWaypointManager())
{
connect(active->getWaypointManager(), SIGNAL(currentWaypointChanged(quint16)), this, SLOT(updateCurrentWaypoint(quint16)));
@ -311,6 +323,7 @@ void QGCToolBar::setActiveUAS(UASInterface* active) @@ -311,6 +323,7 @@ void QGCToolBar::setActiveUAS(UASInterface* active)
toolBarStateLabel->setText(mav->getShortState());
toolBarTimeoutLabel->setStyleSheet(QString(""));
toolBarTimeoutLabel->setText("");
toolBarDistLabel->setText("");
setSystemType(mav, mav->getSystemType());
}
@ -330,7 +343,9 @@ void QGCToolBar::updateArmingState(bool armed) @@ -330,7 +343,9 @@ void QGCToolBar::updateArmingState(bool armed)
void QGCToolBar::updateView()
{
if (!changed) return;
toolBarDistLabel->setText(tr("%1 m").arg(wpDistance, 6, 'f', 2, '0'));
//toolBarDistLabel->setText(tr("%1 m").arg(wpDistance, 6, 'f', 2, '0'));
// XXX add also rel altitude
toolBarDistLabel->setText(QString("%1 m MSL").arg(altitudeMSL, 6, 'f', 2, '0'));
toolBarWpLabel->setText(tr("WP%1").arg(wpId));
toolBarBatteryBar->setValue(batteryPercent);
if (batteryPercent < 30 && toolBarBatteryBar->value() >= 30) {

4
src/ui/QGCToolBar.h

@ -74,6 +74,8 @@ public slots: @@ -74,6 +74,8 @@ public slots:
void updateView();
/** @brief Update connection timeout time */
void heartbeatTimeout(bool timeout, unsigned int ms);
/** @brief Update global position */
void globalPositionChanged(UASInterface* uas, double lat, double lon, double alt, quint64 usec);
/** @brief Create or connect link */
void connectLink(bool connect);
/** @brief Clear status string */
@ -106,6 +108,8 @@ protected: @@ -106,6 +108,8 @@ protected:
float batteryVoltage;
int wpId;
double wpDistance;
float altitudeMSL;
float altitudeRel;
QString state;
QString mode;
QString systemName;

3
src/ui/QGCVehicleConfig.cc

@ -39,6 +39,7 @@ QGCVehicleConfig::QGCVehicleConfig(QWidget *parent) : @@ -39,6 +39,7 @@ QGCVehicleConfig::QGCVehicleConfig(QWidget *parent) :
systemTypeToParamMap["FIXED_WING"] = new QMap<QString,QGCToolWidget*>();
systemTypeToParamMap["QUADROTOR"] = new QMap<QString,QGCToolWidget*>();
systemTypeToParamMap["GROUND_ROVER"] = new QMap<QString,QGCToolWidget*>();
systemTypeToParamMap["BOAT"] = new QMap<QString,QGCToolWidget*>();
libParamToWidgetMap = new QMap<QString,QGCToolWidget*>();
setObjectName("QGC_VEHICLECONFIG");
@ -726,6 +727,8 @@ void QGCVehicleConfig::setActiveUAS(UASInterface* active) @@ -726,6 +727,8 @@ void QGCVehicleConfig::setActiveUAS(UASInterface* active)
{
//Indication that we have no meta data for this system type.
qDebug() << "No parameters defined for system type:" << mav->getSystemTypeName();
systemTypeToParamMap[mav->getSystemTypeName()] = new QMap<QString,QGCToolWidget*>();
paramToWidgetMap = systemTypeToParamMap[mav->getSystemTypeName()];
}
if (!paramTooltips.isEmpty())

4
src/ui/QGCWaypointListMulti.cc

@ -12,7 +12,7 @@ QGCWaypointListMulti::QGCWaypointListMulti(QWidget *parent) : @@ -12,7 +12,7 @@ QGCWaypointListMulti::QGCWaypointListMulti(QWidget *parent) :
connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)), this, SLOT(systemCreated(UASInterface*)));
connect(UASManager::instance(), SIGNAL(activeUASSet(int)), this, SLOT(systemSetActive(int)));
WaypointList* list = new WaypointList(ui->stackedWidget, NULL);
WaypointList* list = new WaypointList(ui->stackedWidget, UASManager::instance()->getActiveUASWaypointManager());
lists.insert(offline_uas_id, list);
ui->stackedWidget->addWidget(list);
@ -40,7 +40,7 @@ void QGCWaypointListMulti::systemDeleted(QObject* uas) @@ -40,7 +40,7 @@ void QGCWaypointListMulti::systemDeleted(QObject* uas)
void QGCWaypointListMulti::systemCreated(UASInterface* uas)
{
WaypointList* list = new WaypointList(ui->stackedWidget, uas);
WaypointList* list = new WaypointList(ui->stackedWidget, uas->getWaypointManager());
lists.insert(uas->getUASID(), list);
ui->stackedWidget->addWidget(list);
// Ensure widget is deleted when system is deleted

10
src/ui/SerialConfigurationWindow.cc

@ -218,6 +218,9 @@ void SerialConfigurationWindow::setupPortList() @@ -218,6 +218,9 @@ void SerialConfigurationWindow::setupPortList()
// Get the ports available on this system
QVector<QString>* ports = link->getCurrentPorts();
QString storedName = this->link->getPortName();
bool storedFound = false;
// Add the ports in reverse order, because we prepend them to the list
for (int i = ports->size() - 1; i >= 0; --i)
{
@ -227,9 +230,14 @@ void SerialConfigurationWindow::setupPortList() @@ -227,9 +230,14 @@ void SerialConfigurationWindow::setupPortList()
ui.portName->insertItem(0, ports->at(i));
if (!userConfigured) ui.portName->setEditText(ports->at(i));
}
// Check if the stored link name is still present
if (ports->at(i).contains(storedName) || storedName.contains(ports->at(i)))
storedFound = true;
}
ui.portName->setEditText(this->link->getPortName());
if (storedFound)
ui.portName->setEditText(storedName);
}
void SerialConfigurationWindow::enableFlowControl(bool flow)

395
src/ui/WaypointList.cc

@ -34,15 +34,17 @@ This file is part of the PIXHAWK project @@ -34,15 +34,17 @@ This file is part of the PIXHAWK project
#include "WaypointList.h"
#include "ui_WaypointList.h"
#include <UASInterface.h>
#include <UAS.h>
#include <UASManager.h>
#include <QDebug>
#include <QFileDialog>
#include <QMessageBox>
#include <QMouseEvent>
WaypointList::WaypointList(QWidget *parent, UASInterface* uas) :
WaypointList::WaypointList(QWidget *parent, UASWaypointManager* wpm) :
QWidget(parent),
uas(NULL),
WPM(wpm),
mavX(0.0),
mavY(0.0),
mavZ(0.0),
@ -96,28 +98,32 @@ WaypointList::WaypointList(QWidget *parent, UASInterface* uas) : @@ -96,28 +98,32 @@ WaypointList::WaypointList(QWidget *parent, UASInterface* uas) :
connect(m_ui->refreshButton, SIGNAL(clicked()), this, SLOT(refresh()));
if (WPM) {
// SET UAS AFTER ALL SIGNALS/SLOTS ARE CONNECTED
if (!WPM->getUAS())
{
// Hide buttons, which don't make sense without valid UAS
m_ui->positionAddButton->hide();
m_ui->transmitButton->hide();
m_ui->readButton->hide();
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); //insert a "NO UAV" info into the Onboard Tab
showOfflineWarning = true;
} else {
setUAS(static_cast<UASInterface*>(WPM->getUAS()));
}
// SET UAS AFTER ALL SIGNALS/SLOTS ARE CONNECTED
if (uas)
{
WPM = uas->getWaypointManager();
}
else
{
// Hide buttons, which don't make sense without valid UAS
m_ui->positionAddButton->hide();
m_ui->transmitButton->hide();
m_ui->readButton->hide();
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); //insert a "NO UAV" info into the Onboard Tab
showOfflineWarning = true;
WPM = new UASWaypointManager(NULL);
/* connect slots */
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)));
}
setUAS(uas);
// STATUS LABEL
updateStatusLabel("");
@ -154,28 +160,38 @@ void WaypointList::updateAttitude(UASInterface* uas, double roll, double pitch, @@ -154,28 +160,38 @@ void WaypointList::updateAttitude(UASInterface* uas, double roll, double pitch,
void WaypointList::setUAS(UASInterface* uas)
{
if (this->uas == NULL && uas != NULL)
{
WPM = uas->getWaypointManager();
}
if (this->uas == NULL)
if (!uas)
return;
if (this->uas != NULL)
{
this->uas = uas;
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)));
// Clear current list
on_clearWPListButton_clicked();
// Disconnect everything
disconnect(WPM, SIGNAL(updateStatusString(const QString &)), this, SLOT(updateStatusLabel(const QString &)));
disconnect(WPM, SIGNAL(waypointEditableListChanged(void)), this, SLOT(waypointEditableListChanged(void)));
disconnect(WPM, SIGNAL(waypointEditableChanged(int,Waypoint*)), this, SLOT(updateWaypointEditable(int,Waypoint*)));
disconnect(WPM, SIGNAL(waypointViewOnlyListChanged(void)), this, SLOT(waypointViewOnlyListChanged(void)));
disconnect(WPM, SIGNAL(waypointViewOnlyChanged(int,Waypoint*)), this, SLOT(updateWaypointViewOnly(int,Waypoint*)));
disconnect(WPM, SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointViewOnlyChanged(quint16)));
disconnect(this->uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updatePosition(UASInterface*,double,double,double,quint64)));
disconnect(this->uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,double,double,double,quint64)));
}
WPM = uas->getWaypointManager();
this->uas = uas;
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)));
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)));
// Update list
read();
}
@ -183,25 +199,13 @@ void WaypointList::setUAS(UASInterface* uas) @@ -183,25 +199,13 @@ void WaypointList::setUAS(UASInterface* uas)
void WaypointList::saveWaypoints()
{
QString fileName = QFileDialog::getSaveFileName(this, tr("Save File"), "./waypoints.txt", tr("Waypoint File (*.txt)"));
WPM->saveWaypoints(fileName);
QString fileName = QFileDialog::getSaveFileName(this, tr("Save File"), "./waypoints.txt", tr("Waypoint File (*.txt)"));
WPM->saveWaypoints(fileName);
}
void WaypointList::loadWaypoints()
{
//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);
msgBox.exec();
showOfflineWarning = false;
}
QString fileName = QFileDialog::getOpenFileName(this, tr("Load File"), ".", tr("Waypoint File (*.txt)"));
WPM->loadWaypoints(fileName);
}
@ -232,115 +236,110 @@ void WaypointList::refresh() @@ -232,115 +236,110 @@ void WaypointList::refresh()
void WaypointList::addEditable()
{
addEditable(false);
}
void WaypointList::addEditable(bool onCurrentPosition)
{
const QVector<Waypoint *> &waypoints = WPM->getWaypointEditableList();
Waypoint *wp;
if (waypoints.size() > 0)
const QList<Waypoint *> &waypoints = WPM->getWaypointEditableList();
Waypoint *wp;
if (waypoints.count() > 0 &&
!(onCurrentPosition && uas && (uas->localPositionKnown() || uas->globalPositionKnown())))
{
// Create waypoint with last frame
Waypoint *last = waypoints.last();
wp = WPM->createWaypoint();
// wp->blockSignals(true);
MAV_FRAME frame = (MAV_FRAME)last->getFrame();
wp->setFrame(frame);
if (frame == MAV_FRAME_GLOBAL || frame == MAV_FRAME_GLOBAL_RELATIVE_ALT)
{
// Create waypoint with last frame
Waypoint *last = waypoints.at(waypoints.size()-1);
wp = new Waypoint(0, last->getX(), last->getY(), last->getZ(), last->getParam1(), last->getParam2(), last->getParam3(), last->getParam4(),
last->getAutoContinue(), false, last->getFrame(), last->getAction());
WPM->addWaypointEditable(wp);
wp->setLatitude(last->getLatitude());
wp->setLongitude(last->getLongitude());
wp->setAltitude(last->getAltitude());
} else {
wp->setX(last->getX());
wp->setY(last->getY());
wp->setZ(last->getZ());
}
else
{
if (uas)
wp->setParam1(last->getParam1());
wp->setParam1(last->getParam2());
wp->setParam1(last->getParam3());
wp->setParam1(last->getParam4());
wp->setAutocontinue(last->getAutoContinue());
// wp->blockSignals(false);
wp->setAction(last->getAction());
// WPM->addWaypointEditable(wp);
}
else
{
if (uas)
{
// Create first waypoint at current MAV position
if (uas->globalPositionKnown())
{
// Create first waypoint at current MAV position
if (uas->localPositionKnown() || uas->globalPositionKnown())
{
if(addCurrentPositionWaypoint())
{
updateStatusLabel(tr("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);
}
}
else
if (onCurrentPosition)
{
// MAV connected, but position unknown, add default waypoint
updateStatusLabel(tr("WARNING: No position known. Adding 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);
if (WPM->getFrameRecommendation() == MAV_FRAME_GLOBAL) {
updateStatusLabel(tr("Added default GLOBAL (Abs alt.) waypoint."));
} else {
updateStatusLabel(tr("Added default GLOBAL (Relative alt.) waypoint."));
}
wp = new Waypoint(0, uas->getLatitude(), uas->getLongitude(), uas->getAltitude(), 0, WPM->getAcceptanceRadiusRecommendation(), 0, 0,true, true, (MAV_FRAME)WPM->getFrameRecommendation(), MAV_CMD_NAV_WAYPOINT);
WPM->addWaypointEditable(wp);
} else {
if (WPM->getFrameRecommendation() == MAV_FRAME_GLOBAL) {
updateStatusLabel(tr("Added default GLOBAL (Abs alt.) waypoint."));
} else {
updateStatusLabel(tr("Added default GLOBAL (Relative alt.) waypoint."));
}
wp = new Waypoint(0, UASManager::instance()->getHomeLatitude(),
UASManager::instance()->getHomeLongitude(),
WPM->getAltitudeRecommendation(), 0, WPM->getAcceptanceRadiusRecommendation(), 0, 0,true, true, (MAV_FRAME)WPM->getFrameRecommendation(), MAV_CMD_NAV_WAYPOINT);
WPM->addWaypointEditable(wp);
}
}
else
else if (uas->localPositionKnown())
{
//Since no UAV available, create first default waypoint.
updateStatusLabel(tr("No UAV connected. Adding 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)
if (onCurrentPosition)
{
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);
msgBox.exec();
showOfflineWarning = false;
updateStatusLabel(tr("Added default LOCAL (NED) waypoint."));
wp = new Waypoint(0, uas->getLocalX(), uas->getLocalY(), uas->getLocalZ(), 0, WPM->getAcceptanceRadiusRecommendation(), 0, 0,true, true, MAV_FRAME_LOCAL_NED, MAV_CMD_NAV_WAYPOINT);
WPM->addWaypointEditable(wp);
} else {
updateStatusLabel(tr("Added default LOCAL (NED) waypoint."));
wp = new Waypoint(0, 0, 0, -0.50, 0, WPM->getAcceptanceRadiusRecommendation(), 0, 0,true, true, MAV_FRAME_LOCAL_NED, MAV_CMD_NAV_WAYPOINT);
WPM->addWaypointEditable(wp);
}
}
}
}
int WaypointList::addCurrentPositionWaypoint()
{
if (uas)
{
const QVector<Waypoint *> &waypoints = WPM->getWaypointEditableList();
Waypoint *wp;
Waypoint *last = 0;
if (waypoints.size() > 0)
{
last = waypoints.at(waypoints.size()-1);
}
if (uas->globalPositionKnown())
{
float acceptanceRadiusGlobal = 10.0f;
float holdTime = 0.0f;
float yawGlobal = 0.0f;
if (last)
{
acceptanceRadiusGlobal = last->getAcceptanceRadius();
holdTime = last->getHoldTime();
yawGlobal = last->getYaw();
}
// Create global frame waypoint per default
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"));
return 0;
}
else if (uas->localPositionKnown())
{
float acceptanceRadiusLocal = 0.2f;
float holdTime = 0.5f;
if (last)
else
{
acceptanceRadiusLocal = last->getAcceptanceRadius();
holdTime = last->getHoldTime();
// MAV connected, but position unknown, add default waypoint
updateStatusLabel(tr("WARNING: No position known. Adding default LOCAL (NED) waypoint"));
wp = new Waypoint(0, UASManager::instance()->getHomeLatitude(),
UASManager::instance()->getHomeLongitude(),
WPM->getAltitudeRecommendation(), 0, WPM->getAcceptanceRadiusRecommendation(), 0, 0,true, true, (MAV_FRAME)WPM->getFrameRecommendation(), MAV_CMD_NAV_WAYPOINT);
WPM->addWaypointEditable(wp);
}
// Create local frame waypoint as second option
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"));
return 0;
}
else
{
// Do nothing
updateStatusLabel(tr("Not adding waypoint, no position of MAV known yet."));
return 1;
//Since no UAV available, create first default waypoint.
updateStatusLabel(tr("No UAV connected. Adding default GLOBAL (NED) waypoint"));
wp = new Waypoint(0, UASManager::instance()->getHomeLatitude(),
UASManager::instance()->getHomeLongitude(),
WPM->getAltitudeRecommendation(), 0, WPM->getAcceptanceRadiusRecommendation(), 0, 0,true, true, (MAV_FRAME)WPM->getFrameRecommendation(), MAV_CMD_NAV_WAYPOINT);
WPM->addWaypointEditable(wp);
}
}
return 1;
}
void WaypointList::addCurrentPositionWaypoint() {
addEditable(true);
}
void WaypointList::updateStatusLabel(const QString &string)
@ -364,11 +363,11 @@ void WaypointList::changeCurrentWaypoint(quint16 seq) @@ -364,11 +363,11 @@ void WaypointList::changeCurrentWaypoint(quint16 seq)
void WaypointList::currentWaypointEditableChanged(quint16 seq)
{
WPM->setCurrentEditable(seq);
const QVector<Waypoint *> &waypoints = WPM->getWaypointEditableList();
const QList<Waypoint *> &waypoints = WPM->getWaypointEditableList();
if (seq < waypoints.size())
if (seq < waypoints.count())
{
for(int i = 0; i < waypoints.size(); i++)
for(int i = 0; i < waypoints.count(); i++)
{
WaypointEditableView* widget = wpEditableViews.find(waypoints[i]).value();
@ -387,11 +386,11 @@ void WaypointList::currentWaypointEditableChanged(quint16 seq) @@ -387,11 +386,11 @@ void WaypointList::currentWaypointEditableChanged(quint16 seq)
// Update waypointViews to correctly indicate the new current waypoint
void WaypointList::currentWaypointViewOnlyChanged(quint16 seq)
{
const QVector<Waypoint *> &waypoints = WPM->getWaypointViewOnlyList();
const QList<Waypoint *> &waypoints = WPM->getWaypointViewOnlyList();
if (seq < waypoints.size())
if (seq < waypoints.count())
{
for(int i = 0; i < waypoints.size(); i++)
for(int i = 0; i < waypoints.count(); i++)
{
WaypointViewOnlyView* widget = wpViewOnlyViews.find(waypoints[i]).value();
@ -425,7 +424,7 @@ void WaypointList::waypointViewOnlyListChanged() @@ -425,7 +424,7 @@ void WaypointList::waypointViewOnlyListChanged()
{
// Prevent updates to prevent visual flicker
this->setUpdatesEnabled(false);
const QVector<Waypoint *> &waypoints = WPM->getWaypointViewOnlyList();
const QList<Waypoint *> &waypoints = WPM->getWaypointViewOnlyList();
if (!wpViewOnlyViews.empty()) {
QMapIterator<Waypoint*,WaypointViewOnlyView*> viewIt(wpViewOnlyViews);
@ -434,12 +433,12 @@ void WaypointList::waypointViewOnlyListChanged() @@ -434,12 +433,12 @@ void WaypointList::waypointViewOnlyListChanged()
viewIt.next();
Waypoint *cur = viewIt.key();
int i;
for (i = 0; i < waypoints.size(); i++) {
for (i = 0; i < waypoints.count(); i++) {
if (waypoints[i] == cur) {
break;
}
}
if (i == waypoints.size()) {
if (i == waypoints.count()) {
WaypointViewOnlyView* widget = wpViewOnlyViews.find(cur).value();
widget->hide();
viewOnlyListLayout->removeWidget(widget);
@ -449,7 +448,7 @@ void WaypointList::waypointViewOnlyListChanged() @@ -449,7 +448,7 @@ void WaypointList::waypointViewOnlyListChanged()
}
// then add/update the views for each waypoint in the list
for(int i = 0; i < waypoints.size(); i++) {
for(int i = 0; i < waypoints.count(); i++) {
Waypoint *wp = waypoints[i];
if (!wpViewOnlyViews.contains(wp)) {
WaypointViewOnlyView* wpview = new WaypointViewOnlyView(wp, this);
@ -477,7 +476,7 @@ void WaypointList::waypointEditableListChanged() @@ -477,7 +476,7 @@ void WaypointList::waypointEditableListChanged()
{
// Prevent updates to prevent visual flicker
this->setUpdatesEnabled(false);
const QVector<Waypoint *> &waypoints = WPM->getWaypointEditableList();
const QList<Waypoint *> &waypoints = WPM->getWaypointEditableList();
if (!wpEditableViews.empty()) {
QMapIterator<Waypoint*,WaypointEditableView*> viewIt(wpEditableViews);
@ -486,12 +485,12 @@ void WaypointList::waypointEditableListChanged() @@ -486,12 +485,12 @@ void WaypointList::waypointEditableListChanged()
viewIt.next();
Waypoint *cur = viewIt.key();
int i;
for (i = 0; i < waypoints.size(); i++) {
for (i = 0; i < waypoints.count(); i++) {
if (waypoints[i] == cur) {
break;
}
}
if (i == waypoints.size()) {
if (i == waypoints.count()) {
WaypointEditableView* widget = wpEditableViews.find(cur).value();
widget->hide();
editableListLayout->removeWidget(widget);
@ -501,7 +500,7 @@ void WaypointList::waypointEditableListChanged() @@ -501,7 +500,7 @@ void WaypointList::waypointEditableListChanged()
}
// then add/update the views for each waypoint in the list
for(int i = 0; i < waypoints.size(); i++) {
for(int i = 0; i < waypoints.count(); i++) {
Waypoint *wp = waypoints[i];
if (!wpEditableViews.contains(wp)) {
WaypointEditableView* wpview = new WaypointEditableView(wp, this);
@ -531,34 +530,34 @@ void WaypointList::waypointEditableListChanged() @@ -531,34 +530,34 @@ void WaypointList::waypointEditableListChanged()
void WaypointList::moveUp(Waypoint* wp)
{
const QVector<Waypoint *> &waypoints = WPM->getWaypointEditableList();
const QList<Waypoint *> &waypoints = WPM->getWaypointEditableList();
//get the current position of wp in the local storage
int i;
for (i = 0; i < waypoints.size(); i++) {
for (i = 0; i < waypoints.count(); i++) {
if (waypoints[i] == wp)
break;
}
// if wp was found and its not the first entry, move it
if (i < waypoints.size() && i > 0) {
if (i < waypoints.count() && i > 0) {
WPM->moveWaypoint(i, i-1);
}
}
void WaypointList::moveDown(Waypoint* wp)
{
const QVector<Waypoint *> &waypoints = WPM->getWaypointEditableList();
const QList<Waypoint *> &waypoints = WPM->getWaypointEditableList();
//get the current position of wp in the local storage
int i;
for (i = 0; i < waypoints.size(); i++) {
for (i = 0; i < waypoints.count(); i++) {
if (waypoints[i] == wp)
break;
}
// if wp was found and its not the last entry, move it
if (i < waypoints.size()-1) {
if (i < waypoints.count()-1) {
WPM->moveWaypoint(i, i+1);
}
}
@ -583,75 +582,27 @@ void WaypointList::changeEvent(QEvent *e) @@ -583,75 +582,27 @@ void WaypointList::changeEvent(QEvent *e)
void WaypointList::on_clearWPListButton_clicked()
{
if (uas) {
emit clearPathclicked();
const QVector<Waypoint *> &waypoints = WPM->getWaypointEditableList();
while(!waypoints.isEmpty()) { //for(int i = 0; i <= waypoints.size(); i++)
const QList<Waypoint *> &waypoints = WPM->getWaypointEditableList();
while(!waypoints.isEmpty()) {
WaypointEditableView* widget = wpEditableViews.find(waypoints[0]).value();
widget->remove();
}
} else {
// if(isGlobalWP)
// {
// emit clearPathclicked();
// }
}
}
///** @brief The MapWidget informs that a waypoint global was changed on the map */
//void WaypointList::waypointGlobalChanged(QPointF coordinate, int indexWP)
//{
// if (uas)
// {
// const QVector<Waypoint *> &waypoints = WPM->getWaypointEditableList();
// if (waypoints.size() > 0)
// {
// Waypoint *temp = waypoints.at(indexWP);
// temp->setX(coordinate.x());
// temp->setY(coordinate.y());
// //WaypointGlobalView* widget = wpGlobalViews.find(waypoints[indexWP]).value();
// //widget->updateValues();
// }
// }
//}
///** @brief The MapWidget informs that a waypoint global was changed on the map */
//void WaypointList::waypointGlobalPositionChanged(Waypoint* wp)
//{
// QPointF coordinate;
// coordinate.setX(wp->getX());
// coordinate.setY(wp->getY());
// emit ChangeWaypointGlobalPosition(wp->getId(), coordinate);
void WaypointList::clearWPWidget()
{
// Get list
const QList<Waypoint *> &waypoints = WPM->getWaypointEditableList();
//}
// XXX delete wps as well
void WaypointList::clearWPWidget()
{
const QVector<Waypoint *> &waypoints = WPM->getWaypointEditableList();
while(!waypoints.isEmpty()) { //for(int i = 0; i <= waypoints.size(); i++)
// Clear UI elements
while(!waypoints.isEmpty()) {
WaypointEditableView* widget = wpEditableViews.find(waypoints[0]).value();
widget->remove();
}
}
}
//void WaypointList::setIsLoadFileWP()
//{
// loadFileGlobalWP = true;
//}
//void WaypointList::setIsReadGlobalWP(bool value)
//{
// // FIXME James Check this
// Q_UNUSED(value);
// // readGlobalWP = value;
//}

8
src/ui/WaypointList.h

@ -56,7 +56,7 @@ class WaypointList : public QWidget @@ -56,7 +56,7 @@ class WaypointList : public QWidget
Q_OBJECT
Q_DISABLE_COPY(WaypointList)
public:
WaypointList(QWidget* parent = NULL, UASInterface* uas = NULL);
WaypointList(QWidget* parent = NULL, UASWaypointManager* wpm = NULL);
virtual ~WaypointList();
public slots:
@ -77,9 +77,11 @@ public slots: @@ -77,9 +77,11 @@ public slots:
/** @brief Read the remote waypoint list to "view"-tab only*/
void refresh();
/** @brief Add a waypoint to "edit"-tab */
void addEditable();
void addEditable();
/** @brief Add a waypoint to "edit"-tab on current MAV position or on generic position (home) */
void addEditable(bool onCurrentPosition);
/** @brief Add a waypoint at the current MAV position */
int addCurrentPositionWaypoint();
void addCurrentPositionWaypoint();
/** @brief Add a waypoint by mouse click over the map */
//Update events

34
src/ui/designer/QGCParamSlider.cc

@ -260,11 +260,7 @@ void QGCParamSlider::endEditMode() @@ -260,11 +260,7 @@ void QGCParamSlider::endEditMode()
switch (parameterValue.type())
{
case QVariant::Char:
ui->intValueSpinBox->show();
break;
case QVariant::Int:
ui->intValueSpinBox->show();
break;
case QVariant::UInt:
ui->intValueSpinBox->show();
break;
@ -378,14 +374,6 @@ void QGCParamSlider::setParameterValue(int uas, int component, int paramCount, i @@ -378,14 +374,6 @@ void QGCParamSlider::setParameterValue(int uas, int component, int paramCount, i
ui->editSelectParamComboBox->addItem(parameterName, paramIndex);
}
if (this->parameterName == "RC5_MIN")
{
int stopper = 1;
}
if (parameterName == "RC5_MIN")
{
int stpoper = 1;
}
if (visibleParam != "")
{
if (parameterName == visibleParam)
@ -424,51 +412,51 @@ void QGCParamSlider::setParameterValue(int uas, int component, int paramCount, i @@ -424,51 +412,51 @@ void QGCParamSlider::setParameterValue(int uas, int component, int paramCount, i
ui->intValueSpinBox->setEnabled(true);
ui->doubleValueSpinBox->hide();
ui->intValueSpinBox->setValue(value.toUInt());
ui->intValueSpinBox->setMinimum(-ui->intValueSpinBox->maximum());
ui->valueSlider->setValue(floatToScaledInt(value.toUInt()));
ui->intValueSpinBox->setRange(0, UINT8_MAX);
if (parameterMax == 0 && parameterMin == 0)
{
ui->editMaxSpinBox->setValue(255);
ui->editMaxSpinBox->setValue(UINT8_MAX);
ui->editMinSpinBox->setValue(0);
}
ui->valueSlider->setValue(floatToScaledInt(value.toUInt()));
break;
case QVariant::Int:
ui->intValueSpinBox->show();
ui->intValueSpinBox->setEnabled(true);
ui->doubleValueSpinBox->hide();
ui->intValueSpinBox->setValue(value.toInt());
ui->valueSlider->setValue(floatToScaledInt(value.toInt()));
ui->intValueSpinBox->setMinimum(-ui->intValueSpinBox->maximum());
ui->intValueSpinBox->setRange(INT32_MIN, INT32_MAX);
if (parameterMax == 0 && parameterMin == 0)
{
ui->editMaxSpinBox->setValue(65535);
ui->editMinSpinBox->setValue(0);
ui->editMaxSpinBox->setValue(INT32_MAX);
ui->editMinSpinBox->setValue(INT32_MIN);
}
ui->valueSlider->setValue(floatToScaledInt(value.toInt()));
break;
case QVariant::UInt:
ui->intValueSpinBox->show();
ui->intValueSpinBox->setEnabled(true);
ui->doubleValueSpinBox->hide();
ui->intValueSpinBox->setValue(value.toUInt());
ui->valueSlider->setValue(floatToScaledInt(value.toUInt()));
ui->intValueSpinBox->setMinimum(0);
ui->intValueSpinBox->setRange(0, UINT32_MAX);
if (parameterMax == 0 && parameterMin == 0)
{
ui->editMaxSpinBox->setValue(65535);
ui->editMaxSpinBox->setValue(UINT32_MAX);
ui->editMinSpinBox->setValue(0);
}
ui->valueSlider->setValue(floatToScaledInt(value.toUInt()));
break;
case QMetaType::Float:
ui->doubleValueSpinBox->setValue(value.toFloat());
ui->doubleValueSpinBox->show();
ui->doubleValueSpinBox->setEnabled(true);
ui->intValueSpinBox->hide();
ui->valueSlider->setValue(floatToScaledInt(value.toFloat()));
if (parameterMax == 0 && parameterMin == 0)
{
ui->editMaxSpinBox->setValue(10000);
ui->editMinSpinBox->setValue(0);
}
ui->valueSlider->setValue(floatToScaledInt(value.toFloat()));
break;
default:
qCritical() << "ERROR: NO VALID PARAM TYPE";

162
src/ui/map/QGCMapWidget.cc

@ -17,10 +17,10 @@ QGCMapWidget::QGCMapWidget(QWidget *parent) : @@ -17,10 +17,10 @@ QGCMapWidget::QGCMapWidget(QWidget *parent) :
followUAVID(0),
mapInitialized(false),
homeAltitude(0),
uas(0)
uas(NULL)
{
//currWPManager = new UASWaypointManager(NULL); //Create a waypoint manager that is null.
currWPManager = UASManager::instance()->getActiveUASWaypointManager();
waypointLines.insert(0, new QGraphicsItemGroup(map));
connect(currWPManager, SIGNAL(waypointEditableListChanged(int)), this, SLOT(updateWaypointList(int)));
connect(currWPManager, SIGNAL(waypointEditableChanged(int, Waypoint*)), this, SLOT(updateWaypoint(int,Waypoint*)));
connect(this, SIGNAL(waypointCreated(Waypoint*)), currWPManager, SLOT(addWaypointEditable(Waypoint*)));
@ -207,6 +207,18 @@ void QGCMapWidget::loadSettings(bool changePosition) @@ -207,6 +207,18 @@ void QGCMapWidget::loadSettings(bool changePosition)
trailInterval = settings.value("TRAIL_INTERVAL", trailInterval).toFloat();
settings.endGroup();
// SET CORRECT MENU CHECKBOXES
// Set the correct trail interval
if (trailType == mapcontrol::UAVTrailType::ByDistance)
{
// XXX
#warning Settings loading for trail type not implemented
}
else if (trailType == mapcontrol::UAVTrailType::ByTimeElapsed)
{
// XXX
}
// SET TRAIL TYPE
foreach (mapcontrol::UAVItem* uav, GetUAVS())
{
@ -245,25 +257,22 @@ void QGCMapWidget::storeSettings() @@ -245,25 +257,22 @@ void QGCMapWidget::storeSettings()
void QGCMapWidget::mouseDoubleClickEvent(QMouseEvent* event)
{
// FIXME HACK!
//if (currEditMode == EDIT_MODE_WAYPOINTS)
// If a waypoint manager is available
if (currWPManager)
{
// If a waypoint manager is available
if (currWPManager)
{
// Create new waypoint
internals::PointLatLng pos = map->FromLocalToLatLng(event->pos().x(), event->pos().y());
Waypoint* wp = currWPManager->createWaypoint();
// wp->blockSignals(true);
// wp->setFrame(MAV_FRAME_GLOBAL_RELATIVE_ALT);
wp->setLatitude(pos.Lat());
wp->setLongitude(pos.Lng());
wp->setAltitude(0);
// wp->blockSignals(false);
// currWPManager->notifyOfChangeEditable(wp);
}
// Create new waypoint
internals::PointLatLng pos = map->FromLocalToLatLng(event->pos().x(), event->pos().y());
Waypoint* wp = currWPManager->createWaypoint();
// wp->blockSignals(true);
// wp->setFrame(MAV_FRAME_GLOBAL_RELATIVE_ALT);
wp->setLatitude(pos.Lat());
wp->setLongitude(pos.Lng());
wp->setFrame((MAV_FRAME)currWPManager->getFrameRecommendation());
wp->setAltitude(currWPManager->getAltitudeRecommendation());
// wp->blockSignals(false);
// currWPManager->notifyOfChangeEditable(wp);
}
OPMapWidget::mouseDoubleClickEvent(event);
}
@ -276,6 +285,14 @@ void QGCMapWidget::addUAS(UASInterface* uas) @@ -276,6 +285,14 @@ void QGCMapWidget::addUAS(UASInterface* uas)
{
connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateGlobalPosition(UASInterface*,double,double,double,quint64)));
connect(uas, SIGNAL(systemSpecsChanged(int)), this, SLOT(updateSystemSpecs(int)));
if (!waypointLines.value(uas->getUASID(), NULL)) {
waypointLines.insert(uas->getUASID(), new QGraphicsItemGroup(map));
} else {
foreach (QGraphicsItem* item, waypointLines.value(uas->getUASID())->childItems())
{
delete item;
}
}
}
void QGCMapWidget::activeUASSet(UASInterface* uas)
@ -294,45 +311,17 @@ void QGCMapWidget::activeUASSet(UASInterface* uas) @@ -294,45 +311,17 @@ void QGCMapWidget::activeUASSet(UASInterface* uas)
disconnect(this, SIGNAL(waypointChanged(Waypoint*)), currWPManager, SLOT(notifyOfChangeEditable(Waypoint*)));
}
if (uas)
{
//UASWaypointManager *old = currWPManager;
currWPManager = uas->getWaypointManager();
updateSelectedSystem(uas->getUASID());
followUAVID = uas->getUASID();
updateWaypointList(uas->getUASID());
currWPManager = uas->getWaypointManager();
// Connect the waypoint manager / data storage to the UI
connect(currWPManager, SIGNAL(waypointEditableListChanged(int)), this, SLOT(updateWaypointList(int)));
connect(currWPManager, SIGNAL(waypointEditableChanged(int, Waypoint*)), this, SLOT(updateWaypoint(int,Waypoint*)));
connect(this, SIGNAL(waypointCreated(Waypoint*)), currWPManager, SLOT(addWaypointEditable(Waypoint*)));
connect(this, SIGNAL(waypointChanged(Waypoint*)), currWPManager, SLOT(notifyOfChangeEditable(Waypoint*)));
updateSelectedSystem(uas->getUASID());
followUAVID = uas->getUASID();
updateWaypointList(uas->getUASID());
/*if (offlineMode)
{
if (QMessageBox::question(0,"Question","Do you want to append the offline waypoints to the ones currently on the UAV?",QMessageBox::Yes,QMessageBox::No) == QMessageBox::Yes)
{
//Need to transfer all waypoints from the offline mode WPManager to the online mode.
for (int i=0;i<old->getWaypointEditableList().size();i++)
{
Waypoint *wp = currWPManager->createWaypoint();
wp->setLatitude(old->getWaypointEditableList()[i]->getLatitude());
wp->setLongitude(old->getWaypointEditableList()[i]->getLongitude());
wp->setAltitude(old->getWaypointEditableList()[i]->getAltitude());
}
}
offlineMode = false;
old->deleteLater();
}*/
// Delete all waypoints and add waypoint from new system
}
// Connect the waypoint manager / data storage to the UI
connect(currWPManager, SIGNAL(waypointEditableListChanged(int)), this, SLOT(updateWaypointList(int)));
connect(currWPManager, SIGNAL(waypointEditableChanged(int, Waypoint*)), this, SLOT(updateWaypoint(int,Waypoint*)));
connect(this, SIGNAL(waypointCreated(Waypoint*)), currWPManager, SLOT(addWaypointEditable(Waypoint*)));
connect(this, SIGNAL(waypointChanged(Waypoint*)), currWPManager, SLOT(notifyOfChangeEditable(Waypoint*)));
}
/**
@ -360,9 +349,17 @@ void QGCMapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lo @@ -360,9 +349,17 @@ void QGCMapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lo
newUAV->setParentItem(map);
UAVS.insert(uas->getUASID(), newUAV);
uav = GetUAV(uas->getUASID());
uav->SetTrailTime(1);
uav->SetTrailDistance(5);
uav->SetTrailType(mapcontrol::UAVTrailType::ByTimeElapsed);
// Set the correct trail type
uav->SetTrailType(trailType);
// Set the correct trail interval
if (trailType == mapcontrol::UAVTrailType::ByDistance)
{
uav->SetTrailDistance(trailInterval);
}
else if (trailType == mapcontrol::UAVTrailType::ByTimeElapsed)
{
uav->SetTrailTime(trailInterval);
}
}
// Set new lat/lon position of UAV icon
@ -551,6 +548,11 @@ void QGCMapWidget::handleMapWaypointEdit(mapcontrol::WayPointItem* waypoint) @@ -551,6 +548,11 @@ void QGCMapWidget::handleMapWaypointEdit(mapcontrol::WayPointItem* waypoint)
{
// Block circle updates
Waypoint* wp = iconsToWaypoints.value(waypoint, NULL);
// Delete UI element if wp doesn't exist
if (!wp)
WPDelete(waypoint);
// Protect from vicious double update cycle
if (firingWaypointChange == wp) return;
// Not in cycle, block now from entering it
@ -565,8 +567,8 @@ void QGCMapWidget::handleMapWaypointEdit(mapcontrol::WayPointItem* waypoint) @@ -565,8 +567,8 @@ void QGCMapWidget::handleMapWaypointEdit(mapcontrol::WayPointItem* waypoint)
wp->setLatitude(pos.Lat());
wp->setLongitude(pos.Lng());
// XXX Magic values
wp->setAltitude(homeAltitude + 50.0f);
wp->setAcceptanceRadius(10.0f);
// wp->setAltitude(homeAltitude + 50.0f);
// wp->setAcceptanceRadius(10.0f);
wp->blockSignals(false);
@ -589,13 +591,15 @@ void QGCMapWidget::handleMapWaypointEdit(mapcontrol::WayPointItem* waypoint) @@ -589,13 +591,15 @@ void QGCMapWidget::handleMapWaypointEdit(mapcontrol::WayPointItem* waypoint)
*/
void QGCMapWidget::updateWaypoint(int uas, Waypoint* wp)
{
qDebug() << "UPDATING WP FUNCTION CALLED";
qDebug() << __FILE__ << __LINE__ << "UPDATING WP FUNCTION CALLED";
// Source of the event was in this widget, do nothing
if (firingWaypointChange == wp) return;
if (firingWaypointChange == wp) {
return;
}
// Currently only accept waypoint updates from the UAS in focus
// this has to be changed to accept read-only updates from other systems as well.
UASInterface* uasInstance = UASManager::instance()->getUASForId(uas);
if (!uasInstance || uasInstance->getWaypointManager() == currWPManager || uas == -1)
if (currWPManager)
{
// Only accept waypoints in global coordinate frame
if (((wp->getFrame() == MAV_FRAME_GLOBAL) || (wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT)) && wp->isNavigationType())
@ -607,7 +611,7 @@ void QGCMapWidget::updateWaypoint(int uas, Waypoint* wp) @@ -607,7 +611,7 @@ void QGCMapWidget::updateWaypoint(int uas, Waypoint* wp)
// as we're only handling global waypoints
int wpindex = currWPManager->getGlobalFrameAndNavTypeIndexOf(wp);
// If not found, return (this should never happen, but helps safety)
if (wpindex == -1) return;
if (wpindex < 0) return;
// Mark this wp as currently edited
firingWaypointChange = wp;
@ -630,7 +634,7 @@ void QGCMapWidget::updateWaypoint(int uas, Waypoint* wp) @@ -630,7 +634,7 @@ void QGCMapWidget::updateWaypoint(int uas, Waypoint* wp)
if (wpindex > 0)
{
// Get predecessor of this WP
QVector<Waypoint* > wps = currWPManager->getGlobalFrameAndNavTypeWaypointList();
QList<Waypoint* > wps = currWPManager->getGlobalFrameAndNavTypeWaypointList();
Waypoint* wp1 = wps.at(wpindex-1);
mapcontrol::WayPointItem* prevIcon = waypointsToIcons.value(wp1, NULL);
// If we got a valid graphics item, continue
@ -686,7 +690,7 @@ void QGCMapWidget::updateWaypoint(int uas, Waypoint* wp) @@ -686,7 +690,7 @@ void QGCMapWidget::updateWaypoint(int uas, Waypoint* wp)
// waypoint list. This implies that the coordinate frame of this
// waypoint was changed and the list containing only global
// waypoints was shortened. Thus update the whole list
if (waypointsToIcons.size() > currWPManager->getGlobalFrameAndNavTypeCount())
if (waypointsToIcons.count() > currWPManager->getGlobalFrameAndNavTypeCount())
{
updateWaypointList(uas);
}
@ -705,16 +709,26 @@ void QGCMapWidget::updateWaypointList(int uas) @@ -705,16 +709,26 @@ void QGCMapWidget::updateWaypointList(int uas)
// Currently only accept waypoint updates from the UAS in focus
// this has to be changed to accept read-only updates from other systems as well.
UASInterface* uasInstance = UASManager::instance()->getUASForId(uas);
if ((uasInstance && (uasInstance->getWaypointManager() == currWPManager)) || uas == -1)
if (currWPManager)
{
// ORDER MATTERS HERE!
// TWO LOOPS ARE NEEDED - INFINITY LOOP ELSE
qDebug() << "DELETING NOW OLD WPS";
// Delete connecting waypoint lines
QGraphicsItemGroup* group = waypointLines.value(uas, NULL);
if (group)
{
foreach (QGraphicsItem* item, group->childItems())
{
delete item;
}
}
// Delete first all old waypoints
// this is suboptimal (quadratic, but wps should stay in the sub-100 range anyway)
QVector<Waypoint* > wps = currWPManager->getGlobalFrameAndNavTypeWaypointList();
QList<Waypoint* > wps = currWPManager->getGlobalFrameAndNavTypeWaypointList();
foreach (Waypoint* wp, waypointsToIcons.keys())
{
if (!wps.contains(wp))
@ -742,16 +756,6 @@ void QGCMapWidget::updateWaypointList(int uas) @@ -742,16 +756,6 @@ void QGCMapWidget::updateWaypointList(int uas)
if (!waypointsToIcons.contains(wp)) updateWaypoint(uas, wp);
}
// Delete connecting waypoint lines
QGraphicsItemGroup* group = waypointLines.value(uas, NULL);
if (group)
{
foreach (QGraphicsItem* item, group->childItems())
{
delete item;
}
}
// Add line element if this is NOT the first waypoint
mapcontrol::WayPointItem* prevIcon = NULL;
foreach (Waypoint* wp, wps)

8
src/ui/map3D/Pixhawk3DWidget.cc

@ -834,7 +834,7 @@ Pixhawk3DWidget::moveWaypointPosition(void) @@ -834,7 +834,7 @@ Pixhawk3DWidget::moveWaypointPosition(void)
return;
}
const QVector<Waypoint *> waypoints =
const QList<Waypoint *> waypoints =
mActiveUAS->getWaypointManager()->getWaypointEditableList();
Waypoint* waypoint = waypoints.at(mSelectedWpIndex);
@ -882,7 +882,7 @@ Pixhawk3DWidget::moveWaypointHeading(void) @@ -882,7 +882,7 @@ Pixhawk3DWidget::moveWaypointHeading(void)
return;
}
const QVector<Waypoint *> waypoints =
const QList<Waypoint *> waypoints =
mActiveUAS->getWaypointManager()->getWaypointEditableList();
Waypoint* waypoint = waypoints.at(mSelectedWpIndex);
@ -929,7 +929,7 @@ Pixhawk3DWidget::setWaypointAltitude(void) @@ -929,7 +929,7 @@ Pixhawk3DWidget::setWaypointAltitude(void)
}
bool ok;
const QVector<Waypoint *> waypoints =
const QList<Waypoint *> waypoints =
mActiveUAS->getWaypointManager()->getWaypointEditableList();
Waypoint* waypoint = waypoints.at(mSelectedWpIndex);
@ -960,7 +960,7 @@ Pixhawk3DWidget::clearAllWaypoints(void) @@ -960,7 +960,7 @@ Pixhawk3DWidget::clearAllWaypoints(void)
{
if (mActiveUAS)
{
const QVector<Waypoint *> waypoints =
const QList<Waypoint *> waypoints =
mActiveUAS->getWaypointManager()->getWaypointEditableList();
for (int i = waypoints.size() - 1; i >= 0; --i)
{

4
src/ui/map3D/QGCGoogleEarthView.cc

@ -265,7 +265,7 @@ void QGCGoogleEarthView::updateWaypointList(int uas) @@ -265,7 +265,7 @@ void QGCGoogleEarthView::updateWaypointList(int uas)
if (uasInstance)
{
// Get all waypoints, including non-global waypoints
QVector<Waypoint*> wpList = uasInstance->getWaypointManager()->getGlobalFrameAndNavTypeWaypointList();
QList<Waypoint*> wpList = uasInstance->getWaypointManager()->getGlobalFrameAndNavTypeWaypointList();
// Trim internal list to number of global waypoints in the waypoint manager list
javaScript(QString("updateWaypointListLength(%1,%2);").arg(uas).arg(wpList.count()));
@ -712,7 +712,7 @@ void QGCGoogleEarthView::updateState() @@ -712,7 +712,7 @@ void QGCGoogleEarthView::updateState()
// Update waypoint or symbol
if (mav)
{
QVector<Waypoint*> wps = mav->getWaypointManager()->getGlobalFrameAndNavTypeWaypointList();
QList<Waypoint*> wps = mav->getWaypointManager()->getGlobalFrameAndNavTypeWaypointList();
bool ok;
int index = idText.toInt(&ok);

13
src/ui/map3D/WaypointGroupNode.cc

@ -36,6 +36,7 @@ This file is part of the QGROUNDCONTROL project @@ -36,6 +36,7 @@ This file is part of the QGROUNDCONTROL project
#include <osg/ShapeDrawable>
#include "Imagery.h"
#include "UASManager.h"
WaypointGroupNode::WaypointGroupNode(const QColor& color)
: mColor(color)
@ -70,6 +71,16 @@ WaypointGroupNode::update(UASInterface* uas, MAV_FRAME frame) @@ -70,6 +71,16 @@ WaypointGroupNode::update(UASInterface* uas, MAV_FRAME frame)
Imagery::LLtoUTM(latitude, longitude, robotX, robotY, utmZone);
robotZ = -altitude;
}
else if (frame == MAV_FRAME_GLOBAL_RELATIVE_ALT)
{
double latitude = uas->getLatitude();
double longitude = uas->getLongitude();
double altitude = uas->getAltitude() + UASManager::instance()->getHomeAltitude();
QString utmZone;
Imagery::LLtoUTM(latitude, longitude, robotX, robotY, utmZone);
robotZ = -altitude;
}
else if (frame == MAV_FRAME_LOCAL_NED)
{
robotX = uas->getLocalX();
@ -82,7 +93,7 @@ WaypointGroupNode::update(UASInterface* uas, MAV_FRAME frame) @@ -82,7 +93,7 @@ WaypointGroupNode::update(UASInterface* uas, MAV_FRAME frame)
removeChild(0, getNumChildren());
}
const QVector<Waypoint *>& list = uas->getWaypointManager()->getWaypointEditableList();
const QList<Waypoint *>& list = uas->getWaypointManager()->getWaypointEditableList();
for (int i = 0; i < list.size(); i++)
{

Loading…
Cancel
Save