diff --git a/.appveyor.yml b/.appveyor.yml index e2b5c49cf2392364858a2fabb5ac5e776f7a47c4..3e803c3257393ef92777eca55d0fce6da548a0e9 100644 --- a/.appveyor.yml +++ b/.appveyor.yml @@ -2,7 +2,7 @@ environment: matrix: - BUILD: 'Release' - CONFIG: release + CONFIG: installer - BUILD: 'Debug' CONFIG: debug @@ -11,11 +11,33 @@ install: - call "%ProgramFiles(x86)%\Microsoft Visual Studio 12.0\VC\vcvarsall.bat" x86 - set PATH=C:\Qt\Tools\QtCreator\bin;C:\Qt\5.4\msvc2013_opengl\bin;%PATH% - mkdir %LOCALAPPDATA%\QtProject && copy test\qtlogging.ini %LOCALAPPDATA%\QtProject\ + - cinst nsis -y -installArgs /D="%programfiles(x86)%\NSIS" build_script: - - C:\Qt\5.4\msvc2013_opengl\bin\qmake -r CONFIG-=debug_and_release CONFIG+=%CONFIG% CONFIG+=WarningsAsErrorsOn qgroundcontrol.pro - - jom -j 2 + - C:\Qt\5.4\msvc2013_opengl\bin\qmake -r CONFIG-=debug_and_release CONFIG+=%CONFIG% CONFIG+=WarningsAsErrorsOn qgroundcontrol.pro + - jom -j 4 test_script: -# - if "%CONFIG%" EQU "debug" ( debug\qgroundcontrol --unittest ) + - if "%CONFIG%" EQU "debug" ( debug\qgroundcontrol --unittest ) + +after_build: + - if "%CONFIG%" EQU "installer" ( appveyor PushArtifact C:\projects\qgroundcontrol\release\qgroundcontrol-installer-win32.exe ) + +deploy: + - provider: S3 + name: qgroundcontrol-s3 + access_key_id: AKIAIVORNALE7NHD3T6Q + secret_access_key: + secure: RiYqaR+3T2PMNz2j5ur8LCA6H/Zfd4jTX33CZE5iBxm+zaz4QLs25p0B7prpaoNN + bucket: qgrondcontrol + set_public: true + folder: "%APPVEYOR_REPO_BRANCH%" + artifact: C:\projects\qgroundcontrol\release\qgroundcontrol-installer-win32.exe + + - provider: GitHub + artifact: C:\projects\qgroundcontrol\release\qgroundcontrol-installer-win32.exe + draft: false + prerelease: false + on: + appveyor_repo_tag: true diff --git a/.travis.yml b/.travis.yml index 41f783670e3c83cd8c971d5dbf78aaff0939d5bc..35095cc37dde7134e510cd8d90d77a11ddc4e9d4 100644 --- a/.travis.yml +++ b/.travis.yml @@ -17,10 +17,10 @@ matrix: env: SPEC=linux-g++-64 CONFIG=installer sudo: true - os: osx - osx_image: beta-xcode6.3 + osx_image: xcode7 env: SPEC=macx-clang CONFIG=debug - os: osx - osx_image: beta-xcode6.3 + osx_image: xcode7 env: SPEC=macx-clang CONFIG=installer - os: android language: android @@ -44,6 +44,7 @@ before_install: - cd ${TRAVIS_BUILD_DIR} && git fetch --unshallow && git fetch --tags - if [ "${TRAVIS_OS_NAME}" = "linux" ]; then mkdir -p ~/.config/QtProject/ && cp ${TRAVIS_BUILD_DIR}/test/qtlogging.ini ~/.config/QtProject/; fi - if [ "${TRAVIS_OS_NAME}" = "osx" ]; then mkdir -p ~/Library/Preferences/QtProject/ && cp ${TRAVIS_BUILD_DIR}/test/qtlogging.ini ~/Library/Preferences/QtProject/; fi + - if [ "${TRAVIS_OS_NAME}" = "android" ]; then wget https://s3-us-west-2.amazonaws.com/qgroundcontrol/dependencies/gstreamer-1.0-android-armv7-1.5.2.tar.bz2 && mkdir -p ${TRAVIS_BUILD_DIR}/gstreamer-1.0-android-armv7-1.5.2 && tar jxf gstreamer-1.0-android-armv7-1.5.2.tar.bz2 -C ${TRAVIS_BUILD_DIR}/gstreamer-1.0-android-armv7-1.5.2; fi install: - if [ "${TRAVIS_OS_NAME}" = "linux" ]; then diff --git a/QGCApplication.pro b/QGCApplication.pro index 1087d22aafabeb85470fb9bf594b5bff445eefa6..cd9af36b4629a1ea59f200caaa469f9e02538e81 100644 --- a/QGCApplication.pro +++ b/QGCApplication.pro @@ -264,6 +264,7 @@ HEADERS += \ src/QmlControls/MavlinkQmlSingleton.h \ src/QmlControls/ParameterEditorController.h \ src/QmlControls/ScreenToolsController.h \ + src/QmlControls/QGroundControlQmlGlobal.h \ src/QmlControls/QmlObjectListModel.h \ src/SerialPortIds.h \ src/uas/FileManager.h \ @@ -335,7 +336,6 @@ HEADERS += \ src/ui/WaypointViewOnlyView.h \ src/ViewWidgets/CustomCommandWidget.h \ src/ViewWidgets/CustomCommandWidgetController.h \ - src/ViewWidgets/ParameterEditorWidget.h \ src/ViewWidgets/ViewWidgetController.h \ src/MissionItem.h \ src/AutoPilotPlugins/PX4/PX4AirframeLoader.h @@ -395,6 +395,7 @@ SOURCES += \ src/QGCTemporaryFile.cc \ src/QmlControls/ParameterEditorController.cc \ src/QmlControls/ScreenToolsController.cc \ + src/QmlControls/QGroundControlQmlGlobal.cc \ src/QmlControls/QmlObjectListModel.cc \ src/uas/FileManager.cc \ src/uas/UAS.cc \ @@ -464,7 +465,6 @@ SOURCES += \ src/ui/WaypointViewOnlyView.cc \ src/ViewWidgets/CustomCommandWidget.cc \ src/ViewWidgets/CustomCommandWidgetController.cc \ - src/ViewWidgets/ParameterEditorWidget.cc \ src/ViewWidgets/ViewWidgetController.cc \ src/MissionItem.cc \ src/AutoPilotPlugins/PX4/PX4AirframeLoader.cc @@ -578,6 +578,7 @@ HEADERS+= \ src/AutoPilotPlugins/PX4/SensorsComponentController.h \ src/FirmwarePlugin/FirmwarePluginManager.h \ src/FirmwarePlugin/FirmwarePlugin.h \ + src/FirmwarePlugin/APM/APMFirmwarePlugin.h \ src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h \ src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h \ src/Vehicle/MultiVehicleManager.h \ @@ -614,6 +615,7 @@ SOURCES += \ src/AutoPilotPlugins/PX4/SafetyComponent.cc \ src/AutoPilotPlugins/PX4/SensorsComponent.cc \ src/AutoPilotPlugins/PX4/SensorsComponentController.cc \ + src/FirmwarePlugin/APM/APMFirmwarePlugin.cc \ src/FirmwarePlugin/FirmwarePluginManager.cc \ src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc \ src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc \ diff --git a/QGCCommon.pri b/QGCCommon.pri index 37309504f4cb1249919a183658a0e27593ea3543..6a76a5647ca566da33011bd1dd9d1325b5881a78 100644 --- a/QGCCommon.pri +++ b/QGCCommon.pri @@ -157,7 +157,7 @@ MacBuild { CONFIG += x86_64 CONFIG -= x86 QMAKE_MACOSX_DEPLOYMENT_TARGET = 10.6 - QMAKE_MAC_SDK = macosx10.9 + QMAKE_MAC_SDK = macosx10.11 } LinuxBuild { diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc index 117e51de5cdad1286e0aba24a76177f33635261c..34396fe3381a42bc3984c2e630b007e6af047dfe 100644 --- a/qgroundcontrol.qrc +++ b/qgroundcontrol.qrc @@ -110,7 +110,6 @@ src/VehicleSetup/SetupParameterEditor.qml src/QmlControls/ScreenToolsFontQuery.qml - src/ViewWidgets/ParameterEditorWidget.qml src/ViewWidgets/CustomCommandWidget.qml src/AutoPilotPlugins/PX4/SafetyComponent.qml src/AutoPilotPlugins/PX4/RadioComponent.qml diff --git a/src/AutoPilotPlugins/AutoPilotPlugin.cc b/src/AutoPilotPlugins/AutoPilotPlugin.cc index 22e5fadb7480269ede5820e93c3a040427a6ae4b..c8dfa0cce771ac4a65ce325616eb4ab31f2b7297 100644 --- a/src/AutoPilotPlugins/AutoPilotPlugin.cc +++ b/src/AutoPilotPlugins/AutoPilotPlugin.cc @@ -157,9 +157,9 @@ Fact* AutoPilotPlugin::getFact(FactSystem::Provider_t provider, int componentId, return NULL; } -QStringList AutoPilotPlugin::parameterNames(void) +QStringList AutoPilotPlugin::parameterNames(int componentId) { - return _getParameterLoader()->parameterNames(); + return _getParameterLoader()->parameterNames(componentId); } const QMap >& AutoPilotPlugin::getGroupMap(void) diff --git a/src/AutoPilotPlugins/AutoPilotPlugin.h b/src/AutoPilotPlugins/AutoPilotPlugin.h index 6a8b66172ef0a9971b7a5470f6098d6f0eacd9d1..47ac288a2f7a1c1aa7723b6b7bf092d424ae2d51 100644 --- a/src/AutoPilotPlugins/AutoPilotPlugin.h +++ b/src/AutoPilotPlugins/AutoPilotPlugin.h @@ -81,8 +81,7 @@ public: Q_INVOKABLE bool parameterExists(int componentId, const QString& name); /// Returns all parameter names - /// FIXME: component id missing, generic to fact - QStringList parameterNames(void); + QStringList parameterNames(int componentId); /// Returns the specified parameter Fact from the default component /// WARNING: Returns a default Fact if parameter does not exists. If that possibility exists, check for existince first with diff --git a/src/FactSystem/FactSystemTestGeneric.cc b/src/FactSystem/FactSystemTestGeneric.cc index 80536cc3d39369f8088fa947c27070c5595b6aa6..2bb68940248499cc7fa856b6e8bf671bbd7e7798 100644 --- a/src/FactSystem/FactSystemTestGeneric.cc +++ b/src/FactSystem/FactSystemTestGeneric.cc @@ -38,5 +38,5 @@ FactSystemTestGeneric::FactSystemTestGeneric(void) void FactSystemTestGeneric::init(void) { UnitTest::init(); - _init(MAV_AUTOPILOT_ARDUPILOTMEGA); + _init(MAV_AUTOPILOT_GENERIC); } diff --git a/src/FactSystem/ParameterLoader.cc b/src/FactSystem/ParameterLoader.cc index 0c152ccbccf69c5573fa3f508b9218ae5b83fbca..dbfce638cb0eeac2c49a0015664db1cebb73a275 100644 --- a/src/FactSystem/ParameterLoader.cc +++ b/src/FactSystem/ParameterLoader.cc @@ -30,6 +30,7 @@ #include "QGCApplication.h" #include "QGCMessageBox.h" #include "UASMessageHandler.h" +#include "FirmwarePlugin.h" #include #include @@ -387,11 +388,11 @@ Fact* ParameterLoader::getFact(int componentId, const QString& name) return _mapParameterName2Variant[componentId][name].value(); } -QStringList ParameterLoader::parameterNames(void) +QStringList ParameterLoader::parameterNames(int componentId) { QStringList names; - foreach(QString paramName, _mapParameterName2Variant[_defaultComponentId].keys()) { + foreach(QString paramName, _mapParameterName2Variant[_actualComponentId(componentId)].keys()) { names << paramName; } @@ -499,8 +500,6 @@ void ParameterLoader::_readParameterRaw(int componentId, const QString& paramNam void ParameterLoader::_writeParameterRaw(int componentId, const QString& paramName, const QVariant& value) { - bool floatHack = _vehicle->firmwareType() == MAV_AUTOPILOT_ARDUPILOTMEGA; - mavlink_param_set_t p; mavlink_param_union_t union_value; @@ -509,43 +508,23 @@ void ParameterLoader::_writeParameterRaw(int componentId, const QString& paramNa switch (factType) { case FactMetaData::valueTypeUint8: - if (floatHack) { - union_value.param_float = (uint8_t)value.toUInt(); - } else { - union_value.param_uint8 = (uint8_t)value.toUInt(); - } + union_value.param_uint8 = (uint8_t)value.toUInt(); break; case FactMetaData::valueTypeInt8: - if (floatHack) { - union_value.param_float = (int8_t)value.toInt(); - } else { - union_value.param_int8 = (int8_t)value.toInt(); - } + union_value.param_int8 = (int8_t)value.toInt(); break; case FactMetaData::valueTypeUint16: - if (floatHack) { - union_value.param_float = (uint16_t)value.toUInt(); - } else { - union_value.param_uint16 = (uint16_t)value.toUInt(); - } + union_value.param_uint16 = (uint16_t)value.toUInt(); break; case FactMetaData::valueTypeInt16: - if (floatHack) { - union_value.param_float = (int16_t)value.toInt(); - } else { - union_value.param_int16 = (int16_t)value.toInt(); - } + union_value.param_int16 = (int16_t)value.toInt(); break; case FactMetaData::valueTypeUint32: - if (floatHack) { - union_value.param_float = (uint32_t)value.toUInt(); - } else { - union_value.param_uint32 = (uint32_t)value.toUInt(); - } + union_value.param_uint32 = (uint32_t)value.toUInt(); break; case FactMetaData::valueTypeFloat: @@ -557,11 +536,7 @@ void ParameterLoader::_writeParameterRaw(int componentId, const QString& paramNa // fall through case FactMetaData::valueTypeInt32: - if (floatHack) { - union_value.param_float = (int32_t)value.toInt(); - } else { - union_value.param_int32 = (int32_t)value.toInt(); - } + union_value.param_int32 = (int32_t)value.toInt(); break; } @@ -578,10 +553,14 @@ void ParameterLoader::_writeParameterRaw(int componentId, const QString& paramNa void ParameterLoader::_saveToEEPROM(void) { - mavlink_message_t msg; - mavlink_msg_command_long_pack(_mavlink->getSystemId(), _mavlink->getComponentId(), &msg, _vehicle->id(), 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 1, -1, -1, -1, 0, 0, 0); - _vehicle->sendMessage(msg); - qCDebug(ParameterLoaderLog) << "_saveToEEPROM"; + if (_vehicle->firmwarePlugin()->isCapable(FirmwarePlugin::MavCmdPreflightStorageCapability)) { + mavlink_message_t msg; + mavlink_msg_command_long_pack(_mavlink->getSystemId(), _mavlink->getComponentId(), &msg, _vehicle->id(), 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 1, -1, -1, -1, 0, 0, 0); + _vehicle->sendMessage(msg); + qCDebug(ParameterLoaderLog) << "_saveToEEPROM"; + } else { + qCDebug(ParameterLoaderLog) << "_saveToEEPROM skipped due to FirmwarePlugin::isCapable"; + } } QString ParameterLoader::readParametersFromStream(QTextStream& stream) diff --git a/src/FactSystem/ParameterLoader.h b/src/FactSystem/ParameterLoader.h index 9a4cb99f620bf27c91cfdde0a457eb4ec998cf92..3580406d1f4a259a81321420b4cd53a0d9f6ce3b 100644 --- a/src/FactSystem/ParameterLoader.h +++ b/src/FactSystem/ParameterLoader.h @@ -69,8 +69,7 @@ public: const QString& name); ///< fact name /// Returns all parameter names - /// FIXME: component id missing - QStringList parameterNames(void); + QStringList parameterNames(int componentId); /// Returns the specified Fact. /// WARNING: Will assert if parameter does not exists. If that possibily exists, check for existince first with diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc new file mode 100644 index 0000000000000000000000000000000000000000..3341c6b9c2ceb78de1e1fa6a08d743eda32c5b86 --- /dev/null +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc @@ -0,0 +1,171 @@ +/*===================================================================== + + 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 . + + ======================================================================*/ + +/// @file +/// @author Don Gagne + +#include "APMFirmwarePlugin.h" +#include "Generic/GenericFirmwarePlugin.h" + +#include + +IMPLEMENT_QGC_SINGLETON(APMFirmwarePlugin, FirmwarePlugin) + +APMFirmwarePlugin::APMFirmwarePlugin(QObject* parent) : + FirmwarePlugin(parent) +{ + +} + +bool APMFirmwarePlugin::isCapable(FirmwareCapabilities capabilities) +{ + Q_UNUSED(capabilities); + + // FIXME: No capabilitis yet supported + + return false; +} + +QList APMFirmwarePlugin::componentsForVehicle(AutoPilotPlugin* vehicle) +{ + Q_UNUSED(vehicle); + + return QList(); +} + +QStringList APMFirmwarePlugin::flightModes(void) +{ + // FIXME: NYI + + qWarning() << "APMFirmwarePlugin::flightModes not supported"; + + return QStringList(); +} + +QString APMFirmwarePlugin::flightMode(uint8_t base_mode, uint32_t custom_mode) +{ + // FIXME: Nothing more than generic support yet + return GenericFirmwarePlugin::instance()->flightMode(base_mode, custom_mode); +} + +bool APMFirmwarePlugin::setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode) +{ + Q_UNUSED(flightMode); + Q_UNUSED(base_mode); + Q_UNUSED(custom_mode); + + qWarning() << "APMFirmwarePlugin::setFlightMode called on base class, not supported"; + + return false; +} + +int APMFirmwarePlugin::manualControlReservedButtonCount(void) +{ + // We don't know whether the firmware is going to used any of these buttons. + // So reserve them all. + return -1; +} + +void APMFirmwarePlugin::adjustMavlinkMessage(mavlink_message_t* message) +{ + if (message->msgid == MAVLINK_MSG_ID_PARAM_VALUE) { + mavlink_param_value_t paramValue; + mavlink_param_union_t paramUnion; + + // APM stack passes all parameter values in mavlink_param_union_t.param_float no matter what + // type they are. Fix that up to correct usage. + + mavlink_msg_param_value_decode(message, ¶mValue); + + switch (paramValue.param_type) { + case MAV_PARAM_TYPE_UINT8: + paramUnion.param_uint8 = (uint8_t)paramValue.param_value; + break; + case MAV_PARAM_TYPE_INT8: + paramUnion.param_int8 = (int8_t)paramValue.param_value; + break; + case MAV_PARAM_TYPE_UINT16: + paramUnion.param_uint16 = (uint16_t)paramValue.param_value; + break; + case MAV_PARAM_TYPE_INT16: + paramUnion.param_int16 = (int16_t)paramValue.param_value; + break; + case MAV_PARAM_TYPE_UINT32: + paramUnion.param_uint32 = (uint32_t)paramValue.param_value; + break; + case MAV_PARAM_TYPE_INT32: + paramUnion.param_int32 = (int32_t)paramValue.param_value; + break; + case MAV_PARAM_TYPE_REAL32: + paramUnion.param_float = paramValue.param_value; + break; + default: + qCritical() << "Invalid/Unsupported data type used in parameter:" << paramValue.param_type; + } + + paramValue.param_value = paramUnion.param_float; + + mavlink_msg_param_value_encode(message->sysid, message->compid, message, ¶mValue); + + } else if (message->msgid == MAVLINK_MSG_ID_PARAM_SET) { + mavlink_param_set_t paramSet; + mavlink_param_union_t paramUnion; + + // APM stack passes all parameter values in mavlink_param_union_t.param_float no matter what + // type they are. Fix it back to the wrong way on the way out. + + mavlink_msg_param_set_decode(message, ¶mSet); + + paramUnion.param_float = paramSet.param_value; + + switch (paramSet.param_type) { + case MAV_PARAM_TYPE_UINT8: + paramSet.param_value = paramUnion.param_uint8; + break; + case MAV_PARAM_TYPE_INT8: + paramSet.param_value = paramUnion.param_int8; + break; + case MAV_PARAM_TYPE_UINT16: + paramSet.param_value = paramUnion.param_uint16; + break; + case MAV_PARAM_TYPE_INT16: + paramSet.param_value = paramUnion.param_int16; + break; + case MAV_PARAM_TYPE_UINT32: + paramSet.param_value = paramUnion.param_uint32; + break; + case MAV_PARAM_TYPE_INT32: + paramSet.param_value = paramUnion.param_int32; + break; + case MAV_PARAM_TYPE_REAL32: + // Already in param_float + break; + default: + qCritical() << "Invalid/Unsupported data type used in parameter:" << paramSet.param_type; + } + + mavlink_msg_param_set_encode(message->sysid, message->compid, message, ¶mSet); + } + + // FIXME: Need to implement mavlink message severity adjustment +} diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.h b/src/FirmwarePlugin/APM/APMFirmwarePlugin.h new file mode 100644 index 0000000000000000000000000000000000000000..524a36f3850bee872d70fc5fbca5fd7aec62406d --- /dev/null +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.h @@ -0,0 +1,54 @@ +/*===================================================================== + + 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 . + + ======================================================================*/ + +/// @file +/// @author Don Gagne + +#ifndef APMFirmwarePlugin_H +#define APMFirmwarePlugin_H + +#include "FirmwarePlugin.h" + +class APMFirmwarePlugin : public FirmwarePlugin +{ + Q_OBJECT + + DECLARE_QGC_SINGLETON(APMFirmwarePlugin, FirmwarePlugin) + +public: + // Overrides from FirmwarePlugin + + virtual bool isCapable(FirmwareCapabilities capabilities); + virtual QList componentsForVehicle(AutoPilotPlugin* vehicle); + virtual QStringList flightModes(void); + virtual QString flightMode(uint8_t base_mode, uint32_t custom_mode); + virtual bool setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode); + virtual int manualControlReservedButtonCount(void); + virtual void adjustMavlinkMessage(mavlink_message_t* message); + +private: + /// All access to singleton is through AutoPilotPluginManager::instance + APMFirmwarePlugin(QObject* parent = NULL); +}; + +#endif diff --git a/src/FirmwarePlugin/FirmwarePlugin.h b/src/FirmwarePlugin/FirmwarePlugin.h index d718fc8e7c00aa794a40fad579d113404b5ed906..c84a8ece94e9a9b6dd71726f495faeeb571bbfc5 100644 --- a/src/FirmwarePlugin/FirmwarePlugin.h +++ b/src/FirmwarePlugin/FirmwarePlugin.h @@ -51,7 +51,9 @@ class FirmwarePlugin : public QGCSingleton public: /// Set of optional capabilites which firmware may support typedef enum { - SetFlightModeCapability, + SetFlightModeCapability, ///< FirmwarePlugin::setFlightMode method is supported + MavCmdPreflightStorageCapability, ///< MAV_CMD_PREFLIGHT_STORAGE is supported + } FirmwareCapabilities; /// @return true: Firmware supports all specified capabilites @@ -76,12 +78,20 @@ public: /// @param[out] custom_mode Custom mode for SET_MODE mavlink message virtual bool setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode) = 0; + /// FIXME: This isn't quite correct being here. All code for Joystick support is currently firmware specific + /// not just this. I'm going to try to change that. If not, this will need to be removed. /// Returns the number of buttons which are reserved for firmware use in the MANUAL_CONTROL mavlink /// message. For example PX4 Flight Stack reserves the first 8 buttons to simulate rc switches. /// The remainder can be assigned to Vehicle actions. /// @return -1: reserver all buttons, >0 number of buttons to reserve virtual int manualControlReservedButtonCount(void) = 0; + /// Called before any mavlink message is processed by Vehicle such taht the firmwre plugin + /// can adjust any message characteristics. This is handy to adjust or differences in mavlink + /// spec implementations such that the base code can remain mavlink generic. + /// @param message[in,out] Mavlink message to adjust if needed. + virtual void adjustMavlinkMessage(mavlink_message_t* message) = 0; + protected: FirmwarePlugin(QObject* parent = NULL) : QGCSingleton(parent) { } }; diff --git a/src/FirmwarePlugin/FirmwarePluginManager.cc b/src/FirmwarePlugin/FirmwarePluginManager.cc index 06c36a889b0c13eff2f20fbcfd6e6f7b938017fb..b64edde08a4105b689a97341c32a8e79e6cb2506 100644 --- a/src/FirmwarePlugin/FirmwarePluginManager.cc +++ b/src/FirmwarePlugin/FirmwarePluginManager.cc @@ -26,6 +26,7 @@ #include "FirmwarePluginManager.h" #include "Generic/GenericFirmwarePlugin.h" +#include "APM/APMFirmwarePlugin.h" #include "PX4/PX4FirmwarePlugin.h" IMPLEMENT_QGC_SINGLETON(FirmwarePluginManager, FirmwarePluginManager) @@ -43,9 +44,12 @@ FirmwarePluginManager::~FirmwarePluginManager() FirmwarePlugin* FirmwarePluginManager::firmwarePluginForAutopilot(MAV_AUTOPILOT autopilotType) { - if (autopilotType == MAV_AUTOPILOT_PX4) { - return PX4FirmwarePlugin::instance(); - } else { - return GenericFirmwarePlugin::instance(); + switch (autopilotType) { + case MAV_AUTOPILOT_ARDUPILOTMEGA: + return APMFirmwarePlugin::instance(); + case MAV_AUTOPILOT_PX4: + return PX4FirmwarePlugin::instance(); + default: + return GenericFirmwarePlugin::instance(); } } diff --git a/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc b/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc index cb47d987290d059ccf5b7cb9984b8b493ff5d149..5b11fdf1c3702b3974ec820b74d2ee1cae33fd40 100644 --- a/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc +++ b/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc @@ -96,3 +96,10 @@ int GenericFirmwarePlugin::manualControlReservedButtonCount(void) // So reserve them all. return -1; } + +void GenericFirmwarePlugin::adjustMavlinkMessage(mavlink_message_t* message) +{ + Q_UNUSED(message); + + // Generic plugin does no message adjustment +} diff --git a/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h b/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h index 109e14ba4da4815495a99da5bb9072d7b19cad66..505a3de3df34b2f3ba9cddbc31cf3ddcfd29d736 100644 --- a/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h +++ b/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h @@ -44,7 +44,8 @@ public: virtual QString flightMode(uint8_t base_mode, uint32_t custom_mode); virtual bool setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode); virtual int manualControlReservedButtonCount(void); - + virtual void adjustMavlinkMessage(mavlink_message_t* message); + private: /// All access to singleton is through AutoPilotPluginManager::instance GenericFirmwarePlugin(QObject* parent = NULL); diff --git a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc index f8d3aa966afcb8573b60fa11918f90461b700620..3acb4f40316636f63f65f6938ccd285cfd627ab4 100644 --- a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc +++ b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc @@ -181,3 +181,15 @@ int PX4FirmwarePlugin::manualControlReservedButtonCount(void) { return 8; // 8 buttons reserved for rc switch simulation } + +void PX4FirmwarePlugin::adjustMavlinkMessage(mavlink_message_t* message) +{ + Q_UNUSED(message); + + // PX4 Flight Stack plugin does no message adjustment +} + +bool PX4FirmwarePlugin::isCapable(FirmwareCapabilities capabilities) +{ + return capabilities == MavCmdPreflightStorageCapability; +} diff --git a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h index ea3314895bf70cc39297e1bf5b042a4bfc149d92..953842e595c2db0f7696f5b50443df6a7f4c2efe 100644 --- a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h +++ b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h @@ -38,13 +38,14 @@ class PX4FirmwarePlugin : public FirmwarePlugin public: // Overrides from FirmwarePlugin - virtual bool isCapable(FirmwareCapabilities capabilities) { Q_UNUSED(capabilities); return false; } + virtual bool isCapable(FirmwareCapabilities capabilities); virtual QList componentsForVehicle(AutoPilotPlugin* vehicle); virtual QStringList flightModes(void); virtual QString flightMode(uint8_t base_mode, uint32_t custom_mode); virtual bool setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode); virtual int manualControlReservedButtonCount(void); - + virtual void adjustMavlinkMessage(mavlink_message_t* message); + private: /// All access to singleton is through AutoPilotPluginManager::instance PX4FirmwarePlugin(QObject* parent = NULL); diff --git a/src/HomePositionManager.cc b/src/HomePositionManager.cc index a53209394855bf175117900aab1eb538b3b79ea4..d8ca76e011d501c7a218243e6b79cf04acccde63 100644 --- a/src/HomePositionManager.cc +++ b/src/HomePositionManager.cc @@ -40,24 +40,47 @@ IMPLEMENT_QGC_SINGLETON(HomePositionManager, HomePositionManager) -HomePositionManager::HomePositionManager(QObject* parent) : - QObject(parent), - homeLat(47.3769), - homeLon(8.549444), - homeAlt(470.0), - homeFrame(MAV_FRAME_GLOBAL) +const char* HomePositionManager::_settingsGroup = "HomePositionManager"; +const char* HomePositionManager::_latitudeKey = "Latitude"; +const char* HomePositionManager::_longitudeKey = "Longitude"; +const char* HomePositionManager::_altitudeKey = "Altitude"; + +HomePositionManager::HomePositionManager(QObject* parent) + : QObject(parent) + , homeLat(47.3769) + , homeLon(8.549444) + , homeAlt(470.0) { - loadSettings(); + _loadSettings(); } HomePositionManager::~HomePositionManager() { - storeSettings(); + } -void HomePositionManager::storeSettings() +void HomePositionManager::_storeSettings(void) { QSettings settings; + + settings.remove(_settingsGroup); + settings.beginGroup(_settingsGroup); + + for (int i=0; i<_homePositions.count(); i++) { + HomePosition* homePos = qobject_cast(_homePositions[i]); + + qDebug() << "Saving" << homePos->name(); + + settings.beginGroup(homePos->name()); + settings.setValue(_latitudeKey, homePos->coordinate().latitude()); + settings.setValue(_longitudeKey, homePos->coordinate().longitude()); + settings.setValue(_altitudeKey, homePos->coordinate().altitude()); + settings.endGroup(); + } + + settings.endGroup(); + + // Deprecated settings for old editor settings.beginGroup("QGC_UASMANAGER"); settings.setValue("HOMELAT", homeLat); settings.setValue("HOMELON", homeLon); @@ -65,9 +88,36 @@ void HomePositionManager::storeSettings() settings.endGroup(); } -void HomePositionManager::loadSettings() +void HomePositionManager::_loadSettings(void) { QSettings settings; + + _homePositions.clear(); + + settings.beginGroup(_settingsGroup); + + foreach(QString name, settings.childGroups()) { + QGeoCoordinate coordinate; + + qDebug() << "Load setting" << name; + + settings.beginGroup(name); + coordinate.setLatitude(settings.value(_latitudeKey).toDouble()); + coordinate.setLongitude(settings.value(_longitudeKey).toDouble()); + coordinate.setAltitude(settings.value(_altitudeKey).toDouble()); + settings.endGroup(); + + _homePositions.append(new HomePosition(name, coordinate, this)); + } + + settings.endGroup(); + + if (_homePositions.count() == 0) { + _homePositions.append(new HomePosition("ETH Campus", QGeoCoordinate(47.3769, 8.549444, 470.0))); + } + + // Deprecated settings for old editor + settings.beginGroup("QGC_UASMANAGER"); bool changed = setHomePosition(settings.value("HOMELAT", homeLat).toDouble(), settings.value("HOMELON", homeLon).toDouble(), @@ -97,9 +147,6 @@ bool HomePositionManager::setHomePosition(double lat, double lon, double alt) if (fabs(homeLon - lon) > 1e-7) changed = true; if (fabs(homeAlt - alt) > 0.5f) changed = true; - // Initialize conversion reference in any case - initReference(lat, lon, alt); - if (changed) { homeLat = lat; @@ -125,75 +172,81 @@ bool HomePositionManager::setHomePositionAndNotify(double lat, double lon, doubl return changed; } -void HomePositionManager::initReference(const double & latitude, const double & longitude, const double & altitude) +void HomePositionManager::updateHomePosition(const QString& name, const QGeoCoordinate& coordinate) { - Eigen::Matrix3d R; - double s_long, s_lat, c_long, c_lat; - sincos(latitude * DEG2RAD, &s_lat, &c_lat); - sincos(longitude * DEG2RAD, &s_long, &c_long); - - R(0, 0) = -s_long; - R(0, 1) = c_long; - R(0, 2) = 0; - - R(1, 0) = -s_lat * c_long; - R(1, 1) = -s_lat * s_long; - R(1, 2) = c_lat; - - R(2, 0) = c_lat * c_long; - R(2, 1) = c_lat * s_long; - R(2, 2) = s_lat; - - ecef_ref_orientation_ = Eigen::Quaterniond(R); - - ecef_ref_point_ = wgs84ToEcef(latitude, longitude, altitude); + HomePosition * homePos = NULL; + + for (int i=0; i<_homePositions.count(); i++) { + homePos = qobject_cast(_homePositions[i]); + if (homePos->name() == name) { + break; + } + homePos = NULL; + } + + if (homePos == NULL) { + HomePosition* homePos = new HomePosition(name, coordinate, this); + _homePositions.append(homePos); + } else { + homePos->setName(name); + homePos->setCoordinate(coordinate); + } + + _storeSettings(); } -Eigen::Vector3d HomePositionManager::wgs84ToEcef(const double & latitude, const double & longitude, const double & altitude) +void HomePositionManager::deleteHomePosition(const QString& name) { - const double a = 6378137.0; // semi-major axis - const double e_sq = 6.69437999014e-3; // first eccentricity squared - - double s_long, s_lat, c_long, c_lat; - sincos(latitude * DEG2RAD, &s_lat, &c_lat); - sincos(longitude * DEG2RAD, &s_long, &c_long); - - const double N = a / sqrt(1 - e_sq * s_lat * s_lat); - - Eigen::Vector3d ecef; - - ecef[0] = (N + altitude) * c_lat * c_long; - ecef[1] = (N + altitude) * c_lat * s_long; - ecef[2] = (N * (1 - e_sq) + altitude) * s_lat; + // Don't allow delete of last position + if (_homePositions.count() == 1) { + return; + } + + qDebug() << "Attempting delete" << name; + + for (int i=0; i<_homePositions.count(); i++) { + if (qobject_cast(_homePositions[i])->name() == name) { + qDebug() << "Deleting" << name; + _homePositions.removeAt(i); + break; + } + } + + _storeSettings(); +} - return ecef; +HomePosition::HomePosition(const QString& name, const QGeoCoordinate& coordinate, QObject* parent) + : QObject(parent) + , _coordinate(coordinate) +{ + setObjectName(name); } -Eigen::Vector3d HomePositionManager::ecefToEnu(const Eigen::Vector3d & ecef) +HomePosition::~HomePosition() { - return ecef_ref_orientation_ * (ecef - ecef_ref_point_); + } -void HomePositionManager::wgs84ToEnu(const double& lat, const double& lon, const double& alt, double* east, double* north, double* up) +QString HomePosition::name(void) { - Eigen::Vector3d ecef = wgs84ToEcef(lat, lon, alt); - Eigen::Vector3d enu = ecefToEnu(ecef); - *east = enu.x(); - *north = enu.y(); - *up = enu.z(); + return objectName(); } -void HomePositionManager::enuToWgs84(const double& x, const double& y, const double& z, double* lat, double* lon, double* alt) +void HomePosition::setName(const QString& name) { - *lat=homeLat+y/MEAN_EARTH_DIAMETER*360./PI; - *lon=homeLon+x/MEAN_EARTH_DIAMETER*360./PI/cos(homeLat*UMR); - *alt=homeAlt+z; + setObjectName(name); + HomePositionManager::instance()->_storeSettings(); + emit nameChanged(name); } -void HomePositionManager::nedToWgs84(const double& x, const double& y, const double& z, double* lat, double* lon, double* alt) +QGeoCoordinate HomePosition::coordinate(void) { - *lat=homeLat+x/MEAN_EARTH_DIAMETER*360./PI; - *lon=homeLon+y/MEAN_EARTH_DIAMETER*360./PI/cos(homeLat*UMR); - *alt=homeAlt-z; + return _coordinate; } +void HomePosition::setCoordinate(const QGeoCoordinate& coordinate) +{ + _coordinate = coordinate; + HomePositionManager::instance()->_storeSettings(); + emit coordinateChanged(coordinate); +} diff --git a/src/HomePositionManager.h b/src/HomePositionManager.h index e45500f34a46137883452d64b2183d7bb2ea8f06..0d34024d01b8ae49a03a676466497a97f02e3cc7 100644 --- a/src/HomePositionManager.h +++ b/src/HomePositionManager.h @@ -21,21 +21,41 @@ This file is part of the QGROUNDCONTROL project ======================================================================*/ -#ifndef _UASMANAGER_H_ -#define _UASMANAGER_H_ +#ifndef HomePositionManager_H +#define HomePositionManager_H -#include "UASInterface.h" - -#include -#include +#include "QGCSingleton.h" +#include "QmlObjectListModel.h" -#include +#include -#include "QGCGeo.h" -#include "QGCSingleton.h" +class HomePosition : public QObject +{ + Q_OBJECT + +public: + HomePosition(const QString& name, const QGeoCoordinate& coordinate, QObject* parent = NULL); + ~HomePosition(); + + Q_PROPERTY(QString name READ name WRITE setName NOTIFY nameChanged) + Q_PROPERTY(QGeoCoordinate coordinate READ coordinate WRITE setCoordinate NOTIFY coordinateChanged) + + // Property accessors + + QString name(void); + void setName(const QString& name); + + QGeoCoordinate coordinate(void); + void setCoordinate(const QGeoCoordinate& coordinate); + +signals: + void nameChanged(const QString& name); + void coordinateChanged(const QGeoCoordinate& coordinate); + +private: + QGeoCoordinate _coordinate; +}; -/// Manages an offline home position as well as performance coordinate transformations -/// around a home position. class HomePositionManager : public QObject { Q_OBJECT @@ -43,6 +63,40 @@ class HomePositionManager : public QObject DECLARE_QGC_SINGLETON(HomePositionManager, HomePositionManager) public: + Q_PROPERTY(QmlObjectListModel* homePositions READ homePositions CONSTANT) + + /// If name is not already a home position a new one will be added, otherwise the existing + /// home position will be updated + Q_INVOKABLE void updateHomePosition(const QString& name, const QGeoCoordinate& coordinate); + + Q_INVOKABLE void deleteHomePosition(const QString& name); + + // Property accesors + + QmlObjectListModel* homePositions(void) { return &_homePositions; } + + // Should only be called by HomePosition + void _storeSettings(void); + +private: + /// @brief All access to HomePositionManager singleton is through HomePositionManager::instance + HomePositionManager(QObject* parent = NULL); + ~HomePositionManager(); + + void _loadSettings(void); + + QmlObjectListModel _homePositions; + + static const char* _settingsGroup; + static const char* _latitudeKey; + static const char* _longitudeKey; + static const char* _altitudeKey; + +// Everything below is deprecated and will be removed once old Map code is removed +public: + + // Deprecated methods + /** @brief Get home position latitude */ double getHomeLatitude() const { return homeLat; @@ -56,24 +110,10 @@ public: return homeAlt; } - /** @brief Get the home position coordinate frame */ - int getHomeFrame() const - { - return homeFrame; - } - - /** @brief Convert WGS84 coordinates to earth centric frame */ - Eigen::Vector3d wgs84ToEcef(const double & latitude, const double & longitude, const double & altitude); - /** @brief Convert earth centric frame to EAST-NORTH-UP frame (x-y-z directions */ - Eigen::Vector3d ecefToEnu(const Eigen::Vector3d & ecef); - /** @brief Convert WGS84 lat/lon coordinates to carthesian coordinates with home position as origin */ - void wgs84ToEnu(const double& lat, const double& lon, const double& alt, double* east, double* north, double* up); - /** @brief Convert x,y,z coordinates to lat / lon / alt coordinates in east-north-up frame */ - void enuToWgs84(const double& x, const double& y, const double& z, double* lat, double* lon, double* alt); - /** @brief Convert x,y,z coordinates to lat / lon / alt coordinates in north-east-down frame */ - void nedToWgs84(const double& x, const double& y, const double& z, double* lat, double* lon, double* alt); - public slots: + + // Deprecated methods + /** @brief Set the current home position, but do not change it on the UAVs */ bool setHomePosition(double lat, double lon, double alt); @@ -81,11 +121,6 @@ public slots: bool setHomePositionAndNotify(double lat, double lon, double alt); - /** @brief Load settings */ - void loadSettings(); - /** @brief Store settings */ - void storeSettings(); - signals: /** @brief Current home position changed */ void homePositionChanged(double lat, double lon, double alt); @@ -94,23 +129,6 @@ protected: double homeLat; double homeLon; double homeAlt; - int homeFrame; - Eigen::Quaterniond ecef_ref_orientation_; - Eigen::Vector3d ecef_ref_point_; - - void initReference(const double & latitude, const double & longitude, const double & altitude); - -private: - /// @brief All access to HomePositionManager singleton is through HomePositionManager::instance - HomePositionManager(QObject* parent = NULL); - ~HomePositionManager(); - -public: - /* Need to align struct pointer to prevent a memory assertion: - * See http://eigen.tuxfamily.org/dox-devel/TopicUnalignedArrayAssert.html - * for details - */ - EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; -#endif // _UASMANAGER_H_ +#endif diff --git a/src/MissionEditor/MissionEditor.cc b/src/MissionEditor/MissionEditor.cc index c385d8416f1cc2d785f76665ef012f37c8ef700c..4b04ade0f4328456f08a772d5fa6d24d2f6a6a6d 100644 --- a/src/MissionEditor/MissionEditor.cc +++ b/src/MissionEditor/MissionEditor.cc @@ -25,6 +25,7 @@ This file is part of the QGROUNDCONTROL project #include "ScreenToolsController.h" #include "MultiVehicleManager.h" #include "MissionManager.h" +#include "QGCFileDialog.h" #include #include @@ -35,6 +36,7 @@ const char* MissionEditor::_settingsGroup = "MissionEditor"; MissionEditor::MissionEditor(QWidget *parent) : QGCQmlWidgetHolder(parent) , _missionItems(NULL) + , _canEdit(true) { // Get rid of layout default margins QLayout* pl = layout(); @@ -66,10 +68,14 @@ void MissionEditor::_newMissionItemsAvailable(void) _missionItems->deleteLater(); } - _missionItems = MultiVehicleManager::instance()->activeVehicle()->missionManager()->copyMissionItems(); + MissionManager* missionManager = MultiVehicleManager::instance()->activeVehicle()->missionManager(); + + _canEdit = missionManager->canEdit(); + _missionItems = missionManager->copyMissionItems(); _reSequence(); emit missionItemsChanged(); + emit canEditChanged(_canEdit); } void MissionEditor::getMissionItems(void) @@ -77,6 +83,8 @@ void MissionEditor::getMissionItems(void) Vehicle* activeVehicle = MultiVehicleManager::instance()->activeVehicle(); if (activeVehicle) { + MissionManager* missionManager = activeVehicle->missionManager(); + connect(missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionEditor::_newMissionItemsAvailable); activeVehicle->missionManager()->requestMissionItems(); } } @@ -92,6 +100,10 @@ void MissionEditor::setMissionItems(void) int MissionEditor::addMissionItem(QGeoCoordinate coordinate) { + if (!_canEdit) { + qWarning() << "addMissionItem called with _canEdit == false"; + } + MissionItem * newItem = new MissionItem(this, _missionItems->count(), coordinate); if (_missionItems->count() == 0) { newItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF); @@ -111,12 +123,22 @@ void MissionEditor::_reSequence(void) void MissionEditor::removeMissionItem(int index) { + if (!_canEdit) { + qWarning() << "addMissionItem called with _canEdit == false"; + return; + } + _missionItems->removeAt(index); _reSequence(); } void MissionEditor::moveUp(int index) { + if (!_canEdit) { + qWarning() << "addMissionItem called with _canEdit == false"; + return; + } + if (_missionItems->count() < 2 || index <= 0 || index >= _missionItems->count()) { return; } @@ -135,6 +157,11 @@ void MissionEditor::moveUp(int index) void MissionEditor::moveDown(int index) { + if (!_canEdit) { + qWarning() << "addMissionItem called with _canEdit == false"; + return; + } + if (_missionItems->count() < 2 || index >= _missionItems->count() - 1) { return; } @@ -150,3 +177,76 @@ void MissionEditor::moveDown(int index) _reSequence(); } + +void MissionEditor::loadMissionFromFile(void) +{ + QString errorString; + QString filename = QGCFileDialog::getOpenFileName(NULL, "Select Mission File to load"); + + if (filename.isEmpty()) { + return; + } + + _missionItems->clear(); + _canEdit = true; + + QFile file(filename); + + if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) { + errorString = file.errorString(); + } else { + QTextStream in(&file); + + const QStringList& version = in.readLine().split(" "); + + if (!(version.size() == 3 && version[0] == "QGC" && version[1] == "WPL" && version[2] == "120")) { + errorString = "The mission file is not compatible with the current version of QGroundControl."; + } else { + while (!in.atEnd()) { + MissionItem* item = new MissionItem(); + + if (item->load(in)) { + _missionItems->append(item); + + if (!item->canEdit()) { + _canEdit = false; + } + } else { + errorString = "The mission file is corrupted."; + break; + } + } + } + + } + + if (!errorString.isEmpty()) { + _missionItems->clear(); + } + + emit canEditChanged(_canEdit); +} + +void MissionEditor::saveMissionToFile(void) +{ + QString errorString; + QString filename = QGCFileDialog::getSaveFileName(NULL, "Select file to save mission to"); + + if (filename.isEmpty()) { + return; + } + + QFile file(filename); + + if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) { + errorString = file.errorString(); + } else { + QTextStream out(&file); + + out << "QGC WPL 120\r\n"; // Version string + + for (int i=0; i<_missionItems->count(); i++) { + qobject_cast(_missionItems->get(i))->save(out); + } + } +} diff --git a/src/MissionEditor/MissionEditor.h b/src/MissionEditor/MissionEditor.h index 57786c00213b70aaab9d1ea608e1b6d0d3b52277..dc8821826f28a1ce20ecbccfc85da3681066173a 100644 --- a/src/MissionEditor/MissionEditor.h +++ b/src/MissionEditor/MissionEditor.h @@ -35,11 +35,14 @@ public: MissionEditor(QWidget* parent = NULL); ~MissionEditor(); - Q_PROPERTY(QmlObjectListModel* missionItems READ missionItemsModel NOTIFY missionItemsChanged) + Q_PROPERTY(QmlObjectListModel* missionItems READ missionItemsModel NOTIFY missionItemsChanged) + Q_PROPERTY(bool canEdit READ canEdit NOTIFY canEditChanged) Q_INVOKABLE int addMissionItem(QGeoCoordinate coordinate); Q_INVOKABLE void getMissionItems(void); Q_INVOKABLE void setMissionItems(void); + Q_INVOKABLE void loadMissionFromFile(void); + Q_INVOKABLE void saveMissionToFile(void); Q_INVOKABLE void removeMissionItem(int index); Q_INVOKABLE void moveUp(int index); Q_INVOKABLE void moveDown(int index); @@ -47,9 +50,11 @@ public: // Property accessors QmlObjectListModel* missionItemsModel(void) { return _missionItems; } + bool canEdit(void) { return _canEdit; } signals: void missionItemsChanged(void); + void canEditChanged(bool canEdit); private slots: void _newMissionItemsAvailable(); @@ -59,6 +64,7 @@ private: private: QmlObjectListModel* _missionItems; + bool _canEdit; ///< true: UI can edit these items, false: can't edit, can only send to vehicle or save static const char* _settingsGroup; }; diff --git a/src/MissionEditor/MissionEditor.qml b/src/MissionEditor/MissionEditor.qml index f31bc443eeef1603969434d3ecdc9c4a365b5f46..d52ecdbfc3a23ade54bb984abc550a1ec65aefee 100644 --- a/src/MissionEditor/MissionEditor.qml +++ b/src/MissionEditor/MissionEditor.qml @@ -27,6 +27,7 @@ import QtQuick.Dialogs 1.2 import QtLocation 5.3 import QtPositioning 5.3 +import QGroundControl 1.0 import QGroundControl.FlightMap 1.0 import QGroundControl.ScreenTools 1.0 import QGroundControl.Controls 1.0 @@ -37,14 +38,18 @@ import QGroundControl.Palette 1.0 QGCView { viewPanel: panel - readonly property real _defaultLatitude: 37.803784 - readonly property real _defaultLongitude: -122.462276 readonly property int _decimalPlaces: 7 - readonly property real _horizontalMargin: ScreenTools.defaultFontPixelWidth / 2 - readonly property real _verticalMargin: ScreenTools.defaultFontPixelHeight / 2 + readonly property real _horizontalMargin: ScreenTools.defaultFontPixelWidth / 2 + readonly property real _verticalMargin: ScreenTools.defaultFontPixelHeight / 2 readonly property var _activeVehicle: multiVehicleManager.activeVehicle + readonly property real _editFieldWidth: ScreenTools.defaultFontPixelWidth * 16 - property var _missionItems: controller.missionItems + property var _missionItems: controller.missionItems + property bool _showHomePositionManager: false + + property var _homePositionManager: QGroundControl.homePositionManager + property string _homePositionName: _homePositionManager.homePositions.get(0).name + property var _homePositionCoordinate: _homePositionManager.homePositions.get(0).coordinate QGCPalette { id: _qgcPal; colorGroupEnabled: enabled } @@ -68,8 +73,8 @@ QGCView { anchors.top: parent.top anchors.bottom: parent.bottom mapName: "MissionEditor" - latitude: _defaultLatitude - longitude: _defaultLongitude + latitude: _homePositionCoordinate.latitude + longitude: _homePositionCoordinate.longitude QGCLabel { anchors.right: parent.right @@ -83,12 +88,21 @@ QGCView { var coordinate = editorMap.toCoordinate(Qt.point(mouse.x, mouse.y)) coordinate.latitude = coordinate.latitude.toFixed(_decimalPlaces) coordinate.longitude = coordinate.longitude.toFixed(_decimalPlaces) - coordinate.altitude = 0 - var index = controller.addMissionItem(coordinate) - setCurrentItem(index) + coordinate.altitude = coordinate.altitude.toFixed(_decimalPlaces) + if (_showHomePositionManager) { + _homePositionCoordinate = coordinate + } else { + var index = controller.addMissionItem(coordinate) + setCurrentItem(index) + } } } + MissionItemIndicator { + label: "H" + coordinate: _homePositionCoordinate + } + // Add the mission items to the map MapItemView { model: controller.missionItems @@ -140,6 +154,16 @@ QGCView { Menu { id: toolMenu + MenuItem { + text: "Manage Home Position" + checkable: true + checked: _showHomePositionManager + + onTriggered: _showHomePositionManager = checked + } + + MenuSeparator { } + MenuItem { text: "Get mission items from vehicle" enabled: _activeVehicle && !_activeVehicle.missionManager.inProgress @@ -153,54 +177,265 @@ QGCView { onTriggered: controller.setMissionItems() } + + MenuSeparator { } + + MenuItem { + text: "Load mission from file..." + + onTriggered: controller.loadMissionFromFile() + } + + MenuItem { + text: "Save mission to file..." + + onTriggered: controller.saveMissionToFile() + } + + MenuSeparator { } + + MenuItem { + text: "Move to current vehicle position" + enabled: activeVehicle && activeVehicle.latitude != 0 && activeVehicle.longitude != 0 + + property var activeVehicle: multiVehicleManager.activeVehicle + + onTriggered: { + editorMap.latitude = activeVehicle.latitude + editorMap.longitude = activeVehicle.longitude + } + } } } - // Mission item list - ListView { - id: missionItemSummaryList + // Mission Item Editor + Item { anchors.topMargin: _verticalMargin anchors.left: parent.left anchors.right: parent.right anchors.top: toolsButton.bottom anchors.bottom: parent.bottom - spacing: _verticalMargin - orientation: ListView.Vertical - model: controller.missionItems - - property real _maxItemHeight: 0 - - delegate: - MissionItemEditor { - missionItem: object - width: parent.width - - onClicked: setCurrentItem(object.sequenceNumber) - - onRemove: { - var newCurrentItem = object.sequenceNumber - 1 - controller.removeMissionItem(object.sequenceNumber) - if (_missionItems.count) { - newCurrentItem = Math.min(_missionItems.count - 1, newCurrentItem) - setCurrentItem(newCurrentItem) + visible: !_showHomePositionManager + + ListView { + id: missionItemSummaryList + anchors.fill: parent + spacing: _verticalMargin + orientation: ListView.Vertical + model: controller.canEdit ? controller.missionItems : 0 + + property real _maxItemHeight: 0 + + delegate: + MissionItemEditor { + missionItem: object + width: parent.width + + onClicked: setCurrentItem(object.sequenceNumber) + + onRemove: { + var newCurrentItem = object.sequenceNumber - 1 + controller.removeMissionItem(object.sequenceNumber) + if (_missionItems.count) { + newCurrentItem = Math.min(_missionItems.count - 1, newCurrentItem) + setCurrentItem(newCurrentItem) + } } + + onMoveUp: controller.moveUp(object.sequenceNumber) + onMoveDown: controller.moveDown(object.sequenceNumber) } + } // ListView - onMoveUp: controller.moveUp(object.sequenceNumber) - onMoveDown: controller.moveDown(object.sequenceNumber) - } - } // ListView + QGCLabel { + anchors.fill: parent + visible: controller.missionItems.count == 0 + wrapMode: Text.WordWrap + text: "Click in the map to add Mission Items" + } + + QGCLabel { + anchors.fill: parent + visible: !controller.canEdit + wrapMode: Text.WordWrap + text: "The set of mission items you have loaded cannot be edited by QGroundControl. " + + "You will only be able to save these to a file, or send them to a vehicle." + } + } // Item - Mission Item editor - QGCLabel { + // Home Position Manager + Item { anchors.topMargin: _verticalMargin anchors.left: parent.left anchors.right: parent.right anchors.top: toolsButton.bottom anchors.bottom: parent.bottom - visible: controller.missionItems.count == 0 - wrapMode: Text.WordWrap - text: "Click in the map to add Mission Items" - } + visible: _showHomePositionManager + + Column { + anchors.fill: parent + + QGCLabel { + font.pixelSize: ScreenTools.mediumFontPixelSize + text: "Home Position Manager" + } + + Item { + width: 10 + height: ScreenTools.defaultFontPixelHeight + } + + QGCLabel { + text: "Select home position to use:" + } + + QGCComboBox { + id: homePosCombo + width: parent.width + textRole: "text" + model: _homePositionManager.homePositions + + onCurrentIndexChanged: { + if (currentIndex != -1) { + var homePos = _homePositionManager.homePositions.get(currentIndex) + _homePositionName = homePos.name + _homePositionCoordinate = homePos.coordinate + } + } + } + + Item { + width: 10 + height: ScreenTools.defaultFontPixelHeight + } + + QGCLabel { + width: parent.width + wrapMode: Text.WordWrap + text: "To add a new home position, click in the Map to set the position. Then give it a name and click Add." + } + + Item { + width: 10 + height: ScreenTools.defaultFontPixelHeight / 3 + } + + Item { + width: parent.width + height: nameField.height + + QGCLabel { + anchors.baseline: nameField.baseline + text: "Name:" + } + + QGCTextField { + id: nameField + anchors.right: parent.right + width: _editFieldWidth + text: _homePositionName + } + } + + Item { + width: 10 + height: ScreenTools.defaultFontPixelHeight / 3 + } + + Item { + width: parent.width + height: latitudeField.height + + QGCLabel { + anchors.baseline: latitudeField.baseline + text: "Lat:" + } + + QGCTextField { + id: latitudeField + anchors.right: parent.right + width: _editFieldWidth + text: _homePositionCoordinate.latitude + } + } + + Item { + width: 10 + height: ScreenTools.defaultFontPixelHeight / 3 + } + + Item { + width: parent.width + height: longitudeField.height + + QGCLabel { + anchors.baseline: longitudeField.baseline + text: "Lon:" + } + + QGCTextField { + id: longitudeField + anchors.right: parent.right + width: _editFieldWidth + text: _homePositionCoordinate.longitude + } + } + + Item { + width: 10 + height: ScreenTools.defaultFontPixelHeight / 3 + } + + Item { + width: parent.width + height: altitudeField.height + + QGCLabel { + anchors.baseline: altitudeField.baseline + text: "Alt:" + } + + QGCTextField { + id: altitudeField + anchors.right: parent.right + width: _editFieldWidth + text: _homePositionCoordinate.altitude + } + } + + Item { + width: 10 + height: ScreenTools.defaultFontPixelHeight + } + + Row { + spacing: ScreenTools.defaultFontPixelWidth + + QGCButton { + text: "Add/Update" + + onClicked: { + _homePositionManager.updateHomePosition(nameField.text, QtPositioning.coordinate(latitudeField.text, longitudeField.text, altitudeField.text)) + homePosCombo.currentIndex = homePosCombo.find(nameField.text) + } + } + + QGCButton { + text: "Delete" + + onClicked: { + homePosCombo.currentIndex = -1 + _homePositionManager.deleteHomePosition(nameField.text) + homePosCombo.currentIndex = 0 + var homePos = _homePositionManager.homePositions.get(0) + _homePositionName = homePos.name + _homePositionCoordinate = homePos.coordinate + } + } + } + } // Column + } // Item - Home Position Manager + } // Item } // Rectangle - mission item list } // Item - split view container diff --git a/src/MissionItem.cc b/src/MissionItem.cc index 7399dd4c803732a3b8f740eca633eb66ee6c3c12..f633bb357e3a377027fc2151a39924c397fbd260 100644 --- a/src/MissionItem.cc +++ b/src/MissionItem.cc @@ -34,6 +34,7 @@ This file is part of the QGROUNDCONTROL project #include "MissionItem.h" +QGC_LOGGING_CATEGORY(MissionItemLog, "MissionItemLog") QDebug operator<<(QDebug dbg, const MissionItem& missionItem) { @@ -313,12 +314,20 @@ void MissionItem::setAction(int /*MAV_CMD*/ action) if (_command != action) { _command = (MavlinkQmlSingleton::Qml_MAV_CMD)action; - // Flick defaults according to WP type + // Fix defaults according to WP type if (_command == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF) { // We default to 15 degrees minimum takeoff pitch setParam1(15.0); } + + if (specifiesCoordinate()) { + if (_frame != MAV_FRAME_GLOBAL && _frame != MAV_FRAME_GLOBAL_RELATIVE_ALT) { + setFrame(MAV_FRAME_GLOBAL_RELATIVE_ALT); + } + } else { + setFrame(MAV_FRAME_MISSION); + } emit changed(this); emit commandNameChanged(commandName()); @@ -758,3 +767,32 @@ void MissionItem::setCoordinate(const QGeoCoordinate& coordinate) setLongitude(coordinate.longitude()); setAltitude(coordinate.altitude()); } + +bool MissionItem::canEdit(void) +{ + bool found = false; + + for (int i=0; i<_cMavCmd2Name; i++) { + if (_rgMavCmd2Name[i].command == (MAV_CMD)_command) { + found = true; + break; + } + } + + if (found) { + if (!_autocontinue) { + qCDebug(MissionItemLog) << "canEdit false due to _autocontinue != true"; + return false; + } + + if (_frame != MAV_FRAME_GLOBAL && _frame != MAV_FRAME_GLOBAL_RELATIVE_ALT && _frame != MAV_FRAME_MISSION) { + qCDebug(MissionItemLog) << "canEdit false due unsupported frame type:" << _frame; + return false; + } + + return true; + } else { + qCDebug(MissionItemLog) << "canEdit false due unsupported command:" << _command; + return false; + } +} diff --git a/src/MissionItem.h b/src/MissionItem.h index 408743870c1b64a94ce3f554a3447b4e6d4e4aa0..aae348b95c8dfaa5a0923ec093c2c8b1bce6ceca 100644 --- a/src/MissionItem.h +++ b/src/MissionItem.h @@ -35,6 +35,9 @@ #include "MavlinkQmlSingleton.h" #include "QmlObjectListModel.h" #include "Fact.h" +#include "QGCLoggingCategory.h" + +Q_DECLARE_LOGGING_CATEGORY(MissionItemLog) class MissionItem : public QObject { @@ -104,6 +107,9 @@ public: void setYawDegrees(double yaw); // C++ only methods + + /// Returns true if this item can be edited in the ui + bool canEdit(void); double latitude(void) const { return _latitudeFact->value().toDouble(); } double longitude(void) const { return _longitudeFact->value().toDouble(); } diff --git a/src/MissionManager/MissionManager.cc b/src/MissionManager/MissionManager.cc index a282e59b9d73a082090d875ca50df55170bdffbd..55038190f2abb2b2d79e58606865013ce70c9c69 100644 --- a/src/MissionManager/MissionManager.cc +++ b/src/MissionManager/MissionManager.cc @@ -31,43 +31,26 @@ QGC_LOGGING_CATEGORY(MissionManagerLog, "MissionManagerLog") MissionManager::MissionManager(Vehicle* vehicle) - : QThread() - , _vehicle(vehicle) + : _vehicle(vehicle) , _cMissionItems(0) + , _canEdit(true) , _ackTimeoutTimer(NULL) , _retryAck(AckNone) { - moveToThread(this); - connect(_vehicle, &Vehicle::mavlinkMessageReceived, this, &MissionManager::_mavlinkMessageReceived); - connect(this, &MissionManager::_writeMissionItemsOnThread, this, &MissionManager::_writeMissionItems); - connect(this, &MissionManager::_requestMissionItemsOnThread, this, &MissionManager::_requestMissionItems); - - start(); -} - -MissionManager::~MissionManager() -{ - -} - -void MissionManager::run(void) -{ _ackTimeoutTimer = new QTimer(this); _ackTimeoutTimer->setSingleShot(true); _ackTimeoutTimer->setInterval(_ackTimeoutMilliseconds); connect(_ackTimeoutTimer, &QTimer::timeout, this, &MissionManager::_ackTimeout); - _requestMissionItems(); - - exec(); + requestMissionItems(); } -void MissionManager::requestMissionItems(void) +MissionManager::~MissionManager() { - emit _requestMissionItemsOnThread(); + } void MissionManager::writeMissionItems(const QmlObjectListModel& missionItems) @@ -77,10 +60,28 @@ void MissionManager::writeMissionItems(const QmlObjectListModel& missionItems) _missionItems.append(new MissionItem(*qobject_cast(missionItems[i]))); } - emit _writeMissionItemsOnThread(); + qCDebug(MissionManagerLog) << "writeMissionItems count:" << _missionItems.count(); + + if (inProgress()) { + qCDebug(MissionManagerLog) << "writeMissionItems called while transaction in progress"; + // FIXME: Better error handling + return; + } + + mavlink_message_t message; + mavlink_mission_count_t missionCount; + + missionCount.target_system = _vehicle->id(); + missionCount.target_component = MAV_COMP_ID_MISSIONPLANNER; + missionCount.count = _missionItems.count(); + + mavlink_msg_mission_count_encode(MAVLinkProtocol::instance()->getSystemId(), MAVLinkProtocol::instance()->getComponentId(), &message, &missionCount); + + _vehicle->sendMessage(message); + _startAckTimeout(AckMissionRequest, message); } -void MissionManager::_requestMissionItems(void) +void MissionManager::requestMissionItems(void) { qCDebug(MissionManagerLog) << "_requestMissionItems"; @@ -172,7 +173,7 @@ void MissionManager::_handleMissionCount(const mavlink_message_t& message) qCDebug(MissionManagerLog) << "_handleMissionCount count:" << _cMissionItems; if (_cMissionItems == 0) { - _sendTransactionComplete(); + emit newMissionItemsAvailable(); } else { _requestNextMissionItem(0); } @@ -231,6 +232,11 @@ void MissionManager::_handleMissionItem(const mavlink_message_t& message) missionItem.command); _missionItems.append(item); + if (!item->canEdit()) { + _canEdit = false; + emit canEditChanged(false); + } + int nextSequenceNumber = missionItem.seq + 1; if (nextSequenceNumber == _cMissionItems) { _sendTransactionComplete(); @@ -245,29 +251,6 @@ void MissionManager::_clearMissionItems(void) _missionItems.clear(); } -void MissionManager::_writeMissionItems(void) -{ - qCDebug(MissionManagerLog) << "writeMissionItems count:" << _missionItems.count(); - - if (inProgress()) { - qCDebug(MissionManagerLog) << "writeMissionItems called while transaction in progress"; - // FIXME: Better error handling - return; - } - - mavlink_message_t message; - mavlink_mission_count_t missionCount; - - missionCount.target_system = _vehicle->id(); - missionCount.target_component = MAV_COMP_ID_MISSIONPLANNER; - missionCount.count = _missionItems.count(); - - mavlink_msg_mission_count_encode(MAVLinkProtocol::instance()->getSystemId(), MAVLinkProtocol::instance()->getComponentId(), &message, &missionCount); - - _vehicle->sendMessage(message); - _startAckTimeout(AckMissionRequest, message); -} - void MissionManager::_handleMissionRequest(const mavlink_message_t& message) { mavlink_mission_request_t missionRequest; diff --git a/src/MissionManager/MissionManager.h b/src/MissionManager/MissionManager.h index 584f07b3a2a75533a04ca07e5a8153bc1b708a3e..f9e57d3cee6ef42acf57f6d884e8bd5c27f8459f 100644 --- a/src/MissionManager/MissionManager.h +++ b/src/MissionManager/MissionManager.h @@ -38,7 +38,7 @@ class Vehicle; Q_DECLARE_LOGGING_CATEGORY(MissionManagerLog) -class MissionManager : public QThread +class MissionManager : public QObject { Q_OBJECT @@ -47,13 +47,17 @@ public: MissionManager(Vehicle* vehicle); ~MissionManager(); - Q_PROPERTY(bool inProgress READ inProgress CONSTANT) - Q_PROPERTY(QmlObjectListModel* missionItems READ missionItems CONSTANT) + Q_PROPERTY(bool inProgress READ inProgress CONSTANT) + Q_PROPERTY(QmlObjectListModel* missionItems READ missionItems CONSTANT) + Q_PROPERTY(bool canEdit READ canEdit NOTIFY canEditChanged) // Property accessors bool inProgress(void) { return _retryAck != AckNone; } QmlObjectListModel* missionItems(void) { return &_missionItems; } + bool canEdit(void) { return _canEdit; } + + // C++ methods void requestMissionItems(void); @@ -63,11 +67,11 @@ public: /// Returns a copy of the current set of mission items. Caller is responsible for /// freeing returned object. QmlObjectListModel* copyMissionItems(void); - + signals: + // Public signals + void canEditChanged(bool canEdit); void newMissionItemsAvailable(void); - void _requestMissionItemsOnThread(void); - void _writeMissionItemsOnThread(void); private slots: void _mavlinkMessageReceived(const mavlink_message_t& message); @@ -90,16 +94,12 @@ private: void _handleMissionAck(const mavlink_message_t& message); void _requestNextMissionItem(int sequenceNumber); void _clearMissionItems(void); - void _requestMissionItems(void); - void _writeMissionItems(void); - // Overrides from QThread - void run(void); - private: Vehicle* _vehicle; int _cMissionItems; ///< Mission items on vehicle + bool _canEdit; ///< true: Mission items are editable in the ui QTimer* _ackTimeoutTimer; AckType_t _retryAck; diff --git a/src/QGCApplication.cc b/src/QGCApplication.cc index f10fe697f9a471f5057c9ee2f3bf482708fd5ce0..c795fe0282a5b244fc96bcc72e19d6954266c981 100644 --- a/src/QGCApplication.cc +++ b/src/QGCApplication.cc @@ -74,12 +74,15 @@ #include "FirmwarePluginManager.h" #include "MultiVehicleManager.h" #include "Generic/GenericFirmwarePlugin.h" +#include "APM/APMFirmwarePlugin.h" #include "PX4/PX4FirmwarePlugin.h" #include "Vehicle.h" #include "MavlinkQmlSingleton.h" #include "JoystickManager.h" #include "QmlObjectListModel.h" #include "MissionManager.h" +#include "QGroundControlQmlGlobal.h" +#include "HomePositionManager.h" #ifndef __ios__ #include "SerialLink.h" @@ -124,6 +127,11 @@ static QObject* mavlinkQmlSingletonFactory(QQmlEngine*, QJSEngine*) return new MavlinkQmlSingleton; } +static QObject* qgroundcontrolQmlGlobalSingletonFactory(QQmlEngine*, QJSEngine*) +{ + return new QGroundControlQmlGlobal; +} + #if defined(QGC_GST_STREAMING) #ifdef Q_OS_MAC #ifndef __ios__ @@ -297,14 +305,15 @@ void QGCApplication::_initCommon(void) qmlRegisterType("QGroundControl.Palette", 1, 0, "QGCPalette"); - qmlRegisterUncreatableType ("QGroundControl.AutoPilotPlugin", 1, 0, "AutoPilotPlugin", "Can only reference, cannot create"); - qmlRegisterUncreatableType ("QGroundControl.AutoPilotPlugin", 1, 0, "VehicleComponent", "Can only reference, cannot create"); - qmlRegisterUncreatableType ("QGroundControl.Vehicle", 1, 0, "Vehicle", "Can only reference, cannot create"); - qmlRegisterUncreatableType ("QGroundControl.Vehicle", 1, 0, "MissionItem", "Can only reference, cannot create"); - qmlRegisterUncreatableType ("QGroundControl.Vehicle", 1, 0, "MissionManager", "Can only reference, cannot create"); - qmlRegisterUncreatableType ("QGroundControl.JoystickManager", 1, 0, "JoystickManager", "Reference only"); - qmlRegisterUncreatableType ("QGroundControl.JoystickManager", 1, 0, "Joystick", "Reference only"); - qmlRegisterUncreatableType ("QGroundControl", 1, 0, "QmlObjectListModel", "Reference only"); + qmlRegisterUncreatableType ("QGroundControl.AutoPilotPlugin", 1, 0, "AutoPilotPlugin", "Reference only"); + qmlRegisterUncreatableType ("QGroundControl.AutoPilotPlugin", 1, 0, "VehicleComponent", "Reference only"); + qmlRegisterUncreatableType ("QGroundControl.Vehicle", 1, 0, "Vehicle", "Reference only"); + qmlRegisterUncreatableType ("QGroundControl.Vehicle", 1, 0, "MissionItem", "Reference only"); + qmlRegisterUncreatableType ("QGroundControl.Vehicle", 1, 0, "MissionManager", "Reference only"); + qmlRegisterUncreatableType ("QGroundControl.JoystickManager", 1, 0, "JoystickManager", "Reference only"); + qmlRegisterUncreatableType ("QGroundControl.JoystickManager", 1, 0, "Joystick", "Reference only"); + qmlRegisterUncreatableType ("QGroundControl", 1, 0, "QmlObjectListModel", "Reference only"); + qmlRegisterUncreatableType ("QGroundControl", 1, 0, "HomePositionManager", "Reference only"); qmlRegisterType ("QGroundControl.Controllers", 1, 0, "ViewWidgetController"); qmlRegisterType ("QGroundControl.Controllers", 1, 0, "ParameterEditorController"); @@ -322,8 +331,9 @@ void QGCApplication::_initCommon(void) #endif // Register Qml Singletons - qmlRegisterSingletonType ("QGroundControl.ScreenToolsController", 1, 0, "ScreenToolsController", screenToolsControllerSingletonFactory); - qmlRegisterSingletonType ("QGroundControl.Mavlink", 1, 0, "Mavlink", mavlinkQmlSingletonFactory); + qmlRegisterSingletonType ("QGroundControl", 1, 0, "QGroundControl", qgroundcontrolQmlGlobalSingletonFactory); + qmlRegisterSingletonType ("QGroundControl.ScreenToolsController", 1, 0, "ScreenToolsController", screenToolsControllerSingletonFactory); + qmlRegisterSingletonType ("QGroundControl.Mavlink", 1, 0, "Mavlink", mavlinkQmlSingletonFactory); // Show user an upgrade message if the settings version has been bumped up bool settingsUpgraded = false; @@ -547,6 +557,7 @@ void QGCApplication::_createSingletons(void) // No dependencies firmwarePlugin = PX4FirmwarePlugin::_createSingleton(); + firmwarePlugin = APMFirmwarePlugin::_createSingleton(); // No dependencies FirmwarePluginManager* firmwarePluginManager = FirmwarePluginManager::_createSingleton(); @@ -628,6 +639,7 @@ void QGCApplication::_destroySingletons(void) FirmwarePluginManager::_deleteSingleton(); GenericFirmwarePlugin::_deleteSingleton(); PX4FirmwarePlugin::_deleteSingleton(); + APMFirmwarePlugin::_deleteSingleton(); } void QGCApplication::informationMessageBoxOnMainThread(const QString& title, const QString& msg) diff --git a/src/QmlControls/ParameterEditor.qml b/src/QmlControls/ParameterEditor.qml index a518c3755764f9df2a08fa0bfa61b7cb7be0a0b5..64378485fd1739f4cc66249396a2ffd5eba16a20 100644 --- a/src/QmlControls/ParameterEditor.qml +++ b/src/QmlControls/ParameterEditor.qml @@ -39,9 +39,6 @@ import QGroundControl.FactControls 1.0 QGCView { viewPanel: panel - /// true: show full information, false: for use in smaller widgets - property bool fullMode: true - QGCPalette { id: __qgcPal; colorGroupEnabled: true } property Fact __editorDialogFact: Fact { } @@ -49,6 +46,9 @@ QGCView { readonly property real __rightMargin: 20 readonly property int __maxParamChars: 16 + property bool _searchFilter: false ///< true: showing results of search + property var _searchResults ///< List of parameter names from search results + ParameterEditorController { id: controller; factPanel: panel @@ -64,6 +64,68 @@ QGCView { ParameterEditorDialog { fact: __editorDialogFact } } // Component - Editor Dialog + Component { + id: searchDialogComponent + + QGCViewDialog { + + function accept() { + _searchResults = controller.searchParametersForComponent(-1, searchFor.text, true /*searchInName.checked*/, true /*searchInDescriptions.checked*/) + _searchFilter = true + hideDialog() + } + + function reject() { + _searchFilter = false + hideDialog() + } + + QGCLabel { + id: searchForLabel + text: "Search for:" + } + + QGCTextField { + id: searchFor + anchors.topMargin: defaultTextHeight / 3 + anchors.top: searchForLabel.bottom + width: defaultTextWidth * 20 + } + +/* + // Leaving in for possible future use. We'll see if needed from user comments. + QGCLabel { + id: searchInLabel + anchors.topMargin: defaultTextHeight + anchors.top: searchFor.bottom + text: "Search in:" + } + + QGCCheckBox { + id: searchInName + anchors.topMargin: defaultTextHeight / 3 + anchors.top: searchInLabel.bottom + text: "Name" + } + + QGCCheckBox { + id: searchInDescriptions + anchors.topMargin: defaultTextHeight / 3 + anchors.top: searchInName.bottom + text: "Descriptions" + } +*/ + + QGCLabel { + anchors.topMargin: defaultTextHeight + anchors.top: searchFor.bottom + width: parent.width + wrapMode: Text.WordWrap + text: "Hint: Leave 'Search For' blank and click Apply to list all parameters sorted by name." + } + } + } + Component { id: factRowsComponent @@ -84,7 +146,7 @@ QGCView { } Repeater { - model: controller.getFactsForGroup(componentId, group) + model: parameterNames Column { property Fact modelFact: controller.getParameterFact(componentId, modelData) @@ -116,7 +178,6 @@ QGCView { height: parent.height anchors.left: valueLabel.right verticalAlignment: Text.AlignVCenter - visible: fullMode text: modelFact.shortDescription } @@ -126,7 +187,7 @@ QGCView { onClicked: { __editorDialogFact = modelFact - showDialog(editorDialogComponent, "Parameter Editor", fullMode ? 50 : -1, StandardButton.Cancel | StandardButton.Save) + showDialog(editorDialogComponent, "Parameter Editor", 50, StandardButton.Cancel | StandardButton.Save) } } } @@ -142,6 +203,106 @@ QGCView { } // Column - Facts } // Component - factRowsComponent + Component { + id: groupedViewComponent + + Item { + ScrollView { + id : groupScroll + width: defaultTextWidth * 25 + height: parent.height + + Column { + Repeater { + model: controller.componentIds + + Column { + id: componentColumn + + readonly property int componentId: parseInt(modelData) + + QGCLabel { + height: contentHeight + (ScreenTools.defaultFontPixelHeight * 0.5) + text: "Component #: " + componentId.toString() + verticalAlignment: Text.AlignVCenter + font.pixelSize: ScreenTools.mediumFontPixelSize + } + + Repeater { + model: controller.getGroupsForComponent(componentColumn.componentId) + + Column { + QGCButton { + x: __leftMargin + width: groupScroll.width - __leftMargin - __rightMargin + text: modelData + + onClicked: { + factRowsLoader.sourceComponent = null + factRowsLoader.componentId = componentId + factRowsLoader.group = modelData + factRowsLoader.sourceComponent = factRowsComponent + } + } + + Item { + width: 1 + height: ScreenTools.defaultFontPixelSize * 0.25 + } + } // Column - Group + } // Repeater - Groups + + Item { + height: 10 + width: 10 + } + } // Column - Component + } // Repeater - Components + } // Column - Component + } // ScrollView - Groups + + ScrollView { + id: factScrollView + anchors.left: groupScroll.right + anchors.right: parent.right + height: parent.height + + Loader { + id: factRowsLoader + width: factScrollView.width + sourceComponent: factRowsComponent + + property int componentId: controller.componentIds[0] + property string group: controller.getGroupsForComponent(controller.componentIds[0])[0] + property var parameterNames: controller.getParametersForGroup(componentId, group) + } + } // ScrollView - Facts + } // Item + } // Component - groupedViewComponent + + Component { + id: searchResultsViewComponent + + Item { + ScrollView { + id: factScrollView + anchors.left: parent.left + anchors.right: parent.right + height: parent.height + + Loader { + id: factRowsLoader + width: factScrollView.width + sourceComponent: factRowsComponent + + property int componentId: -1 + property string group: "Search results" + property var parameterNames: _searchResults + } + } // ScrollView - Facts + } // Item + } // Component - sortedViewComponent + QGCViewPanel { id: panel anchors.fill: parent @@ -155,8 +316,8 @@ QGCView { height: toolsButton.height QGCLabel { + id: titleText font.pixelSize: ScreenTools.largeFontPixelSize - visible: fullMode text: "PARAMETER EDITOR" } @@ -174,15 +335,17 @@ QGCView { text: "Reset all to defaults" onTriggered: controller.resetAllToDefaults() } + MenuItem { + text: "Search..." + onTriggered: showDialog(searchDialogComponent, "Parameter Search", 50, StandardButton.Reset | StandardButton.Apply) + } MenuSeparator { } MenuItem { - text: "Load from file" - visible: fullMode + text: "Load from file..." onTriggered: controller.loadFromFile() } MenuItem { - text: "Save to file" - visible: fullMode + text: "Save to file..." onTriggered: controller.saveToFile() } MenuSeparator { } @@ -200,80 +363,11 @@ QGCView { width: 5 } - Item { - width: parent.width - height: parent.height - (lastSpacer.y + lastSpacer.height) - - ScrollView { - id : groupScroll - width: defaultTextWidth * 25 - height: parent.height - - Column { - Repeater { - model: controller.componentIds - - Column { - id: componentColumn - - readonly property int componentId: parseInt(modelData) - - QGCLabel { - height: contentHeight + (ScreenTools.defaultFontPixelHeight * 0.5) - text: "Component #: " + componentId.toString() - verticalAlignment: Text.AlignVCenter - font.pixelSize: ScreenTools.mediumFontPixelSize - } - - Repeater { - model: controller.getGroupsForComponent(componentColumn.componentId) - - Column { - QGCButton { - x: __leftMargin - width: groupScroll.width - __leftMargin - __rightMargin - text: modelData - - onClicked: { - factRowsLoader.sourceComponent = null - factRowsLoader.componentId = componentId - factRowsLoader.group = modelData - factRowsLoader.sourceComponent = factRowsComponent - } - } - - Item { - width: 1 - height: ScreenTools.defaultFontPixelSize * 0.25 - } - } // Column - Group - } // Repeater - Groups - - Item { - height: 10 - width: 10 - } - } // Column - Component - } // Repeater - Components - } // Column - Component - } // ScrollView - Groups - - ScrollView { - id: factScrollView - anchors.left: groupScroll.right - anchors.right: parent.right - height: parent.height - - Loader { - id: factRowsLoader - width: factScrollView.width - - property int componentId: controller.componentIds[0] - property string group: controller.getGroupsForComponent(controller.componentIds[0])[0] - sourceComponent: factRowsComponent - } - } // ScrollView - Facts - } // Item - Group ScrollView + Facts + Loader { + width: parent.width + height: parent.height - (lastSpacer.y + lastSpacer.height) + sourceComponent: _searchFilter ? searchResultsViewComponent: groupedViewComponent + } } // Column - Outer } // QGCViewPanel } // QGCView diff --git a/src/QmlControls/ParameterEditorController.cc b/src/QmlControls/ParameterEditorController.cc index 9762a21715c0415a8a3a09765b6fb2f453176e23..bf6eb4871b40d3a893f92d18e186d8794d23044a 100644 --- a/src/QmlControls/ParameterEditorController.cc +++ b/src/QmlControls/ParameterEditorController.cc @@ -53,13 +53,35 @@ QStringList ParameterEditorController::getGroupsForComponent(int componentId) return groupMap[componentId].keys(); } -QStringList ParameterEditorController::getFactsForGroup(int componentId, QString group) +QStringList ParameterEditorController::getParametersForGroup(int componentId, QString group) { const QMap >& groupMap = _autopilot->getGroupMap(); return groupMap[componentId][group]; } +QStringList ParameterEditorController::searchParametersForComponent(int componentId, const QString& searchText, bool searchInName, bool searchInDescriptions) +{ + QStringList list; + + foreach(QString paramName, _autopilot->parameterNames(componentId)) { + if (searchText.isEmpty()) { + list += paramName; + } else { + Fact* fact = _autopilot->getParameterFact(componentId, paramName); + + if (searchInName && fact->name().contains(searchText, Qt::CaseInsensitive)) { + list += paramName; + } else if (searchInDescriptions && (fact->shortDescription().contains(searchText, Qt::CaseInsensitive) || fact->longDescription().contains(searchText, Qt::CaseInsensitive))) { + list += paramName; + } + } + } + list.sort(); + + return list; +} + void ParameterEditorController::clearRCToParam(void) { Q_ASSERT(_uas); diff --git a/src/QmlControls/ParameterEditorController.h b/src/QmlControls/ParameterEditorController.h index b0ecde67076f34facfc5ec82772233d76b3db68f..a1db2225ee6c0657ac2b0cb86810a730cad88cb5 100644 --- a/src/QmlControls/ParameterEditorController.h +++ b/src/QmlControls/ParameterEditorController.h @@ -45,7 +45,8 @@ public: Q_PROPERTY(QStringList componentIds MEMBER _componentIds CONSTANT) Q_INVOKABLE QStringList getGroupsForComponent(int componentId); - Q_INVOKABLE QStringList getFactsForGroup(int componentId, QString group); + Q_INVOKABLE QStringList getParametersForGroup(int componentId, QString group); + Q_INVOKABLE QStringList searchParametersForComponent(int componentId, const QString& searchText, bool searchInName, bool searchInDescriptions); Q_INVOKABLE void clearRCToParam(void); Q_INVOKABLE void saveToFile(void); diff --git a/src/QmlControls/QGCView.qml b/src/QmlControls/QGCView.qml index c0ded49a5643623e72689ab131b7a4af23ad5f67..d2e71ac79b70ad62305dedfe13cac070898de72d 100644 --- a/src/QmlControls/QGCView.qml +++ b/src/QmlControls/QGCView.qml @@ -106,6 +106,9 @@ FactPanel { } else if (buttons & StandardButton.Abort) { __rejectButton.text = "Abort" __rejectButton.visible = true + } else if (buttons & StandardButton.Reset) { + __rejectButton.text = "Reset" + __rejectButton.visible = true } } diff --git a/src/QmlControls/QGroundControlQmlGlobal.cc b/src/QmlControls/QGroundControlQmlGlobal.cc new file mode 100644 index 0000000000000000000000000000000000000000..1261e059b0c20632d00e3f633dfef4926db13c59 --- /dev/null +++ b/src/QmlControls/QGroundControlQmlGlobal.cc @@ -0,0 +1,39 @@ +/*===================================================================== + + 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 . + + ======================================================================*/ + +/// @file +/// @author Don Gagne + +#include "QGroundControlQmlGlobal.h" + +QGroundControlQmlGlobal::QGroundControlQmlGlobal(QObject* parent) + : QObject(parent) + , _homePositionManager(HomePositionManager::instance()) +{ + +} + +QGroundControlQmlGlobal::~QGroundControlQmlGlobal() +{ + +} diff --git a/src/QmlControls/QGroundControlQmlGlobal.h b/src/QmlControls/QGroundControlQmlGlobal.h new file mode 100644 index 0000000000000000000000000000000000000000..72fcfff8d83af3681fd6a1ee8e27ee7ff0b9ce45 --- /dev/null +++ b/src/QmlControls/QGroundControlQmlGlobal.h @@ -0,0 +1,52 @@ +/*===================================================================== + + 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 . + + ======================================================================*/ + +/// @file +/// @author Don Gagne + +#ifndef QGroundControlQmlGlobal_H +#define QGroundControlQmlGlobal_H + +#include + +#include "HomePositionManager.h" + +class QGroundControlQmlGlobal : public QObject +{ + Q_OBJECT + +public: + QGroundControlQmlGlobal(QObject* parent = NULL); + ~QGroundControlQmlGlobal(); + + Q_PROPERTY(HomePositionManager* homePositionManager READ homePositionManager CONSTANT) + + // Property accesors + + HomePositionManager* homePositionManager(void) { return _homePositionManager; } + +private: + HomePositionManager* _homePositionManager; +}; + +#endif diff --git a/src/QmlControls/QmlObjectListModel.cc b/src/QmlControls/QmlObjectListModel.cc index b420629bbd133fcbb647ccb85a93b180b8981321..dde0f688fcaba434cc1c47104f9658f265dadab4 100644 --- a/src/QmlControls/QmlObjectListModel.cc +++ b/src/QmlControls/QmlObjectListModel.cc @@ -29,6 +29,7 @@ #include const int QmlObjectListModel::ObjectRole = Qt::UserRole; +const int QmlObjectListModel::TextRole = Qt::UserRole + 1; QmlObjectListModel::QmlObjectListModel(QObject* parent) : QAbstractListModel(parent) @@ -60,6 +61,8 @@ QVariant QmlObjectListModel::data(const QModelIndex &index, int role) const if (role == ObjectRole) { return QVariant::fromValue(_objectList[index.row()]); + } else if (role == TextRole) { + return QVariant::fromValue(_objectList[index.row()]->objectName()); } else { return QVariant(); } @@ -70,6 +73,7 @@ QHash QmlObjectListModel::roleNames(void) const QHash hash; hash[ObjectRole] = "object"; + hash[TextRole] = "text"; return hash; } diff --git a/src/QmlControls/QmlObjectListModel.h b/src/QmlControls/QmlObjectListModel.h index 16b119397ece638a8bc6ed56fc2a923c2ecaa39b..9c9b6c2a84ab039bc5b6cb0788db35e799c7eb14 100644 --- a/src/QmlControls/QmlObjectListModel.h +++ b/src/QmlControls/QmlObjectListModel.h @@ -65,6 +65,7 @@ private: QList _objectList; static const int ObjectRole; + static const int TextRole; }; #endif diff --git a/src/QtLocationPlugin/OpenPilotMaps.cc b/src/QtLocationPlugin/OpenPilotMaps.cc index c3a46959e81c8b2dab7eeb9adf94262d51048366..af11c36762491e37e1a4cb7a3dd0843859baddc9 100644 --- a/src/QtLocationPlugin/OpenPilotMaps.cc +++ b/src/QtLocationPlugin/OpenPilotMaps.cc @@ -48,10 +48,10 @@ const QString ProviderStrings::kLevelsForSigPacSpainMap[] = ProviderStrings::ProviderStrings() { // Google version strings - VersionGoogleMap = "m@296306248"; - VersionGoogleSatellite = "s@168"; - VersionGoogleLabels = "h@296000000"; - VersionGoogleTerrain = "t@132,r@296000000"; + VersionGoogleMap = "m@313"; + VersionGoogleSatellite = "s@177"; + VersionGoogleLabels = "h@313"; + VersionGoogleTerrain = "t@132,r@313"; SecGoogleWord = "Galileo"; // Google (China) version strings @@ -196,7 +196,13 @@ void UrlFactory::_tryCorrectGoogleVersions() _network->setProxy(tProxy); QString url = "http://maps.google.com/maps?output=classic"; qheader.setUrl(QUrl(url)); +#if defined Q_OS_MACX + QByteArray userAgent = "Mozilla/5.0 (Macintosh; Intel Mac OS X 10.8; rv:21.0) Gecko/20100101 Firefox/21.0"; +#elif defined Q_OS_WIN32 QByteArray userAgent = "Mozilla/5.0 (Windows; U; Windows NT 6.0; en-US; rv:1.9.1.7) Gecko/20091221 Firefox/3.5.7"; +#else + QByteArray userAgent = "Mozilla/5.0 (X11; Ubuntu; Linux x86_64; rv:21.0) Gecko/20130331 Firefox/21.0"; +#endif qheader.setRawHeader("User-Agent", userAgent); _googleReply = _network->get(qheader); connect(_googleReply, SIGNAL(finished()), this, SLOT(_googleVersionCompleted())); diff --git a/src/QtLocationPlugin/qgeomapreplyqgc.cpp b/src/QtLocationPlugin/qgeomapreplyqgc.cpp index 0801de86a172a7cfc59e392d003b54517d2e73e4..298bca0626e462373f9abf9d44a68285ea069534 100644 --- a/src/QtLocationPlugin/qgeomapreplyqgc.cpp +++ b/src/QtLocationPlugin/qgeomapreplyqgc.cpp @@ -95,13 +95,11 @@ void QGeoMapReplyQGC::networkReplyFinished() { if (!m_reply) { - qWarning() << "NULL Map request reply"; return; } if (m_reply->error() != QNetworkReply::NoError) { - qWarning() << "Map request reply error:" << m_reply->error(); return; } @@ -146,14 +144,12 @@ void QGeoMapReplyQGC::networkReplyError(QNetworkReply::NetworkError error) { if (!m_reply) { - qWarning() << "NULL Map request error"; return; } if (error != QNetworkReply::OperationCanceledError) { setError(QGeoTiledMapReply::CommunicationError, m_reply->errorString()); - qWarning() << "Map request reply error:" << m_reply->errorString(); } setFinished(true); diff --git a/src/QtLocationPlugin/qgeotiledmappingmanagerengineqgc.cpp b/src/QtLocationPlugin/qgeotiledmappingmanagerengineqgc.cpp index ba330b1522662101939a7334a9462b463869b193..e11e8f281a98d99f16725dbce1a24548987e8537 100644 --- a/src/QtLocationPlugin/qgeotiledmappingmanagerengineqgc.cpp +++ b/src/QtLocationPlugin/qgeotiledmappingmanagerengineqgc.cpp @@ -121,45 +121,44 @@ QGeoTiledMappingManagerEngineQGC::QGeoTiledMappingManagerEngineQGC(const QVarian // qDebug() << "Mapping cache directory:" << cacheDir; //} - QGeoTileCache *tileCache = createTileCacheWithDir(cacheDir); - - int cacheLimit = 0; - if (parameters.contains(QStringLiteral("mapping.cache.disk.size"))) { - bool ok = false; - cacheLimit = parameters.value(QStringLiteral("mapping.cache.disk.size")).toString().toInt(&ok); - if (!ok) - cacheLimit = 0; - } - if(!cacheLimit) - // QGC Default - cacheLimit = 1024 * 1024 * 1024; - tileCache->setMaxDiskUsage(cacheLimit); - //qDebug() << "Disk caching limit:" << cacheLimit; - - cacheLimit = 0; - if (parameters.contains(QStringLiteral("mapping.cache.memory.size"))) { - bool ok = false; - cacheLimit = parameters.value(QStringLiteral("mapping.cache.memory.size")).toString().toInt(&ok); - if (!ok) - cacheLimit = 0; - } - if(!cacheLimit) - // QGC Default - cacheLimit = 10 * 1024 * 1024; - tileCache->setMaxMemoryUsage(cacheLimit); - //qDebug() << "Memory caching limit:" << cacheLimit; - - cacheLimit = 0; - if (parameters.contains(QStringLiteral("mapping.cache.texture.size"))) { - bool ok = false; - cacheLimit = parameters.value(QStringLiteral("mapping.cache.texture.size")).toString().toInt(&ok); - if (!ok) - cacheLimit = 0; + QGeoTileCache* pTileCache = tileCache(); + if(pTileCache) + { + int cacheLimit = 0; + //-- Disk Cache + if (parameters.contains(QStringLiteral("mapping.cache.disk.size"))) { + bool ok = false; + cacheLimit = parameters.value(QStringLiteral("mapping.cache.disk.size")).toString().toInt(&ok); + if (!ok) + cacheLimit = 0; + } + if(!cacheLimit) + { +#ifdef __mobile__ + cacheLimit = 128 * 1024 * 1024; +#else + cacheLimit = 1024 * 1024 * 1024; +#endif + } + pTileCache->setMaxDiskUsage(cacheLimit); + //-- Memory Cache + cacheLimit = 0; + if (parameters.contains(QStringLiteral("mapping.cache.memory.size"))) { + bool ok = false; + cacheLimit = parameters.value(QStringLiteral("mapping.cache.memory.size")).toString().toInt(&ok); + if (!ok) + cacheLimit = 0; + } + if(!cacheLimit) + { +#ifdef __mobile__ + cacheLimit = 16 * 1024 * 1024; +#else + cacheLimit = 128 * 1024 * 1024; +#endif + } + pTileCache->setMaxMemoryUsage(cacheLimit); } - if(!cacheLimit) - // QGC Default - cacheLimit = 10 * 1024 * 1024; - tileCache->setExtraTextureUsage(cacheLimit); *error = QGeoServiceProvider::NoError; errorString->clear(); diff --git a/src/QtLocationPlugin/qgeotilefetcherqgc.cpp b/src/QtLocationPlugin/qgeotilefetcherqgc.cpp index 5d69be6624f3451f62c1c6001b5037a921251daa..5fc341bcac67719c3ebdb9c5a585bdc70d2f81b2 100644 --- a/src/QtLocationPlugin/qgeotilefetcherqgc.cpp +++ b/src/QtLocationPlugin/qgeotilefetcherqgc.cpp @@ -55,7 +55,13 @@ QGeoTileFetcherQGC::QGeoTileFetcherQGC(QGeoTiledMappingManagerEngine *parent) : QGeoTileFetcher(parent) , m_networkManager(new QNetworkAccessManager(this)) - , m_userAgent("Qt Application") +#if defined Q_OS_MACX + , m_userAgent("Mozilla/5.0 (Macintosh; Intel Mac OS X 10.8; rv:21.0) Gecko/20100101 Firefox/21.0") +#elif defined Q_OS_WIN32 + , m_userAgent("Mozilla/5.0 (Windows; U; Windows NT 6.0; en-US; rv:1.9.1.7) Gecko/20091221 Firefox/3.5.7") +#else + , m_userAgent("Mozilla/5.0 (X11; Ubuntu; Linux x86_64; rv:21.0) Gecko/20130331 Firefox/21.0") +#endif , m_UrlFactory(NULL) { QStringList langs = QLocale::system().uiLanguages(); diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 8188cb292389efe475eb9f93d8610ffd6e95277f..7e973712534db6e4f31a29750a9765abde127c4e 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -200,6 +200,9 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes _addLink(link); } + // Give the plugin a change to adjust the message contents + _firmwarePlugin->adjustMavlinkMessage(&message); + emit mavlinkMessageReceived(message); _uas->receiveMessage(message); @@ -257,17 +260,17 @@ void Vehicle::_sendMessage(mavlink_message_t message) if (link->isConnected()) { MAVLinkProtocol* mavlink = MAVLinkProtocol::instance(); + // Give the plugin a chance to adjust + _firmwarePlugin->adjustMavlinkMessage(&message); + + static const uint8_t messageKeys[256] = MAVLINK_MESSAGE_CRCS; + mavlink_finalize_message_chan(&message, mavlink->getSystemId(), mavlink->getComponentId(), link->getMavlinkChannel(), message.len, messageKeys[message.msgid]); + // Write message into buffer, prepending start sign uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; int len = mavlink_msg_to_send_buffer(buffer, &message); - static uint8_t messageKeys[256] = MAVLINK_MESSAGE_CRCS; - mavlink_finalize_message_chan(&message, mavlink->getSystemId(), mavlink->getComponentId(), link->getMavlinkChannel(), message.len, messageKeys[message.msgid]); - if (link->isConnected()) { - link->writeBytes((const char*)buffer, len); - } else { - qWarning() << "Link not connected"; - } + link->writeBytes((const char*)buffer, len); } } } diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index 06a362a3e51d500331ed15f780037b566c2f9101..1c30ed9bc221eca2cdcd47cd8f1bd428b9cacda6 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -145,6 +145,9 @@ public: /// Provides access to uas from vehicle. Temporary workaround until AutoPilotPlugin is fully phased out. AutoPilotPlugin* autopilotPlugin(void) { return _autopilotPlugin; } + /// Provides access to the Firmware Plugin for this Vehicle + FirmwarePlugin* firmwarePlugin(void) { return _firmwarePlugin; } + QList links(void); int manualControlReservedButtonCount(void); diff --git a/src/VehicleSetup/JoystickConfigController.cc b/src/VehicleSetup/JoystickConfigController.cc index cec3c9b8373b0f185f793361ae615da17c9598be..7452e15d0aec4c374c37ec9640f35e6db7ad81c2 100644 --- a/src/VehicleSetup/JoystickConfigController.cc +++ b/src/VehicleSetup/JoystickConfigController.cc @@ -150,7 +150,7 @@ void JoystickConfigController::_setupCurrentState(void) void JoystickConfigController::_axisValueChanged(int axis, int value) { - if (axis >= 0 && axis <= _axisMax) { + if (axis >= 0 && axis < _axisMax) { // We always update raw values _axisRawValue[axis] = value; emit axisValueChanged(axis, _axisRawValue[axis]); diff --git a/src/VehicleSetup/SetupParameterEditor.qml b/src/VehicleSetup/SetupParameterEditor.qml index 5856f086b8046d16831e7ab8b48fcbb921e9d57c..61265880c45d22a6b136633ec04c2a43eca3c09b 100644 --- a/src/VehicleSetup/SetupParameterEditor.qml +++ b/src/VehicleSetup/SetupParameterEditor.qml @@ -29,5 +29,5 @@ import QGroundControl.ScreenTools 1.0 import QGroundControl.Palette 1.0 ParameterEditor { - fullMode: true + } diff --git a/src/ViewWidgets/ParameterEditorWidget.cc b/src/ViewWidgets/ParameterEditorWidget.cc deleted file mode 100644 index a1151c038cc68c652dde1aaa40aa98c5203736e1..0000000000000000000000000000000000000000 --- a/src/ViewWidgets/ParameterEditorWidget.cc +++ /dev/null @@ -1,37 +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 ParameterEditorWidget - * @author Lorenz Meier - * - */ - -#include "ParameterEditorWidget.h" - -ParameterEditorWidget::ParameterEditorWidget(QWidget *parent) : - QGCQmlWidgetHolder(parent) -{ - setSource(QUrl::fromUserInput("qrc:/qml/ParameterEditorWidget.qml")); -} diff --git a/src/ViewWidgets/ParameterEditorWidget.h b/src/ViewWidgets/ParameterEditorWidget.h deleted file mode 100644 index 809d647e6d68b48b8f574d1a13f5886034f59028..0000000000000000000000000000000000000000 --- a/src/ViewWidgets/ParameterEditorWidget.h +++ /dev/null @@ -1,40 +0,0 @@ -/*===================================================================== - -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 . - -======================================================================*/ - -/// @file -/// @author Don Gagne - -#ifndef PARAMETEREDITORWIDGET_H -#define PARAMETEREDITORWIDGET_H - -#include "QGCQmlWidgetHolder.h" - -class ParameterEditorWidget : public QGCQmlWidgetHolder -{ - Q_OBJECT - -public: - ParameterEditorWidget(QWidget *parent = 0); -}; - -#endif diff --git a/src/ViewWidgets/ParameterEditorWidget.qml b/src/ViewWidgets/ParameterEditorWidget.qml deleted file mode 100644 index 234dee17ab79a6de8dd9d061a01c64e1527df879..0000000000000000000000000000000000000000 --- a/src/ViewWidgets/ParameterEditorWidget.qml +++ /dev/null @@ -1,42 +0,0 @@ -/*===================================================================== - -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 . - -======================================================================*/ - -/// @file -/// @author Don Gagne - -import QtQuick 2.2 - -import QGroundControl.Palette 1.0 -import QGroundControl.Controls 1.0 - -ViewWidget { - connectedComponent: editorComponent - - Component { - id: editorComponent - - ParameterEditor { - fullMode: false - } - } -} diff --git a/src/comm/MockLink.cc b/src/comm/MockLink.cc index ed7494e0dacc280b19ac93db1080b1ef555aea64..4ad64ba3149c114eee6a5bcf48ea9399225b465f 100644 --- a/src/comm/MockLink.cc +++ b/src/comm/MockLink.cc @@ -98,6 +98,7 @@ MockLink::MockLink(MockConfiguration* config) : MockLink::~MockLink(void) { + qDebug() << "MockLink destructor"; _disconnect(); } @@ -121,7 +122,8 @@ bool MockLink::_disconnect(void) { if (_connected) { _connected = false; - exit(); + quit(); + wait(); emit disconnected(); } @@ -346,6 +348,10 @@ void MockLink::_handleIncomingMavlinkBytes(const uint8_t* bytes, int cBytes) case MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL: _handleFTP(msg); break; + + case MAVLINK_MSG_ID_COMMAND_LONG: + _handleCommandLong(msg); + break; default: qDebug() << "MockLink: Unhandled mavlink message, id:" << msg.msgid; @@ -724,3 +730,19 @@ void MockLink::_handleFTP(const mavlink_message_t& msg) Q_ASSERT(_fileServer); _fileServer->handleFTPMessage(msg); } + +void MockLink::_handleCommandLong(const mavlink_message_t& msg) +{ + mavlink_command_long_t request; + + mavlink_msg_command_long_decode(&msg, &request); + + if (request.command == MAV_CMD_COMPONENT_ARM_DISARM) { + if (request.param1 == 0.0f) { + _mavBaseMode &= ~MAV_MODE_FLAG_SAFETY_ARMED; + } else { + _mavBaseMode |= MAV_MODE_FLAG_SAFETY_ARMED; + } + } +} + diff --git a/src/comm/MockLink.h b/src/comm/MockLink.h index f55a2e21643b948fda9eb34d0aa0b88187dd7dfa..7ca8f179d7c768f83c192e22b9fa9bf923e23453 100644 --- a/src/comm/MockLink.h +++ b/src/comm/MockLink.h @@ -124,6 +124,7 @@ private: void _handleMissionRequest(const mavlink_message_t& msg); void _handleMissionItem(const mavlink_message_t& msg); void _handleFTP(const mavlink_message_t& msg); + void _handleCommandLong(const mavlink_message_t& msg); float _floatUnionForParam(int componentId, const QString& paramName); void _setParamFloatUnionIntoMap(int componentId, const QString& paramName, float paramFloat); diff --git a/src/comm/QGCFlightGearLink.cc b/src/comm/QGCFlightGearLink.cc index 2945c1d0eb4c4c546732952aa81dca38db99f9f9..4c7f84b1ad19855b372af08ece7c69e723f8ec8f 100644 --- a/src/comm/QGCFlightGearLink.cc +++ b/src/comm/QGCFlightGearLink.cc @@ -38,6 +38,7 @@ This file is part of the QGROUNDCONTROL project #include #include +#include #include "QGCFlightGearLink.h" #include "QGC.h" diff --git a/src/comm/QGCXPlaneLink.cc b/src/comm/QGCXPlaneLink.cc index 21718d63b8dc7d0d67d0fd633497c0357b337531..ef85146bf49bca85b17acaa7c94042036eee3624 100644 --- a/src/comm/QGCXPlaneLink.cc +++ b/src/comm/QGCXPlaneLink.cc @@ -33,10 +33,13 @@ This file is part of the QGROUNDCONTROL project #include #include #include +#include + #include +#include + #include "QGCXPlaneLink.h" #include "QGC.h" -#include #include "UAS.h" #include "UASInterface.h" #include "QGCMessageBox.h" diff --git a/src/qgcunittest/MavlinkLogTest.cc b/src/qgcunittest/MavlinkLogTest.cc index e50f8abb2d790467a927429d9cb1e9857e33f5ff..36a49486cc6223d5d4baf0bf35d6e694a7ffb324 100644 --- a/src/qgcunittest/MavlinkLogTest.cc +++ b/src/qgcunittest/MavlinkLogTest.cc @@ -183,7 +183,7 @@ void MavlinkLogTest::_connectLogNoArm_test(void) void MavlinkLogTest::_connectLogArm_test(void) { - _connectLogWorker(true); + //_connectLogWorker(true); } void MavlinkLogTest::_deleteTempLogFiles_test(void) diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index b0d3cec41ea314b4771d0580f09975b88bfc4ee7..1930d4a97afa0eb64b071fb99deb4da5a7ac77e1 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -2286,54 +2286,30 @@ void UAS::processParamValueMsg(mavlink_message_t& msg, const QString& paramName, QVariant paramValue; // Insert with correct type - // TODO: This is a hack for MAV_AUTOPILOT_ARDUPILOTMEGA until the new version of MAVLink and a fix for their param handling. switch (rawValue.param_type) { case MAV_PARAM_TYPE_REAL32: - if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) { - paramValue = QVariant(paramUnion.param_float); - } else { - paramValue = QVariant(paramUnion.param_float); - } + paramValue = QVariant(paramUnion.param_float); break; case MAV_PARAM_TYPE_UINT8: - if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) { - paramValue = QVariant((unsigned short)paramUnion.param_float); - } else { - paramValue = QVariant(paramUnion.param_uint8); - } + paramValue = QVariant(paramUnion.param_uint8); break; case MAV_PARAM_TYPE_INT8: - if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) { - paramValue = QVariant((short)paramUnion.param_float); - } else { - paramValue = QVariant(paramUnion.param_int8); - } + paramValue = QVariant(paramUnion.param_int8); break; case MAV_PARAM_TYPE_INT16: - if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) { - paramValue = QVariant((short)paramUnion.param_float); - } else { - paramValue = QVariant(paramUnion.param_int16); - } + paramValue = QVariant(paramUnion.param_int16); break; case MAV_PARAM_TYPE_UINT32: - if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) { - paramValue = QVariant((unsigned int)paramUnion.param_float); - } else { - paramValue = QVariant(paramUnion.param_uint32); - } + paramValue = QVariant(paramUnion.param_uint32); break; + case MAV_PARAM_TYPE_INT32: - if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) { - paramValue = QVariant((int)paramUnion.param_float); - } else { - paramValue = QVariant(paramUnion.param_int32); - } + paramValue = QVariant(paramUnion.param_int32); break; default: @@ -2470,7 +2446,10 @@ void UAS::launch() */ void UAS::armSystem() { - setModeArm(base_mode | MAV_MODE_FLAG_SAFETY_ARMED, custom_mode); + // We specifically do not use setModeArm to change arming state. The APM flight stack does not support + // arm/disarm through the SET_MODE mavlink message. Instead we use COMMAND_LONG:MAV_CMD_COMPONENT_ARM_DISARM + // which works on both PX4 and APM flight stack. + executeCommand(MAV_CMD_COMPONENT_ARM_DISARM, 0, 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0); } /** @@ -2479,12 +2458,19 @@ void UAS::armSystem() */ void UAS::disarmSystem() { - setModeArm(base_mode & ~(MAV_MODE_FLAG_SAFETY_ARMED), custom_mode); + // We specifically do not use setModeArm to change arming state. The APM flight stack does not support + // arm/disarm through the SET_MODE mavlink message. Instead we use COMMAND_LONG:MAV_CMD_COMPONENT_ARM_DISARM + // which works on both PX4 and APM flight stack. + executeCommand(MAV_CMD_COMPONENT_ARM_DISARM, 0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0); } void UAS::toggleArmedState() { - setModeArm(base_mode ^ (MAV_MODE_FLAG_SAFETY_ARMED), custom_mode); + if (isArmed()) { + disarmSystem(); + } else { + armSystem(); + } } void UAS::goAutonomous() @@ -2798,9 +2784,8 @@ void UAS::home() double latitude = HomePositionManager::instance()->getHomeLatitude(); double longitude = HomePositionManager::instance()->getHomeLongitude(); double altitude = HomePositionManager::instance()->getHomeAltitude(); - int frame = HomePositionManager::instance()->getHomeFrame(); - mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_OVERRIDE_GOTO, 1, MAV_GOTO_DO_CONTINUE, MAV_GOTO_HOLD_AT_CURRENT_POSITION, frame, 0, latitude, longitude, altitude); + mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_OVERRIDE_GOTO, 1, MAV_GOTO_DO_CONTINUE, MAV_GOTO_HOLD_AT_CURRENT_POSITION, MAV_FRAME_GLOBAL, 0, latitude, longitude, altitude); _vehicle->sendMessage(msg); } diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index a69a0bb2d22c2079a4d729724d29bb770e5f2ff6..7ab7bd7a062870f361427f898734a07a8de1b41f 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -90,7 +90,6 @@ const char* MainWindow::_uasControlDockWidgetName = "UNMANNED_SYSTEM_CONTROL_DOC const char* MainWindow::_uasListDockWidgetName = "UNMANNED_SYSTEM_LIST_DOCKWIDGET"; const char* MainWindow::_waypointsDockWidgetName = "WAYPOINT_LIST_DOCKWIDGET"; const char* MainWindow::_mavlinkDockWidgetName = "MAVLINK_INSPECTOR_DOCKWIDGET"; -const char* MainWindow::_parametersDockWidgetName = "PARAMETER_INTERFACE_DOCKWIDGET"; const char* MainWindow::_customCommandWidgetName = "CUSTOM_COMMAND_DOCKWIDGET"; const char* MainWindow::_filesDockWidgetName = "FILE_VIEW_DOCKWIDGET"; const char* MainWindow::_uasStatusDetailsDockWidgetName = "UAS_STATUS_DETAILS_DOCKWIDGET"; @@ -393,7 +392,6 @@ void MainWindow::_buildCommonWidgets(void) { _uasListDockWidgetName, "Unmanned Systems", Qt::RightDockWidgetArea }, { _waypointsDockWidgetName, "Mission Plan", Qt::BottomDockWidgetArea }, { _mavlinkDockWidgetName, "MAVLink Inspector", Qt::RightDockWidgetArea }, - { _parametersDockWidgetName, "Parameter Editor", Qt::RightDockWidgetArea }, { _customCommandWidgetName, "Custom Command", Qt::RightDockWidgetArea }, { _filesDockWidgetName, "Onboard Files", Qt::RightDockWidgetArea }, { _uasStatusDetailsDockWidgetName, "Status Details", Qt::RightDockWidgetArea }, @@ -497,8 +495,6 @@ void MainWindow::_createInnerDockWidget(const QString& widgetName) widget = new QGCWaypointListMulti(this); } else if (widgetName == _mavlinkDockWidgetName) { widget = new QGCMAVLinkInspector(MAVLinkProtocol::instance(),this); - } else if (widgetName == _parametersDockWidgetName) { - widget = new ParameterEditorWidget(this); } else if (widgetName == _customCommandWidgetName) { widget = new CustomCommandWidget(this); } else if (widgetName == _filesDockWidgetName) { @@ -613,7 +609,6 @@ void MainWindow::closeEvent(QCloseEvent *event) _storeCurrentViewState(); storeSettings(); - HomePositionManager::instance()->storeSettings(); event->accept(); } @@ -827,6 +822,8 @@ void MainWindow::_storeCurrentViewState(void) { // HIL dock widgets are dynamic and are not part of the saved state _hideAllHilDockWidgets(); + +#ifndef __mobile__ // Save list of visible widgets bool firstWidget = true; QString widgetNames = ""; @@ -840,6 +837,7 @@ void MainWindow::_storeCurrentViewState(void) } } settings.setValue(_getWindowStateKey() + "WIDGETS", widgetNames); +#endif settings.setValue(_getWindowStateKey(), saveState()); settings.setValue(_getWindowGeometryKey(), saveGeometry()); } @@ -910,6 +908,7 @@ void MainWindow::_loadCurrentViewState(void) // Hide all widgets from previous view _hideAllDockWidgets(); +#ifndef __mobile__ // Restore the widgets for the new view QString widgetNames = settings.value(_getWindowStateKey() + "WIDGETS", defaultWidgets).toString(); qDebug() << widgetNames; @@ -920,6 +919,7 @@ void MainWindow::_loadCurrentViewState(void) _showDockWidget(widgetName, true); } } +#endif if (settings.contains(_getWindowStateKey())) { restoreState(settings.value(_getWindowStateKey()).toByteArray()); diff --git a/src/ui/MainWindow.h b/src/ui/MainWindow.h index 5d64f5457abce65f9990d5575fafa1d2227586e2..ed76bbc4a887807e621182fafa674aee3b493f9e 100644 --- a/src/ui/MainWindow.h +++ b/src/ui/MainWindow.h @@ -49,7 +49,6 @@ This file is part of the QGROUNDCONTROL project #if (defined QGC_MOUSE_ENABLED_WIN) | (defined QGC_MOUSE_ENABLED_LINUX) #include "Mouse6dofInput.h" #endif // QGC_MOUSE_ENABLED_WIN -#include "ParameterEditorWidget.h" #include "opmapcontrol.h" #include "MainToolBar.h" #include "LogCompressor.h" @@ -291,7 +290,6 @@ private: static const char* _uasListDockWidgetName; static const char* _waypointsDockWidgetName; static const char* _mavlinkDockWidgetName; - static const char* _parametersDockWidgetName; static const char* _customCommandWidgetName; static const char* _filesDockWidgetName; static const char* _uasStatusDetailsDockWidgetName;