diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index e80135e7c07142be020c476644678f06f71db978..01560073aa01824799246b5dfc1db4b72163904a 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -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 diff --git a/src/QGCApplication.cc b/src/QGCApplication.cc index cbe770a72a499d3caa5d4663e31bfbfb48660b18..7c29cfdb84fe27d2c709471e4617dc0a5774fd28 100644 --- a/src/QGCApplication.cc +++ b/src/QGCApplication.cc @@ -1,24 +1,24 @@ /*===================================================================== - + QGroundControl Open Source Ground Control Station - + (c) 2009 - 2015 QGROUNDCONTROL PROJECT - + 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 . - + ======================================================================*/ /** @@ -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(); } diff --git a/src/QGCMessageBox.h b/src/QGCMessageBox.h index 3116264bea0623b4053016f376d144016acf5765..dfda32d18a7bac8e3721784d09ee07f9deb60b63 100644 --- a/src/QGCMessageBox.h +++ b/src/QGCMessageBox.h @@ -1,24 +1,24 @@ /*===================================================================== - + QGroundControl Open Source Ground Control Station - + (c) 2009 - 2014 QGROUNDCONTROL PROJECT - + 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 . - + ======================================================================*/ #ifndef QGCMESSAGEBOX_H @@ -40,34 +40,34 @@ /// @author Don Gagne 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(buttons); int buttonCount = 0; for (size_t i=0; i 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(static_cast(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); diff --git a/src/comm/LinkConfiguration.cc b/src/comm/LinkConfiguration.cc new file mode 100644 index 0000000000000000000000000000000000000000..c3069903cfb5e8b72ecce8c4cf2f133692ee8655 --- /dev/null +++ b/src/comm/LinkConfiguration.cc @@ -0,0 +1,117 @@ +/*===================================================================== + +QGroundControl Open Source Ground Control Station + +(c) 2009, 2010 QGROUNDCONTROL PROJECT + +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 . + +======================================================================*/ + +/*! + @file + @brief Link specific configuration base class + @author Gus Grubba +*/ + +#include "LinkConfiguration.h" +#include "SerialLink.h" +#include "UDPLink.h" + +#ifdef UNITTEST_BUILD +#include "MockLink.h" +#endif + +#define LINK_SETTING_ROOT "LinkConfigurations" + +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()); +} + +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; +#ifdef UNITTEST_BUILD + case LinkConfiguration::TypeMock: + config = new MockConfiguration(name); + break; +#endif + } + 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(source)); + break; + case TypeUdp: + dupe = new UDPConfiguration(dynamic_cast(source)); + break; +#ifdef UNITTEST_BUILD + case TypeMock: + dupe = new MockConfiguration(dynamic_cast(source)); + break; +#endif + } + return dupe; +} diff --git a/src/comm/LinkConfiguration.h b/src/comm/LinkConfiguration.h new file mode 100644 index 0000000000000000000000000000000000000000..0c09ba7670d88061675a829c2ac13f0e999065ec --- /dev/null +++ b/src/comm/LinkConfiguration.h @@ -0,0 +1,176 @@ +/*===================================================================== + +QGroundControl Open Source Ground Control Station + +(c) 2009, 2010 QGROUNDCONTROL PROJECT + +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 . + +======================================================================*/ + +#ifndef LINKCONFIGURATION_H +#define LINKCONFIGURATION_H + +#include + +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 + // 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 +#ifdef UNITTEST_BUILD + TypeMock, ///< Mock Link for Unitesting +#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 diff --git a/src/comm/LinkInterface.h b/src/comm/LinkInterface.h index 5085aeeccbed8c8bb1b2e2ae2cd7671c90b090a4..aa5526d141f93a6717529d5725f7b84e4ac4e359 100644 --- a/src/comm/LinkInterface.h +++ b/src/comm/LinkInterface.h @@ -39,6 +39,7 @@ along with PIXHAWK. If not, see . #include 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*"); } + /** + * @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 }; diff --git a/src/comm/LinkManager.cc b/src/comm/LinkManager.cc index 0e523893e7bb853ea9c41d7a29c8f1270f5c8b77..f51747b1967c23e29ca22ce335f6b67bcb922a7a 100644 --- a/src/comm/LinkManager.cc +++ b/src/comm/LinkManager.cc @@ -32,6 +32,7 @@ This file is part of the QGROUNDCONTROL project #include #include #include +#include #include "LinkManager.h" #include "MainWindow.h" @@ -40,32 +41,76 @@ 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(config)); + break; + case LinkConfiguration::TypeUdp: + pLink = new UDPLink(dynamic_cast(config)); + break; +#ifdef UNITTEST_BUILD + case LinkConfiguration::TypeMock: + pLink = new MockLink(dynamic_cast(config)); + break; +#endif + } + 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 +118,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 +139,7 @@ bool LinkManager::connectAll() if (_connectionsSuspendedMsg()) { return false; } - + bool allConnected = true; _linkListMutex.lock(); @@ -129,7 +174,7 @@ bool LinkManager::disconnectAll() bool LinkManager::connectLink(LinkInterface* link) { Q_ASSERT(link); - + if (_connectionsSuspendedMsg()) { return false; } @@ -144,8 +189,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 +207,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 +235,7 @@ const QList LinkManager::getLinks() return ret; } -const QList LinkManager::getSerialLinks() +const QList LinkManager::getSerialLinks() { _linkListMutex.lock(); QList s; @@ -191,7 +243,7 @@ const QList LinkManager::getSerialLinks() foreach (LinkInterface* link, _links) { Q_ASSERT(link); - + SerialLink* serialLink = qobject_cast(link); if (serialLink) @@ -240,3 +292,176 @@ 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 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; +#ifdef UNITTEST_BUILD + case LinkConfiguration::TypeMock: + pLink = (LinkConfiguration*)new MockConfiguration(name); + pLink->setPreferred(false); + break; +#endif + } + 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(pLink); + if(pSerial->portName() == searchPort) { + return pSerial; + } + } + } + return NULL; +} + +void LinkManager::_updateConfigurationList(void) +{ + if (_configUpdateSuspended || !_configurationsLoaded) { + return; + } + bool saveList = false; + QList 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(); + } +} + diff --git a/src/comm/LinkManager.h b/src/comm/LinkManager.h index 6f6aedf753c60c4e03f080359f5953338f0e6060..ad4e7d62784d3e698133c086f23fc0aa22a3e8d8 100644 --- a/src/comm/LinkManager.h +++ b/src/comm/LinkManager.h @@ -31,8 +31,17 @@ This file is part of the PIXHAWK project #include #include +#include "LinkConfiguration.h" #include "LinkInterface.h" + +// Links #include "SerialLink.h" +#include "UDPLink.h" + +#ifdef UNITTEST_BUILD +#include "MockLink.h" +#endif + #include "ProtocolInterface.h" #include "QGCSingleton.h" #include "MAVLinkProtocol.h" @@ -48,14 +57,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 getLinkConfigurationList(); + + /// Suspend automatic confguration updates (during link maintenance for instance) + void suspendConfigurationUpdates(bool suspend); + /// Returns list of all links const QList getLinks(); @@ -65,53 +98,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 _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 _linkConfigurations; ///< List of configured links + QList _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 diff --git a/src/comm/SerialLink.cc b/src/comm/SerialLink.cc index 582a5e2994aa5c1461150403f21e4bfa4d53b030..947b88dde02a3d306588f4514e608f676d66bc0a 100644 --- a/src/comm/SerialLink.cc +++ b/src/comm/SerialLink.cc @@ -18,253 +18,135 @@ #include "QGC.h" #include -SerialLink::SerialLink(QString portname, int baudRate, bool hardwareFlowControl, bool parity, - int dataBits, int stopBits) : - m_bytesRead(0), - m_port(Q_NULLPTR), - type(""), - m_is_cdc(true), - m_stopp(false), - m_reqReset(false) -{ +SerialLink::SerialLink(SerialConfiguration* config) +{ + _bytesRead = 0; + _port = Q_NULLPTR; + _stopp = false; + _reqReset = 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); - - // Get the name of the current port in use. - m_portName = portname.trimmed(); - QList ports = getCurrentPorts(); - if (m_portName == "" && ports.size() > 0) - { - m_portName = ports.first().trimmed(); - } - - checkIfCDC(); - // Set unique ID and add link to the list of links - m_id = getNextLinkId(); + _id = getNextLinkId(); - m_baud = baudRate; - - if (hardwareFlowControl) - { - m_flowControl = QSerialPort::HardwareControl; - } - else - { - m_flowControl = QSerialPort::NoFlowControl; - } - if (parity) - { - m_parity = QSerialPort::EvenParity; - } - else - { - m_parity = QSerialPort::NoParity; - } - - m_dataBits = dataBits; - m_stopBits = stopBits; - - loadSettings(); - - qDebug() << "create SerialLink " << portname << baudRate << hardwareFlowControl - << parity << dataBits << stopBits; - qDebug() << "m_portName " << m_portName; + qDebug() << "Create SerialLink " << config->portName() << config->baud() << config->flowControl() + << config->parity() << config->dataBits() << config->stopBits(); + qDebug() << "portName: " << config->portName(); } void SerialLink::requestReset() { - QMutexLocker locker(&this->m_stoppMutex); - m_reqReset = true; + QMutexLocker locker(&this->_stoppMutex); + _reqReset = true; } SerialLink::~SerialLink() { + // Disconnect link from configuration + _config->setLink(NULL); _disconnect(); - if(m_port) delete m_port; - m_port = NULL; - + if(_port) delete _port; + _port = NULL; // Tell the thread to exit quit(); // Wait for it to exit wait(); } -QList SerialLink::getCurrentPorts() +bool SerialLink::_isBootloader() { - QList ports; - QList portList = QSerialPortInfo::availablePorts(); - foreach (const QSerialPortInfo &info, portList) - { - ports.append(info.portName()); - } - - return ports; -} - -bool SerialLink::isBootloader() -{ - QList portList = QSerialPortInfo::availablePorts(); - if( portList.count() == 0){ return false; } - foreach (const QSerialPortInfo &info, portList) { // XXX debug statements will be removed once we have 100% stable link reports // qDebug() << "PortName : " << info.portName() // << "Description : " << info.description(); // qDebug() << "Manufacturer: " << info.manufacturer(); - - if (info.portName().trimmed() == this->m_portName.trimmed() && - (info.description().toLower().contains("bootloader") || - info.description().toLower().contains("px4 bl") || - info.description().toLower().contains("px4 fmu v1.6"))) { -// qDebug() << "BOOTLOADER FOUND"; + if (info.portName().trimmed() == _config->portName() && + (info.description().toLower().contains("bootloader") || + info.description().toLower().contains("px4 bl") || + info.description().toLower().contains("px4 fmu v1.6"))) { +// qDebug() << "BOOTLOADER FOUND"; return true; } } - // Not found return false; } -void SerialLink::loadSettings() -{ - // Load defaults from settings - QSettings settings; - if (settings.contains("SERIALLINK_COMM_PORT")) - { - m_portName = settings.value("SERIALLINK_COMM_PORT").toString(); - checkIfCDC(); - - m_baud = settings.value("SERIALLINK_COMM_BAUD").toInt(); - m_parity = settings.value("SERIALLINK_COMM_PARITY").toInt(); - m_stopBits = settings.value("SERIALLINK_COMM_STOPBITS").toInt(); - m_dataBits = settings.value("SERIALLINK_COMM_DATABITS").toInt(); - m_flowControl = settings.value("SERIALLINK_COMM_FLOW_CONTROL").toInt(); - } -} - -void SerialLink::writeSettings() -{ - // Store settings - QSettings settings; - settings.setValue("SERIALLINK_COMM_PORT", getPortName()); - settings.setValue("SERIALLINK_COMM_BAUD", getBaudRateType()); - settings.setValue("SERIALLINK_COMM_PARITY", getParityType()); - settings.setValue("SERIALLINK_COMM_STOPBITS", getStopBits()); - settings.setValue("SERIALLINK_COMM_DATABITS", getDataBits()); - settings.setValue("SERIALLINK_COMM_FLOW_CONTROL", getFlowType()); -} - -void SerialLink::checkIfCDC() -{ - QString description = "X"; - foreach (QSerialPortInfo info,QSerialPortInfo::availablePorts()) - { - if (m_portName == info.portName()) - { - description = info.description(); - break; - } - } - if (description.toLower().contains("mega") && description.contains("2560")) - { - type = "apm"; - m_is_cdc = false; - qDebug() << "Attempting connection to an APM, with description:" << description; - } - else if (description.toLower().contains("px4")) - { - type = "px4"; - m_is_cdc = true; - qDebug() << "Attempting connection to a PX4 unit with description:" << description; - } - else - { - type = "other"; - m_is_cdc = false; - qDebug() << "Attempting connection to something unknown with description:" << description; - } -} - - /** * @brief Runs the thread * **/ void SerialLink::run() { - checkIfCDC(); - // Initialize the connection - if (!hardwareConnect(type)) { - //Need to error out here. + if (!_hardwareConnect(_type)) { + // Need to error out here. QString err("Could not create port."); - if (m_port) { - err = m_port->errorString(); + if (_port) { + err = _port->errorString(); } _emitLinkError("Error connecting: " + err); return; } - qint64 msecs = QDateTime::currentMSecsSinceEpoch(); - qint64 initialmsecs = QDateTime::currentMSecsSinceEpoch(); + qint64 msecs = QDateTime::currentMSecsSinceEpoch(); + qint64 initialmsecs = QDateTime::currentMSecsSinceEpoch(); quint64 bytes = 0; - qint64 timeout = 5000; + qint64 timeout = 5000; int linkErrorCount = 0; // Qt way to make clear what a while(1) loop does forever { { - QMutexLocker locker(&this->m_stoppMutex); - if (m_stopp) { - m_stopp = false; + QMutexLocker locker(&this->_stoppMutex); + if (_stopp) { + _stopp = false; break; // exit the thread } } + // TODO This needs a bit of TLC still... // If there are too many errors on this link, disconnect. if (isConnected() && (linkErrorCount > 150)) { qDebug() << "linkErrorCount too high: re-connecting!"; linkErrorCount = 0; emit communicationUpdate(getName(), tr("Link timeout, not receiving any data, attempting reconnect")); - - if (m_port) { - m_port->close(); - delete m_port; - m_port = NULL; + if (_port) { + _port->close(); + delete _port; + _port = NULL; } - QGC::SLEEP::msleep(500); - unsigned tries = 0; const unsigned tries_max = 15; - while (!hardwareConnect(type) && tries < tries_max) { + while (!_hardwareConnect(_type) && tries < tries_max) { tries++; QGC::SLEEP::msleep(500); } - // Give up if (tries == tries_max) { break; } - } // Write all our buffered data out the serial port. - if (m_transmitBuffer.count() > 0) { - m_writeMutex.lock(); - int numWritten = m_port->write(m_transmitBuffer); - bool txSuccess = m_port->flush(); - txSuccess |= m_port->waitForBytesWritten(10); - if (!txSuccess || (numWritten != m_transmitBuffer.count())) { + if (_transmitBuffer.count() > 0) { + _writeMutex.lock(); + int numWritten = _port->write(_transmitBuffer); + bool txSuccess = _port->flush(); + txSuccess |= _port->waitForBytesWritten(10); + if (!txSuccess || (numWritten != _transmitBuffer.count())) { linkErrorCount++; - qDebug() << "TX Error! written:" << txSuccess << "wrote" << numWritten << ", asked for " << m_transmitBuffer.count() << "bytes"; + qDebug() << "TX Error! written:" << txSuccess << "wrote" << numWritten << ", asked for " << _transmitBuffer.count() << "bytes"; } else { @@ -273,8 +155,8 @@ void SerialLink::run() } // Now that we transmit all of the data in the transmit buffer, flush it. - m_transmitBuffer = m_transmitBuffer.remove(0, numWritten); - m_writeMutex.unlock(); + _transmitBuffer = _transmitBuffer.remove(0, numWritten); + _writeMutex.unlock(); // Log this written data for this timestep. If this value ends up being 0 due to // write() failing, that's what we want as well. @@ -284,14 +166,14 @@ void SerialLink::run() //wait n msecs for data to be ready //[TODO][BB] lower to SerialLink::poll_interval? - m_dataMutex.lock(); - bool success = m_port->waitForReadyRead(20); + _dataMutex.lock(); + bool success = _port->waitForReadyRead(20); if (success) { - QByteArray readData = m_port->readAll(); - while (m_port->waitForReadyRead(10)) - readData += m_port->readAll(); - m_dataMutex.unlock(); + QByteArray readData = _port->readAll(); + while (_port->waitForReadyRead(10)) + readData += _port->readAll(); + _dataMutex.unlock(); if (readData.length() > 0) { emit bytesReceived(this, readData); @@ -300,17 +182,17 @@ void SerialLink::run() logDataRateToBuffer(inDataWriteAmounts, inDataWriteTimes, &inDataIndex, readData.length(), QDateTime::currentMSecsSinceEpoch()); // Track the total amount of data read. - m_bytesRead += readData.length(); + _bytesRead += readData.length(); linkErrorCount = 0; } } else { - m_dataMutex.unlock(); + _dataMutex.unlock(); linkErrorCount++; } - if (bytes != m_bytesRead) { // i.e things are good and data is being read. - bytes = m_bytesRead; + if (bytes != _bytesRead) { // i.e things are good and data is being read. + bytes = _bytesRead; msecs = QDateTime::currentMSecsSinceEpoch(); } else { @@ -330,22 +212,21 @@ void SerialLink::run() QGC::SLEEP::msleep(SerialLink::poll_interval); } // end of forever - if (m_port) { - qDebug() << "Closing Port #"<< __LINE__ << m_port->portName(); - m_port->close(); - delete m_port; - m_port = NULL; + if (_port) { + qDebug() << "Closing Port #" << __LINE__ << _port->portName(); + _port->close(); + delete _port; + _port = NULL; } } void SerialLink::writeBytes(const char* data, qint64 size) { - if(m_port && m_port->isOpen()) { - + if(_port && _port->isOpen()) { QByteArray byteArray(data, size); - m_writeMutex.lock(); - m_transmitBuffer.append(byteArray); - m_writeMutex.unlock(); + _writeMutex.lock(); + _transmitBuffer.append(byteArray); + _writeMutex.unlock(); } else { // Error occured _emitLinkError(tr("Could not send data - link %1 is disconnected!").arg(getName())); @@ -360,21 +241,21 @@ void SerialLink::writeBytes(const char* data, qint64 size) **/ void SerialLink::readBytes() { - if(m_port && m_port->isOpen()) { + if(_port && _port->isOpen()) { const qint64 maxLength = 2048; char data[maxLength]; - m_dataMutex.lock(); - qint64 numBytes = m_port->bytesAvailable(); + _dataMutex.lock(); + qint64 numBytes = _port->bytesAvailable(); if(numBytes > 0) { /* Read as much data in buffer as possible without overflow */ if(maxLength < numBytes) numBytes = maxLength; - m_port->read(data, numBytes); + _port->read(data, numBytes); QByteArray b(data, numBytes); emit bytesReceived(this, b); } - m_dataMutex.unlock(); + _dataMutex.unlock(); } } @@ -388,17 +269,14 @@ bool SerialLink::_disconnect(void) if (isRunning()) { { - QMutexLocker locker(&m_stoppMutex); - m_stopp = true; + QMutexLocker locker(&_stoppMutex); + _stopp = true; } wait(); // This will terminate the thread and close the serial port - return true; } - - m_transmitBuffer.clear(); //clear the output buffer to avoid sending garbage at next connect - - qDebug() << "already disconnected"; + _transmitBuffer.clear(); //clear the output buffer to avoid sending garbage at next connect + qDebug() << "Already disconnected"; return true; } @@ -413,10 +291,9 @@ bool SerialLink::_connect(void) if (isRunning()) _disconnect(); { - QMutexLocker locker(&this->m_stoppMutex); - m_stopp = false; + QMutexLocker locker(&this->_stoppMutex); + _stopp = false; } - start(HighPriority); return true; } @@ -429,80 +306,81 @@ bool SerialLink::_connect(void) * @return True if the connection could be established, false otherwise * @see _connect() For the right function to establish the connection. **/ -bool SerialLink::hardwareConnect(QString &type) +bool SerialLink::_hardwareConnect(QString &type) { - if (m_port) { + if (_port) { qDebug() << "SerialLink:" << QString::number((long)this, 16) << "closing port"; - m_port->close(); + _port->close(); QGC::SLEEP::usleep(50000); - delete m_port; - m_port = NULL; + delete _port; + _port = NULL; } - qDebug() << "SerialLink: hardwareConnect to " << m_portName; + qDebug() << "SerialLink: hardwareConnect to " << _config->portName(); - if (isBootloader()) { + if (_isBootloader()) { qDebug() << "Not connecting to a bootloader, waiting for 2nd chance"; - const unsigned retry_limit = 12; unsigned retries; - for (retries = 0; retries < retry_limit; retries++) { - if (!isBootloader()) { + if (!_isBootloader()) { + QGC::SLEEP::msleep(500); break; } QGC::SLEEP::msleep(500); } - // Check limit if (retries == retry_limit) { - // bail out + qWarning() << "Timeout waiting for something other than booloader"; return false; } } - m_port = new QSerialPort(m_portName); - if (!m_port) { - emit communicationUpdate(getName(),"Error opening port: " + m_portName); + _port = new QSerialPort(_config->portName()); + if (!_port) { + emit communicationUpdate(getName(),"Error opening port: " + _config->portName()); return false; // couldn't create serial port. } - m_port->moveToThread(this); + _port->moveToThread(this); // We need to catch this signal and then emit disconnected. You can't connect // signal to signal otherwise disonnected will have the wrong QObject::Sender - QObject::connect(m_port, SIGNAL(aboutToClose()), this, SLOT(_rerouteDisconnected())); - QObject::connect(m_port, SIGNAL(error(QSerialPort::SerialPortError)), this, SLOT(linkError(QSerialPort::SerialPortError))); + QObject::connect(_port, SIGNAL(aboutToClose()), this, SLOT(_rerouteDisconnected())); + QObject::connect(_port, SIGNAL(error(QSerialPort::SerialPortError)), this, SLOT(linkError(QSerialPort::SerialPortError))); - checkIfCDC(); + // port->setCommTimeouts(QSerialPort::CtScheme_NonBlockingRead); - // port->setCommTimeouts(QSerialPort::CtScheme_NonBlockingRead); + // TODO This needs a bit of TLC still... - if (!m_port->open(QIODevice::ReadWrite)) { - emit communicationUpdate(getName(),"Error opening port: " + m_port->errorString()); - m_port->close(); - return false; // couldn't open serial port + // After the bootloader times out, it still can take a second or so for the USB driver to come up and make + // the port available for open. So we retry a few times to wait for it. + for (int openRetries = 0; openRetries < 4; openRetries++) { + if (!_port->open(QIODevice::ReadWrite)) { + qDebug() << "Port open failed, retrying"; + QGC::SLEEP::msleep(500); + } else { + break; + } } - - // Need to configure the port - // NOTE: THE PORT NEEDS TO BE OPEN! - if (!m_is_cdc) { - qDebug() << "Configuring port"; - m_port->setBaudRate(m_baud); - m_port->setDataBits(static_cast(m_dataBits)); - m_port->setFlowControl(static_cast(m_flowControl)); - m_port->setStopBits(static_cast(m_stopBits)); - m_port->setParity(static_cast(m_parity)); + if (!_port->isOpen() ) { + emit communicationUpdate(getName(),"Error opening port: " + _port->errorString()); + _port->close(); + return false; // couldn't open serial port } - emit communicationUpdate(getName(),"Opened port!"); + qDebug() << "Configuring port"; + _port->setBaudRate (_config->baud()); + _port->setDataBits (static_cast (_config->dataBits())); + _port->setFlowControl (static_cast (_config->flowControl())); + _port->setStopBits (static_cast (_config->stopBits())); + _port->setParity (static_cast (_config->parity())); + emit communicationUpdate(getName(), "Opened port!"); emit connected(); - qDebug() << "CONNECTING LINK: " << __FILE__ << __LINE__ << "type:" << type << "with settings" << m_port->portName() - << getBaudRate() << getDataBits() << getParityType() << getStopBits(); - - writeSettings(); + qDebug() << "CONNECTING LINK: " << __FILE__ << __LINE__ << "type:" << type << "with settings" << _config->portName() + << _config->baud() << _config->dataBits() << _config->parity() << _config->stopBits(); return true; // successful connection } @@ -518,7 +396,6 @@ void SerialLink::linkError(QSerialPort::SerialPortError error) } } - /** * @brief Check if connection is active. * @@ -527,8 +404,8 @@ void SerialLink::linkError(QSerialPort::SerialPortError error) bool SerialLink::isConnected() const { - if (m_port) { - bool isConnected = m_port->isOpen(); + if (_port) { + bool isConnected = _port->isOpen(); // qDebug() << "SerialLink #" << __LINE__ << ":"<< m_port->portName() // << " isConnected =" << QString::number(isConnected); return isConnected; @@ -541,12 +418,12 @@ bool SerialLink::isConnected() const int SerialLink::getId() const { - return m_id; + return _id; } QString SerialLink::getName() const { - return m_portName; + return _config->portName(); } /** @@ -556,10 +433,10 @@ QString SerialLink::getName() const qint64 SerialLink::getConnectionSpeed() const { int baudRate; - if (m_port && !m_is_cdc) { - baudRate = m_port->baudRate(); + if (_port) { + baudRate = _port->baudRate(); } else { - baudRate = m_baud; + baudRate = _config->baud(); } qint64 dataRate; switch (baudRate) @@ -596,275 +473,148 @@ qint64 SerialLink::getConnectionSpeed() const return dataRate; } -QString SerialLink::getPortName() const +void SerialLink::_resetConfiguration() { - return m_portName; + bool somethingChanged = false; + if (_port) { + somethingChanged = _port->setBaudRate (_config->baud()); + somethingChanged |= _port->setDataBits (static_cast (_config->dataBits())); + somethingChanged |= _port->setFlowControl (static_cast (_config->flowControl())); + somethingChanged |= _port->setStopBits (static_cast (_config->stopBits())); + somethingChanged |= _port->setParity (static_cast (_config->parity())); + } + if(somethingChanged) { + qDebug() << "Reconfiguring port"; + emit updateLink(this); + } } -// We should replace the accessors below with one to get the QSerialPort - -int SerialLink::getBaudRate() const +void SerialLink::_rerouteDisconnected(void) { - return getConnectionSpeed(); + emit disconnected(); } -int SerialLink::getBaudRateType() const +void SerialLink::_emitLinkError(const QString& errorMsg) { - int baudRate; - if (m_port && !m_is_cdc) { - baudRate = m_port->baudRate(); - } else { - baudRate = m_baud; - } - return baudRate; + QString msg("Error on link %1. %2"); + emit communicationError(tr("Link Error"), msg.arg(getName()).arg(errorMsg)); } -int SerialLink::getFlowType() const +LinkConfiguration* SerialLink::getLinkConfiguration() { - - int flowControl; - if (m_port && !m_is_cdc) { - flowControl = m_port->flowControl(); - } else { - flowControl = m_flowControl; - } - return flowControl; + return _config; } -int SerialLink::getParityType() const -{ - - int parity; - if (m_port && !m_is_cdc) { - parity = m_port->parity(); - } else { - parity = m_parity; - } - return parity; -} +//-------------------------------------------------------------------------- +//-- SerialConfiguration -int SerialLink::getDataBitsType() const +SerialConfiguration::SerialConfiguration(const QString& name) : LinkConfiguration(name) { - - int dataBits; - if (m_port && !m_is_cdc) { - dataBits = m_port->dataBits(); - } else { - dataBits = m_dataBits; - } - return dataBits; + _baud = 57600; + _flowControl= QSerialPort::NoFlowControl; + _parity = QSerialPort::NoParity; + _dataBits = 8; + _stopBits = 1; } -int SerialLink::getStopBitsType() const +SerialConfiguration::SerialConfiguration(SerialConfiguration* copy) : LinkConfiguration(copy) { - - int stopBits; - if (m_port && !m_is_cdc) { - stopBits = m_port->stopBits(); - } else { - stopBits = m_stopBits; - } - return stopBits; + _baud = copy->baud(); + _flowControl= copy->flowControl(); + _parity = copy->parity(); + _dataBits = copy->dataBits(); + _stopBits = copy->stopBits(); + _portName = copy->portName(); } -int SerialLink::getDataBits() const +void SerialConfiguration::copyFrom(LinkConfiguration *source) { - - int ret; - int dataBits; - if (m_port && !m_is_cdc) { - dataBits = m_port->dataBits(); - } else { - dataBits = m_dataBits; - } - - switch (dataBits) { - case QSerialPort::Data5: - ret = 5; - break; - case QSerialPort::Data6: - ret = 6; - break; - case QSerialPort::Data7: - ret = 7; - break; - case QSerialPort::Data8: - ret = 8; - break; - default: - ret = -1; - break; - } - return ret; + LinkConfiguration::copyFrom(source); + SerialConfiguration* ssource = dynamic_cast(source); + Q_ASSERT(ssource != NULL); + _baud = ssource->baud(); + _flowControl= ssource->flowControl(); + _parity = ssource->parity(); + _dataBits = ssource->dataBits(); + _stopBits = ssource->stopBits(); + _portName = ssource->portName(); } -int SerialLink::getStopBits() const +void SerialConfiguration::updateSettings() { - - int stopBits; - if (m_port && !m_is_cdc) { - stopBits = m_port->stopBits(); - } else { - stopBits = m_stopBits; - } - int ret = -1; - switch (stopBits) { - case QSerialPort::OneStop: - ret = 1; - break; - case QSerialPort::TwoStop: - ret = 2; - break; - default: - ret = -1; - break; + if(_link) { + SerialLink* serialLink = dynamic_cast(_link); + if(serialLink) { + serialLink->_resetConfiguration(); + } } - return ret; } -bool SerialLink::setPortName(QString portName) +void SerialConfiguration::setBaud(int baud) { - qDebug() << "current portName " << m_portName; - qDebug() << "setPortName to " << portName; - bool accepted = true; - if ((portName != m_portName) - && (portName.trimmed().length() > 0)) { - m_portName = portName.trimmed(); - - checkIfCDC(); - - if(m_port) - m_port->setPortName(portName); - - emit nameChanged(m_portName); // [TODO] maybe we can eliminate this - emit updateLink(this); - return accepted; - } - return false; + _baud = baud; } - -bool SerialLink::setBaudRateType(int rateIndex) +void SerialConfiguration::setDataBits(int databits) { - - // These minimum and maximum baud rates were based on those enumerated in - bool result; - const int minBaud = (int)QSerialPort::Baud1200; - const int maxBaud = (int)QSerialPort::Baud115200; - - if ((rateIndex >= minBaud && rateIndex <= maxBaud)) - { - if (!m_is_cdc && m_port) - { - result = m_port->setBaudRate(static_cast(rateIndex)); - emit updateLink(this); - } else { - m_baud = (int)rateIndex; - result = true; - } - } else { - result = false; - } - - return result; + _dataBits = databits; } -bool SerialLink::setBaudRate(int rate) +void SerialConfiguration::setFlowControl(int flowControl) { - bool accepted = false; - if (rate != m_baud) { - m_baud = rate; - accepted = true; - if (m_port && !m_is_cdc) { - accepted = m_port->setBaudRate(rate); - } - emit updateLink(this); - } - return accepted; + _flowControl = flowControl; } -bool SerialLink::setFlowType(int flow) +void SerialConfiguration::setStopBits(int stopBits) { - - bool accepted = false; - if (flow != m_flowControl) { - m_flowControl = static_cast(flow); - accepted = true; - if (m_port && !m_is_cdc) - accepted = m_port->setFlowControl(static_cast(flow)); - emit updateLink(this); - } - return accepted; + _stopBits = stopBits; } -bool SerialLink::setParityType(int parity) +void SerialConfiguration::setParity(int parity) { - - bool accepted = false; - if (parity != m_parity) { - m_parity = static_cast(parity); - accepted = true; - if (m_port && !m_is_cdc) { - switch (parity) { - case QSerialPort::NoParity: - accepted = m_port->setParity(QSerialPort::NoParity); - break; - case 1: // Odd Parity setting for backwards compatibilty - accepted = m_port->setParity(QSerialPort::OddParity); - break; - case QSerialPort::EvenParity: - accepted = m_port->setParity(QSerialPort::EvenParity); - break; - case QSerialPort::OddParity: - accepted = m_port->setParity(QSerialPort::OddParity); - break; - default: - // If none of the above cases matches, there must be an error - accepted = false; - break; - } - emit updateLink(this); - } - } - return accepted; + _parity = parity; } -bool SerialLink::setDataBitsType(int dataBits) +void SerialConfiguration::setPortName(const QString& portName) { - - bool accepted = false; - if (dataBits != m_dataBits) { - m_dataBits = static_cast(dataBits); - accepted = true; - if (m_port && !m_is_cdc) - accepted = m_port->setDataBits(static_cast(dataBits)); - emit updateLink(this); + // No effect on a running connection + QString pname = portName.trimmed(); + if (!pname.isEmpty() && pname != _portName) { + _portName = pname; } - return accepted; } -bool SerialLink::setStopBitsType(int stopBits) +void SerialConfiguration::saveSettings(QSettings& settings, const QString& root) { - - bool accepted = false; - if (stopBits != m_stopBits) { - m_stopBits = static_cast(stopBits); - accepted = true; - if (m_port && !m_is_cdc) - accepted = m_port->setStopBits(static_cast(stopBits)); - emit updateLink(this); - } - return accepted; + settings.beginGroup(root); + settings.setValue("baud", _baud); + settings.setValue("dataBits", _dataBits); + settings.setValue("flowControl", _flowControl); + settings.setValue("stopBits", _stopBits); + settings.setValue("parity", _parity); + settings.setValue("portName", _portName); + settings.endGroup(); } -void SerialLink::_rerouteDisconnected(void) +void SerialConfiguration::loadSettings(QSettings& settings, const QString& root) { - emit disconnected(); + settings.beginGroup(root); + if(settings.contains("baud")) _baud = settings.value("baud").toInt(); + if(settings.contains("dataBits")) _dataBits = settings.value("dataBits").toInt(); + if(settings.contains("flowControl")) _flowControl = settings.value("flowControl").toInt(); + if(settings.contains("stopBits")) _stopBits = settings.value("stopBits").toInt(); + if(settings.contains("parity")) _parity = settings.value("parity").toInt(); + if(settings.contains("portName")) _portName = settings.value("portName").toString(); + settings.endGroup(); } -void SerialLink::_emitLinkError(const QString& errorMsg) +QList SerialConfiguration::getCurrentPorts() { - QString msg("Error on link %1. %2"); - - emit communicationError(tr("Link Error"), msg.arg(getName()).arg(errorMsg)); + QList ports; + QList portList = QSerialPortInfo::availablePorts(); + foreach (const QSerialPortInfo &info, portList) + { + ports.append(info.portName()); + } + return ports; } diff --git a/src/comm/SerialLink.h b/src/comm/SerialLink.h index 7a539f4cd80b503e228b1ec7eef03ab619842e70..3554fb172d8541b815cc6e6990dcc6fc943fa684 100644 --- a/src/comm/SerialLink.h +++ b/src/comm/SerialLink.h @@ -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 #include #include #include -#include "QGCConfig.h" -#include "SerialLinkInterface.h" - -// We use QSerialPort::SerialPortError in a signal so we must declare it as a meta type #include #include + +// 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 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 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(); diff --git a/src/comm/SerialLinkInterface.h b/src/comm/SerialLinkInterface.h index 3d80f3584a070490b40057c4bd4bed0098da553d..985e92a937157722da0b4596fa9969eb8227cf21 100644 --- a/src/comm/SerialLinkInterface.h +++ b/src/comm/SerialLinkInterface.h @@ -37,12 +37,12 @@ This file is part of the QGROUNDCONTROL project #include #include +/* class SerialLinkInterface : public LinkInterface { Q_OBJECT public: - virtual QList 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") diff --git a/src/comm/UDPLink.cc b/src/comm/UDPLink.cc index 77a3656bbf0f93241acf5645070c342880606532..f32409c3aefddcd3d590b514eb19402b91b9c123 100644 --- a/src/comm/UDPLink.cc +++ b/src/comm/UDPLink.cc @@ -32,41 +32,40 @@ This file is part of the QGROUNDCONTROL project #include #include #include +#include #include + #include "UDPLink.h" -#include "LinkManager.h" #include "QGC.h" #include -//#include -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 +74,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 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 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 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 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 +162,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 +172,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 +188,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 +208,30 @@ 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(); + _socket->setProxy(QNetworkProxy::NoProxy); + _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 +239,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(this)); + UDPConfiguration* usource = dynamic_cast(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 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::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::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(_link); + if(ulink) { + ulink->_restartConnection(); + } + } } diff --git a/src/comm/UDPLink.h b/src/comm/UDPLink.h index 6a60f7c6203c9b972e6385aa2fce49b23c3de158..471f151aa79df3f99b47f2cc0e70ff7560cd4624 100644 --- a/src/comm/UDPLink.h +++ b/src/comm/UDPLink.h @@ -21,7 +21,7 @@ This file is part of the QGROUNDCONTROL project ======================================================================*/ -/** +/*! * @file * @brief UDP connection (server) for unmanned vehicles * @author Lorenz Meier @@ -36,39 +36,120 @@ This file is part of the QGROUNDCONTROL project #include #include #include -#include + #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::iterator _it; + QMap _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 getHosts() const { - return hosts; - } // Extensive statistics for scientific purposes qint64 getConnectionSpeed() const; @@ -76,25 +157,25 @@ 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); + LinkConfiguration* getLinkConfiguration() { return _config; } + 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 +184,19 @@ public slots: void writeBytes(const char* data, qint64 length); protected: - QString name; - QHostAddress host; - quint16 port; - int id; - QUdpSocket* socket; - bool connectState; - QList hosts; - QList 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 diff --git a/src/main.cc b/src/main.cc index 3c9534af4a0253a53aa55803af31fed10c555b2a..3435cd535a8180a49f8dfd715c38af58242e5ea7 100644 --- a/src/main.cc +++ b/src/main.cc @@ -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(); qRegisterMetaType(); - + 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 > >(); - + 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; } diff --git a/src/qgcunittest/MockLink.cc b/src/qgcunittest/MockLink.cc index afbb95cd790793601a9c0010f94aa0b29a00dade..d348aac67a7fb9de91e5746acbc1fc1be1b7f0e9 100644 --- a/src/qgcunittest/MockLink.cc +++ b/src/qgcunittest/MockLink.cc @@ -1,24 +1,24 @@ /*===================================================================== - + QGroundControl Open Source Ground Control Station - + (c) 2009 - 2014 QGROUNDCONTROL PROJECT - + 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 . - + ======================================================================*/ #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(¶mFile); - + 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(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; ihandleMessage(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; } diff --git a/src/qgcunittest/MockLink.h b/src/qgcunittest/MockLink.h index 5fbfdc0712f593401183d30aabb7dfd909581392..dad2286657e33476e4a9f368121a0b3997385197 100644 --- a/src/qgcunittest/MockLink.h +++ b/src/qgcunittest/MockLink.h @@ -1,24 +1,24 @@ /*===================================================================== - + QGroundControl Open Source Ground Control Station - + (c) 2009 - 2014 QGROUNDCONTROL PROJECT - + 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 . - + ======================================================================*/ #ifndef MOCKLINK_H @@ -28,7 +28,7 @@ #include #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 +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 _mapParamName2Value; QMap _mapParamName2MavParamType; - + typedef QMap MissionList_t; MissionList_t _missionItems; - + uint8_t _mavBaseMode; uint8_t _mavCustomMode; uint8_t _mavState; - + + MockConfiguration* _config; MAV_AUTOPILOT _autopilotType; }; diff --git a/src/qgcunittest/MockLinkMissionItemHandler.h b/src/qgcunittest/MockLinkMissionItemHandler.h index f1d9a7e809feb354cb794f6819675666c9c7ea90..640f1fcf369380052817e0f692473efe9a2a3910 100644 --- a/src/qgcunittest/MockLinkMissionItemHandler.h +++ b/src/qgcunittest/MockLinkMissionItemHandler.h @@ -1,24 +1,24 @@ /*===================================================================== - + QGroundControl Open Source Ground Control Station - + (c) 2009 - 2014 QGROUNDCONTROL PROJECT - + 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 . - + ======================================================================*/ #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 _missionItems; ///< Current set of mission itemss }; diff --git a/src/ui/CommConfigurationWindow.cc b/src/ui/CommConfigurationWindow.cc deleted file mode 100644 index 85d788aea22fd5b7efa04c51caa498d4985fb503..0000000000000000000000000000000000000000 --- a/src/ui/CommConfigurationWindow.cc +++ /dev/null @@ -1,397 +0,0 @@ -/*===================================================================== - -QGroundControl Open Source Ground Control Station - -(c) 2009, 2010 QGROUNDCONTROL PROJECT - -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 . - -======================================================================*/ - -/** - * @file - * @brief Implementation of CommConfigurationWindow - * - * @author Lorenz Meier - * - */ - -#include - -#include -#include -#include -#include - -#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(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(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(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(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(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(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(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(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(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 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")); - } -} diff --git a/src/ui/CommConfigurationWindow.h b/src/ui/CommConfigurationWindow.h deleted file mode 100644 index f786b51837f4ae7fe5532315a7e7508bde3b75c7..0000000000000000000000000000000000000000 --- a/src/ui/CommConfigurationWindow.h +++ /dev/null @@ -1,106 +0,0 @@ -/*===================================================================== - -QGroundControl Open Source Ground Control Station - -(c) 2009, 2010 QGROUNDCONTROL PROJECT - -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 . - -======================================================================*/ - -/** - * @file - * @brief Definition of class CommConfigurationWindow - * - * @author Lorenz Meier - * - */ - -#ifndef _COMMCONFIGURATIONWINDOW_H_ -#define _COMMCONFIGURATIONWINDOW_H_ - -#include -#include -#include -#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); - -private slots: - void linkCurrentIndexChanged(int currentIndex); - -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(); - -private slots: - void _linkConnected(void); - void _linkDisconnected(void); - -private: - void _connectionState(bool connect); - - Ui::commSettings ui; - LinkInterface* link; - QAction* action; -}; - - -#endif // _COMMCONFIGURATIONWINDOW_H_ diff --git a/src/ui/CommSettings.ui b/src/ui/CommSettings.ui deleted file mode 100644 index e04678c17aa92ae77e776d74776813402c00bbbb..0000000000000000000000000000000000000000 --- a/src/ui/CommSettings.ui +++ /dev/null @@ -1,281 +0,0 @@ - - - commSettings - - - - 0 - 0 - 324 - 475 - - - - Form - - - - - - - - Link &Type: - - - linkType - - - - - - - - - - - - Link - - - - 0 - - - 0 - - - 0 - - - 0 - - - 0 - - - - - true - - - - - 0 - 0 - 298 - 90 - - - - - - - - - - - - &Show Advanced Protocol Options - - - - - - - GroupBox - - - - - - - - -1 - - - - - - - &Protocol: - - - connectionType - - - - - - - &Advanced Options - - - - - - - - - - - - Qt::Horizontal - - - - - - - Protocol - - - - 0 - - - 0 - - - 0 - - - 0 - - - 0 - - - - - true - - - - - 0 - 0 - 298 - 90 - - - - - - - - - - - - 12 - - - QLayout::SetDefaultConstraint - - - - - Connect - - - false - - - - - - - Delete Link - - - - - - - Close - - - true - - - - - - - - - - 0 - 0 - - - - Disconnected - - - - - - - Delete - - - Delete this link - - - - - Connect - - - Connect this link - - - - - Close - - - Close the configuration window - - - line - linkGroupBox - protocolGroupBox - connectionStatusLabel - advCheckBox - protocolTypeGroupBox - linkType - label - - - linkType - linkScrollArea - advCheckBox - connectionType - advancedOptionsCheckBox - protocolScrollArea - connectButton - deleteButton - closeButton - - - - - actionClose - triggered() - commSettings - close() - - - -1 - -1 - - - 224 - 195 - - - - - diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index 4ba12e5cf7daefde972f5e42401a82e903e97e6a..a9fa8aaf0da1c1818773865a751c4a5a72d2cfe3 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -42,9 +42,7 @@ This file is part of the QGROUNDCONTROL project #include "QGC.h" #include "MAVLinkSimulationLink.h" #include "SerialLink.h" -#include "UDPLink.h" #include "MAVLinkProtocol.h" -#include "CommConfigurationWindow.h" #include "QGCWaypointListMulti.h" #include "MainWindow.h" #include "JoystickWidget.h" @@ -81,6 +79,9 @@ This file is part of the QGROUNDCONTROL project #include "LogCompressor.h" +/// The key under which the Main Window settings are saved +const char* MAIN_SETTINGS_GROUP = "QGC_MAINWINDOW"; + const char* MainWindow::_uasControlDockWidgetName = "UNMANNED_SYSTEM_CONTROL_DOCKWIDGET"; const char* MainWindow::_uasListDockWidgetName = "UNMANNED_SYSTEM_LIST_DOCKWIDGET"; const char* MainWindow::_waypointsDockWidgetName = "WAYPOINT_LIST_DOCKWIDGET"; @@ -102,9 +103,9 @@ static MainWindow* _instance = NULL; ///< @brief MainWindow singleton MainWindow* MainWindow::_create(QSplashScreen* splashScreen) { Q_ASSERT(_instance == NULL); - + new MainWindow(splashScreen); - + // _instance is set in constructor Q_ASSERT(_instance); @@ -135,13 +136,13 @@ MainWindow::MainWindow(QSplashScreen* splashScreen) : { Q_ASSERT(_instance == NULL); _instance = this; - + if (splashScreen) { connect(this, &MainWindow::initStatusChanged, splashScreen, &QSplashScreen::showMessage); } - + loadSettings(); - + // Select the proper view. Default to the flight view or load the last one used if it's supported. VIEW_SECTIONS currentViewCandidate = (VIEW_SECTIONS) settings.value("CURRENT_VIEW", _currentView).toInt(); switch (currentViewCandidate) { @@ -159,12 +160,12 @@ MainWindow::MainWindow(QSplashScreen* splashScreen) : #endif _currentView = currentViewCandidate; break; - + default: // Leave _currentView to the default break; } - + // Put it back, which will set it to a valid value settings.setValue("CURRENT_VIEW", _currentView); @@ -172,7 +173,7 @@ MainWindow::MainWindow(QSplashScreen* splashScreen) : // Setup user interface ui.setupUi(this); - + // Setup central widget with a layout to hold the views _centralLayout = new QVBoxLayout(); centralWidget()->setLayout(_centralLayout); @@ -232,16 +233,6 @@ MainWindow::MainWindow(QSplashScreen* splashScreen) : // Create actions connectCommonActions(); - // Populate link menu - emit initStatusChanged(tr("Populating link menu"), Qt::AlignLeft | Qt::AlignBottom, QColor(62, 93, 141)); - QList links = LinkManager::instance()->getLinks(); - foreach(LinkInterface* link, links) - { - _addLinkMenu(link); - } - - connect(LinkManager::instance(), &LinkManager::newLink, this, &MainWindow::_addLinkMenu); - // Connect user interface devices emit initStatusChanged(tr("Initializing joystick interface"), Qt::AlignLeft | Qt::AlignBottom, QColor(62, 93, 141)); joystick = new JoystickInput(); @@ -263,14 +254,7 @@ MainWindow::MainWindow(QSplashScreen* splashScreen) : // Connect link if (autoReconnect) { - LinkManager* linkMgr = LinkManager::instance(); - Q_ASSERT(linkMgr); - - SerialLink* link = new SerialLink(); - - // Add to registry - linkMgr->addLink(link); - linkMgr->connectLink(link); + restoreLastUsedConnection(); } // Set low power mode @@ -348,10 +332,10 @@ MainWindow::MainWindow(QSplashScreen* splashScreen) : connect(&windowNameUpdateTimer, SIGNAL(timeout()), this, SLOT(configureWindowName())); windowNameUpdateTimer.start(15000); emit initStatusChanged(tr("Done"), Qt::AlignLeft | Qt::AlignBottom, QColor(62, 93, 141)); - - if (!qgcApp()->runningUnitTests()) { - show(); - } + + if (!qgcApp()->runningUnitTests()) { + show(); + } } MainWindow::~MainWindow() @@ -374,7 +358,7 @@ MainWindow::~MainWindow() { commsWidgetList[i]->deleteLater(); } - + _instance = NULL; } @@ -401,7 +385,7 @@ QString MainWindow::getWindowGeometryKey() void MainWindow::_buildCustomWidgets(void) { Q_ASSERT(_customWidgets.count() == 0); - + // Create custom widgets _customWidgets = QGCToolWidget::createWidgetsFromSettings(this); @@ -409,11 +393,11 @@ void MainWindow::_buildCustomWidgets(void) { ui.menuTools->addSeparator(); } - + foreach(QGCToolWidget* tool, _customWidgets) { // Check if this widget already has a parent, do not create it in this case QDockWidget* dock = dynamic_cast(tool->parentWidget()); - + if (!dock) { _createDockWidget(tool->getTitle(), tool->objectName(), Qt::BottomDockWidgetArea, tool); } @@ -423,32 +407,32 @@ void MainWindow::_buildCustomWidgets(void) void MainWindow::_createDockWidget(const QString& title, const QString& name, Qt::DockWidgetArea area, QWidget* innerWidget) { Q_ASSERT(!_mapName2DockWidget.contains(name)); - + QGCDockWidget* dockWidget = new QGCDockWidget(title, this); Q_CHECK_PTR(dockWidget); dockWidget->setObjectName(name); dockWidget->setVisible (false); - + if (innerWidget) { // Put inner widget inside QDockWidget innerWidget->setParent(dockWidget); dockWidget->setWidget(innerWidget); innerWidget->setVisible(true); } - + // Add to menu - + QAction* action = new QAction(title, NULL); action->setCheckable(true); action->setData(name); - + connect(action, &QAction::triggered, this, &MainWindow::_showDockWidgetAction); - + ui.menuTools->addAction(action); - + _mapName2DockWidget[name] = dockWidget; _mapDockWidget2Action[dockWidget] = action; - + addDockWidget(area, dockWidget); } @@ -466,13 +450,13 @@ void MainWindow::_buildCommonWidgets(void) // In order for Qt to save and restore state of widgets all widgets must be created ahead of time. We only create the QDockWidget // holders. We do not create the actual inner widget until it is needed. This saves memory and cpu from running widgets that are // never shown. - + struct DockWidgetInfo { const char* name; const char* title; Qt::DockWidgetArea area; }; - + static const struct DockWidgetInfo rgDockWidgetInfo[] = { { _uasControlDockWidgetName, "Control", Qt::LeftDockWidgetArea }, { _uasListDockWidgetName, "Unmanned Systems", Qt::RightDockWidgetArea }, @@ -491,10 +475,10 @@ void MainWindow::_buildCommonWidgets(void) { _debugConsoleDockWidgetName, "Communications Console", Qt::LeftDockWidgetArea } }; static const size_t cDockWidgetInfo = sizeof(rgDockWidgetInfo) / sizeof(rgDockWidgetInfo[0]); - + for (size_t i=0; ititle, pDockInfo->name, pDockInfo->area, NULL /* no inner widget yet */); } @@ -576,7 +560,7 @@ void MainWindow::_showDockWidget(const QString& name, bool show) qWarning() << "Attempt to show unknown dock widget" << name; return; } - + // Create the inner widget if we need to if (!_mapName2DockWidget[name]->widget()) { _createInnerDockWidget(name); @@ -585,9 +569,9 @@ void MainWindow::_showDockWidget(const QString& name, bool show) Q_ASSERT(_mapName2DockWidget.contains(name)); QDockWidget* dockWidget = _mapName2DockWidget[name]; Q_ASSERT(dockWidget); - + dockWidget->setVisible(show); - + Q_ASSERT(_mapDockWidget2Action.contains(dockWidget)); _mapDockWidget2Action[dockWidget]->setChecked(show); } @@ -597,9 +581,9 @@ void MainWindow::_createInnerDockWidget(const QString& widgetName) { Q_ASSERT(_mapName2DockWidget.contains(widgetName)); // QDockWidget should already exist Q_ASSERT(!_mapName2DockWidget[widgetName]->widget()); // Inner widget should not - + QWidget* widget = NULL; - + if (widgetName == _uasControlDockWidgetName) { widget = new UASControlWidget(this); } else if (widgetName == _uasListDockWidgetName) { @@ -625,14 +609,14 @@ void MainWindow::_createInnerDockWidget(const QString& widgetName) acceptList.append("-3.3,ATTITUDE.yaw,deg,+3.3,s"); HDDisplay *hddisplay = new HDDisplay(acceptList,"Flight Display",this); hddisplay->addSource(mavlinkDecoder); - + widget = hddisplay; } else if (widgetName == _hdd2DockWidgetName) { QStringList acceptList; acceptList.append("0,RAW_PRESSURE.pres_abs,hPa,65500"); HDDisplay *hddisplay = new HDDisplay(acceptList,"Actuator Status",this); hddisplay->addSource(mavlinkDecoder); - + widget = hddisplay; } else if (widgetName == _pfdDockWidgetName) { widget = new PrimaryFlightDisplay(this); @@ -645,11 +629,11 @@ void MainWindow::_createInnerDockWidget(const QString& widgetName) } else { qWarning() << "Attempt to create unknown Inner Dock Widget" << widgetName; } - + if (widget) { QDockWidget* dockWidget = _mapName2DockWidget[widgetName]; Q_CHECK_PTR(dockWidget); - + widget->setParent(dockWidget); dockWidget->setWidget(widget); } @@ -658,35 +642,35 @@ void MainWindow::_createInnerDockWidget(const QString& widgetName) void MainWindow::_showHILConfigurationWidgets(void) { UASInterface* uas = UASManager::instance()->getActiveUAS(); - + if (!uas) { return; } - + UAS* mav = dynamic_cast(uas); Q_ASSERT(mav); - + int uasId = mav->getUASID(); if (!_mapUasId2HilDockWidget.contains(uasId)) { - + // Create QDockWidget QGCDockWidget* dockWidget = new QGCDockWidget(tr("HIL Config %1").arg(uasId), this); Q_CHECK_PTR(dockWidget); dockWidget->setObjectName(tr("HIL_CONFIG_%1").arg(uasId)); dockWidget->setVisible (false); - + // Create inner widget and set it QWidget* widget = new QGCHilConfiguration(mav, dockWidget); - + widget->setParent(dockWidget); dockWidget->setWidget(widget); - + _mapUasId2HilDockWidget[uasId] = dockWidget; - + addDockWidget(Qt::LeftDockWidgetArea, dockWidget); } - + if (_currentView == VIEW_SIMULATION) { // HIL dock widgets only show up on simulation view foreach (QDockWidget* dockWidget, _mapUasId2HilDockWidget) { @@ -708,7 +692,7 @@ void MainWindow::normalActionItemCallback() void MainWindow::closeEvent(QCloseEvent *event) { // Disallow window close if there are active connections - + bool foundConnections = false; foreach(LinkInterface* link, LinkManager::instance()->getLinks()) { if (link->isConnected()) { @@ -716,7 +700,7 @@ void MainWindow::closeEvent(QCloseEvent *event) break; } } - + if (foundConnections) { QGCMessageBox::StandardButton button = QGCMessageBox::warning(tr("QGroundControl close"), tr("There are still active connections to vehicles. Do you want to disconnect these before closing?"), @@ -767,7 +751,7 @@ void MainWindow::_createNewCustomWidget(void) QGCToolWidget* tool = new QGCToolWidget(objectName, title); tool->resize(100, 100); _createDockWidget(title, objectName, Qt::BottomDockWidgetArea, tool); - + _mapName2DockWidget[objectName]->setVisible(true); } @@ -781,6 +765,7 @@ void MainWindow::_loadCustomWidgetFromFile(void) QGCToolWidget* tool = new QGCToolWidget("", "", this); if (tool->loadSettings(fileName, true)) { QString objectName = tool->objectName() + "DOCK"; + _createDockWidget(tool->getTitle(), objectName, Qt::LeftDockWidgetArea, tool); _mapName2DockWidget[objectName]->widget()->setVisible(true); } @@ -790,11 +775,11 @@ void MainWindow::_loadCustomWidgetFromFile(void) void MainWindow::loadSettings() { + // Why the screaming? QSettings settings; - - settings.beginGroup("QGC_MAINWINDOW"); + settings.beginGroup(MAIN_SETTINGS_GROUP); autoReconnect = settings.value("AUTO_RECONNECT", autoReconnect).toBool(); - lowPowerMode = settings.value("LOW_POWER_MODE", lowPowerMode).toBool(); + lowPowerMode = settings.value("LOW_POWER_MODE", lowPowerMode).toBool(); settings.endGroup(); } @@ -802,7 +787,7 @@ void MainWindow::storeSettings() { QSettings settings; - settings.beginGroup("QGC_MAINWINDOW"); + settings.beginGroup(MAIN_SETTINGS_GROUP); settings.setValue("AUTO_RECONNECT", autoReconnect); settings.setValue("LOW_POWER_MODE", lowPowerMode); settings.endGroup(); @@ -961,7 +946,7 @@ void MainWindow::connectCommonActions() ui.actionShutdownMAV->setEnabled(false); // Connect actions from ui - connect(ui.actionAdd_Link, SIGNAL(triggered()), this, SLOT(addLink())); + connect(ui.actionAdd_Link, SIGNAL(triggered()), this, SLOT(manageLinks())); // Connect internal actions connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)), this, SLOT(UASCreated(UASInterface*))); @@ -1037,33 +1022,6 @@ void MainWindow::showSettings() settings.exec(); } -// FIXME: Where is this called from -LinkInterface* MainWindow::addLink() -{ - SerialLink* link = new SerialLink(); - // TODO This should be only done in the dialog itself - - LinkManager::instance()->addLink(link); - - // Go fishing for this link's configuration window - QList actions = ui.menuNetwork->actions(); - - const int32_t& linkIndex(LinkManager::instance()->getLinks().indexOf(link)); - const int32_t& linkID(LinkManager::instance()->getLinks()[linkIndex]->getId()); - - foreach (QAction* act, actions) - { - if (act->data().toInt() == linkID) - { - act->trigger(); - break; - } - } - - return link; -} - - bool MainWindow::configLink(LinkInterface *link) { // Go searching for this link's configuration window @@ -1086,32 +1044,6 @@ bool MainWindow::configLink(LinkInterface *link) return found; } -void MainWindow::_addLinkMenu(LinkInterface *link) -{ - // Go fishing for this link's configuration window - QList actions = ui.menuNetwork->actions(); - - bool alreadyAdded = false; - - const int32_t& linkIndex(LinkManager::instance()->getLinks().indexOf(link)); - const int32_t& linkID(LinkManager::instance()->getLinks()[linkIndex]->getId()); - - foreach (QAction* act, actions) { - if (act->data().toInt() == linkID) { - alreadyAdded = true; - break; - } - } - - if (!alreadyAdded) { - CommConfigurationWindow* commWidget = new CommConfigurationWindow(link, this); - commsWidgetList.append(commWidget); - connect(commWidget,SIGNAL(destroyed(QObject*)),this,SLOT(commsWidgetDestroyed(QObject*))); - QAction* action = commWidget->getAction(); - ui.menuNetwork->addAction(action); - } -} - void MainWindow::simulateLink(bool simulate) { if (simulate) { if (!simulationLink) { @@ -1258,7 +1190,7 @@ void MainWindow::_storeCurrentViewState(void) { // HIL dock widgets are dynamic and are not part of the saved state _hideAllHilDockWidgets(); - + // Save list of visible widgets bool firstWidget = true; @@ -1272,7 +1204,7 @@ void MainWindow::_storeCurrentViewState(void) firstWidget = false; } } - + settings.setValue(getWindowStateKey() + "WIDGETS", widgetNames); settings.setValue(getWindowStateKey(), saveState()); settings.setValue(getWindowGeometryKey(), saveGeometry()); @@ -1283,53 +1215,53 @@ void MainWindow::_loadCurrentViewState(void) { QWidget* centerView = NULL; QString defaultWidgets; - + switch (_currentView) { case VIEW_SETUP: _buildSetupView(); centerView = _setupView; break; - + case VIEW_ENGINEER: _buildEngineeringView(); centerView = _engineeringView; defaultWidgets = "MAVLINK_INSPECTOR_DOCKWIDGET,PARAMETER_INTERFACE_DOCKWIDGET,FILE_VIEW_DOCKWIDGET,HEAD_UP_DISPLAY_DOCKWIDGET"; break; - + case VIEW_FLIGHT: _buildPilotView(); centerView = _pilotView; defaultWidgets = "COMMUNICATION_CONSOLE_DOCKWIDGET,UAS_INFO_INFOVIEW_DOCKWIDGET"; break; - + case VIEW_MISSION: _buildPlannerView(); centerView = _plannerView; defaultWidgets = "UNMANNED_SYSTEM_LIST_DOCKWIDGET,WAYPOINT_LIST_DOCKWIDGET"; break; - + case VIEW_SIMULATION: _buildSimView(); centerView = _simView; defaultWidgets = "UNMANNED_SYSTEM_CONTROL_DOCKWIDGET,WAYPOINT_LIST_DOCKWIDGET,PARAMETER_INTERFACE_DOCKWIDGET,PRIMARY_FLIGHT_DISPLAY_DOCKWIDGET"; break; - + case VIEW_TERMINAL: _buildTerminalView(); centerView = _terminalView; break; - + case VIEW_GOOGLEEARTH: _buildGoogleEarthView(); centerView = _googleEarthView; break; - + case VIEW_LOCAL3D: _buildLocal3DView(); centerView = _local3DView; break; } - + // Remove old view if (_currentViewWidget) { _currentViewWidget->setVisible(false); @@ -1338,14 +1270,14 @@ void MainWindow::_loadCurrentViewState(void) Q_ASSERT(child); delete child; } - + // Add the new one Q_ASSERT(centerView); Q_ASSERT(_centralLayout->count() == 0); _currentViewWidget = centerView; _centralLayout->addWidget(_currentViewWidget); _currentViewWidget->setVisible(true); - + // Hide all widgets from previous view _hideAllDockWidgets(); @@ -1362,7 +1294,7 @@ void MainWindow::_loadCurrentViewState(void) if (settings.contains(getWindowStateKey())) { restoreState(settings.value(getWindowStateKey()).toByteArray()); } - + // HIL dock widget are dynamic and don't take part in the saved window state, so this // need to happen after we restore state _showHILConfigurationWidgets(); @@ -1380,7 +1312,7 @@ void MainWindow::_hideAllDockWidgets(void) foreach(QDockWidget* dockWidget, _mapName2DockWidget) { dockWidget->setVisible(false); } - + _hideAllHilDockWidgets(); } @@ -1388,7 +1320,7 @@ void MainWindow::_showDockWidgetAction(bool show) { QAction* action = dynamic_cast(QObject::sender()); Q_ASSERT(action); - + _showDockWidget(action->data().toString(), show); } @@ -1396,7 +1328,7 @@ void MainWindow::_showDockWidgetAction(bool show) void MainWindow::handleMisconfiguration(UASInterface* uas) { static QTime lastTime; - + // We have to debounce this signal if (!lastTime.isValid()) { lastTime.start(); @@ -1406,7 +1338,7 @@ void MainWindow::handleMisconfiguration(UASInterface* uas) return; } } - + // Ask user if he wants to handle this now QMessageBox::StandardButton button = QGCMessageBox::question(tr("Missing or Invalid Onboard Configuration"), tr("The onboard system configuration is missing or incomplete. Do you want to resolve this now?"), @@ -1522,6 +1454,42 @@ void MainWindow::hideSplashScreen(void) } } +void MainWindow::manageLinks() +{ + SettingsDialog settings(joystick, this, SettingsDialog::ShowCommLinks); + settings.exec(); +} + +/// @brief Saves the last used connection +void MainWindow::saveLastUsedConnection(const QString connection) +{ + QSettings settings; + QString key(MAIN_SETTINGS_GROUP); + key += "/LAST_CONNECTION"; + settings.setValue(key, connection); +} + +/// @brief Restore (and connects) the last used connection (if any) +void MainWindow::restoreLastUsedConnection() +{ + // TODO This should check and see of the port/whatever is present + // first. That is, if the last connection was to a PX4 on some serial + // port, it should check and see if the port is present before making + // the connection. + QSettings settings; + QString key(MAIN_SETTINGS_GROUP); + key += "/LAST_CONNECTION"; + QString connection; + if(settings.contains(key)) { + connection = settings.value(connection).toString(); + // Create a link for it + LinkInterface* link = LinkManager::instance()->createLink(connection); + if(link) { + // Connect it + LinkManager::instance()->connectLink(link); + } + } +} #ifdef QGC_MOUSE_ENABLED_LINUX bool MainWindow::x11Event(XEvent *event) diff --git a/src/ui/MainWindow.h b/src/ui/MainWindow.h index 7ebd2fc34c935fa57082b139020cd6e469577fef..5100893b26f023fa2e5e2010d729a293f3879044 100644 --- a/src/ui/MainWindow.h +++ b/src/ui/MainWindow.h @@ -91,13 +91,13 @@ public: /// @brief Returns the MainWindow singleton. Will not create the MainWindow if it has not already /// been created. static MainWindow* instance(void); - + /// @brief Deletes the MainWindow singleton void deleteInstance(void); - + /// @brief Creates the MainWindow singleton. Should only be called once by QGCApplication. static MainWindow* _create(QSplashScreen* splashScreen); - + /// @brief Called to indicate that splash screen is no longer being displayed. void splashScreenFinished(void) { _splashScreen = NULL; } @@ -117,14 +117,19 @@ public: } QList listLinkMenuActions(); - + void hideSplashScreen(void); + /// @brief Saves the last used connection + void saveLastUsedConnection(const QString connection); + + /// @brief Restore (and connects) the last used connection (if any) + void restoreLastUsedConnection(); + + public slots: /** @brief Show the application settings */ void showSettings(); - /** @brief Add a communication link */ - LinkInterface* addLink(); bool configLink(LinkInterface *link); /** @brief Simulate a link */ void simulateLink(bool simulate); @@ -158,6 +163,8 @@ public slots: void loadGoogleEarthView(); /** @brief Load local 3D view */ void loadLocal3DView(); + /** @brief Manage Links */ + void manageLinks(); /** @brief Show the online help for users */ void showHelp(); @@ -178,7 +185,7 @@ public slots: void configureWindowName(); void commsWidgetDestroyed(QObject *obj); - + protected slots: /** * @brief Unchecks the normalActionItem. @@ -243,7 +250,7 @@ protected: QPointer q3DWidget; #endif #ifdef QGC_GOOGLE_EARTH_ENABLED - QPointer earthWidget; + QPointer earthWidget; #endif QPointer firmwareUpdateWidget; @@ -288,9 +295,8 @@ protected: bool lowPowerMode; ///< If enabled, QGC reduces the update rates of all widgets QGCFlightGearLink* fgLink; QTimer windowNameUpdateTimer; - + private slots: - void _addLinkMenu(LinkInterface* link); void _showDockWidgetAction(bool show); void _loadCustomWidgetFromFile(void); void _createNewCustomWidget(void); @@ -301,9 +307,9 @@ private slots: private: /// Constructor is private since all creation should be through MainWindow::_create MainWindow(QSplashScreen* splashScreen); - + void _openUrl(const QString& url, const QString& errorMessage); - + // Center widgets QPointer _plannerView; QPointer _pilotView; @@ -313,10 +319,10 @@ private: QPointer _terminalView; QPointer _googleEarthView; QPointer _local3DView; - + VIEW_SECTIONS _currentView; ///< Currently displayed view QWidget* _currentViewWidget; ///< Currently displayed view widget - + // Dock widget names static const char* _uasControlDockWidgetName; static const char* _uasListDockWidgetName; @@ -333,11 +339,11 @@ private: static const char* _hudDockWidgetName; static const char* _uasInfoViewDockWidgetName; static const char* _debugConsoleDockWidgetName; - + QMap _mapName2DockWidget; QMap _mapUasId2HilDockWidget; QMap _mapDockWidget2Action; - + void _buildPlannerView(void); void _buildPilotView(void); void _buildSetupView(void); @@ -346,10 +352,10 @@ private: void _buildTerminalView(void); void _buildGoogleEarthView(void); void _buildLocal3DView(void); - + void _storeCurrentViewState(void); void _loadCurrentViewState(void); - + void _createDockWidget(const QString& title, const QString& name, Qt::DockWidgetArea area, QWidget* innerWidget); void _createInnerDockWidget(const QString& widgetName); void _buildCustomWidgets(void); @@ -358,18 +364,18 @@ private: void _hideAllDockWidgets(void); void _showDockWidget(const QString &name, bool show); void _showHILConfigurationWidgets(void); - + QList _customWidgets; - + QVBoxLayout* _centralLayout; - + QList commsWidgetList; MenuActionHelper *menuActionHelper; Ui::MainWindow ui; QString getWindowStateKey(); QString getWindowGeometryKey(); - + QSplashScreen* _splashScreen; ///< Splash screen, NULL is splash screen not currently being shown friend class MenuActionHelper; //For VIEW_SECTIONS diff --git a/src/ui/MainWindow.ui b/src/ui/MainWindow.ui index 3435f990cd78d7fcaba42b19093583944f2f9566..85a281eeec0727acb1675223be13a89b9c411d60 100644 --- a/src/ui/MainWindow.ui +++ b/src/ui/MainWindow.ui @@ -170,12 +170,8 @@ - - - :/files/images/actions/list-add.svg:/files/images/actions/list-add.svg - - Add Link + Manage Links diff --git a/src/ui/QGCCommConfiguration.cc b/src/ui/QGCCommConfiguration.cc new file mode 100644 index 0000000000000000000000000000000000000000..3ed561562bf0cfed68718d0e07da02f563c24b9d --- /dev/null +++ b/src/ui/QGCCommConfiguration.cc @@ -0,0 +1,149 @@ +#include + +#include "SerialLink.h" +#include "SerialConfigurationWindow.h" +#include "QGCUDPLinkConfiguration.h" +#include "QGCCommConfiguration.h" +#include "ui_QGCCommConfiguration.h" + +QGCCommConfiguration::QGCCommConfiguration(QWidget *parent, LinkConfiguration *config) : + QDialog(parent), + _ui(new Ui::QGCCommConfiguration) +{ + _ui->setupUi(this); + // Add link types + _config = config; + _ui->typeCombo->addItem(tr("Select Type"), LinkConfiguration::TypeLast); + _ui->typeCombo->addItem(tr("Serial"), LinkConfiguration::TypeSerial); + _ui->typeCombo->addItem(tr("UDP"), LinkConfiguration::TypeUdp); +#ifdef UNITTEST_BUILD + _ui->typeCombo->addItem(tr("Mock"), LinkConfiguration::TypeMock); +#endif + +#if 0 + _ui->typeCombo->addItem(tr("TCP"), LinkConfiguration::TypeTcp); + +#ifdef QGC_RTLAB_ENABLED + _ui->typeCombo->addItem(tr("Opal-RT Link"), LinkConfiguration::TypeOpal); +#endif +#ifdef QGC_XBEE_ENABLED + _ui->typeCombo->addItem(tr("Xbee API"), LinkConfiguration::TypeXbee); +#endif +#endif + + _ui->typeCombo->setEditable(false); + if(config && !config->name().isEmpty()) { + _ui->nameEdit->setText(config->name()); + } else { + _ui->nameEdit->setText(tr("Unnamed")); + } + if(!config) { + setWindowTitle(tr("Add New Communication Link")); + } else { + setWindowTitle(tr("Edit Communication Link")); + _loadTypeConfigWidget(config->type()); + _ui->typeCombo->setEnabled(false); + } + _updateUI(); +} + +QGCCommConfiguration::~QGCCommConfiguration() +{ + delete _ui; +} + +void QGCCommConfiguration::on_typeCombo_currentIndexChanged(int index) +{ + int type = _ui->typeCombo->itemData(index).toInt(); + _changeLinkType(type); +} + +void QGCCommConfiguration::_changeLinkType(int type) +{ + //-- Do we need to change anything? + if(type == LinkConfiguration::TypeLast || (_config && _config->type() == type)) { + return; + } + // Switching connection type. Delete old config. + delete _config; + // Create new config instance + QString name = _ui->nameEdit->text(); + if(name.isEmpty()) { + name = tr("Untitled"); + _ui->nameEdit->setText(name); + } + _config = LinkConfiguration::createSettings(type, name); + Q_ASSERT(_config != NULL); + _loadTypeConfigWidget(type); + _updateUI(); +} + +void QGCCommConfiguration::_loadTypeConfigWidget(int type) +{ + Q_ASSERT(_config != NULL); + switch(type) { + case LinkConfiguration::TypeSerial: { + QWidget* conf = new SerialConfigurationWindow((SerialConfiguration*)_config, this); + _ui->linkScrollArea->setWidget(conf); + _ui->linkGroupBox->setTitle(tr("Serial Link")); + _ui->typeCombo->setCurrentIndex(_ui->typeCombo->findData(LinkConfiguration::TypeSerial)); + } + break; + case LinkConfiguration::TypeUdp: { + QWidget* conf = new QGCUDPLinkConfiguration((UDPConfiguration*)_config, this); + _ui->linkScrollArea->setWidget(conf); + _ui->linkGroupBox->setTitle(tr("UDP Link")); + _ui->typeCombo->setCurrentIndex(_ui->typeCombo->findData(LinkConfiguration::TypeUdp)); + } + break; +#ifdef UNITTEST_BUILD + case LinkConfiguration::TypeMock: { + _ui->linkScrollArea->setWidget(NULL); + _ui->linkGroupBox->setTitle(tr("Mock Link")); + _ui->typeCombo->setCurrentIndex(_ui->typeCombo->findData(LinkConfiguration::TypeMock)); + } + break; +#endif + // Cannot be the case, but in case it gets here, we cannot continue. + default: + reject(); + break; + } + // Remove "Select Type" once something is selected + int idx = _ui->typeCombo->findData(LinkConfiguration::TypeLast); + if(idx >= 0) { + _ui->typeCombo->removeItem(idx); + } +} + +void QGCCommConfiguration::_updateUI() +{ + bool enableOK = false; + if(_config) { + if(!_ui->nameEdit->text().isEmpty()) { + enableOK = true; + } + } + QPushButton* ok = _ui->buttonBox->button(QDialogButtonBox::Ok); + Q_ASSERT(ok != NULL); + ok->setEnabled(enableOK); +} + +void QGCCommConfiguration::on_buttonBox_accepted() +{ + if(_config) { + _config->setName(_ui->nameEdit->text()); + } + accept(); +} + +void QGCCommConfiguration::on_buttonBox_rejected() +{ + reject(); +} + +void QGCCommConfiguration::on_nameEdit_textEdited(const QString &arg1) +{ + Q_UNUSED(arg1); + _updateUI(); +} diff --git a/src/ui/QGCCommConfiguration.h b/src/ui/QGCCommConfiguration.h new file mode 100644 index 0000000000000000000000000000000000000000..192a99d7c015cb343dfe04a0c869ff2f399cab18 --- /dev/null +++ b/src/ui/QGCCommConfiguration.h @@ -0,0 +1,55 @@ +#ifndef QGCCOMMCONFIGURATION_H +#define QGCCOMMCONFIGURATION_H + +#include +#include + +#include "LinkConfiguration.h" + +namespace Ui { +class QGCCommConfiguration; +} + +class QGCCommConfiguration : public QDialog +{ + Q_OBJECT + +public: + explicit QGCCommConfiguration(QWidget *parent, LinkConfiguration* config = 0); + ~QGCCommConfiguration(); + + enum { + 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 + }; + + LinkConfiguration* getConfig() { return _config; } + +private slots: + void on_typeCombo_currentIndexChanged(int index); + void on_buttonBox_accepted(); + void on_buttonBox_rejected(); + void on_nameEdit_textEdited(const QString &arg1); + +private: + void _changeLinkType(int type); + void _loadTypeConfigWidget(int type); + void _updateUI(); + + Ui::QGCCommConfiguration* _ui; + LinkConfiguration* _config; +}; + +#endif // QGCCOMMCONFIGURATION_H diff --git a/src/ui/QGCCommConfiguration.ui b/src/ui/QGCCommConfiguration.ui new file mode 100644 index 0000000000000000000000000000000000000000..6c8e3f877797b061f2a274692ba88e82803a2c72 --- /dev/null +++ b/src/ui/QGCCommConfiguration.ui @@ -0,0 +1,139 @@ + + + QGCCommConfiguration + + + + 0 + 0 + 450 + 450 + + + + + 450 + 450 + + + + + 600 + 600 + + + + Form + + + + + + + + + + + 160 + 0 + + + + Link Name: + + + + + + + + 0 + 0 + + + + + + + + + + + + + 160 + 0 + + + + Link Type: + + + + + + + + 0 + 0 + + + + + + + + + + + + Link + + + + 0 + + + 0 + + + 0 + + + 0 + + + 0 + + + + + true + + + + + 0 + 0 + 418 + 304 + + + + + + + + + + + + QDialogButtonBox::Cancel|QDialogButtonBox::Ok + + + + + + + + diff --git a/src/ui/QGCLinkConfiguration.cc b/src/ui/QGCLinkConfiguration.cc new file mode 100644 index 0000000000000000000000000000000000000000..c9c1cc6a3c3d98a9b333f498f7ddcafda4ca2109 --- /dev/null +++ b/src/ui/QGCLinkConfiguration.cc @@ -0,0 +1,221 @@ +/*===================================================================== + +QGroundControl Open Source Ground Control Station + +(c) 2009, 2010 QGROUNDCONTROL PROJECT + +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 . + +======================================================================*/ + +/** + * @file + * @brief Implementation of QGCLinkConfiguration + * @author Gus Grubba + */ + +#include "SettingsDialog.h" +#include "QGCLinkConfiguration.h" +#include "ui_QGCLinkConfiguration.h" +#include "QGCCommConfiguration.h" +#include "QGCMessageBox.h" + +QGCLinkConfiguration::QGCLinkConfiguration(QWidget *parent) : + QWidget(parent), + _ui(new Ui::QGCLinkConfiguration) +{ + // Stop automatic link updates while this UI is up + LinkManager::instance()->suspendConfigurationUpdates(true); + _ui->setupUi(this); + _viewModel = new LinkViewModel; + _ui->linkView->setModel(_viewModel); + _ui->connectLinkButton->setEnabled(false); + _ui->delLinkButton->setEnabled(false); + _ui->editLinkButton->setEnabled(false); +} + +QGCLinkConfiguration::~QGCLinkConfiguration() +{ + if(_viewModel) delete _viewModel; + if(_ui) delete _ui; + // Resume automatic link updates + LinkManager::instance()->suspendConfigurationUpdates(false); +} + +void QGCLinkConfiguration::on_delLinkButton_clicked() +{ + QModelIndex index = _ui->linkView->currentIndex(); + LinkConfiguration* config = _viewModel->getConfiguration(index.row()); + if(config) { + // Ask user if they are sure + QMessageBox::StandardButton button = QGCMessageBox::question( + tr("Delete Link Configuration"), + tr("Are you sure you want to delete %1?\nDeleting a configuration will also disconnect it if connected.").arg(config->name()), + QMessageBox::Yes | QMessageBox::Cancel, + QMessageBox::Cancel); + if (button == QMessageBox::Yes) { + // Get link attached to this configuration (if any) + LinkInterface* iface = config->getLink(); + if(iface) { + // Disconnect it (if connected) + LinkManager::instance()->disconnectLink(iface); + } + _viewModel->beginChange(); + // Remove configuration + LinkManager::instance()->removeLinkConfiguration(config); + // Save list + LinkManager::instance()->saveLinkConfigurationList(); + _viewModel->endChange(); + } + } +} + +void QGCLinkConfiguration::on_linkView_clicked(const QModelIndex &index) +{ + LinkConfiguration* config = _viewModel->getConfiguration(index.row()); + bool enabled = (config && !config->getLink()); + _ui->connectLinkButton->setEnabled(enabled); + _ui->delLinkButton->setEnabled(config != NULL); + _ui->editLinkButton->setEnabled(config != NULL); +} + +void QGCLinkConfiguration::on_connectLinkButton_clicked() +{ + QModelIndex index = _ui->linkView->currentIndex(); + LinkConfiguration* config = _viewModel->getConfiguration(index.row()); + if(config) { + // Only connect if not already connected + if(!config->getLink()) { + LinkInterface* link = LinkManager::instance()->createLink(config); + if(link) { + // Connect it + LinkManager::instance()->connectLink(link); + // Now go hunting for the parent so we can shut this down + QWidget* pQw = parentWidget(); + while(pQw) { + SettingsDialog* pDlg = dynamic_cast(pQw); + if(pDlg) { + pDlg->accept(); + break; + } + pQw = pQw->parentWidget(); + } + } + } + } +} + +void QGCLinkConfiguration::on_editLinkButton_clicked() +{ + QModelIndex index = _ui->linkView->currentIndex(); + _editLink(index.row()); +} + +void QGCLinkConfiguration::on_addLinkButton_clicked() +{ + QGCCommConfiguration* commDialog = new QGCCommConfiguration(this); + if(commDialog->exec() == QDialog::Accepted) { + // Save changes (if any) + LinkConfiguration* config = commDialog->getConfig(); + if(config) { + //-- Check for "Unnamed" + if (config->name() == tr("Unnamed")) { + switch(config->type()) { + case LinkConfiguration::TypeSerial: + config->setName( + QString("Serial Device on %1").arg(dynamic_cast(config)->portName())); + break; + case LinkConfiguration::TypeUdp: + config->setName( + QString("UDP Link on Port %1").arg(dynamic_cast(config)->localPort())); + break; +#ifdef UNITTEST_BUILD + case LinkConfiguration::TypeMock: + config->setName( + QString("Mock Link")); + break; +#endif + } + } + _viewModel->beginChange(); + LinkManager::instance()->addLinkConfiguration(commDialog->getConfig()); + LinkManager::instance()->saveLinkConfigurationList(); + _viewModel->endChange(); + } + } +} + +void QGCLinkConfiguration::on_linkView_doubleClicked(const QModelIndex &index) +{ + _editLink(index.row()); +} + +void QGCLinkConfiguration::_editLink(int row) +{ + LinkConfiguration* config = _viewModel->getConfiguration(row); + if(config) { + LinkConfiguration* tmpConfig = LinkConfiguration::duplicateSettings(config); + QGCCommConfiguration* commDialog = new QGCCommConfiguration(this, tmpConfig); + if(commDialog->exec() == QDialog::Accepted) { + // Save changes (if any) + if(commDialog->getConfig()) { + _viewModel->beginChange(); + config->copyFrom(tmpConfig); + // Save it + LinkManager::instance()->saveLinkConfigurationList(); + _viewModel->endChange(); + // Tell link about changes (if any) + config->updateSettings(); + } + } + // Discard temporary duplicate + if(commDialog->getConfig()) + delete commDialog->getConfig(); + } +} + +LinkViewModel::LinkViewModel(QObject *parent) : QAbstractListModel(parent) +{ + Q_UNUSED(parent); +} + +int LinkViewModel::rowCount( const QModelIndex & parent) const +{ + Q_UNUSED(parent); + QList cfgList = LinkManager::instance()->getLinkConfigurationList(); + int count = cfgList.count(); + return count; +} + +QVariant LinkViewModel::data( const QModelIndex & index, int role) const +{ + QList cfgList = LinkManager::instance()->getLinkConfigurationList(); + if (role == Qt::DisplayRole && index.row() < cfgList.count()) { + QString name(cfgList.at(index.row())->name()); + return name; + } + return QVariant(); +} + +LinkConfiguration* LinkViewModel::getConfiguration(int row) +{ + QList cfgList = LinkManager::instance()->getLinkConfigurationList(); + if(row < cfgList.count()) { + return cfgList.at(row); + } + return NULL; +} + diff --git a/src/ui/QGCLinkConfiguration.h b/src/ui/QGCLinkConfiguration.h new file mode 100644 index 0000000000000000000000000000000000000000..4052ad39cb753ea055dff3a5ca85bd2857fd03d0 --- /dev/null +++ b/src/ui/QGCLinkConfiguration.h @@ -0,0 +1,49 @@ +#ifndef QGCLINKCONFIGURATION_H +#define QGCLINKCONFIGURATION_H + +#include +#include + +#include "LinkManager.h" + +namespace Ui { +class QGCLinkConfiguration; +} + +class LinkViewModel; + +class QGCLinkConfiguration : public QWidget +{ + Q_OBJECT + +public: + explicit QGCLinkConfiguration(QWidget *parent = 0); + ~QGCLinkConfiguration(); + +private slots: + void on_delLinkButton_clicked(); + void on_editLinkButton_clicked(); + void on_addLinkButton_clicked(); + void on_linkView_doubleClicked(const QModelIndex &index); + void on_linkView_clicked(const QModelIndex &index); + void on_connectLinkButton_clicked(); + +private: + void _editLink(int row); + + Ui::QGCLinkConfiguration* _ui; + LinkViewModel* _viewModel; +}; + +class LinkViewModel : public QAbstractListModel +{ +public: + LinkViewModel(QObject *parent = 0); + int rowCount ( const QModelIndex & parent = QModelIndex() ) const; + QVariant data ( const QModelIndex & index, int role = Qt::DisplayRole ) const; + LinkConfiguration* getConfiguration(int row); + void beginChange() { beginResetModel(); } + void endChange() { endResetModel(); } +}; + +#endif // QGCLINKCONFIGURATION_H diff --git a/src/ui/QGCLinkConfiguration.ui b/src/ui/QGCLinkConfiguration.ui new file mode 100644 index 0000000000000000000000000000000000000000..de16788ec414f422c6794a40dad236ceac424b25 --- /dev/null +++ b/src/ui/QGCLinkConfiguration.ui @@ -0,0 +1,67 @@ + + + QGCLinkConfiguration + + + + 0 + 0 + 400 + 391 + + + + Form + + + + + + + + + 1 + 1 + + + + + + + + + + + + Delete + + + + + + + Edit + + + + + + + Add + + + + + + + Connect + + + + + + + + + + diff --git a/src/ui/QGCToolBar.cc b/src/ui/QGCToolBar.cc index 5c1575119f2357453e5e7227722002dcfe1d8f2a..9dc5e13142c66b3dca1e14891f7f3f40893107e8 100644 --- a/src/ui/QGCToolBar.cc +++ b/src/ui/QGCToolBar.cc @@ -26,13 +26,11 @@ This file is part of the QGROUNDCONTROL project #include #include -#include "SerialLink.h" -#include "UDPLink.h" +#include "SettingsDialog.h" #include "QGCToolBar.h" #include "UASManager.h" #include "MainWindow.h" #include "QGCApplication.h" -#include "CommConfigurationWindow.h" QGCToolBar::QGCToolBar(QWidget *parent) : QToolBar(parent), @@ -49,16 +47,14 @@ QGCToolBar::QGCToolBar(QWidget *parent) : _linkMgr(LinkManager::instance()), _linkCombo(NULL), _linkComboAction(NULL), - _linkSelectedOnce(false), - _baudCombo(NULL), - _baudComboAction(NULL), - _linksConnected(false) + _linksConnected(false), + _linkSelected(false) { setObjectName("QGCToolBar"); setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::MinimumExpanding); - - connect(LinkManager::instance(), &LinkManager::linkConnected, this, &QGCToolBar::_linkConnected); - connect(LinkManager::instance(), &LinkManager::linkDisconnected, this, &QGCToolBar::_linkDisconnected); + connect(LinkManager::instance(), &LinkManager::linkConnected, this, &QGCToolBar::_linkConnected); + connect(LinkManager::instance(), &LinkManager::linkDisconnected, this, &QGCToolBar::_linkDisconnected); + connect(LinkManager::instance(), &LinkManager::linkConfigurationChanged, this, &QGCToolBar::_updateConfigurations); } void QGCToolBar::heartbeatTimeout(bool timeout, unsigned int ms) @@ -161,31 +157,14 @@ void QGCToolBar::createUI() spacer->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding); addWidget(spacer); + // Links to connect to _linkCombo = new QComboBox(this); - _linkCombo->addItem("UDP"); connect(_linkCombo, SIGNAL(activated(int)), SLOT(_linkComboActivated(int))); - _linkCombo->setToolTip(tr("Choose the link to use")); _linkCombo->setEnabled(true); - _linkCombo->setMinimumWidth(100); - + _linkCombo->setMinimumWidth(160); _linkComboAction = addWidget(_linkCombo); - - _baudCombo = new QComboBox(this); - _baudCombo->setToolTip(tr("Choose what baud rate to use")); - _baudCombo->setEnabled(true); - _baudCombo->setMinimumWidth(40); - _baudCombo->addItem("9600", 9600); - _baudCombo->addItem("14400", 14400); - _baudCombo->addItem("19200", 19200); - _baudCombo->addItem("38400", 38400); - _baudCombo->addItem("57600", 57600); - _baudCombo->addItem("115200", 115200); - _baudCombo->addItem("230400", 230400); - _baudCombo->addItem("460800", 460800); - _baudCombo->addItem("921600", 921600); - _baudCombo->setCurrentIndex(_baudCombo->findData(57600)); - _baudComboAction = addWidget(_baudCombo); + _updateConfigurations(); _connectButton = new QPushButton(tr("Connect"), this); _connectButton->setObjectName("connectButton"); @@ -203,9 +182,6 @@ void QGCToolBar::createUI() setActiveUAS(UASManager::instance()->getActiveUAS()); connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*))); - connect(&_portListTimer, &QTimer::timeout, this, &QGCToolBar::_updatePortList); - _portListTimer.start(500); - toolBarMessageAction->setVisible(false); toolBarBatteryBarAction->setVisible(false); @@ -422,7 +398,7 @@ void QGCToolBar::updateView() } if (toolBarBatteryVoltageLabel->isVisible()) { - toolBarBatteryVoltageLabel->setText(tr("%1 V").arg(batteryVoltage, 4, 'f', 1, ' ')); + toolBarBatteryVoltageLabel->setText(tr("%1 V").arg(batteryVoltage, 4, 'f', 1, ' ')); } @@ -601,26 +577,6 @@ void QGCToolBar::receiveTextMessage(int uasid, int componentid, int severity, QS lastSystemMessageTimeMs = QGC::groundTimeMilliseconds(); } -void QGCToolBar::_updatePortList(void) -{ - if (!_linkCombo->isVisible()) { - return; - } - - QList portList = QSerialPortInfo::availablePorts(); - - foreach (QSerialPortInfo portInfo, portList) { - if (_linkCombo->findText(portInfo.portName()) == -1) { - _linkCombo->addItem(portInfo.portName()); - if (!_linkSelectedOnce && portInfo.vendorIdentifier() == 9900) { - // Pre-Select 3DR connection - _linkSelectedOnce = true; - _linkCombo->setCurrentIndex(_linkCombo->findText(portInfo.portName())); - } - } - } -} - void QGCToolBar::_linkConnected(LinkInterface* link) { Q_UNUSED(link); @@ -629,47 +585,38 @@ void QGCToolBar::_linkConnected(LinkInterface* link) void QGCToolBar::_linkDisconnected(LinkInterface* link) { - Q_UNUSED(link); - _updateConnectButton(); + _updateConnectButton(link); } -void QGCToolBar::_updateConnectButton(void) +void QGCToolBar::_updateConnectButton(LinkInterface *disconnectedLink) { QMenu* menu = new QMenu(this); - // If there are multiple connected links add/update the connect button menu - int connectedCount = 0; QList links = _linkMgr->getLinks(); foreach(LinkInterface* link, links) { - if (link->isConnected()) { + if (disconnectedLink != link && link->isConnected()) { connectedCount++; QAction* action = menu->addAction(link->getName()); action->setData(QVariant::fromValue((void*)link)); connect(action, &QAction::triggered, this, &QGCToolBar::_disconnectFromMenu); } } - // Remove old menu QMenu* oldMenu = _connectButton->menu(); _connectButton->setMenu(NULL); if (oldMenu) { oldMenu->deleteLater(); } - // Add new menu if needed if (connectedCount > 1) { _connectButton->setMenu(menu); } else { delete menu; } - _linksConnected = connectedCount != 0; - _connectButton->setText(_linksConnected ? tr("Disconnect") : tr("Connect")); - _linkComboAction->setVisible(!_linksConnected); - _baudComboAction->setVisible(!_linksConnected); toolBarMessageAction->setVisible(_linksConnected); toolBarWpAction->setVisible(_linksConnected); } @@ -677,12 +624,9 @@ void QGCToolBar::_updateConnectButton(void) void QGCToolBar::_connectButtonClicked(bool checked) { Q_UNUSED(checked); - if (_linksConnected) { // Disconnect - // Should be just one connected link, disconnect it - int connectedCount = 0; LinkInterface* connectedLink = NULL; QList links = _linkMgr->getLinks(); @@ -694,27 +638,31 @@ void QGCToolBar::_connectButtonClicked(bool checked) } Q_ASSERT(connectedCount == 1); Q_ASSERT(connectedLink); - + // TODO The link is "disconnected" but not deleted. On subsequent connections, + // new links are created. Why's that? _linkMgr->disconnectLink(connectedLink); } else { + // We don't want the combo box updating under our feet + _linkMgr->suspendConfigurationUpdates(true); // Connect - - QString linkName = _linkCombo->currentText(); - - if (linkName == "UDP") { - UDPLink* link = new UDPLink; - Q_CHECK_PTR(link); - - _linkMgr->addLink(link); - CommConfigurationWindow* commDialog = new CommConfigurationWindow(link, this); - commDialog->exec(); - } else { - // Must be a serial port - SerialLink* link = new SerialLink(linkName, _baudCombo->currentText().toInt()); - Q_CHECK_PTR(link); - - _linkMgr->addLink(link); - _linkMgr->connectLink(link); + int valid = _linkCombo->currentData().toInt(); + // Is this a valid option? + if(valid == 1) { + // Get the configuration name + QString confName = _linkCombo->currentText(); + // Create a link for it + LinkInterface* link = _linkMgr->createLink(confName); + if(link) { + // Connect it + _linkMgr->connectLink(link); + // Save last used connection + MainWindow::instance()->saveLastUsedConnection(confName); + } + _linkMgr->suspendConfigurationUpdates(false); + // Else, it must be Manage Links + } else if(valid == 0) { + _linkMgr->suspendConfigurationUpdates(false); + MainWindow::instance()->manageLinks(); } } } @@ -722,13 +670,10 @@ void QGCToolBar::_connectButtonClicked(bool checked) void QGCToolBar::_disconnectFromMenu(bool checked) { Q_UNUSED(checked); - QAction* action = qobject_cast(sender()); Q_ASSERT(action); - LinkInterface* link = (LinkInterface*)(action->data().value()); Q_ASSERT(link); - _linkMgr->disconnectLink(link); } @@ -743,7 +688,36 @@ void QGCToolBar::clearStatusString() void QGCToolBar::_linkComboActivated(int index) { - Q_UNUSED(index); - - _linkSelectedOnce = true; + int type = _linkCombo->itemData(index).toInt(); + // Check if we should "Manage Connections" + if(type == 0) { + MainWindow::instance()->manageLinks(); + } else { + _linkSelected = true; + } +} + +void QGCToolBar::_updateConfigurations() +{ + bool resetSelected = false; + QString selected = _linkCombo->currentText(); + _linkCombo->clear(); + _linkCombo->addItem("Manage Links", 0); + QList configs = LinkManager::instance()->getLinkConfigurationList(); + foreach(LinkConfiguration* conf, configs) { + if(conf) { + _linkCombo->addItem(conf->name(), 1); + if(!_linkSelected && conf->isPreferred()) { + selected = conf->name(); + resetSelected = true; + } + } + } + int index = _linkCombo->findText(selected); + if(index >= 0) { + _linkCombo->setCurrentIndex(index); + } + if(resetSelected) { + _linkSelected = false; + } } diff --git a/src/ui/QGCToolBar.h b/src/ui/QGCToolBar.h index 6d440a33f287ec7d4b393862904b282ce69acabe..64d33c9f0c3d63f791f08a9aa1d7413c5be86362 100644 --- a/src/ui/QGCToolBar.h +++ b/src/ui/QGCToolBar.h @@ -113,30 +113,26 @@ protected: QAction* firstAction; QToolButton *advancedButton; QButtonGroup *group; - + private slots: void _linkConnected(LinkInterface* link); void _linkDisconnected(LinkInterface* link); void _disconnectFromMenu(bool checked); void _connectButtonClicked(bool checked); void _linkComboActivated(int index); - + void _updateConfigurations(); + private: - void _updateConnectButton(void); - void _updatePortList(void); - + void _updateConnectButton(LinkInterface* disconnectedLink = NULL); + LinkManager* _linkMgr; - + QComboBox* _linkCombo; QAction* _linkComboAction; - bool _linkSelectedOnce; - QTimer _portListTimer; - - QComboBox* _baudCombo; - QAction* _baudComboAction; - + QPushButton* _connectButton; bool _linksConnected; + bool _linkSelected; // User selected a link. Stop autoselecting it. }; #endif // QGCTOOLBAR_H diff --git a/src/ui/QGCUDPLinkConfiguration.cc b/src/ui/QGCUDPLinkConfiguration.cc index 6c243d1621860e5957b534c22cfb53299244cb18..3ef4ead5484dc2adec64689b9db5a6adb869c563 100644 --- a/src/ui/QGCUDPLinkConfiguration.cc +++ b/src/ui/QGCUDPLinkConfiguration.cc @@ -1,42 +1,151 @@ +/*===================================================================== + +QGroundControl Open Source Ground Control Station + +(c) 2009, 2010 QGROUNDCONTROL PROJECT + +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 . + +======================================================================*/ + +/** + * @file + * @brief Implementation of QGCUDPLinkConfiguration + * @author Gus Grubba + */ + #include #include "QGCUDPLinkConfiguration.h" #include "ui_QGCUDPLinkConfiguration.h" -QGCUDPLinkConfiguration::QGCUDPLinkConfiguration(UDPLink* link, QWidget *parent) : - QWidget(parent), - link(link), - ui(new Ui::QGCUDPLinkConfiguration) +QGCUDPLinkConfiguration::QGCUDPLinkConfiguration(UDPConfiguration *config, QWidget *parent) + : QWidget(parent) + , _inConstructor(true) + , _ui(new Ui::QGCUDPLinkConfiguration) { - ui->setupUi(this); - ui->portSpinBox->setValue(link->getPort()); - connect(ui->portSpinBox, SIGNAL(valueChanged(int)), link, SLOT(setPort(int))); - connect(ui->addIPButton, SIGNAL(clicked()), this, SLOT(addHost())); + _config = config; + _ui->setupUi(this); + _viewModel = new UPDViewModel; + _ui->listView->setModel(_viewModel); + _ui->removeHost->setEnabled(false); + _ui->editHost->setEnabled(false); + _ui->portNumber->setRange(1024, 65535); + _ui->portNumber->setValue(_config->localPort()); + _reloadList(); + _inConstructor = false; } QGCUDPLinkConfiguration::~QGCUDPLinkConfiguration() { - delete ui; + delete _ui; } -void QGCUDPLinkConfiguration::changeEvent(QEvent *e) +void QGCUDPLinkConfiguration::_reloadList() { - QWidget::changeEvent(e); - switch (e->type()) { - case QEvent::LanguageChange: - ui->retranslateUi(this); - break; - default: - break; + QString host; + int port; + if(_config->firstHost(host, port)) { + _viewModel->beginChange(); + _viewModel->hosts.clear(); + do { + _viewModel->hosts.append(QString("%1:%2").arg(host, QString::number(port))); + } while (_config->nextHost(host, port)); + _viewModel->endChange(); } } -void QGCUDPLinkConfiguration::addHost() +void QGCUDPLinkConfiguration::_editHost(int row) +{ + if(row < _viewModel->hosts.count()) { + bool ok; + QString hostName = QInputDialog::getText( + this, tr("Edit a MAVLink host target"), + tr("Host (hostname:port): "), QLineEdit::Normal, _viewModel->hosts.at(row), &ok); + if (ok && !hostName.isEmpty()) { + _viewModel->beginChange(); + _viewModel->hosts.replace(row, hostName); + _viewModel->endChange(); + } + } +} + +void QGCUDPLinkConfiguration::on_portNumber_valueChanged(int arg1) +{ + if(!_inConstructor) { + _config->setLocalPort(arg1); + } +} + +void QGCUDPLinkConfiguration::on_listView_clicked(const QModelIndex &index) +{ + bool enabled = index.row() < _viewModel->hosts.count(); + _ui->removeHost->setEnabled(enabled); + _ui->editHost->setEnabled(enabled); +} + +void QGCUDPLinkConfiguration::on_listView_doubleClicked(const QModelIndex &index) +{ + _editHost(index.row()); +} + +void QGCUDPLinkConfiguration::on_addHost_clicked() { bool ok; - QString hostName = QInputDialog::getText(this, tr("Add a new IP address / hostname to MAVLink"), - tr("Host (hostname:port):"), QLineEdit::Normal, - "localhost:14555", &ok); - if (ok && !hostName.isEmpty()) - link->addHost(hostName); + QString hostName = QInputDialog::getText( + this, tr("Add a host target to MAVLink"), + tr("Host (hostname:port): "), + QLineEdit::Normal, QString("localhost:%1").arg(QGC_UDP_PORT), &ok); + if (ok && !hostName.isEmpty()) { + _config->addHost(hostName); + _reloadList(); + } +} + +void QGCUDPLinkConfiguration::on_removeHost_clicked() +{ + QModelIndex index = _ui->listView->currentIndex(); + if(index.row() < _viewModel->hosts.count()) { + _viewModel->hosts.removeAt(index.row()); + _reloadList(); + } +} + +void QGCUDPLinkConfiguration::on_editHost_clicked() +{ + QModelIndex index = _ui->listView->currentIndex(); + _editHost(index.row()); +} + + +UPDViewModel::UPDViewModel(QObject *parent) : QAbstractListModel(parent) +{ + Q_UNUSED(parent); +} + +int UPDViewModel::rowCount( const QModelIndex & parent) const +{ + Q_UNUSED(parent); + return hosts.count(); +} + +QVariant UPDViewModel::data( const QModelIndex & index, int role) const +{ + if (role == Qt::DisplayRole && index.row() < hosts.count()) { + return hosts.at(index.row()); + } + return QVariant(); } diff --git a/src/ui/QGCUDPLinkConfiguration.h b/src/ui/QGCUDPLinkConfiguration.h index b875c6d950dd5881e969e2e4a3bbb5fb2555783e..5834ac951605573127368799f48cb41443dfb799 100644 --- a/src/ui/QGCUDPLinkConfiguration.h +++ b/src/ui/QGCUDPLinkConfiguration.h @@ -2,32 +2,53 @@ #define QGCUDPLINKCONFIGURATION_H #include +#include #include "UDPLink.h" -namespace Ui -{ +namespace Ui { class QGCUDPLinkConfiguration; } +class UPDViewModel; + class QGCUDPLinkConfiguration : public QWidget { Q_OBJECT public: - explicit QGCUDPLinkConfiguration(UDPLink* link, QWidget *parent = 0); + explicit QGCUDPLinkConfiguration(UDPConfiguration* config, QWidget *parent = 0); ~QGCUDPLinkConfiguration(); -public slots: - void addHost(); - -protected: - void changeEvent(QEvent *e); +private slots: + void on_addHost_clicked(); + void on_removeHost_clicked(); + void on_editHost_clicked(); + void on_listView_clicked(const QModelIndex &index); + void on_listView_doubleClicked(const QModelIndex &index); - UDPLink* link; ///< UDP link instance this widget configures + void on_portNumber_valueChanged(int arg1); private: - Ui::QGCUDPLinkConfiguration *ui; + + void _reloadList(); + void _editHost(int row); + + bool _inConstructor; + Ui::QGCUDPLinkConfiguration* _ui; + UDPConfiguration* _config; + UPDViewModel* _viewModel; +}; + +class UPDViewModel : public QAbstractListModel +{ +public: + UPDViewModel(QObject *parent = 0); + int rowCount ( const QModelIndex & parent = QModelIndex() ) const; + QVariant data ( const QModelIndex & index, int role = Qt::DisplayRole ) const; + void beginChange() { beginResetModel(); } + void endChange() { endResetModel(); } + QStringList hosts; }; #endif // QGCUDPLINKCONFIGURATION_H diff --git a/src/ui/QGCUDPLinkConfiguration.ui b/src/ui/QGCUDPLinkConfiguration.ui index 156e0fd824e3b2bb5870056908486b3cf19c6906..e5351d92557ffdf078406663676582a2870a2daf 100644 --- a/src/ui/QGCUDPLinkConfiguration.ui +++ b/src/ui/QGCUDPLinkConfiguration.ui @@ -6,44 +6,82 @@ 0 0 - 400 - 300 + 314 + 285 Form - - - - - UDP Port - - + + + + + + + Listening Port: + + + + + + + + 80 + 0 + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + - - - - 3000 - - - 100000 - - - - - + + - Add remote communication target + Target Hosts - - - - Add IP - - + + + + + + + + + Add + + + + + + + Remove + + + + + + + Edit + + + + diff --git a/src/ui/SerialConfigurationWindow.cc b/src/ui/SerialConfigurationWindow.cc index 42d323dde84be111290ea94ae39be1be20146a2b..f5b2a2420a24d2ff6d0b721bf906d286a194c5a9 100644 --- a/src/ui/SerialConfigurationWindow.cc +++ b/src/ui/SerialConfigurationWindow.cc @@ -28,160 +28,136 @@ This file is part of the QGROUNDCONTROL project * */ -#include #include #include #include +#include -#include "SerialConfigurationWindow.h" -#include "SerialLinkInterface.h" -#include "SerialLink.h" +#include +#include -SerialConfigurationWindow::SerialConfigurationWindow(LinkInterface* link, QWidget *parent, Qt::WindowFlags flags) : QWidget(parent, flags), - userConfigured(false) -{ - SerialLinkInterface* serialLink = dynamic_cast(link); - - if(serialLink != 0) - { - serialLink->loadSettings(); - this->link = serialLink; +#ifndef USE_ANCIENT_RATES +#define USE_ANCIENT_RATES 0 +#endif - // Setup the user interface according to link type - ui.setupUi(this); +SerialConfigurationWindow::SerialConfigurationWindow(SerialConfiguration *config, QWidget *parent, Qt::WindowFlags flags) + : QWidget(parent, flags) + , _userConfigured(false) +{ + _ui.setupUi(this); + Q_ASSERT(config != NULL); + _config = config; - // 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); - setLinkName(link->getName()); + // Scan for serial ports. Let the user know if none were found for debugging purposes + if (!setupPortList()) { + qDebug() << "No serial ports found."; + } - // Scan for serial ports. Let the user know if none were found for debugging purposes - if (!setupPortList()) { - qDebug() << "No serial ports found."; - } + // Set up baud rates + _ui.baudRate->clear(); - // Set up baud rates - ui.baudRate->clear(); - - // Keep track of all desired baud rates by OS. These are iterated through - // later and added to ui.baudRate. - QList supportedBaudRates; + // Keep track of all desired baud rates by OS. These are iterated through + // later and added to _ui.baudRate. + QList supportedBaudRates; - // Baud rates supported only by POSIX systems +#if USE_ANCIENT_RATES + // Baud rates supported only by POSIX systems #if defined(Q_OS_UNIX) || defined(Q_OS_LINUX) || defined(Q_OS_DARWIN) - supportedBaudRates << 50; - supportedBaudRates << 75; - supportedBaudRates << 134; - supportedBaudRates << 150; - supportedBaudRates << 200; - supportedBaudRates << 1800; + supportedBaudRates << 50; + supportedBaudRates << 75; + supportedBaudRates << 134; + supportedBaudRates << 150; + supportedBaudRates << 200; + supportedBaudRates << 1800; #endif +#endif //USE_ANCIENT_RATES - // Baud rates supported only by Windows + // Baud rates supported only by Windows #if defined(Q_OS_WIN) - supportedBaudRates << 14400; - supportedBaudRates << 56000; - supportedBaudRates << 128000; - supportedBaudRates << 256000; + supportedBaudRates << 14400; + supportedBaudRates << 56000; + supportedBaudRates << 128000; + supportedBaudRates << 256000; #endif - // Baud rates supported by everyone - supportedBaudRates << 110; - supportedBaudRates << 300; - supportedBaudRates << 600; - supportedBaudRates << 1200; - supportedBaudRates << 2400; - supportedBaudRates << 4800; - supportedBaudRates << 9600; - supportedBaudRates << 19200; - supportedBaudRates << 38400; - supportedBaudRates << 57600; - supportedBaudRates << 115200; - supportedBaudRates << 230400; - supportedBaudRates << 460800; + // Baud rates supported by everyone +#if USE_ANCIENT_RATES + supportedBaudRates << 110; + supportedBaudRates << 300; + supportedBaudRates << 600; + supportedBaudRates << 1200; +#endif //USE_ANCIENT_RATES + supportedBaudRates << 2400; + supportedBaudRates << 4800; + supportedBaudRates << 9600; + supportedBaudRates << 19200; + supportedBaudRates << 38400; + supportedBaudRates << 57600; + supportedBaudRates << 115200; + supportedBaudRates << 230400; + supportedBaudRates << 460800; #if defined(Q_OS_LINUX) - // Baud rates supported only by Linux - supportedBaudRates << 500000; - supportedBaudRates << 576000; + // Baud rates supported only by Linux + supportedBaudRates << 500000; + supportedBaudRates << 576000; #endif - supportedBaudRates << 921600; - - // Now actually add all of our supported baud rates to the UI. - qSort(supportedBaudRates.begin(), supportedBaudRates.end()); - for (int i = 0; i < supportedBaudRates.size(); ++i) { - ui.baudRate->addItem(QString::number(supportedBaudRates.at(i)), supportedBaudRates.at(i)); - } - - // Load current link config - ui.portName->setCurrentIndex(ui.baudRate->findText(QString("%1").arg(this->link->getPortName()))); - - connect(action, SIGNAL(triggered()), this, SLOT(configureCommunication())); - - // Make sure that a change in the link name will be reflected in the UI - connect(link, SIGNAL(nameChanged(QString)), this, SLOT(setLinkName(QString))); - - // Connect the individual user interface inputs - connect(ui.portName, SIGNAL(editTextChanged(QString)), this, SLOT(setPortName(QString))); - connect(ui.portName, SIGNAL(currentIndexChanged(QString)), this, SLOT(setPortName(QString))); - connect(ui.baudRate, static_cast(&QComboBox::activated), this, &SerialConfigurationWindow::setBaudRate); - connect(ui.flowControlCheckBox, SIGNAL(toggled(bool)), this, SLOT(enableFlowControl(bool))); - connect(ui.parNone, SIGNAL(toggled(bool)), this, SLOT(setParityNone(bool))); - connect(ui.parOdd, SIGNAL(toggled(bool)), this, SLOT(setParityOdd(bool))); - connect(ui.parEven, SIGNAL(toggled(bool)), this, SLOT(setParityEven(bool))); - connect(ui.dataBitsSpinBox, static_cast(&QSpinBox::valueChanged), this, &SerialConfigurationWindow::setDataBits); - connect(ui.stopBitsSpinBox, static_cast(&QSpinBox::valueChanged), this, &SerialConfigurationWindow::setStopBits); - connect(ui.advCheckBox, SIGNAL(clicked(bool)), ui.advGroupBox, SLOT(setVisible(bool))); - ui.advCheckBox->setCheckable(true); - ui.advCheckBox->setChecked(false); - ui.advGroupBox->setVisible(false); - - switch(this->link->getParityType()) { - case 0: - ui.parNone->setChecked(true); - break; - case 1: - ui.parOdd->setChecked(true); - break; - case 2: - ui.parEven->setChecked(true); - break; - default: - // Enforce default: no parity in link - setParityNone(true); - ui.parNone->setChecked(true); - break; - } + supportedBaudRates << 921600; - switch(this->link->getFlowType()) { - case 0: - ui.flowControlCheckBox->setChecked(false); - break; - case 1: - ui.flowControlCheckBox->setChecked(true); - break; - default: - ui.flowControlCheckBox->setChecked(false); - enableFlowControl(false); - } + // Now actually add all of our supported baud rates to the ui. + qSort(supportedBaudRates.begin(), supportedBaudRates.end()); + for (int i = 0; i < supportedBaudRates.size(); ++i) { + _ui.baudRate->addItem(QString::number(supportedBaudRates.at(i)), supportedBaudRates.at(i)); + } - ui.baudRate->setCurrentIndex(ui.baudRate->findText(QString("%1").arg(this->link->getBaudRate()))); + // Connect the individual user interface inputs + connect(_ui.portName, SIGNAL(editTextChanged(QString)), this, SLOT(setPortName(QString))); + connect(_ui.portName, SIGNAL(currentIndexChanged(QString)), this, SLOT(setPortName(QString))); + connect(_ui.baudRate, SIGNAL(activated(int)), this, SLOT(setBaudRate(int))); + connect(_ui.flowControlCheckBox,SIGNAL(toggled(bool)), this, SLOT(enableFlowControl(bool))); + connect(_ui.parNone, SIGNAL(toggled(bool)), this, SLOT(setParityNone(bool))); + connect(_ui.parOdd, SIGNAL(toggled(bool)), this, SLOT(setParityOdd(bool))); + connect(_ui.parEven, SIGNAL(toggled(bool)), this, SLOT(setParityEven(bool))); + connect(_ui.dataBitsSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setDataBits(int))); + connect(_ui.stopBitsSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setStopBits(int))); + connect(_ui.advCheckBox, SIGNAL(clicked(bool)), _ui.advGroupBox, SLOT(setVisible(bool))); + + _ui.advCheckBox->setCheckable(true); + _ui.advCheckBox->setChecked(false); + _ui.advGroupBox->setVisible(false); + + switch(_config->parity()) { + case QSerialPort::NoParity: + _ui.parNone->setChecked(true); + break; + case QSerialPort::OddParity: + _ui.parOdd->setChecked(true); + break; + case QSerialPort::EvenParity: + _ui.parEven->setChecked(true); + break; + default: + // Enforce default: no parity in link + setParityNone(true); + _ui.parNone->setChecked(true); + break; + } - ui.dataBitsSpinBox->setValue(this->link->getDataBits()); - ui.stopBitsSpinBox->setValue(this->link->getStopBits()); - portCheckTimer = new QTimer(this); - portCheckTimer->setInterval(1000); - connect(portCheckTimer, SIGNAL(timeout()), this, SLOT(setupPortList())); + int idx = 0; + _ui.flowControlCheckBox->setChecked(_config->flowControl() == QSerialPort::HardwareControl); + idx = _ui.baudRate->findText(QString("%1").arg(_config->baud())); + if(idx < 0) idx = _ui.baudRate->findText("57600"); + if(idx < 0) idx = 0; + _ui.baudRate->setCurrentIndex(idx); + _ui.dataBitsSpinBox->setValue(_config->dataBits()); + _ui.stopBitsSpinBox->setValue(_config->stopBits()); + _portCheckTimer = new QTimer(this); + _portCheckTimer->setInterval(1000); + connect(_portCheckTimer, SIGNAL(timeout()), this, SLOT(setupPortList())); - // Display the widget - this->window()->setWindowTitle(tr("Serial Communication Settings")); - } - else - { - qDebug() << "Link is NOT a serial link, can't open configuration window"; - } + // Display the widget + setWindowTitle(tr("Serial Communication Settings")); } SerialConfigurationWindow::~SerialConfigurationWindow() @@ -192,84 +168,57 @@ SerialConfigurationWindow::~SerialConfigurationWindow() void SerialConfigurationWindow::showEvent(QShowEvent* event) { Q_UNUSED(event); - portCheckTimer->start(); + _portCheckTimer->start(); } void SerialConfigurationWindow::hideEvent(QHideEvent* event) { Q_UNUSED(event); - portCheckTimer->stop(); -} - -QAction* SerialConfigurationWindow::getAction() -{ - return action; -} - -void SerialConfigurationWindow::configureCommunication() -{ - QString selected = ui.portName->currentText(); - setupPortList(); - ui.portName->setEditText(selected); - this->show(); + _portCheckTimer->stop(); } bool SerialConfigurationWindow::setupPortList() { - if (!link) return false; - // Get the ports available on this system - QList ports = link->getCurrentPorts(); - - QString storedName = this->link->getPortName(); + QList ports = SerialConfiguration::getCurrentPorts(); + QString storedName = _config->portName(); bool storedFound = false; - // Add the ports in reverse order, because we prepend them to the list for (int i = ports.count() - 1; i >= 0; --i) { // Prepend newly found port to the list - if (ui.portName->findText(ports[i]) == -1) + if (_ui.portName->findText(ports[i]) < 0) { - ui.portName->insertItem(0, ports[i]); - if (!userConfigured) ui.portName->setEditText(ports[i]); + _ui.portName->insertItem(0, ports[i]); + if (!_userConfigured) _ui.portName->setEditText(ports[i]); } - // Check if the stored link name is still present if (ports[i].contains(storedName) || storedName.contains(ports[i])) storedFound = true; } - if (storedFound) - ui.portName->setEditText(storedName); - + _ui.portName->setEditText(storedName); return (ports.count() > 0); } void SerialConfigurationWindow::enableFlowControl(bool flow) { - if(flow) - { - link->setFlowType(1); - } - else - { - link->setFlowType(0); - } + _config->setFlowControl(flow ? QSerialPort::HardwareControl : QSerialPort::NoFlowControl); } void SerialConfigurationWindow::setParityNone(bool accept) { - if (accept) link->setParityType(0); + if (accept) _config->setParity(QSerialPort::NoParity); } void SerialConfigurationWindow::setParityOdd(bool accept) { - if (accept) link->setParityType(1); // [TODO] This needs to be Fixed [BB] + if (accept) _config->setParity(QSerialPort::OddParity); } void SerialConfigurationWindow::setParityEven(bool accept) { - if (accept) link->setParityType(2); + if (accept) _config->setParity(QSerialPort::EvenParity); } void SerialConfigurationWindow::setPortName(QString port) @@ -277,42 +226,25 @@ void SerialConfigurationWindow::setPortName(QString port) #ifdef Q_OS_WIN port = port.split("-").first(); #endif - port = port.remove(" "); - - if (this->link->getPortName() != port) { - link->setPortName(port); + port = port.trimmed(); + if (_config->portName() != port) { + _config->setPortName(port); } userConfigured = true; } -void SerialConfigurationWindow::setBaudRate(QString rate) +void SerialConfigurationWindow::setBaudRate(int index) { - bool ok; - int intrate = rate.toInt(&ok); - if (ok) { - link->setBaudRate(intrate); - } - userConfigured = true; + int baud = _ui.baudRate->itemData(index).toInt(); + _config->setBaud(baud); } -void SerialConfigurationWindow::setDataBits(int dataBits) +void SerialConfigurationWindow::setDataBits(int bits) { - link->setDataBitsType(static_cast(dataBits)); - userConfigured = true; + _config->setDataBits(bits); } -void SerialConfigurationWindow::setStopBits(int stopBits) +void SerialConfigurationWindow::setStopBits(int bits) { - link->setStopBitsType(static_cast(stopBits)); - userConfigured = true; + _config->setStopBits(bits); } - -void SerialConfigurationWindow::setLinkName(QString name) -{ - Q_UNUSED(name); - // FIXME - action->setText(tr("Configure ") + link->getName()); - action->setStatusTip(tr("Configure ") + link->getName()); - setWindowTitle(tr("Configuration of ") + link->getName()); -} - diff --git a/src/ui/SerialConfigurationWindow.h b/src/ui/SerialConfigurationWindow.h index d45d5b0167faefaffbb2fc18e55723aacad75f77..60f066f22c40af7ab6a055bf2b5e81583c3b7568 100644 --- a/src/ui/SerialConfigurationWindow.h +++ b/src/ui/SerialConfigurationWindow.h @@ -34,12 +34,10 @@ This file is part of the QGROUNDCONTROL project #include #include -#include #include #include #include -#include -#include +#include "SerialLink.h" #include "ui_SerialSettings.h" class SerialConfigurationWindow : public QWidget @@ -47,23 +45,19 @@ class SerialConfigurationWindow : public QWidget Q_OBJECT public: - SerialConfigurationWindow(LinkInterface* link, QWidget *parent = 0, Qt::WindowFlags flags = Qt::Sheet); + SerialConfigurationWindow(SerialConfiguration* config, QWidget *parent = 0, Qt::WindowFlags flags = Qt::Sheet); ~SerialConfigurationWindow(); - QAction* getAction(); - public slots: - void configureCommunication(); void enableFlowControl(bool flow); void setParityNone(bool accept); void setParityOdd(bool accept); void setParityEven(bool accept); void setPortName(QString port); - void setBaudRate(QString rate); - void setDataBits(int dataBits); - void setStopBits(int stopBits); + void setBaudRate(int index); + void setDataBits(int bits); + void setStopBits(int bits); - void setLinkName(QString name); /** * @brief setupPortList Populates the dropdown with the list of available serial ports. * This function is called at 1s intervals to check that the serial port still exists and to see if @@ -79,10 +73,10 @@ protected: private: - Ui::serialSettings ui; - SerialLinkInterface* link; - QAction* action; - QTimer* portCheckTimer; + bool _userConfigured; + Ui::serialSettings _ui; + SerialConfiguration* _config; + QTimer* _portCheckTimer; }; diff --git a/src/ui/SerialSettings.ui b/src/ui/SerialSettings.ui index 2a23c835ff171a57ff1e8cda16e295ee658236d2..415e372e70efe5ea66e3c5eb42f817be24a6c995 100644 --- a/src/ui/SerialSettings.ui +++ b/src/ui/SerialSettings.ui @@ -6,8 +6,8 @@ 0 0 - 234 - 354 + 325 + 347 @@ -19,7 +19,7 @@ - Serial Port + Serial Port: @@ -60,7 +60,7 @@ - Baud Rate + Baud Rate: @@ -231,12 +231,21 @@ Advanced + + 20 + + + 12 + + + 20 + - Flow Control + Flow Control: @@ -263,7 +272,7 @@ - Parity + Parity: @@ -329,7 +338,7 @@ - Data bits + Data Bits: @@ -347,6 +356,12 @@ 0 + + + 60 + 16777215 + + Number of data bits per symbol. This is almost always 8. @@ -356,6 +371,9 @@ Number of data bits per symbol. This is almost always 8. + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + 5 @@ -363,7 +381,7 @@ 8 - 5 + 8 @@ -374,7 +392,7 @@ - Stop bits + Stop Bits: @@ -386,6 +404,12 @@ 0 + + + 60 + 16777215 + + Number of stop bits per symbol. This is almost always 2. @@ -398,9 +422,15 @@ true + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + false + + QAbstractSpinBox::UpDownArrows + 1 @@ -417,19 +447,6 @@ - - - - Qt::Horizontal - - - - 40 - 20 - - - - diff --git a/src/ui/SettingsDialog.cc b/src/ui/SettingsDialog.cc index 194bb90396409e962fc31adbe4bfe0793d3b9d0b..8479b790d649c18e6bf279c3875fe83d1cff86c4 100644 --- a/src/ui/SettingsDialog.cc +++ b/src/ui/SettingsDialog.cc @@ -1,24 +1,24 @@ /*===================================================================== - + QGroundControl Open Source Ground Control Station - + (c) 2009 - 2015 QGROUNDCONTROL PROJECT - + 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 . - + ======================================================================*/ #include @@ -32,56 +32,74 @@ #include "LinkManager.h" #include "MAVLinkProtocol.h" #include "MAVLinkSettingsWidget.h" +#include "QGCLinkConfiguration.h" #include "GAudioOutput.h" #include "QGCApplication.h" #include "QGCFileDialog.h" #include "QGCMessageBox.h" -SettingsDialog::SettingsDialog(JoystickInput *joystick, QWidget *parent, Qt::WindowFlags flags) : +SettingsDialog::SettingsDialog(JoystickInput *joystick, QWidget *parent, int showTab, Qt::WindowFlags flags) : QDialog(parent, flags), _mainWindow(MainWindow::instance()), _ui(new Ui::SettingsDialog) { _ui->setupUi(this); - + // Center the window on the screen. QRect position = frameGeometry(); position.moveCenter(QApplication::desktop()->availableGeometry().center()); move(position.topLeft()); - + + QGCLinkConfiguration* pLinkConf = new QGCLinkConfiguration(this); + JoystickWidget* pJoystickConf = new JoystickWidget(joystick, this); + MAVLinkSettingsWidget* pMavsettings = new MAVLinkSettingsWidget(MAVLinkProtocol::instance(), this); + + // Add the link settings pane + _ui->tabWidget->addTab(pLinkConf, "Comm Links"); // Add the joystick settings pane - _ui->tabWidget->addTab(new JoystickWidget(joystick, this), "Controllers"); - - MAVLinkSettingsWidget* msettings = new MAVLinkSettingsWidget(MAVLinkProtocol::instance(), this); - _ui->tabWidget->addTab(msettings, "MAVLink"); - + _ui->tabWidget->addTab(pJoystickConf, "Controllers"); + // Add the MAVLink settings pane + _ui->tabWidget->addTab(pMavsettings, "MAVLink"); + this->window()->setWindowTitle(tr("QGroundControl Settings")); - + // Audio preferences _ui->audioMuteCheckBox->setChecked(GAudioOutput::instance()->isMuted()); connect(_ui->audioMuteCheckBox, SIGNAL(toggled(bool)), GAudioOutput::instance(), SLOT(mute(bool))); connect(GAudioOutput::instance(), SIGNAL(mutedChanged(bool)), _ui->audioMuteCheckBox, SLOT(setChecked(bool))); - + // Reconnect _ui->reconnectCheckBox->setChecked(_mainWindow->autoReconnectEnabled()); connect(_ui->reconnectCheckBox, SIGNAL(clicked(bool)), _mainWindow, SLOT(enableAutoReconnect(bool))); - + // Low power mode _ui->lowPowerCheckBox->setChecked(_mainWindow->lowPowerModeEnabled()); connect(_ui->lowPowerCheckBox, SIGNAL(clicked(bool)), _mainWindow, SLOT(enableLowPowerMode(bool))); - + connect(_ui->deleteSettings, &QAbstractButton::toggled, this, &SettingsDialog::_deleteSettingsToggled); - + // Application color style _ui->styleChooser->setCurrentIndex(qgcApp()->styleIsDark() ? 0 : 1); - + _ui->savedFilesLocation->setText(qgcApp()->savedFilesLocation()); _ui->promptFlightDataSave->setChecked(qgcApp()->promptFlightDataSave()); - + // Connect signals connect(_ui->styleChooser, SIGNAL(currentIndexChanged(int)), this, SLOT(styleChanged(int))); connect(_ui->browseSavedFilesLocation, &QPushButton::clicked, this, &SettingsDialog::_selectSavedFilesDirectory); connect(_ui->buttonBox, &QDialogButtonBox::accepted, this, &SettingsDialog::_validateBeforeClose); + + switch (showTab) { + case ShowCommLinks: + _ui->tabWidget->setCurrentWidget(pLinkConf); + break; + case ShowControllers: + _ui->tabWidget->setCurrentWidget(pJoystickConf); + break; + case ShowMavlink: + _ui->tabWidget->setCurrentWidget(pMavsettings); + break; + } } SettingsDialog::~SettingsDialog() @@ -115,21 +133,21 @@ void SettingsDialog::_deleteSettingsToggled(bool checked) void SettingsDialog::_validateBeforeClose(void) { QGCApplication* app = qgcApp(); - + // Validate the saved file location - + QString saveLocation = _ui->savedFilesLocation->text(); if (!app->validatePossibleSavedFilesLocation(saveLocation)) { QGCMessageBox::warning(tr("Bad save location"), tr("The location to save files to is invalid, or cannot be written to. Please provide a valid directory.")); return; } - + // Locations is valid, save app->setSavedFilesLocation(saveLocation); - + qgcApp()->setPromptFlightDataSave(_ui->promptFlightDataSave->checkState() == Qt::Checked); - + // Close dialog accept(); } diff --git a/src/ui/SettingsDialog.h b/src/ui/SettingsDialog.h index 377dff6ba1fd52f216e8b0404df0a57df3d988d0..1499ecd978a9cc71c7a0c0241b85272c66eff5f0 100644 --- a/src/ui/SettingsDialog.h +++ b/src/ui/SettingsDialog.h @@ -1,24 +1,24 @@ /*===================================================================== - + QGroundControl Open Source Ground Control Station - + (c) 2009 - 2015 QGROUNDCONTROL PROJECT - + 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 . - + ======================================================================*/ #ifndef SETTINGSDIALOG_H @@ -35,19 +35,27 @@ namespace Ui class SettingsDialog : public QDialog { Q_OBJECT - + public: - SettingsDialog(JoystickInput *joystick, QWidget *parent = 0, Qt::WindowFlags flags = Qt::Sheet); + + enum { + ShowDefault, + ShowCommLinks, + ShowControllers, + ShowMavlink + }; + + SettingsDialog(JoystickInput *joystick, QWidget *parent = 0, int showTab = ShowDefault, Qt::WindowFlags flags = Qt::Sheet); ~SettingsDialog(); - + public slots: void styleChanged(int index); - + private slots: void _deleteSettingsToggled(bool checked); void _selectSavedFilesDirectory(void); void _validateBeforeClose(void); - + private: MainWindow* _mainWindow; Ui::SettingsDialog* _ui; diff --git a/src/ui/uas/QGCUnconnectedInfoWidget.cc b/src/ui/uas/QGCUnconnectedInfoWidget.cc index 20d1004af8f2728d27d5a7b45dd86f29892c7c1d..ff4180cf21102ac435928941e86e75f2455752d8 100644 --- a/src/ui/uas/QGCUnconnectedInfoWidget.cc +++ b/src/ui/uas/QGCUnconnectedInfoWidget.cc @@ -10,9 +10,8 @@ QGCUnconnectedInfoWidget::QGCUnconnectedInfoWidget(QWidget *parent) : ui(new Ui::QGCUnconnectedInfoWidget) { ui->setupUi(this); - //connect(ui->simulationButton, SIGNAL(clicked()), this, SLOT(simulate())); - connect(ui->connectButton, SIGNAL(clicked()), this, SLOT(addLink())); + //connect(ui->connectButton, SIGNAL(clicked()), this, SLOT(addLink())); } QGCUnconnectedInfoWidget::~QGCUnconnectedInfoWidget() @@ -25,6 +24,7 @@ QGCUnconnectedInfoWidget::~QGCUnconnectedInfoWidget() */ void QGCUnconnectedInfoWidget::simulate() { + // TODO What is this? // Try to get reference to MAVLinkSimulationlink QList links = LinkManager::instance()->getLinks(); foreach(LinkInterface* link, links) { @@ -40,5 +40,6 @@ void QGCUnconnectedInfoWidget::simulate() */ void QGCUnconnectedInfoWidget::addLink() { - MainWindow::instance()->addLink(); + // TODO This doesn't make sense. If you want to connect, use the connect on the toolbar + //MainWindow::instance()->addLink(); }