Commit 4e1c7dcf authored by pixhawk's avatar pixhawk

Improved application persistence

parent 73436f42
......@@ -157,6 +157,9 @@ Core::Core(int &argc, char* argv[]) : QApplication(argc, argv)
**/
Core::~Core()
{
mainWindow->storeSettings();
mainWindow->hide();
mainWindow->deleteLater();
// Delete singletons
delete LinkManager::instance();
delete UASManager::instance();
......
......@@ -30,9 +30,11 @@ This file is part of the QGROUNDCONTROL project
#include <QTimer>
#include <QDebug>
#include <QSettings>
#include <QMutexLocker>
#include "SerialLink.h"
#include "LinkManager.h"
#include "QGC.h"
#include <MG.h>
#ifdef _WIN32
#include "windows.h"
......@@ -54,12 +56,26 @@ SerialLink::SerialLink(QString portname, BaudRateType baudrate, FlowType flow, P
#endif
// Set unique ID and add link to the list of links
this->id = getNextLinkId();
this->baudrate = baudrate;
this->flow = flow;
this->parity = parity;
this->dataBits = dataBits;
this->stopBits = stopBits;
this->timeout = 1; ///< The timeout controls how long the program flow should wait for new serial bytes. As we're polling, we don't want to wait at all.
// Load defaults from settings
QSettings settings(QGC::COMPANYNAME, QGC::APPNAME);
if (settings.contains("SERIALLINK_COMM_PORT"))
{
this->porthandle = settings.value("SERIALLINK_COMM_PORT").toString();
setBaudRate(settings.value("SERIALLINK_COMM_BAUD").toInt());
setParityType(settings.value("SERIALLINK_COMM_PARITY").toInt());
setStopBitsType(settings.value("SERIALLINK_COMM_STOPBITS").toInt());
setDataBitsType(settings.value("SERIALLINK_COMM_DATABITS").toInt());
}
else
{
this->baudrate = baudrate;
this->flow = flow;
this->parity = parity;
this->dataBits = dataBits;
this->stopBits = stopBits;
this->timeout = 1; ///< The timeout controls how long the program flow should wait for new serial bytes. As we're polling, we don't want to wait at all.
}
// Set the port name
if (porthandle == "")
......@@ -282,6 +298,15 @@ bool SerialLink::connect()
**/
bool SerialLink::hardwareConnect()
{
// Store settings
QSettings settings(QGC::COMPANYNAME, QGC::APPNAME);
settings.setValue("SERIALLINK_COMM_PORT", this->porthandle);
settings.setValue("SERIALLINK_COMM_BAUD", this->baudrate);
settings.setValue("SERIALLINK_COMM_PARITY", this->parity);
settings.setValue("SERIALLINK_COMM_STOPBITS", this->stopBits);
settings.setValue("SERIALLINK_COMM_DATABITS", this->dataBits);
settings.sync();
QObject::connect(port, SIGNAL(aboutToClose()), this, SIGNAL(disconnected()));
port->open(QIODevice::ReadWrite);
......
......@@ -365,9 +365,10 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
positionLock = true;
// Send to patch antenna
mavlink_message_t msg;
mavlink_msg_global_position_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, pos.usec, pos.lat, pos.lon, pos.alt, pos.vx, pos.vy, pos.vz);
sendMessage(msg);
// FIXME Message re-routing should be implemented differently
//mavlink_message_t msg;
//mavlink_msg_global_position_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, pos.usec, pos.lat, pos.lon, pos.alt, pos.vx, pos.vy, pos.vz);
//sendMessage(msg);
}
break;
case MAVLINK_MSG_ID_GPS_RAW:
......
......@@ -16,6 +16,7 @@
#include <QHostInfo>
#include "MG.h"
#include "QGC.h"
#include "MAVLinkSimulationLink.h"
#include "SerialLink.h"
#include "UDPLink.h"
......@@ -89,6 +90,32 @@ MainWindow::MainWindow(QWidget *parent) :
// QMenu* centerMenu = createCenterWidgetMenu();
// centerMenu->setTitle("Center");
// ui.menuBar->addMenu(centerMenu);
// Load previous widget setup
// FIXME WORK IN PROGRESS
QSettings settings(QGC::COMPANYNAME, QGC::APPNAME);
QList<QDockWidget *> dockwidgets = qFindChildren<QDockWidget *>(this);
if (dockwidgets.size())
{
settings.beginGroup("mainwindow/dockwidgets");
for (int i = 0; i < dockwidgets.size(); ++i)
{
QDockWidget *dockWidget = dockwidgets.at(i);
if (dockWidget->parentWidget() == this)
{
if (settings.contains(dockWidget->windowTitle()))
{
dockWidget->setVisible(settings.value(dockWidget->windowTitle(), dockWidget->isVisible()).toBool());
}
}
}
settings.endGroup();
}
this->show();
}
......@@ -98,6 +125,27 @@ MainWindow::~MainWindow()
statusBar = NULL;
}
void MainWindow::storeSettings()
{
QSettings settings(QGC::COMPANYNAME, QGC::APPNAME);
QList<QDockWidget *> dockwidgets = qFindChildren<QDockWidget *>(this);
if (dockwidgets.size())
{
settings.beginGroup("mainwindow/dockwidgets");
for (int i = 0; i < dockwidgets.size(); ++i)
{
QDockWidget *dockWidget = dockwidgets.at(i);
if (dockWidget->parentWidget() == this)
{
settings.setValue(dockWidget->windowTitle(), QVariant(dockWidget->isVisible()));
}
}
settings.endGroup();
}
settings.sync();
}
QMenu* MainWindow::createCenterWidgetMenu()
{
QMenu* menu = NULL;
......
......@@ -87,6 +87,9 @@ public:
~MainWindow();
public slots:
/** @brief Store the mainwindow settings */
void storeSettings();
/**
* @brief Shows a status message on the bottom status bar
*
......
......@@ -33,6 +33,7 @@ This file is part of the QGROUNDCONTROL project
#include <SerialConfigurationWindow.h>
#include <SerialLinkInterface.h>
#include <QDir>
#include <QSettings>
#include <QFileInfoList>
#ifdef _WIN32
#include <QextSerialEnumerator.h>
......
......@@ -57,6 +57,7 @@ void XMLCommProtocolWidget::selectXMLFile()
setXML(instanceText);
// Store filename for next time
settings.setValue(mavlinkXML, QFileInfo(file).absoluteFilePath());
settings.sync();
}
else
{
......@@ -112,6 +113,7 @@ void XMLCommProtocolWidget::selectOutputDirectory()
m_ui->outputDirNameLabel->setText(fileNames.first());
// Store directory for next time
settings.setValue(mavlinkOutputDir, QFileInfo(fileNames.first()).absoluteFilePath());
settings.sync();
//QFile file(fileName);
}
}
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment