Commit 0a313314 authored by dogmaphobic's avatar dogmaphobic
Browse files

The ultimate goal is to plug a device, set it up and go fly it without any fuss.

The goal of this first installment is to organize the code a bit so it's more readable,
clean up a bit of left over cruft, and manage link configurations (and links in general).
parent e411b95c
......@@ -271,7 +271,6 @@ INCLUDEPATH += \
FORMS += \
src/ui/MainWindow.ui \
src/ui/CommSettings.ui \
src/ui/SerialSettings.ui \
src/ui/UASControl.ui \
src/ui/UASList.ui \
......@@ -300,7 +299,6 @@ FORMS += \
src/ui/QGCMAVLinkLogPlayer.ui \
src/ui/QGCWaypointListMulti.ui \
src/ui/QGCUASFileViewMulti.ui \
src/ui/QGCUDPLinkConfiguration.ui \
src/ui/QGCTCPLinkConfiguration.ui \
src/ui/SettingsDialog.ui \
src/ui/map/QGCMapTool.ui \
......@@ -344,6 +342,9 @@ FORMS += \
src/ui/QGCUASFileView.ui \
src/QGCQmlWidgetHolder.ui \
src/ui/QGCMapRCToParamDialog.ui \
src/ui/QGCLinkConfiguration.ui \
src/ui/QGCCommConfiguration.ui \
src/ui/QGCUDPLinkConfiguration.ui
HEADERS += \
src/MG.h \
......@@ -354,14 +355,12 @@ HEADERS += \
src/uas/UASManager.h \
src/comm/LinkManager.h \
src/comm/LinkInterface.h \
src/comm/SerialLinkInterface.h \
src/comm/SerialLink.h \
src/comm/ProtocolInterface.h \
src/comm/MAVLinkProtocol.h \
src/comm/QGCFlightGearLink.h \
src/comm/QGCJSBSimLink.h \
src/comm/QGCXPlaneLink.h \
src/ui/CommConfigurationWindow.h \
src/ui/SerialConfigurationWindow.h \
src/ui/MainWindow.h \
src/ui/uas/UASControlWidget.h \
......@@ -416,7 +415,6 @@ HEADERS += \
src/uas/QGCMAVLinkUASFactory.h \
src/ui/QGCWaypointListMulti.h \
src/ui/QGCUASFileViewMulti.h \
src/ui/QGCUDPLinkConfiguration.h \
src/ui/QGCTCPLinkConfiguration.h \
src/ui/SettingsDialog.h \
src/uas/QGCUASParamManager.h \
......@@ -497,6 +495,10 @@ HEADERS += \
src/ui/QGCParamTreeWidget.h \
src/ui/QGCMapRCToParamDialog.h \
src/QGCDockWidget.h \
src/ui/QGCLinkConfiguration.h \
src/comm/LinkConfiguration.h \
src/ui/QGCCommConfiguration.h \
src/ui/QGCUDPLinkConfiguration.h
SOURCES += \
src/main.cc \
......@@ -510,7 +512,6 @@ SOURCES += \
src/comm/QGCFlightGearLink.cc \
src/comm/QGCJSBSimLink.cc \
src/comm/QGCXPlaneLink.cc \
src/ui/CommConfigurationWindow.cc \
src/ui/SerialConfigurationWindow.cc \
src/ui/MainWindow.cc \
src/ui/uas/UASControlWidget.cc \
......@@ -563,7 +564,6 @@ SOURCES += \
src/uas/QGCMAVLinkUASFactory.cc \
src/ui/QGCWaypointListMulti.cc \
src/ui/QGCUASFileViewMulti.cc \
src/ui/QGCUDPLinkConfiguration.cc \
src/ui/QGCTCPLinkConfiguration.cc \
src/ui/SettingsDialog.cc \
src/uas/QGCUASParamManager.cc \
......@@ -639,6 +639,10 @@ SOURCES += \
src/ui/QGCParamTreeWidget.cpp \
src/ui/QGCMapRCToParamDialog.cpp \
src/QGCDockWidget.cc \
src/ui/QGCLinkConfiguration.cc \
src/comm/LinkConfiguration.cc \
src/ui/QGCCommConfiguration.cc \
src/ui/QGCUDPLinkConfiguration.cc
#
# Unit Test specific configuration goes here
......
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009 - 2015 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
......@@ -97,18 +97,18 @@ QGCApplication::QGCApplication(int &argc, char* argv[], bool unitTesting) :
{
Q_ASSERT(_app == NULL);
_app = this;
// This prevents usage of QQuickWidget to fail since it doesn't support native widget siblings
setAttribute(Qt::AA_DontCreateNativeWidgetSiblings);
#ifdef QT_DEBUG
// First thing we want to do is set up the qtlogging.ini file. If it doesn't already exist we copy
// it to the correct location. This way default debug builds will have logging turned off.
static const char* qtProjectDir = "QtProject";
static const char* qtLoggingFile = "qtlogging.ini";
bool loggingDirectoryOk = false;
QDir iniFileLocation(QStandardPaths::writableLocation(QStandardPaths::GenericConfigLocation));
if (!iniFileLocation.cd(qtProjectDir)) {
if (!iniFileLocation.mkdir(qtProjectDir)) {
......@@ -122,7 +122,7 @@ QGCApplication::QGCApplication(int &argc, char* argv[], bool unitTesting) :
} else {
loggingDirectoryOk = true;
}
if (loggingDirectoryOk) {
qDebug () << iniFileLocation;
if (!iniFileLocation.exists(qtLoggingFile)) {
......@@ -132,7 +132,7 @@ QGCApplication::QGCApplication(int &argc, char* argv[], bool unitTesting) :
}
}
#endif
// Set application information
if (_runningUnitTests) {
// We don't want unit tests to use the same QSettings space as the normal app. So we tweak the app
......@@ -143,37 +143,37 @@ QGCApplication::QGCApplication(int &argc, char* argv[], bool unitTesting) :
}
setOrganizationName(QGC_ORG_NAME);
setOrganizationDomain(QGC_ORG_DOMAIN);
// Version string is build from component parts. Format is:
// vMajor.Minor.BuildNumber BuildType
QString versionString("v%1.%2.%3 %4");
versionString = versionString.arg(QGC_APPLICATION_VERSION_MAJOR).arg(QGC_APPLICATION_VERSION_MINOR).arg(QGC_APPLICATION_VERSION_BUILDNUMBER).arg(QGC_APPLICATION_VERSION_BUILDTYPE);
this->setApplicationVersion(versionString);
// Set settings format
QSettings::setDefaultFormat(QSettings::IniFormat);
// Parse command line options
bool fClearSettingsOptions = false; // Clear stored settings
CmdLineOpt_t rgCmdLineOptions[] = {
{ "--clear-settings", &fClearSettingsOptions, QString() },
// Add additional command line option flags here
};
ParseCmdLineOptions(argc, argv, rgCmdLineOptions, sizeof(rgCmdLineOptions)/sizeof(rgCmdLineOptions[0]), false);
QSettings settings;
// The setting will delete all settings on this boot
fClearSettingsOptions |= settings.contains(_deleteAllSettingsKey);
if (_runningUnitTests) {
// Unit tests run with clean settings
fClearSettingsOptions = true;
}
if (fClearSettingsOptions) {
// User requested settings to be cleared on command line
settings.clear();
......@@ -189,7 +189,7 @@ QGCApplication::~QGCApplication()
void QGCApplication::_initCommon(void)
{
QSettings settings;
// Show user an upgrade message if the settings version has been bumped up
bool settingsUpgraded = false;
if (settings.contains(_settingsVersionKey)) {
......@@ -200,7 +200,7 @@ void QGCApplication::_initCommon(void)
// Settings version key is missing and there are settings. This is an upgrade scenario.
settingsUpgraded = true;
}
if (settingsUpgraded) {
settings.clear();
settings.setValue(_settingsVersionKey, QGC_SETTINGS_VERSION);
......@@ -208,29 +208,29 @@ void QGCApplication::_initCommon(void)
tr("The format for QGroundControl saved settings has been modified. "
"Your saved settings have been reset to defaults."));
}
_styleIsDark = settings.value(_styleKey, _styleIsDark).toBool();
_loadCurrentStyle();
// Load saved files location and validate
QString savedFilesLocation;
if (settings.contains(_savedFilesLocationKey)) {
savedFilesLocation = settings.value(_savedFilesLocationKey).toString();
} else {
// No location set. Create a default one in Documents standard location.
QString documentsLocation = QStandardPaths::writableLocation(QStandardPaths::DocumentsLocation);
QDir documentsDir(documentsLocation);
Q_ASSERT(documentsDir.exists());
bool pathCreated = documentsDir.mkpath(_defaultSavedFileDirectoryName);
Q_UNUSED(pathCreated);
Q_ASSERT(pathCreated);
savedFilesLocation = documentsDir.filePath(_defaultSavedFileDirectoryName);
}
if (!savedFilesLocation.isEmpty()) {
if (!validatePossibleSavedFilesLocation(savedFilesLocation)) {
savedFilesLocation.clear();
......@@ -255,9 +255,9 @@ void QGCApplication::_initCommon(void)
bool QGCApplication::_initForNormalAppBoot(void)
{
QSettings settings;
_createSingletons();
// Show splash screen
QPixmap splashImage(":/files/images/splash.png");
QSplashScreen* splashScreen = new QSplashScreen(splashImage);
......@@ -266,7 +266,6 @@ bool QGCApplication::_initForNormalAppBoot(void)
splashScreen->show();
processEvents();
splashScreen->showMessage(tr("Loading application fonts"), Qt::AlignLeft | Qt::AlignBottom, QColor(62, 93, 141));
// Exit main application when last window is closed
connect(this, SIGNAL(lastWindowClosed()), this, SLOT(quit()));
......@@ -274,17 +273,18 @@ bool QGCApplication::_initForNormalAppBoot(void)
splashScreen->showMessage(tr("Starting user interface"), Qt::AlignLeft | Qt::AlignBottom, QColor(62, 93, 141));
MainWindow* mainWindow = MainWindow::_create(splashScreen);
Q_CHECK_PTR(mainWindow);
// If we made it this far and we still don't have a location. Either the specfied location was invalid
// or we coudn't create a default location. Either way, we need to let the user know and prompt for a new
/// settings.
QString savedFilesLocation = settings.value(_savedFilesLocationKey).toString();
if (savedFilesLocation.isEmpty()) {
QGCMessageBox::warning(tr("Bad save location"),
tr("The location to save files to is invalid, or cannot be written to. Please provide a new one."));
QGCMessageBox::warning(
tr("Bad save location"),
tr("The location to save files to is invalid, or cannot be written to. Please provide a new one."));
mainWindow->showSettings();
}
// Remove splash screen
splashScreen->finish(mainWindow);
mainWindow->splashScreenFinished();
......@@ -292,7 +292,10 @@ bool QGCApplication::_initForNormalAppBoot(void)
// Now that main window is upcheck for lost log files
connect(this, &QGCApplication::checkForLostLogFiles, MAVLinkProtocol::instance(), &MAVLinkProtocol::checkForLostLogFiles);
emit checkForLostLogFiles();
// Load known link configurations
LinkManager::instance()->loadLinkConfigurationList();
return true;
}
......@@ -322,22 +325,22 @@ void QGCApplication::setSavedFilesLocation(QString& location)
bool QGCApplication::validatePossibleSavedFilesLocation(QString& location)
{
// Make sure we can write to the directory
QString filename = QDir(location).filePath("QGCTempXXXXXXXX.tmp");
QGCTemporaryFile tempFile(filename);
if (!tempFile.open()) {
return false;
}
tempFile.remove();
return true;
}
QString QGCApplication::savedFilesLocation(void)
{
QSettings settings;
Q_ASSERT(settings.contains(_savedFilesLocationKey));
return settings.value(_savedFilesLocationKey).toString();
}
......@@ -346,9 +349,9 @@ QString QGCApplication::savedParameterFilesLocation(void)
{
QString location;
QDir parentDir(savedFilesLocation());
location = parentDir.filePath(_savedFileParameterDirectoryName);
if (!QDir(location).exists()) {
// If directory doesn't exist, try to create it
if (!parentDir.mkpath(_savedFileParameterDirectoryName)) {
......@@ -356,7 +359,7 @@ QString QGCApplication::savedParameterFilesLocation(void)
location.clear();
}
}
return location;
}
......@@ -364,9 +367,9 @@ QString QGCApplication::mavlinkLogFilesLocation(void)
{
QString location;
QDir parentDir(savedFilesLocation());
location = parentDir.filePath(_savedFileMavlinkLogDirectoryName);
if (!QDir(location).exists()) {
// If directory doesn't exist, try to create it
if (!parentDir.mkpath(_savedFileMavlinkLogDirectoryName)) {
......@@ -374,14 +377,14 @@ QString QGCApplication::mavlinkLogFilesLocation(void)
location.clear();
}
}
return location;
}
bool QGCApplication::promptFlightDataSave(void)
{
QSettings settings;
return settings.value(_promptFlightDataSave, true).toBool();
}
......@@ -404,11 +407,11 @@ QGCApplication* qgcApp(void)
void QGCApplication::_createSingletons(void)
{
// The order here is important since the singletons reference each other
GAudioOutput* audio = GAudioOutput::_createSingleton();
Q_UNUSED(audio);
Q_ASSERT(audio);
LinkManager* linkManager = LinkManager::_createSingleton();
Q_UNUSED(linkManager);
Q_ASSERT(linkManager);
......@@ -427,7 +430,7 @@ void QGCApplication::_createSingletons(void)
FactSystem* factSystem = FactSystem::_createSingleton();
Q_UNUSED(factSystem);
Q_ASSERT(factSystem);
// Needs everything!
MAVLinkProtocol* mavlink = MAVLinkProtocol::_createSingleton();
Q_UNUSED(mavlink);
......@@ -439,7 +442,7 @@ void QGCApplication::_destroySingletons(void)
if (MainWindow::instance()) {
delete MainWindow::instance();
}
if (LinkManager::instance(true /* nullOk */)) {
// This will close/delete all connections
LinkManager::instance()->_shutdown();
......@@ -449,10 +452,10 @@ void QGCApplication::_destroySingletons(void)
// This will delete all uas from the system
UASManager::instance()->_shutdown();
}
// Let the signals flow through the main thread
processEvents(QEventLoop::ExcludeUserInputEvents);
// Take down singletons in reverse order of creation
MAVLinkProtocol::_deleteSingleton();
......@@ -495,7 +498,7 @@ void QGCApplication::saveTempFlightDataLogOnMainThread(QString tempLogfile)
void QGCApplication::setStyle(bool styleIsDark)
{
QSettings settings;
settings.setValue(_styleKey, styleIsDark);
_styleIsDark = styleIsDark;
_loadCurrentStyle();
......@@ -506,10 +509,10 @@ void QGCApplication::_loadCurrentStyle(void)
{
bool success = true;
QString styles;
// Signal to the user that the app will pause to apply a new stylesheet
setOverrideCursor(Qt::WaitCursor);
// The dark style sheet is the master. Any other selected style sheet just overrides
// the colors of the master sheet.
QFile masterStyleSheet(_darkStyleFile);
......@@ -519,7 +522,7 @@ void QGCApplication::_loadCurrentStyle(void)
qDebug() << "Unable to load master dark style sheet";
success = false;
}
if (success && !_styleIsDark) {
qDebug() << "LOADING LIGHT";
// Load the slave light stylesheet.
......@@ -531,18 +534,18 @@ void QGCApplication::_loadCurrentStyle(void)
success = false;
}
}
if (!styles.isEmpty()) {
setStyleSheet(styles);
}
if (!success) {
// Fall back to plastique if we can't load our own
setStyle("plastique");
}
QGCPalette::setGlobalTheme(_styleIsDark ? QGCPalette::Dark : QGCPalette::Light);
// Finally restore the cursor before returning.
restoreOverrideCursor();
}
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
#ifndef QGCMESSAGEBOX_H
......@@ -40,34 +40,34 @@
/// @author Don Gagne <don@thegagnes.com>
class QGCMessageBox : public QMessageBox {
public:
static StandardButton critical(const QString& title, const QString& text, StandardButtons buttons = Ok, StandardButton defaultButton = NoButton, QWidget* parent = NULL)
{ return _messageBox(QMessageBox::Critical, title, text, buttons, defaultButton, parent); }
static StandardButton information(const QString & title, const QString& text, StandardButtons buttons = Ok, StandardButton defaultButton = NoButton, QWidget* parent = NULL)
{ return _messageBox(QMessageBox::Information, title, text, buttons, defaultButton, parent); }
static StandardButton question(const QString& title, const QString& text, StandardButtons buttons = Ok, StandardButton defaultButton = NoButton, QWidget* parent = NULL)
{ return _messageBox(QMessageBox::Question, title, text, buttons, defaultButton, parent); }
static StandardButton warning(const QString& title, const QString& text, StandardButtons buttons = Ok, StandardButton defaultButton = NoButton, QWidget* parent = NULL)
{ return _messageBox(QMessageBox::Warning, title, text, buttons, defaultButton, parent); }
private slots:
/// @brief The exec slot is private becasue when only want QGCMessageBox users to use the static methods. Otherwise it will break
/// unit testing.
int exec(void) { return QMessageBox::exec(); }
private:
static QWidget* _validateParameters(StandardButtons buttons, StandardButton* defaultButton, QWidget* parent)
{
// This is an obsolete bit which unit tests use for signalling. It should not be used in regular code.
Q_ASSERT(!(buttons & QMessageBox::Escape));
// If there is more than one button displayed, make sure a default button is set. Without this unit test code
// will not be able to respond to unexpected message boxes.
unsigned int bits = static_cast<unsigned int>(buttons);
int buttonCount = 0;
for (size_t i=0; i<sizeof(bits)*8; i++) {
......@@ -76,14 +76,14 @@ private:
}
}
Q_ASSERT(buttonCount != 0);
if (buttonCount > 1) {
Q_ASSERT(buttons & *defaultButton);
} else {
// Force default button to be set correctly for single button case to make unit test code simpler
*defaultButton = static_cast<QMessageBox::StandardButton>(static_cast<int>(buttons));
}
return (parent == NULL) ? MainWindow::instance() : parent;
}
......@@ -91,9 +91,9 @@ private:
{
// You can't use QGCMessageBox if QGCApplication is not created yet.
Q_ASSERT(qgcApp());
Q_ASSERT_X(QThread::currentThread() == qgcApp()->thread(), "Threading issue", "QGCMessageBox can only be called from main thread");
parent = _validateParameters(buttons, &defaultButton, parent);
if (MainWindow::instance()) {
......@@ -102,7 +102,7 @@ private:
parent = MainWindow::instance();
}
}
#ifdef QT_DEBUG
if (qgcApp()->runningUnitTests()) {
qDebug() << "QGCMessageBox (unit testing)" << title << text;
......@@ -115,6 +115,10 @@ private:
QMessageBox box(icon, emptyTitle, title, buttons, parent);
box.setDefaultButton(defaultButton);
box.setInformativeText(text);
// Get this thing off a proper size
QSpacerItem* horizontalSpacer = new QSpacerItem(500, 0, QSizePolicy::Minimum, QSizePolicy::Expanding);
QGridLayout* layout = (QGridLayout*)box.layout();
layout->addItem(horizontalSpacer, layout->rowCount(), 0, 1, layout->columnCount());
#else
QMessageBox box(icon, title, text, buttons, parent);
box.setDefaultButton(defaultButton);
......
......@@ -21,86 +21,90 @@ This file is part of the QGROUNDCONTROL project
======================================================================*/
/**
* @file
* @brief Definition of class CommConfigurationWindow
*
* @author Lorenz Meier <mavteam@student.ethz.ch>
*
*/
#ifndef _COMMCONFIGURATIONWINDOW_H_
#define _COMMCONFIGURATIONWINDOW_H_
#include <QObject>
#include <QDialog>
#include <QAction>
#include "LinkInterface.h"
#include "ProtocolInterface.h"
#include "ui_CommSettings.h"
enum qgc_link_t {
QGC_LINK_SERIAL,
QGC_LINK_UDP,
QGC_LINK_TCP,
QGC_LINK_SIMULATION,
QGC_LINK_FORWARDING,
#ifdef UNITTEST_BUILD
QGC_LINK_MOCK,
#endif
#ifdef QGC_XBEE_ENABLED
QGC_LINK_XBEE,
#endif
#ifdef QGC_RTLAB_ENABLED
QGC_LINK_OPAL
#endif
};
enum qgc_protocol_t {
QGC_PROTOCOL_MAVLINK,
};
#ifdef QGC_RTLAB_ENABLED
#include "OpalLink.h"
#endif
/**
* @brief Configuration window for communication links
*/
class CommConfigurationWindow : public QDialog
{
Q_OBJECT
public:
CommConfigurationWindow(LinkInterface* link, QWidget *parent = 0);
~CommConfigurationWindow();
QAction* getAction();
void setLinkType(qgc_link_t linktype);
/*!
@file
@brief Link specific configuration base class
@author Gus Grubba <mavlink@grubba.com>
*/
private slots:
void linkCurrentIndexChanged(int currentIndex);
#include "LinkConfiguration.h"
#include "SerialLink.h"
#include "UDPLink.h"
#include "MockLink.h"
public slots:
/** @brief Set the protocol for this link */
void setProtocol(int protocol);
void setConnection();
void setLinkName(QString name);
/** @brief Disconnects the associated link, removes it from all menus and closes the window. */
void remove();
#define LINK_SETTING_ROOT "LinkConfigurations"
private slots:
void _linkConnected(void);
void _linkDisconnected(void);
private:
void _connectionState(bool connect);
Ui::commSettings ui;
LinkInterface* link;
QAction* action;
};
LinkConfiguration::LinkConfiguration(const QString& name)
: _preferred(false)
{
_link = NULL;
_name = name;
Q_ASSERT(!_name.isEmpty());
}
LinkConfiguration::LinkConfiguration(LinkConfiguration* copy)
{
_link = copy->getLink();
_name = copy->name();
_preferred = copy->isPreferred();
Q_ASSERT(!_name.isEmpty());
}
#endif // _COMMCONFIGURATIONWINDOW_H_
void LinkConfiguration::copyFrom(LinkConfiguration* source)
{
Q_ASSERT(source != NULL);
_link = source->getLink();
_name = source->name();
_preferred = source->isPreferred();
}
/*!
Where the settings are saved
@return The root path of the setting.
*/
const QString LinkConfiguration::settingsRoot()
{
return QString(LINK_SETTING_ROOT);
}
/*!
Configuration Factory
@return A new instance of the given type
*/
LinkConfiguration* LinkConfiguration::createSettings(int type, const QString& name)
{
LinkConfiguration* config = NULL;
switch(type) {
case LinkConfiguration::TypeSerial:
config = new SerialConfiguration(name);
break;
case LinkConfiguration::TypeUdp:
config = new UDPConfiguration(name);
break;
case LinkConfiguration::TypeMock:
config = new MockConfiguration(name);
break;
}
return config;
}
/*!
Duplicate link settings
@return A new copy of the given settings instance
*/
LinkConfiguration* LinkConfiguration::duplicateSettings(LinkConfiguration* source)
{
LinkConfiguration* dupe = NULL;
switch(source->type()) {
case TypeSerial:
dupe = new SerialConfiguration(dynamic_cast<SerialConfiguration*>(source));
break;
case TypeUdp:
dupe = new UDPConfiguration(dynamic_cast<UDPConfiguration*>(source));
break;
case TypeMock:
dupe = new MockConfiguration(dynamic_cast<MockConfiguration*>(source));
break;
}
return dupe;
}
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
#ifndef LINKCONFIGURATION_H
#define LINKCONFIGURATION_H
#include <QSettings>
class LinkInterface;
/// Interface holding link specific settings.
class LinkConfiguration
{
public:
LinkConfiguration(const QString& name);
LinkConfiguration(LinkConfiguration* copy);
virtual ~LinkConfiguration() {}
/// The link types supported by QGC
enum {
TypeSerial, ///< Serial Link
TypeUdp, ///< UDP Link
TypeMock, ///< Mock Link for Unitesting
// TODO Below is not yet implemented
#if 0
TypeTcp, ///< TCP Link
TypeSimulation, ///< Simulation Link
TypeForwarding, ///< Forwarding Link
TypeXbee, ///< XBee Proprietary Link
TypeOpal, ///< Opal-RT Link
#endif
TypeLast // Last type value (type >= TypeLast == invalid)
};
/*!
* @brief Get configuration name
*
* This is the user friendly name shown in the connection drop down box and the name used to save the configuration in the settings.
* @return The name of this link.
*/
const QString name() { return _name; }
/*!
* @brief Set the name of this link configuration.
*
* This is the user friendly name shown in the connection drop down box and the name used to save the configuration in the settings.
* @param[in] name The configuration name
*/
void setName(const QString name) {_name = name; }
/*!
* @brief Set the link this configuration is currently attched to.
*
* @param[in] link The pointer to the current LinkInterface instance (if any)
*/
void setLink(LinkInterface* link) { _link = link; }
/*!
* @brief Get the link this configuration is currently attched to.
*
* @return The pointer to the current LinkInterface instance (if any)
*/
LinkInterface* getLink() { return _link; }
/*!
*
* Is this a preferred configuration? (decided at runtime)
* @return True if this is a known configuration (PX4, etc.)
*/
bool isPreferred() { return _preferred; }
/*!
* Set if this is this a preferred configuration. (decided at runtime)
*/
void setPreferred(bool preferred = true) { _preferred = preferred; }
/// Virtual Methods
/*!
* @brief Connection type
*
* Pure virtual method returning one of the -TypeXxx types above.
* @return The type of links these settings belong to.
*/
virtual int type() = 0;
/*!
* @brief Load settings
*
* Pure virtual method telling the instance to load its configuration.
* @param[in] settings The QSettings instance to use
* @param[in] root The root path of the setting.
*/
virtual void loadSettings(QSettings& settings, const QString& root) = 0;
/*!
* @brief Save settings
*
* Pure virtual method telling the instance to save its configuration.
* @param[in] settings The QSettings instance to use
* @param[in] root The root path of the setting.
*/
virtual void saveSettings(QSettings& settings, const QString& root) = 0;
/*!
* @brief Update settings
*
* After editing the settings, use this method to tell the connected link (if any) to reload its configuration.
*/
virtual void updateSettings() {}
/*!
* @brief Copy instance data
*
* When manipulating data, you create a copy of the configuration using the copy constructor,
* edit it and then transfer its content to the original using this method.
* @param[in] source The source instance (the edited copy)
*/
virtual void copyFrom(LinkConfiguration* source);
/// Helper static methods
/*!
* @brief Root path for QSettings
*
* @return The root path of the settings.
*/
static const QString settingsRoot();
/*!
* @brief Create new link configuration instance
*
* Configuration Factory. Creates an appropriate configuration instance based on the given type.
* @return A new instance of the given type
*/
static LinkConfiguration* createSettings(int type, const QString& name);
/*!
* @brief Duplicate configuration instance
*
* Helper method to create a new instance copy for editing.
* @return A new copy of the given settings instance
*/
static LinkConfiguration* duplicateSettings(LinkConfiguration *source);
protected:
LinkInterface* _link; ///< Link currently using this configuration (if any)
private:
QString _name;
bool _preferred; ///< Determined internally if this is a preferred connection. It comes up first in the drop down box.
};
#endif // LINKCONFIGURATION_H
......@@ -39,6 +39,7 @@ along with PIXHAWK. If not, see <http://www.gnu.org/licenses/>.
#include <QMetaType>
class LinkManager;
class LinkConfiguration;
/**
* The link interface defines the interface for all links used to communicate
......@@ -48,10 +49,10 @@ class LinkManager;
class LinkInterface : public QThread
{
Q_OBJECT
// Only LinkManager is allowed to _connect, _disconnect or delete a link
friend class LinkManager;
public:
LinkInterface() :
QThread(0),
......@@ -59,27 +60,33 @@ public:
_deletedByLinkManager(false)
{
// Initialize everything for the data rate calculation buffers.
inDataIndex = 0;
inDataIndex = 0;
outDataIndex = 0;
// Initialize our data rate buffers manually, cause C++<03 is dumb.
for (int i = 0; i < dataRateBufferSize; ++i)
{
inDataWriteAmounts[i] = 0;
inDataWriteTimes[i] = 0;
outDataWriteAmounts[i] = 0;
outDataWriteTimes[i] = 0;
}
// Initialize our data rate buffers.
memset(inDataWriteAmounts, 0, sizeof(inDataWriteAmounts));
memset(inDataWriteTimes, 0, sizeof(inDataWriteTimes));
memset(outDataWriteAmounts,0, sizeof(outDataWriteAmounts));
memset(outDataWriteTimes, 0, sizeof(outDataWriteTimes));
qRegisterMetaType<LinkInterface*>("LinkInterface*");
}
/**
* @brief Destructor
* LinkManager take ownership of Links once they are added to it. Once added to LinkManager
* use LinkManager::deleteLink to remove if necessary.
**/
virtual ~LinkInterface() {
// LinkManager take ownership of Links once they are added to it. Once added to LinkManager
// user LinkManager::deleteLink to remove if necessary/
Q_ASSERT(!_ownedByLinkManager || _deletedByLinkManager);
}
/**
* @brief Get link configuration (if used)
* @return A pointer to the instance of LinkConfiguration if supported. NULL otherwise.
**/
virtual LinkConfiguration* getLinkConfiguration() { return NULL; }
/* Connection management */
/**
......@@ -142,7 +149,7 @@ public:
{
return getCurrentDataRate(outDataIndex, outDataWriteTimes, outDataWriteAmounts);
}
// These are left unimplemented in order to cause linker errors which indicate incorrect usage of
// connect/disconnect on link directly. All connect/disconnect calls should be made through LinkManager.
bool connect(void);
......@@ -323,14 +330,14 @@ private:
* @return True if connection could be established, false otherwise
**/
virtual bool _connect(void) = 0;
/**
* @brief Disconnect this interface logically
*
* @return True if connection could be terminated, false otherwise
**/
virtual bool _disconnect(void) = 0;
bool _ownedByLinkManager; ///< true: This link has been added to LinkManager, false: Link not added to LinkManager
bool _deletedByLinkManager; ///< true: Link being deleted from LinkManager, false: error, Links should only be deleted from LinkManager
};
......
......@@ -32,6 +32,7 @@ This file is part of the QGROUNDCONTROL project
#include <QList>
#include <QApplication>
#include <QDebug>
#include <QSerialPortInfo>
#include "LinkManager.h"
#include "MainWindow.h"
......@@ -40,32 +41,74 @@ This file is part of the QGROUNDCONTROL project
IMPLEMENT_QGC_SINGLETON(LinkManager, LinkManager)
/**
* @brief Private singleton constructor
*
* This class implements the singleton design pattern and has therefore only a private constructor.
**/
LinkManager::LinkManager(QObject* parent) :
QGCSingleton(parent),
_connectionsSuspended(false)
LinkManager::LinkManager(QObject* parent)
: QGCSingleton(parent)
, _configUpdateSuspended(false)
, _configurationsLoaded(false)
, _connectionsSuspended(false)
{
connect(&_portListTimer, &QTimer::timeout, this, &LinkManager::_updateConfigurationList);
_portListTimer.start(1000);
}
LinkManager::~LinkManager()
{
// Clear configuration list
while(_linkConfigurations.count()) {
LinkConfiguration* pLink = _linkConfigurations.at(0);
if(pLink) delete pLink;
_linkConfigurations.removeAt(0);
}
Q_ASSERT_X(_links.count() == 0, "LinkManager", "LinkManager::_shutdown should have been called previously");
}
LinkInterface* LinkManager::createLink(LinkConfiguration* config)
{
Q_ASSERT(config);
LinkInterface* pLink = NULL;
switch(config->type()) {
case LinkConfiguration::TypeSerial:
pLink = new SerialLink(dynamic_cast<SerialConfiguration*>(config));
break;
case LinkConfiguration::TypeUdp:
pLink = new UDPLink(dynamic_cast<UDPConfiguration*>(config));
break;
case LinkConfiguration::TypeMock:
pLink = new MockLink(dynamic_cast<MockConfiguration*>(config));
break;
}
if(pLink) {
addLink(pLink);
}
return pLink;
}
LinkInterface* LinkManager::createLink(const QString& name)
{
Q_ASSERT(name.isEmpty() == false);
for(int i = 0; i < _linkConfigurations.count(); i++) {
LinkConfiguration* conf = _linkConfigurations.at(i);
if(conf && conf->name() == name)
return createLink(conf);
}
return NULL;
}
void LinkManager::addLink(LinkInterface* link)
{
Q_ASSERT(link);
// Take ownership for delete
link->_ownedByLinkManager = true;
_linkListMutex.lock();
if (!_links.contains(link)) {
_links.append(link);
_linkListMutex.unlock();
......@@ -73,18 +116,18 @@ void LinkManager::addLink(LinkInterface* link)
} else {
_linkListMutex.unlock();
}
// MainWindow may be around when doing things like running unit tests
if (MainWindow::instance()) {
connect(link, &LinkInterface::communicationError, qgcApp(), &QGCApplication::criticalMessageBoxOnMainThread);
}
MAVLinkProtocol* mavlink = MAVLinkProtocol::instance();
connect(link, &LinkInterface::bytesReceived, mavlink, &MAVLinkProtocol::receiveBytes);
connect(link, &LinkInterface::connected, mavlink, &MAVLinkProtocol::linkConnected);
connect(link, &LinkInterface::disconnected, mavlink, &MAVLinkProtocol::linkDisconnected);
mavlink->resetMetadataForLink(link);
connect(link, &LinkInterface::connected, this, &LinkManager::_linkConnected);
connect(link, &LinkInterface::disconnected, this, &LinkManager::_linkDisconnected);
}
......@@ -94,7 +137,7 @@ bool LinkManager::connectAll()
if (_connectionsSuspendedMsg()) {
return false;
}
bool allConnected = true;
_linkListMutex.lock();
......@@ -129,7 +172,7 @@ bool LinkManager::disconnectAll()
bool LinkManager::connectLink(LinkInterface* link)
{
Q_ASSERT(link);
if (_connectionsSuspendedMsg()) {
return false;
}
......@@ -144,8 +187,15 @@ bool LinkManager::connectLink(LinkInterface* link)
bool LinkManager::disconnectLink(LinkInterface* link)
{
Q_ASSERT(link);
if (link->_disconnect()) {
// TODO There is no point in disconnecting it if will stay around.
// This should be turned into a delete link instead. Deleting a link
// is not yet possible as LinkManager is broken.
// Disconnect this link from its configuration
LinkConfiguration* config = link->getLinkConfiguration();
if(config) {
config->setLink(NULL);
}
return true;
} else {
return false;
......@@ -155,18 +205,18 @@ bool LinkManager::disconnectLink(LinkInterface* link)
void LinkManager::deleteLink(LinkInterface* link)
{
Q_ASSERT(link);
_linkListMutex.lock();
Q_ASSERT(_links.contains(link));
_links.removeOne(link);
Q_ASSERT(!_links.contains(link));
_linkListMutex.unlock();
// Emit removal of link
emit linkDeleted(link);
Q_ASSERT(link->_ownedByLinkManager);
link->_deletedByLinkManager = true; // Signal that this is a valid delete
delete link;
......@@ -183,7 +233,7 @@ const QList<LinkInterface*> LinkManager::getLinks()
return ret;
}
const QList<SerialLink*> LinkManager::getSerialLinks()
const QList<SerialLink *> LinkManager::getSerialLinks()
{
_linkListMutex.lock();
QList<SerialLink*> s;
......@@ -191,7 +241,7 @@ const QList<SerialLink*> LinkManager::getSerialLinks()
foreach (LinkInterface* link, _links)
{
Q_ASSERT(link);
SerialLink* serialLink = qobject_cast<SerialLink*>(link);
if (serialLink)
......@@ -240,3 +290,174 @@ void LinkManager::_linkDisconnected(void)
{
emit linkDisconnected((LinkInterface*)sender());
}
void LinkManager::addLinkConfiguration(LinkConfiguration* link)
{
Q_ASSERT(link != NULL);
//-- If not there already, add it
int idx = _linkConfigurations.indexOf(link);
if(idx < 0)
{
_linkConfigurations.append(link);
}
}
void LinkManager::removeLinkConfiguration(LinkConfiguration *link)
{
Q_ASSERT(link != NULL);
int idx = _linkConfigurations.indexOf(link);
if(idx >= 0)
{
_linkConfigurations.removeAt(idx);
delete link;
}
}
const QList<LinkConfiguration*> LinkManager::getLinkConfigurationList()
{
return _linkConfigurations;
}
void LinkManager::suspendConfigurationUpdates(bool suspend)
{
_configUpdateSuspended = suspend;
}
void LinkManager::saveLinkConfigurationList()
{
QSettings settings;
settings.remove(LinkConfiguration::settingsRoot());
QString root(LinkConfiguration::settingsRoot());
settings.setValue(root + "/count", _linkConfigurations.count());
int index = 0;
foreach (LinkConfiguration* pLink, _linkConfigurations) {
Q_ASSERT(pLink != NULL);
root = LinkConfiguration::settingsRoot();
root += QString("/Link%1").arg(index++);
settings.setValue(root + "/name", pLink->name());
settings.setValue(root + "/type", pLink->type());
settings.setValue(root + "/preferred", pLink->isPreferred());
// Have the instance save its own values
pLink->saveSettings(settings, root);
}
emit linkConfigurationChanged();
}
void LinkManager::loadLinkConfigurationList()
{
QSettings settings;
// Is the group even there?
if(settings.contains(LinkConfiguration::settingsRoot() + "/count")) {
// Find out how many configurations we have
int count = settings.value(LinkConfiguration::settingsRoot() + "/count").toInt();
for(int i = 0; i < count; i++) {
QString root(LinkConfiguration::settingsRoot());
root += QString("/Link%1").arg(i);
if(settings.contains(root + "/type")) {
int type = settings.value(root + "/type").toInt();
if(type < LinkConfiguration::TypeLast) {
if(settings.contains(root + "/name")) {
QString name = settings.value(root + "/name").toString();
if(!name.isEmpty()) {
bool preferred = false;
if(settings.contains(root + "/preferred")) {
preferred = settings.value(root + "/preferred").toBool();
}
LinkConfiguration* pLink = NULL;
switch(type) {
case LinkConfiguration::TypeSerial:
pLink = (LinkConfiguration*)new SerialConfiguration(name);
pLink->setPreferred(preferred);
break;
case LinkConfiguration::TypeUdp:
pLink = (LinkConfiguration*)new UDPConfiguration(name);
pLink->setPreferred(preferred);
break;
case LinkConfiguration::TypeMock:
pLink = (LinkConfiguration*)new MockConfiguration(name);
pLink->setPreferred(false);
break;
}
if(pLink) {
// Have the instance load its own values
pLink->loadSettings(settings, root);
addLinkConfiguration(pLink);
}
} else {
qWarning() << "Link Configuration " << root << " has an empty name." ;
}
} else {
qWarning() << "Link Configuration " << root << " has no name." ;
}
} else {
qWarning() << "Link Configuration " << root << " an invalid type: " << type;
}
} else {
qWarning() << "Link Configuration " << root << " has no type." ;
}
}
emit linkConfigurationChanged();
}
// Enable automatic PX4 hunting
_configurationsLoaded = true;
}
SerialConfiguration* LinkManager::_findSerialConfiguration(const QString& portName)
{
QString searchPort = portName.trimmed();
foreach (LinkConfiguration* pLink, _linkConfigurations) {
Q_ASSERT(pLink != NULL);
if(pLink->type() == LinkConfiguration::TypeSerial) {
SerialConfiguration* pSerial = dynamic_cast<SerialConfiguration*>(pLink);
if(pSerial->portName() == searchPort) {
return pSerial;
}
}
}
return NULL;
}
void LinkManager::_updateConfigurationList(void)
{
if (_configUpdateSuspended || !_configurationsLoaded) {
return;
}
bool saveList = false;
QList<QSerialPortInfo> portList = QSerialPortInfo::availablePorts();
// Iterate Comm Ports
foreach (QSerialPortInfo portInfo, portList) {
#if 0
qDebug() << "-----------------------------------------------------";
qDebug() << "portName: " << portInfo.portName();
qDebug() << "systemLocation: " << portInfo.systemLocation();
qDebug() << "description: " << portInfo.description();
qDebug() << "manufacturer: " << portInfo.manufacturer();
qDebug() << "serialNumber: " << portInfo.serialNumber();
qDebug() << "vendorIdentifier: " << portInfo.vendorIdentifier();
#endif
// Is this a PX4?
if (portInfo.vendorIdentifier() == 9900) {
SerialConfiguration* pSerial = _findSerialConfiguration(portInfo.portName());
if (pSerial) {
//-- If this port is configured make sure it has the preferred flag set
if(!pSerial->isPreferred()) {
pSerial->setPreferred(true);
saveList = true;
}
} else {
// Lets create a new Serial configuration automatically
pSerial = new SerialConfiguration(QString("Pixhawk on %1").arg(portInfo.portName().trimmed()));
pSerial->setPreferred(true);
pSerial->setBaud(115200);
pSerial->setPortName(portInfo.portName());
addLinkConfiguration(pSerial);
saveList = true;
}
}
}
// Save configuration list, which will also trigger a signal for the UI
if(saveList) {
saveLinkConfigurationList();
}
}
......@@ -31,8 +31,14 @@ This file is part of the PIXHAWK project
#include <QMultiMap>
#include <QMutex>
#include "LinkConfiguration.h"
#include "LinkInterface.h"
// Links
#include "SerialLink.h"
#include "UDPLink.h"
#include "MockLink.h"
#include "ProtocolInterface.h"
#include "QGCSingleton.h"
#include "MAVLinkProtocol.h"
......@@ -48,14 +54,38 @@ class LinkManagerTest;
class LinkManager : public QGCSingleton
{
Q_OBJECT
DECLARE_QGC_SINGLETON(LinkManager, LinkManager)
/// Unit Test has access to private constructor/destructor
friend class LinkManagerTest;
public:
/*!
Add a new link configuration setting to the list
@param[in] link An instance of the link setting.
*/
void addLinkConfiguration(LinkConfiguration* link);
/*!
Removes (and deletes) an existing link configuration setting from the list
@param[in] link An instance of the link setting.
*/
void removeLinkConfiguration(LinkConfiguration* link);
/// Load list of link configurations from disk
void loadLinkConfigurationList();
/// Save list of link configurations from disk
void saveLinkConfigurationList();
/// Get a list of the configured links. This is the list of configured links that can be used by QGC.
const QList<LinkConfiguration*> getLinkConfigurationList();
/// Suspend automatic confguration updates (during link maintenance for instance)
void suspendConfigurationUpdates(bool suspend);
/// Returns list of all links
const QList<LinkInterface*> getLinks();
......@@ -65,53 +95,69 @@ public:
/// Sets the flag to suspend the all new connections
/// @param reason User visible reason to suspend connections
void setConnectionsSuspended(QString reason);
/// Sets the flag to allow new connections to be made
void setConnectionsAllowed(void) { _connectionsSuspended = false; }
/// Creates (and adds) a link based on the given configuration instance. LinkManager takes ownership of this object. To delete
/// it, call LinkManager::deleteLink.
LinkInterface* createLink(LinkConfiguration* config);
/// Creates (and adds) a link based on the given configuration name. LinkManager takes ownership of this object. To delete
/// it, call LinkManager::deleteLink.
LinkInterface* createLink(const QString& name);
/// Adds the link to the LinkManager. LinkManager takes ownership of this object. To delete
/// it, call LinkManager::deleteLink.
void addLink(LinkInterface* link);
/// Deletes the specified link. Will disconnect if connected.
// TODO Will also crash if called. MAVLink protocol is not handling the disconnect properly.
void deleteLink(LinkInterface* link);
/// Re-connects all existing links
bool connectAll();
/// Disconnects all existing links
bool disconnectAll();
/// Connect the specified link
bool connectLink(LinkInterface* link);
/// Disconnect the specified link
bool disconnectLink(LinkInterface* link);
signals:
void newLink(LinkInterface* link);
void linkDeleted(LinkInterface* link);
void linkConnected(LinkInterface* link);
void linkDisconnected(LinkInterface* link);
void linkConfigurationChanged();
private slots:
void _linkConnected(void);
void _linkDisconnected(void);
private:
/// All access to LinkManager is through LinkManager::instance
LinkManager(QObject* parent = NULL);
~LinkManager();
virtual void _shutdown(void);
bool _connectionsSuspendedMsg(void);
QList<LinkInterface*> _links; ///< List of available links
QMutex _linkListMutex; ///< Mutex for thread safe access to _links list
bool _connectionsSuspended; ///< true: all new connections should not be allowed
QString _connectionsSuspendedReason; ///< User visible reason for suspension
void _updateConfigurationList(void);
SerialConfiguration* _findSerialConfiguration(const QString& portName);
QList<LinkConfiguration*> _linkConfigurations; ///< List of configured links
QList<LinkInterface*> _links; ///< List of available links
QMutex _linkListMutex; ///< Mutex for thread safe access to _links list
bool _configUpdateSuspended; ///< true: stop updating configuration list
bool _configurationsLoaded; ///< true: Link configurations have been loaded
bool _connectionsSuspended; ///< true: all new connections should not be allowed
QString _connectionsSuspendedReason; ///< User visible reason for suspension
QTimer _portListTimer;
};
#endif
This diff is collapsed.
......@@ -32,18 +32,65 @@ This file is part of the QGROUNDCONTROL project
#ifndef SERIALLINK_H
#define SERIALLINK_H
class LinkInterface;
class SerialConfiguration;
class SerialLink;
#include <QObject>
#include <QThread>
#include <QMutex>
#include <QString>
#include "QGCConfig.h"
#include "SerialLinkInterface.h"
// We use QSerialPort::SerialPortError in a signal so we must declare it as a meta type
#include <QSerialPort>
#include <QMetaType>
// We use QSerialPort::SerialPortError in a signal so we must declare it as a meta type
Q_DECLARE_METATYPE(QSerialPort::SerialPortError)
#include "QGCConfig.h"
#include "LinkManager.h"
class SerialConfiguration : public LinkConfiguration
{
public:
SerialConfiguration(const QString& name);
SerialConfiguration(SerialConfiguration* copy);
int baud() { return _baud; }
int dataBits() { return _dataBits; }
int flowControl() { return _flowControl; } ///< QSerialPort Enums
int stopBits() { return _stopBits; }
int parity() { return _parity; } ///< QSerialPort Enums
const QString portName() { return _portName; }
void setBaud (int baud);
void setDataBits (int databits);
void setFlowControl (int flowControl); ///< QSerialPort Enums
void setStopBits (int stopBits);
void setParity (int parity); ///< QSerialPort Enums
void setPortName (const QString& portName);
/// From LinkConfiguration
int type() { return LinkConfiguration::TypeSerial; }
void copyFrom(LinkConfiguration* source);
void loadSettings(QSettings& settings, const QString& root);
void saveSettings(QSettings& settings, const QString& root);
void updateSettings();
/*! @brief Get a list of the currently available ports */
static QList<QString> getCurrentPorts();
private:
int _baud;
int _dataBits;
int _flowControl;
int _stopBits;
int _parity;
QString _portName;
};
/**
* @brief The SerialLink class provides cross-platform access to serial links.
* It takes care of the link management and provides a common API to higher
......@@ -52,84 +99,36 @@ Q_DECLARE_METATYPE(QSerialPort::SerialPortError)
* safe.
*
*/
class SerialLink : public SerialLinkInterface
class SerialLink : public LinkInterface
{
Q_OBJECT
//Q_INTERFACES(SerialLinkInterface:LinkInterface)
friend class SerialConfiguration;
public:
SerialLink(QString portname = "",
int baudrate=57600,
bool flow=false,
bool parity=false,
int dataBits=8,
int stopBits=1);
~SerialLink();
static const int poll_interval = SERIAL_POLL_INTERVAL; ///< Polling interval, defined in QGCConfig.h
/** @brief Get a list of the currently available ports */
QList<QString> getCurrentPorts();
/** @brief Check if the current port is a bootloader */
bool isBootloader();
void requestReset();
SerialLink(SerialConfiguration* config);
~SerialLink();
bool isConnected() const;
// LinkInterface
/**
* @brief The port handle
*/
QString getPortName() const;
/**
* @brief The human readable port name
*/
LinkConfiguration* getLinkConfiguration();
int getId() const;
QString getName() const;
int getBaudRate() const;
int getDataBits() const;
int getStopBits() const;
// ENUM values
int getBaudRateType() const;
int getFlowType() const;
int getParityType() const;
int getDataBitsType() const;
int getStopBitsType() const;
qint64 getConnectionSpeed() const;
qint64 getCurrentInDataRate() const;
qint64 getCurrentOutDataRate() const;
void loadSettings();
void writeSettings();
void checkIfCDC();
void requestReset();
bool isConnected() const;
qint64 getConnectionSpeed() const;
// These are left unimplemented in order to cause linker errors which indicate incorrect usage of
// connect/disconnect on link directly. All connect/disconnect calls should be made through LinkManager.
bool connect(void);
bool disconnect(void);
void run();
void run2();
int getId() const;
// These are left unimplemented in order to cause linker errors which indicate incorrect usage of
// connect/disconnect on link directly. All connect/disconnect calls should be made through LinkManager.
bool connect(void);
bool disconnect(void);
static const int poll_interval = SERIAL_POLL_INTERVAL; ///< Polling interval, defined in QGCConfig.h
signals: //[TODO] Refactor to Linkinterface
void updateLink(LinkInterface*);
public slots:
bool setPortName(QString portName);
bool setBaudRate(int rate);
// Set ENUM values
bool setBaudRateType(int rateIndex);
bool setFlowType(int flow);
bool setParityType(int parity);
bool setDataBitsType(int dataBits);
bool setStopBitsType(int stopBits);
void readBytes();
/**
......@@ -143,37 +142,34 @@ public slots:
void linkError(QSerialPort::SerialPortError error);
protected:
quint64 m_bytesRead;
QSerialPort* m_port;
int m_baud;
int m_dataBits;
int m_flowControl;
int m_stopBits;
int m_parity;
QString m_portName;
int m_timeout;
int m_id;
QMutex m_dataMutex; // Mutex for reading data from m_port
QMutex m_writeMutex; // Mutex for accessing the m_transmitBuffer.
QString type;
bool m_is_cdc;
QSerialPort* _port;
quint64 _bytesRead;
int _timeout;
int _id;
QMutex _dataMutex; // Mutex for reading data from _port
QMutex _writeMutex; // Mutex for accessing the _transmitBuffer.
QString _type;
private slots:
void _rerouteDisconnected(void);
private:
// From LinkInterface
virtual bool _connect(void);
virtual bool _disconnect(void);
void _emitLinkError(const QString& errorMsg);
bool _connect(void);
bool _disconnect(void);
volatile bool m_stopp;
volatile bool m_reqReset;
QMutex m_stoppMutex; // Mutex for accessing m_stopp
QByteArray m_transmitBuffer; // An internal buffer for receiving data from member functions and actually transmitting them via the serial port.
bool hardwareConnect(QString &type);
// Internal methods
void _emitLinkError(const QString& errorMsg);
bool _hardwareConnect(QString &_type);
bool _isBootloader();
void _resetConfiguration();
// Local data
volatile bool _stopp;
volatile bool _reqReset;
QMutex _stoppMutex; // Mutex for accessing _stopp
QByteArray _transmitBuffer; // An internal buffer for receiving data from member functions and actually transmitting them via the serial port.
SerialConfiguration* _config;
signals:
void aboutToCloseFlag();
......
......@@ -37,12 +37,12 @@ This file is part of the QGROUNDCONTROL project
#include <QVector>
#include <LinkInterface.h>
/*
class SerialLinkInterface : public LinkInterface
{
Q_OBJECT
public:
virtual QList<QString> getCurrentPorts() = 0;
virtual QString getPortName() const = 0;
virtual int getBaudRate() const = 0;
virtual int getDataBits() const = 0;
......@@ -66,7 +66,7 @@ public slots:
virtual void writeSettings() = 0;
};
*/
/* Declare C++ interface as Qt interface */
//Q_DECLARE_INTERFACE(SerialLinkInterface, "org.openground.comm.links.SerialLinkInterface/1.0")
......
......@@ -33,40 +33,38 @@ This file is part of the QGROUNDCONTROL project
#include <QDebug>
#include <QMutexLocker>
#include <iostream>
#include "UDPLink.h"
#include "LinkManager.h"
#include "QGC.h"
#include <QHostInfo>
//#include <netinet/in.h>
UDPLink::UDPLink(QHostAddress host, quint16 port) :
socket(NULL)
UDPLink::UDPLink(UDPConfiguration* config)
: _socket(NULL)
, _connectState(false)
{
Q_ASSERT(config != NULL);
_config = config;
_config->setLink(this);
// We're doing it wrong - because the Qt folks got the API wrong:
// http://blog.qt.digia.com/blog/2010/06/17/youre-doing-it-wrong/
moveToThread(this);
this->host = host;
this->port = port;
this->connectState = false;
// Set unique ID and add link to the list of links
this->id = getNextLinkId();
this->name = tr("UDP Link (port:%1)").arg(this->port);
emit nameChanged(this->name);
// LinkManager::instance()->add(this);
qDebug() << "UDP Created " << name;
_id = getNextLinkId();
qDebug() << "UDP Created " << _config->name();
}
UDPLink::~UDPLink()
{
// Disconnect link from configuration
_config->setLink(NULL);
_disconnect();
// Tell the thread to exit
quit();
// Wait for it to exit
wait();
this->deleteLater();
this->deleteLater();
}
/**
......@@ -75,163 +73,86 @@ UDPLink::~UDPLink()
**/
void UDPLink::run()
{
hardwareConnect();
_hardwareConnect();
exec();
}
void UDPLink::setAddress(QHostAddress host)
void UDPLink::_restartConnection()
{
bool reconnect(false);
if(this->isConnected())
{
_disconnect();
reconnect = true;
}
this->host = host;
if(reconnect)
{
_connect();
}
if(this->isConnected())
{
_disconnect();
_connect();
}
}
void UDPLink::setPort(int port)
QString UDPLink::getName() const
{
bool reconnect(false);
if(this->isConnected())
{
_disconnect();
reconnect = true;
}
this->port = port;
this->name = tr("UDP Link (port:%1)").arg(this->port);
emit nameChanged(this->name);
if(reconnect)
{
_connect();
}
return _config->name();
}
/**
* @param host Hostname in standard formatting, e.g. localhost:14551 or 192.168.1.1:14551
*/
void UDPLink::addHost(const QString& host)
{
qDebug() << "UDP:" << "ADDING HOST:" << host;
if (host.contains(":"))
{
//qDebug() << "HOST: " << host.split(":").first();
QHostInfo info = QHostInfo::fromName(host.split(":").first());
if (info.error() == QHostInfo::NoError)
{
// Add host
QList<QHostAddress> hostAddresses = info.addresses();
QHostAddress address;
for (int i = 0; i < hostAddresses.size(); i++)
{
// Exclude loopback IPv4 and all IPv6 addresses
if (!hostAddresses.at(i).toString().contains(":"))
{
address = hostAddresses.at(i);
}
}
hosts.append(address);
//qDebug() << "Address:" << address.toString();
// Set port according to user input
ports.append(host.split(":").last().toInt());
}
}
else
{
QHostInfo info = QHostInfo::fromName(host);
if (info.error() == QHostInfo::NoError)
{
// Add host
hosts.append(info.addresses().first());
// Set port according to default (this port)
ports.append(port);
}
}
_config->addHost(host);
}
void UDPLink::removeHost(const QString& hostname)
void UDPLink::removeHost(const QString& host)
{
QString host = hostname;
if (host.contains(":")) host = host.split(":").first();
host = host.trimmed();
QHostInfo info = QHostInfo::fromName(host);
QHostAddress address;
QList<QHostAddress> hostAddresses = info.addresses();
for (int i = 0; i < hostAddresses.size(); i++)
{
// Exclude loopback IPv4 and all IPv6 addresses
if (!hostAddresses.at(i).toString().contains(":"))
{
address = hostAddresses.at(i);
}
}
for (int i = 0; i < hosts.count(); ++i)
{
if (hosts.at(i) == address)
{
hosts.removeAt(i);
ports.removeAt(i);
}
}
_config->removeHost(host);
}
#define UDPLINK_DEBUG 0
void UDPLink::writeBytes(const char* data, qint64 size)
{
// Broadcast to all connected systems
for (int h = 0; h < hosts.size(); h++)
{
QHostAddress currentHost = hosts.at(h);
quint16 currentPort = ports.at(h);
//#define UDPLINK_DEBUG
#ifdef UDPLINK_DEBUG
QString bytes;
QString ascii;
for (int i=0; i<size; i++)
{
unsigned char v = data[i];
bytes.append(QString().sprintf("%02x ", v));
if (data[i] > 31 && data[i] < 127)
{
ascii.append(data[i]);
}
else
{
ascii.append(219);
QString host;
int port;
if(_config->firstHost(host, port)) {
do {
if(UDPLINK_DEBUG) {
QString bytes;
QString ascii;
for (int i=0; i<size; i++)
{
unsigned char v = data[i];
bytes.append(QString().sprintf("%02x ", v));
if (data[i] > 31 && data[i] < 127)
{
ascii.append(data[i]);
}
else
{
ascii.append(219);
}
}
qDebug() << "Sent" << size << "bytes to" << host << ":" << port << "data:";
qDebug() << bytes;
qDebug() << "ASCII:" << ascii;
}
}
qDebug() << "Sent" << size << "bytes to" << currentHost.toString() << ":" << currentPort << "data:";
qDebug() << bytes;
qDebug() << "ASCII:" << ascii;
#endif
socket->writeDatagram(data, size, currentHost, currentPort);
// Log the amount and time written out for future data rate calculations.
QMutexLocker dataRateLocker(&dataRateMutex);
logDataRateToBuffer(outDataWriteAmounts, outDataWriteTimes, &outDataIndex, size, QDateTime::currentMSecsSinceEpoch());
QHostAddress currentHost(host);
_socket->writeDatagram(data, size, currentHost, (quint16)port);
// Log the amount and time written out for future data rate calculations.
QMutexLocker dataRateLocker(&dataRateMutex);
logDataRateToBuffer(outDataWriteAmounts, outDataWriteTimes, &outDataIndex, size, QDateTime::currentMSecsSinceEpoch());
} while (_config->nextHost(host, port));
}
}
/**
* @brief Read a number of bytes from the interface.
*
* @param data Pointer to the data byte array to write the bytes to
* @param maxLength The maximum number of bytes to write
**/
void UDPLink::readBytes()
{
while (socket->hasPendingDatagrams())
while (_socket->hasPendingDatagrams())
{
QByteArray datagram;
datagram.resize(socket->pendingDatagramSize());
datagram.resize(_socket->pendingDatagramSize());
QHostAddress sender;
quint16 senderPort;
socket->readDatagram(datagram.data(), datagram.size(), &sender, &senderPort);
_socket->readDatagram(datagram.data(), datagram.size(), &sender, &senderPort);
// FIXME TODO Check if this method is better than retrieving the data by individual processes
emit bytesReceived(this, datagram);
......@@ -240,7 +161,6 @@ void UDPLink::readBytes()
QMutexLocker dataRateLocker(&dataRateMutex);
logDataRateToBuffer(inDataWriteAmounts, inDataWriteTimes, &inDataIndex, datagram.length(), QDateTime::currentMSecsSinceEpoch());
// // Echo data for debugging purposes
// std::cerr << __FILE__ << __LINE__ << "Received datagram:" << std::endl;
// int i;
......@@ -251,19 +171,12 @@ void UDPLink::readBytes()
// }
// std::cerr << std::endl;
// Add host to broadcast list if not yet present
if (!hosts.contains(sender))
{
hosts.append(sender);
ports.append(senderPort);
// ports->insert(sender, senderPort);
}
else
{
int index = hosts.indexOf(sender);
ports.replace(index, senderPort);
}
// TODO This doesn't validade the sender. Anything sending UDP packets to this port gets
// added to the list and will start receiving datagrams from here. Even a port scanner
// would trigger this.
// Add host to broadcast list if not yet present, or update its port
QString host(sender.toString() + ":" + QString("%1").arg((int)senderPort));
_config->addHost(host);
}
}
......@@ -274,19 +187,17 @@ void UDPLink::readBytes()
**/
bool UDPLink::_disconnect(void)
{
this->quit();
this->wait();
if (socket) {
// Make sure delete happen on correct thread
socket->deleteLater();
socket = NULL;
this->quit();
this->wait();
if (_socket) {
// Make sure delete happen on correct thread
_socket->deleteLater();
_socket = NULL;
emit disconnected();
}
connectState = false;
return !connectState;
}
// TODO When would this ever return false?
_connectState = false;
return !_connectState;
}
/**
......@@ -296,67 +207,29 @@ bool UDPLink::_disconnect(void)
**/
bool UDPLink::_connect(void)
{
if(this->isRunning())
{
this->quit();
this->wait();
}
if(this->isRunning())
{
this->quit();
this->wait();
}
// TODO When would this ever return false?
bool connected = true;
start(HighPriority);
return connected;
}
bool UDPLink::hardwareConnect(void)
bool UDPLink::_hardwareConnect()
{
socket = new QUdpSocket();
//Check if we are using a multicast-address
// bool multicast = false;
// if (host.isInSubnet(QHostAddress("224.0.0.0"),4))
// {
// multicast = true;
// connectState = socket->bind(port, QUdpSocket::ShareAddress);
// }
// else
// {
connectState = socket->bind(host, port);
// }
//Provides Multicast functionality to UdpSocket
/* not working yet
if (multicast)
{
int sendingFd = socket->socketDescriptor();
if (sendingFd != -1)
{
// set up destination address
struct sockaddr_in sendAddr;
memset(&sendAddr,0,sizeof(sendAddr));
sendAddr.sin_family=AF_INET;
sendAddr.sin_addr.s_addr=inet_addr(HELLO_GROUP);
sendAddr.sin_port=htons(port);
// set TTL
unsigned int ttl = 1; // restricted to the same subnet
if (setsockopt(sendingFd, IPPROTO_IP, IP_MULTICAST_TTL, (unsigned int*)&ttl, sizeof(ttl) ) < 0)
{
std::cout << "TTL failed\n";
}
}
}
*/
//QObject::connect(socket, SIGNAL(readyRead()), this, SLOT(readPendingDatagrams()));
QObject::connect(socket, SIGNAL(readyRead()), this, SLOT(readBytes()));
if (connectState) {
QHostAddress host = QHostAddress::Any;
_socket = new QUdpSocket();
_connectState = _socket->bind(host, _config->localPort());
QObject::connect(_socket, SIGNAL(readyRead()), this, SLOT(readBytes()));
if (_connectState) {
emit connected();
}
return connectState;
return _connectState;
}
/**
* @brief Check if connection is active.
*
......@@ -364,37 +237,190 @@ bool UDPLink::hardwareConnect(void)
**/
bool UDPLink::isConnected() const
{
return connectState;
return _connectState;
}
int UDPLink::getId() const
{
return id;
return _id;
}
QString UDPLink::getName() const
qint64 UDPLink::getConnectionSpeed() const
{
return name;
return 54000000; // 54 Mbit
}
qint64 UDPLink::getCurrentInDataRate() const
{
return 0;
}
void UDPLink::setName(QString name)
qint64 UDPLink::getCurrentOutDataRate() const
{
this->name = name;
emit nameChanged(this->name);
return 0;
}
//--------------------------------------------------------------------------
//-- UDPConfiguration
qint64 UDPLink::getConnectionSpeed() const
UDPConfiguration::UDPConfiguration(const QString& name) : LinkConfiguration(name)
{
return 54000000; // 54 Mbit
_localPort = QGC_UDP_PORT;
}
qint64 UDPLink::getCurrentInDataRate() const
UDPConfiguration::UDPConfiguration(UDPConfiguration* source) : LinkConfiguration(source)
{
return 0;
_localPort = source->localPort();
_hosts.clear();
QString host;
int port;
if(source->firstHost(host, port)) {
do {
addHost(host, port);
} while(source->nextHost(host, port));
}
}
qint64 UDPLink::getCurrentOutDataRate() const
void UDPConfiguration::copyFrom(LinkConfiguration *source)
{
return 0;
_confMutex.lock();
LinkConfiguration::copyFrom(dynamic_cast<LinkConfiguration*>(this));
UDPConfiguration* usource = dynamic_cast<UDPConfiguration*>(source);
Q_ASSERT(usource != NULL);
_localPort = usource->localPort();
QString host;
int port;
if(usource->firstHost(host, port)) {
do {
addHost(host, port);
} while(usource->nextHost(host, port));
}
_confMutex.unlock();
}
/**
* @param host Hostname in standard formatt, e.g. localhost:14551 or 192.168.1.1:14551
*/
void UDPConfiguration::addHost(const QString& host)
{
qDebug() << "UDP:" << "ADDING HOST:" << host;
if (host.contains(":"))
{
QHostInfo info = QHostInfo::fromName(host.split(":").first());
if (info.error() == QHostInfo::NoError)
{
// Add host
QList<QHostAddress> hostAddresses = info.addresses();
QHostAddress address;
for (int i = 0; i < hostAddresses.size(); i++)
{
// Exclude loopback IPv4 and all IPv6 addresses
if (!hostAddresses.at(i).toString().contains(":"))
{
address = hostAddresses.at(i);
}
}
_hosts[address.toString()] = host.split(":").last().toInt();
}
}
else
{
QHostInfo info = QHostInfo::fromName(host);
if (info.error() == QHostInfo::NoError)
{
// Set port according to default (same as local port)
_hosts[info.addresses().first().toString()] = (int)_localPort;
}
}
}
void UDPConfiguration::addHost(const QString& host, int port)
{
_hosts[host.trimmed()] = port;
}
void UDPConfiguration::removeHost(const QString& host)
{
QString tHost = host;
if (tHost.contains(":")) {
tHost = tHost.split(":").first();
}
tHost = tHost.trimmed();
QMap<QString, int>::iterator i = _hosts.find(tHost);
if(i != _hosts.end()) {
_hosts.erase(i);
}
}
bool UDPConfiguration::firstHost(QString& host, int& port)
{
_it = _hosts.begin();
if(_it == _hosts.end()) {
return false;
}
return nextHost(host, port);
}
bool UDPConfiguration::nextHost(QString& host, int& port)
{
if(_it != _hosts.end()) {
host = _it.key();
port = _it.value();
_it++;
return true;
}
return false;
}
void UDPConfiguration::setLocalPort(quint16 port)
{
_localPort = port;
}
void UDPConfiguration::saveSettings(QSettings& settings, const QString& root)
{
_confMutex.lock();
settings.beginGroup(root);
settings.setValue("port", (int)_localPort);
settings.setValue("hostCount", _hosts.count());
int index = 0;
QMap<QString, int>::const_iterator it = _hosts.begin();
while(it != _hosts.end()) {
QString hkey = QString("host%1").arg(index);
settings.setValue(hkey, it.key());
QString pkey = QString("port%1").arg(index);
settings.setValue(pkey, it.value());
it++;
index++;
}
settings.endGroup();
_confMutex.unlock();
}
void UDPConfiguration::loadSettings(QSettings& settings, const QString& root)
{
_confMutex.lock();
settings.beginGroup(root);
_hosts.clear();
_localPort = (quint16)settings.value("port", QGC_UDP_PORT).toUInt();
int hostCount = settings.value("hostCount", 0).toInt();
for(int i = 0; i < hostCount; i++) {
QString hkey = QString("host%1").arg(i);
QString pkey = QString("port%1").arg(i);
if(settings.contains(hkey) && settings.contains(pkey)) {
addHost(settings.value(hkey).toString(), settings.value(pkey).toInt());
}
}
settings.endGroup();
_confMutex.unlock();
}
void UDPConfiguration::updateSettings()
{
if(_link) {
UDPLink* ulink = dynamic_cast<UDPLink*>(_link);
if(ulink) {
ulink->_restartConnection();
}
}
}
......@@ -21,7 +21,7 @@ This file is part of the QGROUNDCONTROL project
======================================================================*/
/**
/*!
* @file
* @brief UDP connection (server) for unmanned vehicles
* @author Lorenz Meier <mavteam@student.ethz.ch>
......@@ -36,39 +36,120 @@ This file is part of the QGROUNDCONTROL project
#include <QMap>
#include <QMutex>
#include <QUdpSocket>
#include <LinkInterface.h>
#include "QGCConfig.h"
#include "LinkManager.h"
#define QGC_UDP_PORT 14550
class UDPConfiguration : public LinkConfiguration
{
public:
/*!
* @brief Regular constructor
*
* @param[in] name Configuration (user friendly) name
*/
UDPConfiguration(const QString& name);
/*!
* @brief Copy contructor
*
* When manipulating data, you create a copy of the configuration, edit it
* and then transfer its content to the original (using copyFrom() below). Use this
* contructor to create an editable copy.
*
* @param[in] source Original configuration
*/
UDPConfiguration(UDPConfiguration* source);
/*!
* @brief Begin iteration through the list of target hosts
*
* @param[out] host Host name
* @param[out] port Port number
* @return Returns false if list is empty
*/
bool firstHost (QString& host, int& port);
/*!
* @brief Continues iteration through the list of target hosts
*
* @param[out] host Host name
* @param[out] port Port number
* @return Returns false if reached the end of the list (in which case, both host and port are unchanged)
*/
bool nextHost (QString& host, int& port);
/*!
* @brief Get the number of target hosts
*
* @return Number of hosts in list
*/
int hostCount () { return _hosts.count(); }
/*!
* @brief The UDP port we bind to
*
* @return Port number
*/
quint16 localPort () { return _localPort; }
/*!
* @brief Add a target host
*
* @param[in] host Host name in standard formatt, e.g. localhost:14551 or 192.168.1.1:14551
*/
void addHost (const QString& host);
/*!
* @brief Add a target host
*
* @param[in] host Host name, e.g. localhost or 192.168.1.1
* @param[in] port Port number
*/
void addHost (const QString& host, int port);
/*!
* @brief Remove a target host from the list
*
* @param[in] host Host name, e.g. localhost or 192.168.1.1
*/
void removeHost (const QString& host);
/*!
* @brief Set the UDP port we bind to
*
* @param[in] port Port number
*/
void setLocalPort (quint16 port);
/// From LinkConfiguration
int type() { return LinkConfiguration::TypeUdp; }
void copyFrom(LinkConfiguration* source);
void loadSettings(QSettings& settings, const QString& root);
void saveSettings(QSettings& settings, const QString& root);
void updateSettings();
private:
QMutex _confMutex;
QMap<QString, int>::iterator _it;
QMap<QString, int> _hosts; ///< ("host", port)
quint16 _localPort;
};
class UDPLink : public LinkInterface
{
Q_OBJECT
//Q_INTERFACES(UDPLinkInterface:LinkInterface)
friend class UDPConfiguration;
public:
UDPLink(QHostAddress host = QHostAddress::Any, quint16 port = 14550);
//UDPLink(QHostAddress host = "239.255.76.67", quint16 port = 7667);
UDPLink(UDPConfiguration* config);
~UDPLink();
void requestReset() { }
bool isConnected() const;
int getPort() const {
return port;
}
/**
* @brief The human readable port name
*/
QString getName() const;
int getBaudRate() const;
int getBaudRateType() const;
int getFlowType() const;
int getParityType() const;
int getDataBitsType() const;
int getStopBitsType() const;
QList<QHostAddress> getHosts() const {
return hosts;
}
// Extensive statistics for scientific purposes
qint64 getConnectionSpeed() const;
......@@ -76,25 +157,23 @@ public:
qint64 getCurrentOutDataRate() const;
void run();
int getId() const;
// These are left unimplemented in order to cause linker errors which indicate incorrect usage of
// connect/disconnect on link directly. All connect/disconnect calls should be made through LinkManager.
bool connect(void);
bool disconnect(void);
public slots:
void setAddress(QHostAddress host);
void setPort(int port);
/** @brief Add a new host to broadcast messages to */
void addHost(const QString& host);
/** @brief Remove a host from broadcasting messages to */
void removeHost(const QString& host);
// void readPendingDatagrams();
/*! @brief Add a new host to broadcast messages to */
void addHost (const QString& host);
/*! @brief Remove a host from broadcasting messages to */
void removeHost (const QString& host);
void readBytes();
/**
/*!
* @brief Write a number of bytes to the interface.
*
* @param data Pointer to the data byte array
......@@ -103,25 +182,19 @@ public slots:
void writeBytes(const char* data, qint64 length);
protected:
QString name;
QHostAddress host;
quint16 port;
int id;
QUdpSocket* socket;
bool connectState;
QList<QHostAddress> hosts;
QList<quint16> ports;
QMutex dataMutex;
void setName(QString name);
QUdpSocket* _socket;
UDPConfiguration* _config;
bool _connectState;
int _id;
private:
// From LinkInterface
virtual bool _connect(void);
virtual bool _disconnect(void);
bool hardwareConnect(void);
bool _hardwareConnect();
void _restartConnection();
signals:
//Signals are defined by LinkInterface
......
......@@ -34,8 +34,6 @@ This file is part of the QGROUNDCONTROL project
#include "QGCApplication.h"
#include "MainWindow.h"
#include "configuration.h"
#include "SerialLink.h"
#include "TCPLink.h"
#ifdef QT_DEBUG
#include "UnitTest.h"
#include "CmdLineOptParser.h"
......@@ -67,7 +65,7 @@ void msgHandler(QtMsgType type, const QMessageLogContext &context, const QString
int WindowsCrtReportHook(int reportType, char* message, int* returnValue)
{
Q_UNUSED(reportType);
std::cerr << message << std::endl; // Output message to stderr
*returnValue = 0; // Don't break into debugger
return true; // We handled this fully ourselves
......@@ -103,23 +101,23 @@ int main(int argc, char *argv[])
// anyway to silence the debug output.
qRegisterMetaType<QSerialPort::SerialPortError>();
qRegisterMetaType<QAbstractSocket::SocketError>();
bool runUnitTests = false; // Run unit tests
#ifdef QT_DEBUG
// We parse a small set of command line options here prior to QGCApplication in order to handle the ones
// which need to be handled before a QApplication object is started.
bool quietWindowsAsserts = false; // Don't let asserts pop dialog boxes
CmdLineOpt_t rgCmdLineOptions[] = {
{ "--unittest", &runUnitTests, QString() },
{ "--no-windows-assert-ui", &quietWindowsAsserts, QString() },
// Add additional command line option flags here
};
ParseCmdLineOptions(argc, argv, rgCmdLineOptions, sizeof(rgCmdLineOptions)/sizeof(rgCmdLineOptions[0]), false);
if (quietWindowsAsserts) {
#ifdef Q_OS_WIN
_CrtSetReportHook(WindowsCrtReportHook);
......@@ -135,27 +133,27 @@ int main(int argc, char *argv[])
}
#endif
#endif // QT_DEBUG
QGCApplication* app = new QGCApplication(argc, argv, runUnitTests);
Q_CHECK_PTR(app);
// There appears to be a threading issue in qRegisterMetaType which can cause it to throw a qWarning
// about duplicate type converters. This is caused by a race condition in the Qt code. Still working
// with them on tracking down the bug. For now we register the type which is giving us problems here
// while we only have the main thread. That should prevent it from hitting the race condition later
// on in the code.
qRegisterMetaType<QList<QPair<QByteArray,QByteArray> > >();
app->_initCommon();
int exitCode;
#ifdef QT_DEBUG
if (runUnitTests) {
if (!app->_initForUnitTests()) {
return -1;
}
// Run the test
int failures = UnitTest::run(rgCmdLineOptions[0].optionArg);
if (failures == 0) {
......@@ -172,10 +170,10 @@ int main(int argc, char *argv[])
}
exitCode = app->exec();
}
delete app;
qDebug() << "After app delete";
return exitCode;
}
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
#include "MockLink.h"
......@@ -65,7 +65,7 @@ union px4_custom_mode {
float data_float;
};
MockLink::MockLink(void) :
MockLink::MockLink(MockConfiguration* config) :
_linkId(getNextLinkId()),
_name("MockLink"),
_connected(false),
......@@ -77,6 +77,7 @@ MockLink::MockLink(void) :
_mavState(MAV_STATE_STANDBY),
_autopilotType(MAV_AUTOPILOT_PX4)
{
_config = config;
union px4_custom_mode px4_cm;
px4_cm.data = 0;
......@@ -85,7 +86,7 @@ MockLink::MockLink(void) :
_missionItemHandler = new MockLinkMissionItemHandler(_vehicleSystemId, this);
Q_CHECK_PTR(_missionItemHandler);
moveToThread(this);
_loadParams();
QObject::connect(this, &MockLink::_incomingBytes, this, &MockLink::_handleIncomingBytes);
......@@ -108,7 +109,7 @@ bool MockLink::_connect(void)
start();
emit connected();
}
return true;
}
......@@ -116,10 +117,10 @@ bool MockLink::_disconnect(void)
{
if (_connected) {
_connected = false;
exit();
exit();
emit disconnected();
}
return true;
}
......@@ -128,17 +129,17 @@ void MockLink::run(void)
QTimer _timer1HzTasks;
QTimer _timer10HzTasks;
QTimer _timer50HzTasks;
QObject::connect(&_timer1HzTasks, &QTimer::timeout, this, &MockLink::_run1HzTasks);
QObject::connect(&_timer10HzTasks, &QTimer::timeout, this, &MockLink::_run10HzTasks);
QObject::connect(&_timer50HzTasks, &QTimer::timeout, this, &MockLink::_run50HzTasks);
_timer1HzTasks.start(1000);
_timer10HzTasks.start(100);
_timer50HzTasks.start(20);
exec();
QObject::disconnect(&_timer1HzTasks, &QTimer::timeout, this, &MockLink::_run1HzTasks);
QObject::disconnect(&_timer10HzTasks, &QTimer::timeout, this, &MockLink::_run10HzTasks);
QObject::disconnect(&_timer50HzTasks, &QTimer::timeout, this, &MockLink::_run50HzTasks);
......@@ -166,27 +167,27 @@ void MockLink::_run50HzTasks(void)
void MockLink::_loadParams(void)
{
QFile paramFile(":/unittest/MockLink.param");
bool success = paramFile.open(QFile::ReadOnly);
Q_UNUSED(success);
Q_ASSERT(success);
QTextStream paramStream(&paramFile);
while (!paramStream.atEnd()) {
QString line = paramStream.readLine();
if (line.startsWith("#")) {
continue;
}
QStringList paramData = line.split("\t");
Q_ASSERT(paramData.count() == 5);
QString paramName = paramData.at(2);
QString valStr = paramData.at(3);
uint paramType = paramData.at(4).toUInt();
QVariant paramValue;
switch (paramType) {
case MAV_PARAM_TYPE_REAL32:
......@@ -205,9 +206,9 @@ void MockLink::_loadParams(void)
Q_ASSERT(false);
break;
}
qCDebug(MockLinkLog) << "Loading param" << paramName << paramValue;
_mapParamName2Value[paramName] = paramValue;
_mapParamName2MavParamType[paramName] = static_cast<MAV_PARAM_TYPE>(paramType);
}
......@@ -237,7 +238,7 @@ void MockLink::writeBytes(const char* bytes, qint64 cBytes)
{
// Package up the data so we can signal it over to the right thread
QByteArray byteArray(bytes, cBytes);
emit _incomingBytes(byteArray);
}
......@@ -251,7 +252,7 @@ void MockLink::_handleIncomingBytes(const QByteArray bytes)
_inNSH = true;
_handleIncomingNSHBytes(&bytes.constData()[3], bytes.count() - 3);
}
_handleIncomingMavlinkBytes((uint8_t *)bytes.constData(), bytes.count());
}
}
......@@ -260,7 +261,7 @@ void MockLink::_handleIncomingBytes(const QByteArray bytes)
void MockLink::_handleIncomingNSHBytes(const char* bytes, int cBytes)
{
Q_UNUSED(cBytes);
// Drop back out of NSH
if (cBytes == 4 && bytes[0] == '\r' && bytes[1] == '\r' && bytes[2] == '\r') {
_inNSH = false;
......@@ -269,7 +270,7 @@ void MockLink::_handleIncomingNSHBytes(const char* bytes, int cBytes)
if (cBytes > 0) {
qDebug() << "NSH:" << (const char*)bytes;
if (strncmp(bytes, "sh /etc/init.d/rc.usb\n", cBytes) == 0) {
// This is the mavlink start command
_mavlinkStarted = true;
......@@ -282,55 +283,55 @@ void MockLink::_handleIncomingMavlinkBytes(const uint8_t* bytes, int cBytes)
{
mavlink_message_t msg;
mavlink_status_t comm;
for (qint64 i=0; i<cBytes; i++)
{
if (!mavlink_parse_char(_linkId, bytes[i], &msg, &comm)) {
continue;
}
Q_ASSERT(_missionItemHandler);
_missionItemHandler->handleMessage(msg);
switch (msg.msgid) {
case MAVLINK_MSG_ID_HEARTBEAT:
_handleHeartBeat(msg);
break;
case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
_handleParamRequestList(msg);
break;
case MAVLINK_MSG_ID_SET_MODE:
_handleSetMode(msg);
break;
case MAVLINK_MSG_ID_PARAM_SET:
_handleParamSet(msg);
break;
case MAVLINK_MSG_ID_PARAM_REQUEST_READ:
_handleParamRequestRead(msg);
break;
case MAVLINK_MSG_ID_MISSION_REQUEST_LIST:
_handleMissionRequestList(msg);
break;
case MAVLINK_MSG_ID_MISSION_REQUEST:
_handleMissionRequest(msg);
break;
case MAVLINK_MSG_ID_MISSION_ITEM:
_handleMissionItem(msg);
break;
#if 0
case MAVLINK_MSG_ID_MISSION_COUNT:
_handleMissionCount(msg);
break;
#endif
default:
qDebug() << "MockLink: Unhandled mavlink message, id:" << msg.msgid;
break;
......@@ -341,7 +342,7 @@ void MockLink::_handleIncomingMavlinkBytes(const uint8_t* bytes, int cBytes)
void MockLink::_emitMavlinkMessage(const mavlink_message_t& msg)
{
uint8_t outputBuffer[MAVLINK_MAX_PACKET_LEN];
int cBuffer = mavlink_msg_to_send_buffer(outputBuffer, &msg);
QByteArray bytes((char *)outputBuffer, cBuffer);
emit bytesReceived(this, bytes);
......@@ -360,9 +361,9 @@ void MockLink::_handleSetMode(const mavlink_message_t& msg)
{
mavlink_set_mode_t request;
mavlink_msg_set_mode_decode(&msg, &request);
Q_ASSERT(request.target_system == _vehicleSystemId);
_mavBaseMode = request.base_mode;
_mavCustomMode = request.custom_mode;
}
......@@ -370,37 +371,37 @@ void MockLink::_handleSetMode(const mavlink_message_t& msg)
void MockLink::_setParamFloatUnionIntoMap(const QString& paramName, float paramFloat)
{
mavlink_param_union_t valueUnion;
Q_ASSERT(_mapParamName2Value.contains(paramName));
Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
valueUnion.param_float = paramFloat;
MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
QVariant paramVariant;
switch (paramType) {
case MAV_PARAM_TYPE_INT8:
paramVariant = QVariant::fromValue(valueUnion.param_int8);
break;
case MAV_PARAM_TYPE_INT32:
paramVariant = QVariant::fromValue(valueUnion.param_int32);
break;
case MAV_PARAM_TYPE_UINT32:
paramVariant = QVariant::fromValue(valueUnion.param_uint32);
break;
case MAV_PARAM_TYPE_REAL32:
paramVariant = QVariant::fromValue(valueUnion.param_float);
break;
default:
qCritical() << "Invalid parameter type" << paramType;
}
qCDebug(MockLinkLog) << "_setParamFloatUnionIntoMap" << paramName << paramVariant;
_mapParamName2Value[paramName] = paramVariant;
}
......@@ -409,34 +410,34 @@ void MockLink::_setParamFloatUnionIntoMap(const QString& paramName, float paramF
float MockLink::_floatUnionForParam(const QString& paramName)
{
mavlink_param_union_t valueUnion;
Q_ASSERT(_mapParamName2Value.contains(paramName));
Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
QVariant paramVar = _mapParamName2Value[paramName];
switch (paramType) {
case MAV_PARAM_TYPE_INT8:
valueUnion.param_int8 = (unsigned char)paramVar.toChar().toLatin1();
break;
case MAV_PARAM_TYPE_INT32:
valueUnion.param_int32 = paramVar.toInt();
break;
case MAV_PARAM_TYPE_UINT32:
valueUnion.param_uint32 = paramVar.toUInt();
break;
case MAV_PARAM_TYPE_REAL32:
valueUnion.param_float = paramVar.toFloat();
break;
default:
qCritical() << "Invalid parameter type" << paramType;
}
return valueUnion.param_float;
}
......@@ -444,27 +445,27 @@ void MockLink::_handleParamRequestList(const mavlink_message_t& msg)
{
uint16_t paramIndex = 0;
mavlink_param_request_list_t request;
mavlink_msg_param_request_list_decode(&msg, &request);
int cParameters = _mapParamName2Value.count();
Q_ASSERT(request.target_system == _vehicleSystemId);
foreach(QString paramName, _mapParamName2Value.keys()) {
char paramId[MAVLINK_MSG_ID_PARAM_VALUE_LEN];
mavlink_message_t responseMsg;
Q_ASSERT(_mapParamName2Value.contains(paramName));
Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
Q_ASSERT(paramName.length() <= MAVLINK_MSG_ID_PARAM_VALUE_LEN);
strncpy(paramId, paramName.toLocal8Bit().constData(), MAVLINK_MSG_ID_PARAM_VALUE_LEN);
qCDebug(MockLinkLog) << "Sending msg_param_value" << paramId << paramType;
mavlink_msg_param_value_pack(_vehicleSystemId,
_vehicleComponentId,
&responseMsg, // Outgoing message
......@@ -481,19 +482,19 @@ void MockLink::_handleParamSet(const mavlink_message_t& msg)
{
mavlink_param_set_t request;
mavlink_msg_param_set_decode(&msg, &request);
Q_ASSERT(request.target_system == _vehicleSystemId);
// Param may not be null terminated if exactly fits
char paramId[MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN + 1];
strncpy(paramId, request.param_id, MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN);
Q_ASSERT(_mapParamName2Value.contains(paramId));
Q_ASSERT(request.param_type == _mapParamName2MavParamType[paramId]);
// Save the new value
_setParamFloatUnionIntoMap(paramId, request.param_value);
// Respond with a param_value to ack
mavlink_message_t responseMsg;
mavlink_msg_param_value_pack(_vehicleSystemId,
......@@ -511,20 +512,20 @@ void MockLink::_handleParamRequestRead(const mavlink_message_t& msg)
{
mavlink_param_request_read_t request;
mavlink_msg_param_request_read_decode(&msg, &request);
char paramId[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN + 1];
paramId[0] = 0;
Q_ASSERT(request.target_system == _vehicleSystemId);
if (request.param_index == -1) {
// Request is by param name. Param may not be null terminated if exactly fits
strncpy(paramId, request.param_id, MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN);
} else {
// Request is by index
Q_ASSERT(request.param_index >= 0 && request.param_index < _mapParamName2Value.count());
QString key = _mapParamName2Value.keys().at(request.param_index);
Q_ASSERT(key.length() <= MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN);
strcpy(paramId, key.toLocal8Bit().constData());
......@@ -532,9 +533,9 @@ void MockLink::_handleParamRequestRead(const mavlink_message_t& msg)
Q_ASSERT(_mapParamName2Value.contains(paramId));
Q_ASSERT(_mapParamName2MavParamType.contains(paramId));
mavlink_message_t responseMsg;
mavlink_msg_param_value_pack(_vehicleSystemId,
_vehicleComponentId,
&responseMsg, // Outgoing message
......@@ -549,11 +550,11 @@ void MockLink::_handleParamRequestRead(const mavlink_message_t& msg)
void MockLink::_handleMissionRequestList(const mavlink_message_t& msg)
{
mavlink_mission_request_list_t request;
mavlink_msg_mission_request_list_decode(&msg, &request);
Q_ASSERT(request.target_system == _vehicleSystemId);
mavlink_message_t responseMsg;
mavlink_msg_mission_count_pack(_vehicleSystemId,
......@@ -568,12 +569,12 @@ void MockLink::_handleMissionRequestList(const mavlink_message_t& msg)
void MockLink::_handleMissionRequest(const mavlink_message_t& msg)
{
mavlink_mission_request_t request;
mavlink_msg_mission_request_decode(&msg, &request);
Q_ASSERT(request.target_system == _vehicleSystemId);
Q_ASSERT(request.seq < _missionItems.count());
mavlink_message_t responseMsg;
mavlink_mission_item_t item = _missionItems[request.seq];
......@@ -596,13 +597,13 @@ void MockLink::_handleMissionRequest(const mavlink_message_t& msg)
void MockLink::_handleMissionItem(const mavlink_message_t& msg)
{
mavlink_mission_item_t request;
mavlink_msg_mission_item_decode(&msg, &request);
Q_ASSERT(request.target_system == _vehicleSystemId);
// FIXME: What do you do with duplication sequence numbers?
Q_ASSERT(!_missionItems.contains(request.seq));
_missionItems[request.seq] = request;
}
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
#ifndef MOCKLINK_H
......@@ -28,7 +28,7 @@
#include <QLoggingCategory>
#include "MockLinkMissionItemHandler.h"
#include "LinkInterface.h"
#include "LinkManager.h"
#include "QGCMAVLink.h"
Q_DECLARE_LOGGING_CATEGORY(MockLinkLog)
......@@ -38,14 +38,28 @@ Q_DECLARE_LOGGING_CATEGORY(MockLinkLog)
///
/// @author Don Gagne <don@thegagnes.com>
class MockConfiguration : public LinkConfiguration
{
public:
MockConfiguration(const QString& name) : LinkConfiguration(name) {}
MockConfiguration(MockConfiguration* source) : LinkConfiguration(source) {}
int type() { return LinkConfiguration::TypeMock; }
void copyFrom(LinkConfiguration* source) { LinkConfiguration::copyFrom(source); }
void loadSettings(QSettings& settings, const QString& root) { Q_UNUSED(settings); Q_UNUSED(root); }
void saveSettings(QSettings& settings, const QString& root) { Q_UNUSED(settings); Q_UNUSED(root); }
void updateSettings() {}
};
class MockLink : public LinkInterface
{
Q_OBJECT
public:
MockLink(void);
// LinkConfiguration is optional for MockLink
MockLink(MockConfiguration* config = NULL);
~MockLink(void);
// Virtuals from LinkInterface
virtual int getId(void) const { return _linkId; }
virtual QString getName(void) const { return _name; }
......@@ -53,40 +67,42 @@ public:
virtual bool isConnected(void) const { return _connected; }
virtual qint64 getConnectionSpeed(void) const { return 100000000; }
virtual qint64 bytesAvailable(void) { return 0; }
// MockLink methods
MAV_AUTOPILOT getAutopilotType(void) { return _autopilotType; }
void setAutopilotType(MAV_AUTOPILOT autopilot) { _autopilotType = autopilot; }
// These are left unimplemented in order to cause linker errors which indicate incorrect usage of
// connect/disconnect on link directly. All connect/disconnect calls should be made through LinkManager.
bool connect(void);
bool disconnect(void);
LinkConfiguration* getLinkConfiguration() { return _config; }
signals:
/// @brief Used internally to move data to the thread.
void _incomingBytes(const QByteArray bytes);
public slots:
virtual void writeBytes(const char *bytes, qint64 cBytes);
protected slots:
// FIXME: This should not be part of LinkInterface. It is an internal link implementation detail.
virtual void readBytes(void);
private slots:
void _run1HzTasks(void);
void _run10HzTasks(void);
void _run50HzTasks(void);
private:
// From LinkInterface
virtual bool _connect(void);
virtual bool _disconnect(void);
// QThread override
virtual void run(void);
// MockLink methods
void _sendHeartBeat(void);
void _handleIncomingBytes(const QByteArray bytes);
......@@ -106,27 +122,28 @@ private:
void _setParamFloatUnionIntoMap(const QString& paramName, float paramFloat);
MockLinkMissionItemHandler* _missionItemHandler;
int _linkId;
QString _name;
bool _connected;
uint8_t _vehicleSystemId;
uint8_t _vehicleComponentId;
bool _inNSH;
bool _mavlinkStarted;
QMap<QString, QVariant> _mapParamName2Value;
QMap<QString, MAV_PARAM_TYPE> _mapParamName2MavParamType;
typedef QMap<uint16_t, mavlink_mission_item_t> MissionList_t;
MissionList_t _missionItems;
uint8_t _mavBaseMode;
uint8_t _mavCustomMode;
uint8_t _mavState;
MockConfiguration* _config;
MAV_AUTOPILOT _autopilotType;
};
......
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
#ifndef MOCKLINKMISSIONITEMHANDLER_H
......@@ -32,6 +32,7 @@
#include "MAVLinkSimulationLink.h"
#include "QGCMAVLink.h"
/* Alreedy defined in MAVLinkSimulationLink.h above!
enum PX_WAYPOINTPLANNER_STATES {
PX_WPP_IDLE = 0,
PX_WPP_SENDLIST,
......@@ -40,14 +41,15 @@ enum PX_WAYPOINTPLANNER_STATES {
PX_WPP_GETLIST_GETWPS,
PX_WPP_GETLIST_GOTALL
};
*/
class MockLinkMissionItemHandler : public QObject
{
Q_OBJECT
public:
MockLinkMissionItemHandler(uint16_t systemId, QObject* parent = NULL);
/// @brief Called to handle mission item related messages. All messages should be passed to this method.
/// It will handle the appropriate set.
void handleMessage(const mavlink_message_t& msg);
......@@ -98,10 +100,10 @@ protected:
float distanceToPoint(uint16_t seq, float x, float y);
void mavlink_handler(const mavlink_message_t* msg);
#endif
private:
uint16_t _vehicleSystemId; ///< System id of this vehicle
QList<mavlink_mission_item_t> _missionItems; ///< Current set of mission itemss
};
......
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief Implementation of CommConfigurationWindow
*
* @author Lorenz Meier <mavteam@student.ethz.ch>
*
*/
#include <QDebug>
#include <QDir>
#include <QFileInfoList>
#include <QBoxLayout>
#include <QWidget>
#include "CommConfigurationWindow.h"
#include "SerialConfigurationWindow.h"
#include "SerialLink.h"
#include "UDPLink.h"
#include "TCPLink.h"
#include "MAVLinkSimulationLink.h"
#ifdef UNITTEST_BUILD
#include "MockLink.h"
#endif
#ifdef QGC_XBEE_ENABLED
#include "XbeeLink.h"
#include "XbeeConfigurationWindow.h"
#endif // QGC_XBEE_ENABLED
#ifdef QGC_RTLAB_ENABLED
#include "OpalLink.h"
#include "OpalLinkConfigurationWindow.h"
#endif
#include "MAVLinkProtocol.h"
#include "MAVLinkSettingsWidget.h"
#include "QGCUDPLinkConfiguration.h"
#include "QGCTCPLinkConfiguration.h"
#include "LinkManager.h"
#include "MainWindow.h"
CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, QWidget *parent) : QDialog(parent)
{
this->link = link;
// Setup the user interface according to link type
ui.setupUi(this);
// Initialize basic ui state
// Do not allow changes here unless advanced is checked
ui.connectionType->setEnabled(false);
ui.protocolGroupBox->setVisible(false);
ui.protocolTypeGroupBox->setVisible(false);
// Connect UI element visibility to checkbox
//connect(ui.advancedOptionsCheckBox, SIGNAL(clicked(bool)), ui.connectionType, SLOT(setEnabled(bool)));
//connect(ui.advancedOptionsCheckBox, SIGNAL(clicked(bool)), ui.linkType, SLOT(setEnabled(bool)));
//connect(ui.advancedOptionsCheckBox, SIGNAL(clicked(bool)), ui.protocolGroupBox, SLOT(setVisible(bool)));
ui.advancedOptionsCheckBox->setVisible(false);
//connect(ui.advCheckBox,SIGNAL(clicked(bool)),ui.advancedOptionsCheckBox,SLOT(setChecked(bool)));
connect(ui.advCheckBox,SIGNAL(clicked(bool)),ui.protocolTypeGroupBox,SLOT(setVisible(bool)));
connect(ui.advCheckBox, SIGNAL(clicked(bool)), ui.connectionType, SLOT(setEnabled(bool)));
connect(ui.advCheckBox, SIGNAL(clicked(bool)), ui.protocolGroupBox, SLOT(setVisible(bool)));
// add link types
ui.linkType->addItem(tr("Serial"), QGC_LINK_SERIAL);
ui.linkType->addItem(tr("UDP"), QGC_LINK_UDP);
ui.linkType->addItem(tr("TCP"), QGC_LINK_TCP);
if(dynamic_cast<MAVLinkSimulationLink*>(link)) {
//Only show simulation option if already setup elsewhere as a simulation
ui.linkType->addItem(tr("Simulation"), QGC_LINK_SIMULATION);
}
#ifdef UNITTEST_BUILD
ui.linkType->addItem(tr("Mock"), QGC_LINK_MOCK);
#endif
#ifdef QGC_RTLAB_ENABLED
ui.linkType->addItem(tr("Opal-RT Link"), QGC_LINK_OPAL);
#endif
#ifdef QGC_XBEE_ENABLED
ui.linkType->addItem(tr("Xbee API"),QGC_LINK_XBEE);
#endif // QGC_XBEE_ENABLED
ui.linkType->setEditable(false);
ui.connectionType->addItem("MAVLink", QGC_PROTOCOL_MAVLINK);
// Create action to open this menu
// Create configuration action for this link
// Connect the current UAS
action = new QAction(QIcon(":/files/images/devices/network-wireless.svg"), "", this);
action->setData(link->getId());
action->setEnabled(true);
action->setVisible(true);
setLinkName(link->getName());
connect(action, SIGNAL(triggered()), this, SLOT(show()));
// Make sure that a change in the link name will be reflected in the UI
connect(link, SIGNAL(nameChanged(QString)), this, SLOT(setLinkName(QString)));
// Setup user actions and link notifications
connect(ui.connectButton, SIGNAL(clicked()), this, SLOT(setConnection()));
connect(ui.closeButton, SIGNAL(clicked()), this->window(), SLOT(close()));
connect(ui.deleteButton, SIGNAL(clicked()), this, SLOT(remove()));
connect(link, &LinkInterface::connected, this, &CommConfigurationWindow::_linkConnected);
connect(link, &LinkInterface::disconnected, this, &CommConfigurationWindow::_linkDisconnected);
// Fill in the current data
if(this->link->isConnected()) ui.connectButton->setChecked(true);
if(this->link->isConnected()) {
ui.connectionStatusLabel->setText(tr("Connected"));
// TODO Deactivate all settings to force user to manually disconnect first
} else {
ui.connectionStatusLabel->setText(tr("Disconnected"));
}
// TODO Move these calls to each link so that dynamic casts vanish
// Open details pane for serial link if necessary
SerialLink* serial = dynamic_cast<SerialLink*>(link);
if(serial != 0) {
QWidget* conf = new SerialConfigurationWindow(serial, this);
ui.linkScrollArea->setWidget(conf);
ui.linkGroupBox->setTitle(tr("Serial Link"));
ui.linkType->setCurrentIndex(ui.linkType->findData(QGC_LINK_SERIAL));
}
UDPLink* udp = dynamic_cast<UDPLink*>(link);
if (udp != 0) {
QWidget* conf = new QGCUDPLinkConfiguration(udp, this);
ui.linkScrollArea->setWidget(conf);
ui.linkGroupBox->setTitle(tr("UDP Link"));
ui.linkType->setCurrentIndex(ui.linkType->findData(QGC_LINK_UDP));
}
TCPLink* tcp = dynamic_cast<TCPLink*>(link);
if (tcp != 0) {
QWidget* conf = new QGCTCPLinkConfiguration(tcp, this);
ui.linkScrollArea->setWidget(conf);
ui.linkGroupBox->setTitle(tr("TCP Link"));
ui.linkType->setCurrentIndex(ui.linkType->findData(QGC_LINK_TCP));
}
MAVLinkSimulationLink* sim = dynamic_cast<MAVLinkSimulationLink*>(link);
if (sim != 0) {
ui.linkType->setCurrentIndex(ui.linkType->findData(QGC_LINK_SIMULATION));
ui.linkType->setEnabled(false); //Don't allow the user to change to a non-simulation
ui.linkGroupBox->setTitle(tr("MAVLink Simulation Link"));
}
#ifdef UNITTEST_BUILD
MockLink* mock = dynamic_cast<MockLink*>(link);
if (mock != 0) {
ui.linkGroupBox->setTitle(tr("Mock Link"));
ui.linkType->setCurrentIndex(ui.linkType->findData(QGC_LINK_MOCK));
}
#endif
#ifdef QGC_RTLAB_ENABLED
OpalLink* opal = dynamic_cast<OpalLink*>(link);
if (opal != 0) {
QWidget* conf = new OpalLinkConfigurationWindow(opal, this);
QBoxLayout* layout = new QBoxLayout(QBoxLayout::LeftToRight, ui.linkGroupBox);
layout->addWidget(conf);
ui.linkGroupBox->setLayout(layout);
ui.linkType->setCurrentIndex(ui.linkType->findData(QGC_LINK_OPAL));
ui.linkGroupBox->setTitle(tr("Opal-RT Link"));
}
#endif
#ifdef QGC_XBEE_ENABLED
XbeeLink* xbee = dynamic_cast<XbeeLink*>(link); // new Konrad
if(xbee != 0)
{
QWidget* conf = new XbeeConfigurationWindow(xbee,this);
ui.linkScrollArea->setWidget(conf);
ui.linkGroupBox->setTitle(tr("Xbee Link"));
ui.linkType->setCurrentIndex(ui.linkType->findData(QGC_LINK_XBEE));
connect(xbee,SIGNAL(tryConnectBegin(bool)),ui.actionConnect,SLOT(setDisabled(bool)));
connect(xbee,SIGNAL(tryConnectEnd(bool)),ui.actionConnect,SLOT(setEnabled(bool)));
}
#endif // QGC_XBEE_ENABLED
if (serial == 0 && udp == 0 && sim == 0 && tcp == 0
#ifdef UNITTEST_BUILD
&& mock == 0
#endif
#ifdef QGC_RTLAB_ENABLED
&& opal == 0
#endif
#ifdef QGC_XBEE_ENABLED
&& xbee == 0
#endif // QGC_XBEE_ENABLED
) {
qDebug() << "Link is NOT a known link, can't open configuration window";
}
connect(ui.linkType,SIGNAL(currentIndexChanged(int)),this,SLOT(linkCurrentIndexChanged(int)));
// Open details pane for MAVLink if necessary
MAVLinkProtocol* mavlink = MAVLinkProtocol::instance();
QWidget* conf = new MAVLinkSettingsWidget(mavlink, this);
ui.protocolScrollArea->setWidget(conf);
ui.protocolGroupBox->setTitle(mavlink->getName()+" (Global Settings)");
// Open details for UDP link if necessary
// TODO
// Display the widget
this->window()->setWindowTitle(tr("Settings for ") + this->link->getName());
this->hide();
}
CommConfigurationWindow::~CommConfigurationWindow()
{
}
QAction* CommConfigurationWindow::getAction()
{
return action;
}
void CommConfigurationWindow::linkCurrentIndexChanged(int currentIndex)
{
setLinkType(static_cast<qgc_link_t>(ui.linkType->itemData(currentIndex).toInt()));
}
void CommConfigurationWindow::setLinkType(qgc_link_t linktype)
{
if(link->isConnected())
{
// close old configuration window
this->window()->close();
}
else
{
// delete old configuration window
this->remove();
}
LinkInterface *tmpLink(NULL);
switch(linktype)
{
#ifdef QGC_XBEE_ENABLED
case QGC_LINK_XBEE:
{
XbeeLink *xbee = new XbeeLink();
tmpLink = xbee;
break;
}
#endif // QGC_XBEE_ENABLED
case QGC_LINK_UDP:
{
UDPLink *udp = new UDPLink();
tmpLink = udp;
break;
}
case QGC_LINK_TCP:
{
TCPLink *tcp = new TCPLink();
tmpLink = tcp;
break;
}
#ifdef QGC_RTLAB_ENABLED
case QGC_LINK_OPAL:
{
OpalLink* opal = new OpalLink();
tmpLink = opal;
break;
}
#endif // QGC_RTLAB_ENABLED
#ifdef UNITTEST_BUILD
case QGC_LINK_MOCK:
{
MockLink* mock = new MockLink;
tmpLink = mock;
break;
}
#endif
default:
case QGC_LINK_SERIAL:
{
SerialLink *serial = new SerialLink();
tmpLink = serial;
break;
}
}
if (tmpLink) {
LinkManager::instance()->addLink(tmpLink);
}
// trigger new window
const int32_t& linkIndex(LinkManager::instance()->getLinks().indexOf(tmpLink));
const int32_t& linkID(LinkManager::instance()->getLinks()[linkIndex]->getId());
QList<QAction*> actions = MainWindow::instance()->listLinkMenuActions();
foreach (QAction* act, actions)
{
if (act->data().toInt() == linkID)
{
act->trigger();
break;
}
}
}
void CommConfigurationWindow::setProtocol(int protocol)
{
qDebug() << "Changing to protocol" << protocol;
}
void CommConfigurationWindow::setConnection()
{
if(!link->isConnected()) {
LinkManager::instance()->connectLink(link);
QGC::SLEEP::msleep(100);
if (link->isConnected())
// Auto-close window on connect
this->window()->close();
} else {
LinkManager::instance()->disconnectLink(link);
}
}
void CommConfigurationWindow::setLinkName(QString name)
{
action->setText(tr("%1 Settings").arg(name));
action->setStatusTip(tr("Adjust setting for link %1").arg(name));
this->window()->setWindowTitle(tr("Settings for %1").arg(name));
}
void CommConfigurationWindow::remove()
{
if(action) delete action; //delete action first since it has a pointer to link
action=NULL;
if(link) {
link->deleteLater();
}
link=NULL;
this->window()->close();
this->deleteLater();
}
void CommConfigurationWindow::_linkConnected(void) {
_connectionState(true);
}
void CommConfigurationWindow::_linkDisconnected(void) {
_connectionState(false);
}
void CommConfigurationWindow::_connectionState(bool connect)
{
ui.connectButton->setChecked(connect);
if(connect) {
ui.connectionStatusLabel->setText(tr("Connected"));
ui.connectButton->setText(tr("Disconnect"));
} else {
ui.connectionStatusLabel->setText(tr("Disconnected"));
ui.connectButton->setText(tr("Connect"));
}
}
This diff is collapsed.
This diff is collapsed.
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