From f1070496e093a029a3423b080264601751daa17b Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Sun, 25 Oct 2015 11:26:37 -0700 Subject: [PATCH 01/16] Move ParameterLoader override to FirmwarePlugin --- QGCApplication.pro | 12 +- src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc | 79 +++++ src/AutoPilotPlugins/APM/APMAutoPilotPlugin.h | 52 +++ src/AutoPilotPlugins/AutoPilotPlugin.cc | 24 +- src/AutoPilotPlugins/AutoPilotPlugin.h | 15 +- src/AutoPilotPlugins/AutoPilotPluginManager.cc | 12 +- .../Generic/GenericAutoPilotPlugin.cc | 13 +- .../Generic/GenericAutoPilotPlugin.h | 12 +- .../Generic/GenericParameterFacts.cc | 35 -- .../Generic/GenericParameterFacts.h | 50 --- src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.cc | 15 +- src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.h | 8 +- src/AutoPilotPlugins/PX4/PX4ParameterLoader.cc | 352 --------------------- src/AutoPilotPlugins/PX4/PX4ParameterLoader.h | 78 ----- src/FactSystem/ParameterLoader.h | 8 +- src/FirmwarePlugin/APM/APMFirmwarePlugin.cc | 22 +- src/FirmwarePlugin/APM/APMFirmwarePlugin.h | 4 +- src/FirmwarePlugin/APM/APMParameterLoader.cc | 113 +++++++ src/FirmwarePlugin/APM/APMParameterLoader.h | 78 +++++ src/FirmwarePlugin/FirmwarePlugin.h | 3 + .../Generic/GenericFirmwarePlugin.cc | 20 +- src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h | 4 + .../Generic/GenericParameterLoader.cc | 37 +++ .../Generic/GenericParameterLoader.h | 48 +++ src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc | 22 +- src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h | 4 + src/FirmwarePlugin/PX4/PX4ParameterLoader.cc | 352 +++++++++++++++++++++ src/FirmwarePlugin/PX4/PX4ParameterLoader.h | 78 +++++ 28 files changed, 965 insertions(+), 585 deletions(-) create mode 100644 src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc create mode 100644 src/AutoPilotPlugins/APM/APMAutoPilotPlugin.h delete mode 100644 src/AutoPilotPlugins/Generic/GenericParameterFacts.cc delete mode 100644 src/AutoPilotPlugins/Generic/GenericParameterFacts.h delete mode 100644 src/AutoPilotPlugins/PX4/PX4ParameterLoader.cc delete mode 100644 src/AutoPilotPlugins/PX4/PX4ParameterLoader.h create mode 100644 src/FirmwarePlugin/APM/APMParameterLoader.cc create mode 100644 src/FirmwarePlugin/APM/APMParameterLoader.h create mode 100644 src/FirmwarePlugin/Generic/GenericParameterLoader.cc create mode 100644 src/FirmwarePlugin/Generic/GenericParameterLoader.h create mode 100644 src/FirmwarePlugin/PX4/PX4ParameterLoader.cc create mode 100644 src/FirmwarePlugin/PX4/PX4ParameterLoader.h diff --git a/QGCApplication.pro b/QGCApplication.pro index 3333a76..fd71693 100644 --- a/QGCApplication.pro +++ b/QGCApplication.pro @@ -507,8 +507,8 @@ INCLUDEPATH += \ HEADERS+= \ src/AutoPilotPlugins/AutoPilotPlugin.h \ src/AutoPilotPlugins/AutoPilotPluginManager.h \ + src/AutoPilotPlugins/APM/APMAutoPilotPlugin.h \ src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.h \ - src/AutoPilotPlugins/Generic/GenericParameterFacts.h \ src/AutoPilotPlugins/PX4/AirframeComponent.h \ src/AutoPilotPlugins/PX4/AirframeComponentAirframes.h \ src/AutoPilotPlugins/PX4/AirframeComponentController.h \ @@ -518,7 +518,6 @@ HEADERS+= \ src/AutoPilotPlugins/PX4/PowerComponentController.h \ src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.h \ src/AutoPilotPlugins/PX4/PX4Component.h \ - src/AutoPilotPlugins/PX4/PX4ParameterLoader.h \ src/AutoPilotPlugins/PX4/RadioComponent.h \ src/AutoPilotPlugins/PX4/RadioComponentController.h \ src/AutoPilotPlugins/PX4/SafetyComponent.h \ @@ -527,11 +526,14 @@ HEADERS+= \ src/FirmwarePlugin/FirmwarePluginManager.h \ src/FirmwarePlugin/FirmwarePlugin.h \ src/FirmwarePlugin/APM/APMFirmwarePlugin.h \ + src/FirmwarePlugin/APM/APMParameterLoader.h \ src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h \ src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.h \ src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h \ src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h \ + src/FirmwarePlugin/Generic/GenericParameterLoader.h \ src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h \ + src/FirmwarePlugin/PX4/PX4ParameterLoader.h \ src/Vehicle/MultiVehicleManager.h \ src/Vehicle/Vehicle.h \ src/VehicleSetup/VehicleComponent.h \ @@ -548,8 +550,8 @@ HEADERS += \ SOURCES += \ src/AutoPilotPlugins/AutoPilotPlugin.cc \ src/AutoPilotPlugins/AutoPilotPluginManager.cc \ + src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc \ src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.cc \ - src/AutoPilotPlugins/Generic/GenericParameterFacts.cc \ src/AutoPilotPlugins/PX4/AirframeComponent.cc \ src/AutoPilotPlugins/PX4/AirframeComponentAirframes.cc \ src/AutoPilotPlugins/PX4/AirframeComponentController.cc \ @@ -559,19 +561,21 @@ SOURCES += \ src/AutoPilotPlugins/PX4/PowerComponentController.cc \ src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.cc \ src/AutoPilotPlugins/PX4/PX4Component.cc \ - src/AutoPilotPlugins/PX4/PX4ParameterLoader.cc \ src/AutoPilotPlugins/PX4/RadioComponent.cc \ src/AutoPilotPlugins/PX4/RadioComponentController.cc \ src/AutoPilotPlugins/PX4/SafetyComponent.cc \ src/AutoPilotPlugins/PX4/SensorsComponent.cc \ src/AutoPilotPlugins/PX4/SensorsComponentController.cc \ src/FirmwarePlugin/APM/APMFirmwarePlugin.cc \ + src/FirmwarePlugin/APM/APMParameterLoader.cc \ src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc \ src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.cc \ src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc \ src/FirmwarePlugin/FirmwarePluginManager.cc \ src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc \ + src/FirmwarePlugin/Generic/GenericParameterLoader.cc \ src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc \ + src/FirmwarePlugin/PX4/PX4ParameterLoader.cc \ src/Vehicle/MultiVehicleManager.cc \ src/Vehicle/Vehicle.cc \ src/VehicleSetup/VehicleComponent.cc \ diff --git a/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc b/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc new file mode 100644 index 0000000..0eb799c --- /dev/null +++ b/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc @@ -0,0 +1,79 @@ +/*===================================================================== + + QGroundControl Open Source Ground Control Station + + (c) 2009 - 2015 QGROUNDCONTROL PROJECT + + This file is part of the QGROUNDCONTROL project + + QGROUNDCONTROL is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + QGROUNDCONTROL is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with QGROUNDCONTROL. If not, see . + + ======================================================================*/ + +#include "APMAutoPilotPlugin.h" +#include "AutoPilotPluginManager.h" +#include "QGCMessageBox.h" +#include "UAS.h" +#include "FirmwarePlugin/APM/APMParameterLoader.h" // FIXME: Hack +#include "FirmwarePlugin/APM/APMFirmwarePlugin.h" // FIXME: Hack + +/// This is the AutoPilotPlugin implementatin for the MAV_AUTOPILOT_ARDUPILOT type. +APMAutoPilotPlugin::APMAutoPilotPlugin(Vehicle* vehicle, QObject* parent) : + AutoPilotPlugin(vehicle, parent), + _incorrectParameterVersion(false) +{ + Q_ASSERT(vehicle); + + // This kicks off parameter load + _firmwarePlugin->getParameterLoader(this, vehicle); +} + +APMAutoPilotPlugin::~APMAutoPilotPlugin() +{ + +} + +void APMAutoPilotPlugin::clearStaticData(void) +{ + APMParameterLoader::clearStaticData(); +} + +const QVariantList& APMAutoPilotPlugin::vehicleComponents(void) +{ + static const QVariantList emptyList; + + return emptyList; +} + +/// This will perform various checks prior to signalling that the plug in ready +void APMAutoPilotPlugin::_parametersReadyPreChecks(bool missingParameters) +{ +#if 0 + I believe APM has parameter version stamp, we should check that + + // Check for older parameter version set + // FIXME: Firmware is moving to version stamp parameter set. Once that is complete the version stamp + // should be used instead. + if (parameterExists(FactSystem::defaultComponentId, "SENS_GYRO_XOFF")) { + _incorrectParameterVersion = true; + QGCMessageBox::warning("Setup", "This version of GroundControl can only perform vehicle setup on a newer version of firmware. " + "Please perform a Firmware Upgrade if you wish to use Vehicle Setup."); + } +#endif + + _parametersReady = true; + _missingParameters = missingParameters; + emit missingParametersChanged(_missingParameters); + emit parametersReadyChanged(_parametersReady); +} diff --git a/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.h b/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.h new file mode 100644 index 0000000..4ebacf8 --- /dev/null +++ b/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.h @@ -0,0 +1,52 @@ +/*===================================================================== + + QGroundControl Open Source Ground Control Station + + (c) 2009 - 2015 QGROUNDCONTROL PROJECT + + This file is part of the QGROUNDCONTROL project + + QGROUNDCONTROL is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + QGROUNDCONTROL is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with QGROUNDCONTROL. If not, see . + + ======================================================================*/ + +#ifndef APMAutoPilotPlugin_H +#define APMAutoPilotPlugin_H + +#include "AutoPilotPlugin.h" +#include "Vehicle.h" + +/// This is the APM specific implementation of the AutoPilot class. +class APMAutoPilotPlugin : public AutoPilotPlugin +{ + Q_OBJECT + +public: + APMAutoPilotPlugin(Vehicle* vehicle, QObject* parent); + ~APMAutoPilotPlugin(); + + // Overrides from AutoPilotPlugin + virtual const QVariantList& vehicleComponents(void); + + static void clearStaticData(void); + +public slots: + // FIXME: This is public until we restructure AutoPilotPlugin/FirmwarePlugin/Vehicle + void _parametersReadyPreChecks(bool missingParameters); + +private: + bool _incorrectParameterVersion; ///< true: parameter version incorrect, setup not allowed +}; + +#endif diff --git a/src/AutoPilotPlugins/AutoPilotPlugin.cc b/src/AutoPilotPlugins/AutoPilotPlugin.cc index 1613dd2..eb2b9c7 100644 --- a/src/AutoPilotPlugins/AutoPilotPlugin.cc +++ b/src/AutoPilotPlugins/AutoPilotPlugin.cc @@ -30,10 +30,12 @@ #include "MainWindow.h" #include "ParameterLoader.h" #include "UAS.h" +#include "FirmwarePlugin.h" AutoPilotPlugin::AutoPilotPlugin(Vehicle* vehicle, QObject* parent) : QObject(parent) , _vehicle(vehicle) + , _firmwarePlugin(vehicle->firmwarePlugin()) , _parametersReady(false) , _missingParameters(false) , _setupComplete(false) @@ -107,34 +109,34 @@ void AutoPilotPlugin::resetAllParametersToDefaults(void) void AutoPilotPlugin::refreshAllParameters(void) { - _getParameterLoader()->refreshAllParameters(); + _firmwarePlugin->getParameterLoader(this, _vehicle)->refreshAllParameters(); } void AutoPilotPlugin::refreshParameter(int componentId, const QString& name) { - _getParameterLoader()->refreshParameter(componentId, name); + _firmwarePlugin->getParameterLoader(this, _vehicle)->refreshParameter(componentId, name); } void AutoPilotPlugin::refreshParametersPrefix(int componentId, const QString& namePrefix) { - _getParameterLoader()->refreshParametersPrefix(componentId, namePrefix); + _firmwarePlugin->getParameterLoader(this, _vehicle)->refreshParametersPrefix(componentId, namePrefix); } bool AutoPilotPlugin::parameterExists(int componentId, const QString& name) { - return _getParameterLoader()->parameterExists(componentId, name); + return _firmwarePlugin->getParameterLoader(this, _vehicle)->parameterExists(componentId, name); } Fact* AutoPilotPlugin::getParameterFact(int componentId, const QString& name) { - return _getParameterLoader()->getFact(componentId, name); + return _firmwarePlugin->getParameterLoader(this, _vehicle)->getFact(componentId, name); } bool AutoPilotPlugin::factExists(FactSystem::Provider_t provider, int componentId, const QString& name) { switch (provider) { case FactSystem::ParameterProvider: - return _getParameterLoader()->parameterExists(componentId, name); + return _firmwarePlugin->getParameterLoader(this, _vehicle)->parameterExists(componentId, name); // Other providers will go here once they come online } @@ -147,7 +149,7 @@ Fact* AutoPilotPlugin::getFact(FactSystem::Provider_t provider, int componentId, { switch (provider) { case FactSystem::ParameterProvider: - return _getParameterLoader()->getFact(componentId, name); + return _firmwarePlugin->getParameterLoader(this, _vehicle)->getFact(componentId, name); // Other providers will go here once they come online } @@ -158,20 +160,20 @@ Fact* AutoPilotPlugin::getFact(FactSystem::Provider_t provider, int componentId, QStringList AutoPilotPlugin::parameterNames(int componentId) { - return _getParameterLoader()->parameterNames(componentId); + return _firmwarePlugin->getParameterLoader(this, _vehicle)->parameterNames(componentId); } const QMap >& AutoPilotPlugin::getGroupMap(void) { - return _getParameterLoader()->getGroupMap(); + return _firmwarePlugin->getParameterLoader(this, _vehicle)->getGroupMap(); } void AutoPilotPlugin::writeParametersToStream(QTextStream &stream) { - _getParameterLoader()->writeParametersToStream(stream, _vehicle->uas()->getUASName()); + _firmwarePlugin->getParameterLoader(this, _vehicle)->writeParametersToStream(stream, _vehicle->uas()->getUASName()); } QString AutoPilotPlugin::readParametersFromStream(QTextStream &stream) { - return _getParameterLoader()->readParametersFromStream(stream); + return _firmwarePlugin->getParameterLoader(this, _vehicle)->readParametersFromStream(stream); } diff --git a/src/AutoPilotPlugins/AutoPilotPlugin.h b/src/AutoPilotPlugins/AutoPilotPlugin.h index 6fb8803..654d5aa 100644 --- a/src/AutoPilotPlugins/AutoPilotPlugin.h +++ b/src/AutoPilotPlugins/AutoPilotPlugin.h @@ -38,6 +38,7 @@ class ParameterLoader; class Vehicle; +class FirmwarePlugin; /// This is the base class for AutoPilot plugins /// @@ -132,20 +133,18 @@ protected: /// All access to AutoPilotPugin objects is through getInstanceForAutoPilotPlugin AutoPilotPlugin(QObject* parent = NULL) : QObject(parent) { } - /// Returns the ParameterLoader - virtual ParameterLoader* _getParameterLoader(void) = 0; - - Vehicle* _vehicle; - bool _parametersReady; - bool _missingParameters; - bool _setupComplete; + Vehicle* _vehicle; + FirmwarePlugin* _firmwarePlugin; + bool _parametersReady; + bool _missingParameters; + bool _setupComplete; private slots: void _uasDisconnected(void); void _parametersReadyChanged(bool parametersReady); private: - void _recalcSetupComplete(void); + void _recalcSetupComplete(void); }; #endif diff --git a/src/AutoPilotPlugins/AutoPilotPluginManager.cc b/src/AutoPilotPlugins/AutoPilotPluginManager.cc index 245d064..88435df 100644 --- a/src/AutoPilotPlugins/AutoPilotPluginManager.cc +++ b/src/AutoPilotPlugins/AutoPilotPluginManager.cc @@ -26,6 +26,7 @@ #include "AutoPilotPluginManager.h" #include "PX4/PX4AutoPilotPlugin.h" +#include "APM/APMAutoPilotPlugin.h" #include "Generic/GenericAutoPilotPlugin.h" IMPLEMENT_QGC_SINGLETON(AutoPilotPluginManager, AutoPilotPluginManager) @@ -44,9 +45,12 @@ AutoPilotPluginManager::~AutoPilotPluginManager() AutoPilotPlugin* AutoPilotPluginManager::newAutopilotPluginForVehicle(Vehicle* vehicle) { - if (vehicle->firmwareType() == MAV_AUTOPILOT_PX4) { - return new PX4AutoPilotPlugin(vehicle, vehicle); - } else { - return new GenericAutoPilotPlugin(vehicle, vehicle); + switch (vehicle->firmwareType()) { + case MAV_AUTOPILOT_PX4: + return new PX4AutoPilotPlugin(vehicle, vehicle); + case MAV_AUTOPILOT_ARDUPILOTMEGA: + return new APMAutoPilotPlugin(vehicle, vehicle); + default: + return new GenericAutoPilotPlugin(vehicle, vehicle); } } diff --git a/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.cc b/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.cc index 8dee503..21ddf36 100644 --- a/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.cc +++ b/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.cc @@ -25,17 +25,15 @@ /// @author Don Gagne #include "GenericAutoPilotPlugin.h" +#include "FirmwarePlugin/Generic/GenericFirmwarePlugin.h" // FIXME: Hack GenericAutoPilotPlugin::GenericAutoPilotPlugin(Vehicle* vehicle, QObject* parent) : AutoPilotPlugin(vehicle, parent) { Q_ASSERT(vehicle); - - _parameterFacts = new GenericParameterFacts(this, vehicle, this); - Q_CHECK_PTR(_parameterFacts); - - connect(_parameterFacts, &GenericParameterFacts::parametersReady, this, &GenericAutoPilotPlugin::_parametersReadySlot); - connect(_parameterFacts, &GenericParameterFacts::parameterListProgress, this, &GenericAutoPilotPlugin::parameterListProgress); + + // This kicks off parameter load + _firmwarePlugin->getParameterLoader(this, vehicle); } void GenericAutoPilotPlugin::clearStaticData(void) @@ -50,7 +48,8 @@ const QVariantList& GenericAutoPilotPlugin::vehicleComponents(void) return emptyList; } -void GenericAutoPilotPlugin::_parametersReadySlot(bool missingParameters) +/// This will perform various checks prior to signalling that the plug in ready +void GenericAutoPilotPlugin::_parametersReadyPreChecks(bool missingParameters) { _parametersReady = true; _missingParameters = missingParameters; diff --git a/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.h b/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.h index 827a68e..161280c 100644 --- a/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.h +++ b/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.h @@ -25,7 +25,6 @@ #define GENERICAUTOPILOT_H #include "AutoPilotPlugin.h" -#include "GenericParameterFacts.h" /// @file /// @brief This is the generic implementation of the AutoPilotPlugin class for mavs @@ -44,14 +43,9 @@ public: static void clearStaticData(void); -private slots: - void _parametersReadySlot(bool missingParameters); - -private: - // Overrides from AutoPilotPlugin - virtual ParameterLoader* _getParameterLoader(void) { return _parameterFacts; } - - GenericParameterFacts* _parameterFacts; +public slots: + // FIXME: This is public until we restructure AutoPilotPlugin/FirmwarePlugin/Vehicle + void _parametersReadyPreChecks(bool missingParameters); }; #endif diff --git a/src/AutoPilotPlugins/Generic/GenericParameterFacts.cc b/src/AutoPilotPlugins/Generic/GenericParameterFacts.cc deleted file mode 100644 index 24831fc..0000000 --- a/src/AutoPilotPlugins/Generic/GenericParameterFacts.cc +++ /dev/null @@ -1,35 +0,0 @@ -/*===================================================================== - - 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 "GenericParameterFacts.h" - -#include - -GenericParameterFacts::GenericParameterFacts(AutoPilotPlugin* autopilot, Vehicle* vehicle, QObject* parent) : - ParameterLoader(autopilot, vehicle, parent) -{ - Q_ASSERT(vehicle); -} diff --git a/src/AutoPilotPlugins/Generic/GenericParameterFacts.h b/src/AutoPilotPlugins/Generic/GenericParameterFacts.h deleted file mode 100644 index c7a90c6..0000000 --- a/src/AutoPilotPlugins/Generic/GenericParameterFacts.h +++ /dev/null @@ -1,50 +0,0 @@ -/*===================================================================== - - QGroundControl Open Source Ground Control Station - - (c) 2009 - 2014 QGROUNDCONTROL PROJECT - - This file is part of the QGROUNDCONTROL project - - QGROUNDCONTROL is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - QGROUNDCONTROL is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with QGROUNDCONTROL. If not, see . - - ======================================================================*/ - -#ifndef GenericParameterFacts_h -#define GenericParameterFacts_h - -#include - -#include "ParameterLoader.h" -#include "UASInterface.h" -#include "AutoPilotPlugin.h" - -/// @file -/// @author Don Gagne - -/// Collection of Parameter Facts for Generic AutoPilot - -class GenericParameterFacts : public ParameterLoader -{ - Q_OBJECT - -public: - /// @param uas Uas which this set of facts is associated with - GenericParameterFacts(AutoPilotPlugin* autopilot, Vehicle* vehicle, QObject* parent = NULL); - - /// Override from ParameterLoader - virtual QString getDefaultComponentIdParam(void) const { return QString(); } -}; - -#endif \ No newline at end of file diff --git a/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.cc b/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.cc index 2507d34..c4bc00e 100644 --- a/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.cc +++ b/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.cc @@ -23,12 +23,13 @@ #include "PX4AutoPilotPlugin.h" #include "AutoPilotPluginManager.h" -#include "PX4ParameterLoader.h" #include "PX4AirframeLoader.h" #include "FlightModesComponentController.h" #include "AirframeComponentController.h" #include "QGCMessageBox.h" #include "UAS.h" +#include "FirmwarePlugin/PX4/PX4ParameterLoader.h" // FIXME: Hack +#include "FirmwarePlugin/PX4/PX4FirmwarePlugin.h" // FIXME: Hack /// @file /// @brief This is the AutoPilotPlugin implementatin for the MAV_AUTOPILOT_PX4 type. @@ -66,7 +67,6 @@ union px4_custom_mode { PX4AutoPilotPlugin::PX4AutoPilotPlugin(Vehicle* vehicle, QObject* parent) : AutoPilotPlugin(vehicle, parent), - _parameterFacts(NULL), _airframeComponent(NULL), _radioComponent(NULL), _flightModesComponent(NULL), @@ -77,22 +77,17 @@ PX4AutoPilotPlugin::PX4AutoPilotPlugin(Vehicle* vehicle, QObject* parent) : { Q_ASSERT(vehicle); - _parameterFacts = new PX4ParameterLoader(this, vehicle, this); - Q_CHECK_PTR(_parameterFacts); - - connect(_parameterFacts, &PX4ParameterLoader::parametersReady, this, &PX4AutoPilotPlugin::_parametersReadyPreChecks); - connect(_parameterFacts, &PX4ParameterLoader::parameterListProgress, this, &PX4AutoPilotPlugin::parameterListProgress); - _airframeFacts = new PX4AirframeLoader(this, _vehicle->uas(), this); Q_CHECK_PTR(_airframeFacts); - PX4ParameterLoader::loadParameterFactMetaData(); PX4AirframeLoader::loadAirframeFactMetaData(); + + // This kicks off parameter load + _firmwarePlugin->getParameterLoader(this, vehicle); } PX4AutoPilotPlugin::~PX4AutoPilotPlugin() { - delete _parameterFacts; delete _airframeFacts; } diff --git a/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.h b/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.h index cf90463..09b2ea8 100644 --- a/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.h +++ b/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.h @@ -25,7 +25,6 @@ #define PX4AUTOPILOT_H #include "AutoPilotPlugin.h" -#include "PX4ParameterLoader.h" #include "PX4AirframeLoader.h" #include "AirframeComponent.h" #include "RadioComponent.h" @@ -62,14 +61,11 @@ public: SafetyComponent* safetyComponent(void) { return _safetyComponent; } PowerComponent* powerComponent(void) { return _powerComponent; } -private slots: +public slots: + // FIXME: This is public until we restructure AutoPilotPlugin/FirmwarePlugin/Vehicle void _parametersReadyPreChecks(bool missingParameters); private: - // Overrides from AutoPilotPlugin - virtual ParameterLoader* _getParameterLoader(void) { return _parameterFacts; } - - PX4ParameterLoader* _parameterFacts; PX4AirframeLoader* _airframeFacts; QVariantList _components; AirframeComponent* _airframeComponent; diff --git a/src/AutoPilotPlugins/PX4/PX4ParameterLoader.cc b/src/AutoPilotPlugins/PX4/PX4ParameterLoader.cc deleted file mode 100644 index aea72c1..0000000 --- a/src/AutoPilotPlugins/PX4/PX4ParameterLoader.cc +++ /dev/null @@ -1,352 +0,0 @@ -/*===================================================================== - - 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 "PX4ParameterLoader.h" -#include "QGCApplication.h" -#include "QGCLoggingCategory.h" - -#include -#include -#include -#include - -QGC_LOGGING_CATEGORY(PX4ParameterLoaderLog, "PX4ParameterLoaderLog") - -bool PX4ParameterLoader::_parameterMetaDataLoaded = false; -QMap PX4ParameterLoader::_mapParameterName2FactMetaData; - -PX4ParameterLoader::PX4ParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, QObject* parent) : - ParameterLoader(autopilot, vehicle, parent) -{ - Q_ASSERT(vehicle); -} - -/// Converts a string to a typed QVariant -/// @param string String to convert -/// @param type Type for Fact which dictates the QVariant type as well -/// @param convertOk Returned: true: conversion success, false: conversion failure -/// @return Returns the correctly type QVariant -QVariant PX4ParameterLoader::_stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool* convertOk) -{ - QVariant var(string); - - int convertTo = QVariant::Int; // keep compiler warning happy - switch (type) { - case FactMetaData::valueTypeUint8: - case FactMetaData::valueTypeUint16: - case FactMetaData::valueTypeUint32: - convertTo = QVariant::UInt; - break; - case FactMetaData::valueTypeInt8: - case FactMetaData::valueTypeInt16: - case FactMetaData::valueTypeInt32: - convertTo = QVariant::Int; - break; - case FactMetaData::valueTypeFloat: - convertTo = QMetaType::Float; - break; - case FactMetaData::valueTypeDouble: - convertTo = QVariant::Double; - break; - } - - *convertOk = var.convert(convertTo); - - return var; -} - -/// Load Parameter Fact meta data -/// -/// The meta data comes from firmware parameters.xml file. -void PX4ParameterLoader::loadParameterFactMetaData(void) -{ - if (_parameterMetaDataLoaded) { - return; - } - _parameterMetaDataLoaded = true; - - qCDebug(PX4ParameterLoaderLog) << "Loading PX4 parameter fact meta data"; - - Q_ASSERT(_mapParameterName2FactMetaData.count() == 0); - - QString parameterFilename; - - // We want unit test builds to always use the resource based meta data to provide repeatable results - if (!qgcApp()->runningUnitTests()) { - // First look for meta data that comes from a firmware download. Fall back to resource if not there. - QSettings settings; - QDir parameterDir = QFileInfo(settings.fileName()).dir(); - parameterFilename = parameterDir.filePath("PX4ParameterFactMetaData.xml"); - } - if (parameterFilename.isEmpty() || !QFile(parameterFilename).exists()) { - parameterFilename = ":/AutoPilotPlugins/PX4/ParameterFactMetaData.xml"; - } - - qCDebug(PX4ParameterLoaderLog) << "Loading parameter meta data:" << parameterFilename; - - QFile xmlFile(parameterFilename); - Q_ASSERT(xmlFile.exists()); - - bool success = xmlFile.open(QIODevice::ReadOnly); - Q_UNUSED(success); - Q_ASSERT(success); - - QXmlStreamReader xml(xmlFile.readAll()); - xmlFile.close(); - if (xml.hasError()) { - qWarning() << "Badly formed XML" << xml.errorString(); - return; - } - - QString factGroup; - QString errorString; - FactMetaData* metaData = NULL; - int xmlState = XmlStateNone; - bool badMetaData = true; - - while (!xml.atEnd()) { - if (xml.isStartElement()) { - QString elementName = xml.name().toString(); - - if (elementName == "parameters") { - if (xmlState != XmlStateNone) { - qWarning() << "Badly formed XML"; - return; - } - xmlState = XmlStateFoundParameters; - - } else if (elementName == "version") { - if (xmlState != XmlStateFoundParameters) { - qWarning() << "Badly formed XML"; - return; - } - xmlState = XmlStateFoundVersion; - - bool convertOk; - QString strVersion = xml.readElementText(); - int intVersion = strVersion.toInt(&convertOk); - if (!convertOk) { - qWarning() << "Badly formed XML"; - return; - } - if (intVersion <= 2) { - // We can't read these old files - qDebug() << "Parameter version stamp too old, skipping load. Found:" << intVersion << "Want: 3 File:" << parameterFilename; - return; - } - - - } else if (elementName == "group") { - if (xmlState != XmlStateFoundVersion) { - // We didn't get a version stamp, assume older version we can't read - qDebug() << "Parameter version stamp not found, skipping load" << parameterFilename; - return; - } - xmlState = XmlStateFoundGroup; - - if (!xml.attributes().hasAttribute("name")) { - qWarning() << "Badly formed XML"; - return; - } - factGroup = xml.attributes().value("name").toString(); - qCDebug(PX4ParameterLoaderLog) << "Found group: " << factGroup; - - } else if (elementName == "parameter") { - if (xmlState != XmlStateFoundGroup) { - qWarning() << "Badly formed XML"; - return; - } - xmlState = XmlStateFoundParameter; - - if (!xml.attributes().hasAttribute("name") || !xml.attributes().hasAttribute("type")) { - qWarning() << "Badly formed XML"; - return; - } - - QString name = xml.attributes().value("name").toString(); - QString type = xml.attributes().value("type").toString(); - QString strDefault = xml.attributes().value("default").toString(); - - qCDebug(PX4ParameterLoaderLog) << "Found parameter name:" << name << " type:" << type << " default:" << strDefault; - - // Convert type from string to FactMetaData::ValueType_t - - struct String2Type { - const char* strType; - FactMetaData::ValueType_t type; - }; - - static const struct String2Type rgString2Type[] = { - { "FLOAT", FactMetaData::valueTypeFloat }, - { "INT32", FactMetaData::valueTypeInt32 }, - }; - static const size_t crgString2Type = sizeof(rgString2Type) / sizeof(rgString2Type[0]); - - bool found = false; - FactMetaData::ValueType_t foundType; - for (size_t i=0; istrType) { - found = true; - foundType = info->type; - break; - } - } - if (!found) { - qWarning() << "Parameter meta data with bad type:" << type << " name:" << name; - return; - } - - // Now that we know type we can create meta data object and add it to the system - - metaData = new FactMetaData(foundType); - Q_CHECK_PTR(metaData); - if (_mapParameterName2FactMetaData.contains(name)) { - // We can't trust the meta dafa since we have dups - qCWarning(PX4ParameterLoaderLog) << "Duplicate parameter found:" << name; - badMetaData = true; - // Reset to default meta data - _mapParameterName2FactMetaData[name] = metaData; - } else { - _mapParameterName2FactMetaData[name] = metaData; - metaData->setName(name); - metaData->setGroup(factGroup); - - if (xml.attributes().hasAttribute("default") && !strDefault.isEmpty()) { - QVariant varDefault; - - if (metaData->convertAndValidate(strDefault, false, varDefault, errorString)) { - metaData->setDefaultValue(varDefault); - } else { - qCWarning(PX4ParameterLoaderLog) << "Invalid default value, name:" << name << " type:" << type << " default:" << strDefault << " error:" << errorString; - } - } - } - - } else { - // We should be getting meta data now - if (xmlState != XmlStateFoundParameter) { - qWarning() << "Badly formed XML"; - return; - } - - if (!badMetaData) { - if (elementName == "short_desc") { - Q_ASSERT(metaData); - QString text = xml.readElementText(); - text = text.replace("\n", " "); - qCDebug(PX4ParameterLoaderLog) << "Short description:" << text; - metaData->setShortDescription(text); - - } else if (elementName == "long_desc") { - Q_ASSERT(metaData); - QString text = xml.readElementText(); - text = text.replace("\n", " "); - qCDebug(PX4ParameterLoaderLog) << "Long description:" << text; - metaData->setLongDescription(text); - - } else if (elementName == "min") { - Q_ASSERT(metaData); - QString text = xml.readElementText(); - qCDebug(PX4ParameterLoaderLog) << "Min:" << text; - - QVariant varMin; - if (metaData->convertAndValidate(text, true /* convertOnly */, varMin, errorString)) { - metaData->setMin(varMin); - } else { - qCWarning(PX4ParameterLoaderLog) << "Invalid min value, name:" << metaData->name() << " type:" << metaData->type() << " min:" << text << " error:" << errorString; - } - - } else if (elementName == "max") { - Q_ASSERT(metaData); - QString text = xml.readElementText(); - qCDebug(PX4ParameterLoaderLog) << "Max:" << text; - - QVariant varMax; - if (metaData->convertAndValidate(text, true /* convertOnly */, varMax, errorString)) { - metaData->setMax(varMax); - } else { - qCWarning(PX4ParameterLoaderLog) << "Invalid max value, name:" << metaData->name() << " type:" << metaData->type() << " max:" << text << " error:" << errorString; - } - - } else if (elementName == "unit") { - Q_ASSERT(metaData); - QString text = xml.readElementText(); - qCDebug(PX4ParameterLoaderLog) << "Unit:" << text; - metaData->setUnits(text); - - } else { - qDebug() << "Unknown element in XML: " << elementName; - } - } - } - } else if (xml.isEndElement()) { - QString elementName = xml.name().toString(); - - if (elementName == "parameter") { - // Done loading this parameter, validate default value - if (metaData->defaultValueAvailable()) { - QVariant var; - - if (!metaData->convertAndValidate(metaData->defaultValue(), false /* convertOnly */, var, errorString)) { - qCWarning(PX4ParameterLoaderLog) << "Invalid default value, name:" << metaData->name() << " type:" << metaData->type() << " default:" << metaData->defaultValue() << " error:" << errorString; - } - } - - // Reset for next parameter - metaData = NULL; - badMetaData = false; - xmlState = XmlStateFoundGroup; - } else if (elementName == "group") { - xmlState = XmlStateFoundVersion; - } else if (elementName == "parameters") { - xmlState = XmlStateFoundParameters; - } - } - xml.readNext(); - } -} - -void PX4ParameterLoader::clearStaticData(void) -{ - foreach(QString parameterName, _mapParameterName2FactMetaData.keys()) { - delete _mapParameterName2FactMetaData[parameterName]; - } - _mapParameterName2FactMetaData.clear(); - _parameterMetaDataLoaded = false; -} - -/// Override from FactLoad which connects the meta data to the fact -void PX4ParameterLoader::_addMetaDataToFact(Fact* fact) -{ - if (_mapParameterName2FactMetaData.contains(fact->name())) { - fact->setMetaData(_mapParameterName2FactMetaData[fact->name()]); - } else { - // Use generic meta data - ParameterLoader::_addMetaDataToFact(fact); - } -} diff --git a/src/AutoPilotPlugins/PX4/PX4ParameterLoader.h b/src/AutoPilotPlugins/PX4/PX4ParameterLoader.h deleted file mode 100644 index 8d4b8b9..0000000 --- a/src/AutoPilotPlugins/PX4/PX4ParameterLoader.h +++ /dev/null @@ -1,78 +0,0 @@ -/*===================================================================== - - QGroundControl Open Source Ground Control Station - - (c) 2009 - 2014 QGROUNDCONTROL PROJECT - - This file is part of the QGROUNDCONTROL project - - QGROUNDCONTROL is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - QGROUNDCONTROL is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with QGROUNDCONTROL. If not, see . - - ======================================================================*/ - -#ifndef PX4PARAMETERLOADER_H -#define PX4PARAMETERLOADER_H - -#include -#include -#include -#include - -#include "ParameterLoader.h" -#include "FactSystem.h" -#include "AutoPilotPlugin.h" -#include "Vehicle.h" - -/// @file -/// @author Don Gagne - -Q_DECLARE_LOGGING_CATEGORY(PX4ParameterLoaderLog) - -/// Collection of Parameter Facts for PX4 AutoPilot - -class PX4ParameterLoader : public ParameterLoader -{ - Q_OBJECT - -public: - /// @param uas Uas which this set of facts is associated with - PX4ParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, QObject* parent = NULL); - - /// Override from ParameterLoader - virtual QString getDefaultComponentIdParam(void) const { return QString("SYS_AUTOSTART"); } - - static void loadParameterFactMetaData(void); - static void clearStaticData(void); - -private: - enum { - XmlStateNone, - XmlStateFoundParameters, - XmlStateFoundVersion, - XmlStateFoundGroup, - XmlStateFoundParameter, - XmlStateDone - }; - - // Overrides from ParameterLoader - virtual void _addMetaDataToFact(Fact* fact); - - // Class methods - static QVariant _stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool* convertOk); - - static bool _parameterMetaDataLoaded; ///< true: parameter meta data already loaded - static QMap _mapParameterName2FactMetaData; ///< Maps from a parameter name to FactMetaData -}; - -#endif \ No newline at end of file diff --git a/src/FactSystem/ParameterLoader.h b/src/FactSystem/ParameterLoader.h index 9502e90..14f4a6c 100644 --- a/src/FactSystem/ParameterLoader.h +++ b/src/FactSystem/ParameterLoader.h @@ -105,6 +105,10 @@ protected: /// Base implementation adds generic meta data based on variant type. Derived class can override to provide /// more details meta data. virtual void _addMetaDataToFact(Fact* fact); + + AutoPilotPlugin* _autopilot; + Vehicle* _vehicle; + MAVLinkProtocol* _mavlink; private slots: void _parameterUpdate(int uasId, int componentId, QString parameterName, int parameterCount, int parameterId, int mavType, QVariant value); @@ -128,10 +132,6 @@ private: void _saveToEEPROM(void); void _checkInitialLoadComplete(void); - AutoPilotPlugin* _autopilot; - Vehicle* _vehicle; - MAVLinkProtocol* _mavlink; - /// First mapping is by component id /// Second mapping is parameter name, to Fact* in QVariant QMap _mapParameterName2Variant; diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc index f2cfa3e..4b4f7f4 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc @@ -26,6 +26,7 @@ #include "APMFirmwarePlugin.h" #include "Generic/GenericFirmwarePlugin.h" +#include "AutoPilotPlugins/APM/APMAutoPilotPlugin.h" // FIXME: Hack #include "QGCMAVLink.h" QGC_LOGGING_CATEGORY(APMFirmwarePluginLog, "APMFirmwarePluginLog") @@ -138,8 +139,9 @@ QString APMCustomMode::modeString() const return mode; } -APMFirmwarePlugin::APMFirmwarePlugin(QObject* parent) : - FirmwarePlugin(parent) +APMFirmwarePlugin::APMFirmwarePlugin(QObject* parent) + : FirmwarePlugin(parent) + , _parameterLoader(NULL) { _textSeverityAdjustmentNeeded = false; } @@ -384,3 +386,19 @@ bool APMFirmwarePlugin::sendHomePositionToVehicle(void) // APM stack wants the home position sent in the first position return true; } + +ParameterLoader* APMFirmwarePlugin::getParameterLoader(AutoPilotPlugin* autopilotPlugin, Vehicle* vehicle) +{ + if (!_parameterLoader) { + _parameterLoader = new APMParameterLoader(autopilotPlugin, vehicle, this); + Q_CHECK_PTR(_parameterLoader); + + // FIXME: Why do I need SIGNAL/SLOT to make this work + connect(_parameterLoader, SIGNAL(parametersReady(bool)), autopilotPlugin, SLOT(_parametersReadyPreChecks(bool))); + connect(_parameterLoader, &APMParameterLoader::parameterListProgress, autopilotPlugin, &APMAutoPilotPlugin::parameterListProgress); + + _parameterLoader->loadParameterFactMetaData(); + } + + return _parameterLoader; +} diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.h b/src/FirmwarePlugin/APM/APMFirmwarePlugin.h index 6d92ab7..2a7370b 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.h +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.h @@ -29,6 +29,7 @@ #include "FirmwarePlugin.h" #include "QGCLoggingCategory.h" +#include "APMParameterLoader.h" Q_DECLARE_LOGGING_CATEGORY(APMFirmwarePluginLog) @@ -88,6 +89,7 @@ public: virtual void adjustMavlinkMessage(mavlink_message_t* message); virtual void initializeVehicle(Vehicle* vehicle); virtual bool sendHomePositionToVehicle(void); + virtual ParameterLoader* getParameterLoader(AutoPilotPlugin *autopilotPlugin, Vehicle* vehicle); protected: /// All access to singleton is through stack specific implementation @@ -101,7 +103,7 @@ private: APMFirmwareVersion _firmwareVersion; bool _textSeverityAdjustmentNeeded; QList _supportedModes; - + APMParameterLoader* _parameterLoader; }; #endif diff --git a/src/FirmwarePlugin/APM/APMParameterLoader.cc b/src/FirmwarePlugin/APM/APMParameterLoader.cc new file mode 100644 index 0000000..c24acf3 --- /dev/null +++ b/src/FirmwarePlugin/APM/APMParameterLoader.cc @@ -0,0 +1,113 @@ +/*===================================================================== + + 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 "APMParameterLoader.h" +#include "QGCApplication.h" +#include "QGCLoggingCategory.h" + +#include +#include +#include +#include + +QGC_LOGGING_CATEGORY(APMParameterLoaderLog, "APMParameterLoaderLog") + +bool APMParameterLoader::_parameterMetaDataLoaded = false; +QMap APMParameterLoader::_mapParameterName2FactMetaData; + +APMParameterLoader::APMParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, QObject* parent) : + ParameterLoader(autopilot, vehicle, parent) +{ + Q_ASSERT(vehicle); +} + +/// Converts a string to a typed QVariant +/// @param string String to convert +/// @param type Type for Fact which dictates the QVariant type as well +/// @param convertOk Returned: true: conversion success, false: conversion failure +/// @return Returns the correctly type QVariant +QVariant APMParameterLoader::_stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool* convertOk) +{ + QVariant var(string); + + int convertTo = QVariant::Int; // keep compiler warning happy + switch (type) { + case FactMetaData::valueTypeUint8: + case FactMetaData::valueTypeUint16: + case FactMetaData::valueTypeUint32: + convertTo = QVariant::UInt; + break; + case FactMetaData::valueTypeInt8: + case FactMetaData::valueTypeInt16: + case FactMetaData::valueTypeInt32: + convertTo = QVariant::Int; + break; + case FactMetaData::valueTypeFloat: + convertTo = QMetaType::Float; + break; + case FactMetaData::valueTypeDouble: + convertTo = QVariant::Double; + break; + } + + *convertOk = var.convert(convertTo); + + return var; +} + +/// Load Parameter Fact meta data +/// +/// The meta data comes from firmware parameters.xml file. +void APMParameterLoader::loadParameterFactMetaData(void) +{ + if (_parameterMetaDataLoaded) { + return; + } + _parameterMetaDataLoaded = true; + + // FIXME: NYI + + // Static meta data should load all MAV_TYPEs from single meta data file in such a way that the loader + // has multiple sets of static meta data +} + +void APMParameterLoader::clearStaticData(void) +{ + foreach(QString parameterName, _mapParameterName2FactMetaData.keys()) { + delete _mapParameterName2FactMetaData[parameterName]; + } + _mapParameterName2FactMetaData.clear(); + _parameterMetaDataLoaded = false; +} + +/// Override from FactLoad which connects the meta data to the fact +void APMParameterLoader::_addMetaDataToFact(Fact* fact) +{ + // FIXME: Will need to switch here based on _vehicle->firmwareType() to pull right set of meta data + + // Use generic meta data + ParameterLoader::_addMetaDataToFact(fact); +} diff --git a/src/FirmwarePlugin/APM/APMParameterLoader.h b/src/FirmwarePlugin/APM/APMParameterLoader.h new file mode 100644 index 0000000..4853b8a --- /dev/null +++ b/src/FirmwarePlugin/APM/APMParameterLoader.h @@ -0,0 +1,78 @@ +/*===================================================================== + + QGroundControl Open Source Ground Control Station + + (c) 2009 - 2014 QGROUNDCONTROL PROJECT + + This file is part of the QGROUNDCONTROL project + + QGROUNDCONTROL is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + QGROUNDCONTROL is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with QGROUNDCONTROL. If not, see . + + ======================================================================*/ + +#ifndef APMParameterLoader_H +#define APMParameterLoader_H + +#include +#include +#include +#include + +#include "ParameterLoader.h" +#include "FactSystem.h" +#include "AutoPilotPlugin.h" +#include "Vehicle.h" + +/// @file +/// @author Don Gagne + +Q_DECLARE_LOGGING_CATEGORY(APMParameterLoaderLog) + +/// Collection of Parameter Facts for PX4 AutoPilot + +class APMParameterLoader : public ParameterLoader +{ + Q_OBJECT + +public: + /// @param uas Uas which this set of facts is associated with + APMParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, QObject* parent = NULL); + + /// Override from ParameterLoader + virtual QString getDefaultComponentIdParam(void) const { return QString("SYSID_SW_TYPE"); } + + static void loadParameterFactMetaData(void); + static void clearStaticData(void); + +private: + enum { + XmlStateNone, + XmlStateFoundParameters, + XmlStateFoundVersion, + XmlStateFoundGroup, + XmlStateFoundParameter, + XmlStateDone + }; + + // Overrides from ParameterLoader + virtual void _addMetaDataToFact(Fact* fact); + + // Class methods + static QVariant _stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool* convertOk); + + static bool _parameterMetaDataLoaded; ///< true: parameter meta data already loaded + static QMap _mapParameterName2FactMetaData; ///< Maps from a parameter name to FactMetaData +}; + +#endif diff --git a/src/FirmwarePlugin/FirmwarePlugin.h b/src/FirmwarePlugin/FirmwarePlugin.h index eacd29e..a6a0b0a 100644 --- a/src/FirmwarePlugin/FirmwarePlugin.h +++ b/src/FirmwarePlugin/FirmwarePlugin.h @@ -105,6 +105,9 @@ public: /// false: Do not send first item to vehicle, sequence numbers must be adjusted virtual bool sendHomePositionToVehicle(void) = 0; + /// Returns the ParameterLoader + virtual ParameterLoader* getParameterLoader(AutoPilotPlugin* autopilotPlugin, Vehicle* vehicle) = 0; + protected: FirmwarePlugin(QObject* parent = NULL) : QGCSingleton(parent) { } }; diff --git a/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc b/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc index 0971990..a703627 100644 --- a/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc +++ b/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc @@ -25,13 +25,15 @@ /// @author Don Gagne #include "GenericFirmwarePlugin.h" +#include "AutoPilotPlugins/Generic/GenericAutoPilotPlugin.h" // FIXME: Hack #include IMPLEMENT_QGC_SINGLETON(GenericFirmwarePlugin, FirmwarePlugin) -GenericFirmwarePlugin::GenericFirmwarePlugin(QObject* parent) : - FirmwarePlugin(parent) +GenericFirmwarePlugin::GenericFirmwarePlugin(QObject* parent) + : FirmwarePlugin(parent) + , _parameterLoader(NULL) { } @@ -118,3 +120,17 @@ bool GenericFirmwarePlugin::sendHomePositionToVehicle(void) // This is the mavlink spec default. return false; } + +ParameterLoader* GenericFirmwarePlugin::getParameterLoader(AutoPilotPlugin* autopilotPlugin, Vehicle* vehicle) +{ + if (!_parameterLoader) { + _parameterLoader = new GenericParameterLoader(autopilotPlugin, vehicle, this); + Q_CHECK_PTR(_parameterLoader); + + // FIXME: Why do I need SIGNAL/SLOT to make this work + connect(_parameterLoader, SIGNAL(parametersReady(bool)), autopilotPlugin, SLOT(_parametersReadyPreChecks(bool))); + connect(_parameterLoader, &GenericParameterLoader::parameterListProgress, autopilotPlugin, &GenericAutoPilotPlugin::parameterListProgress); + } + + return _parameterLoader; +} diff --git a/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h b/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h index abeb96e..afc8c8d 100644 --- a/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h +++ b/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h @@ -28,6 +28,7 @@ #define GenericFirmwarePlugin_H #include "FirmwarePlugin.h" +#include "GenericParameterLoader.h" class GenericFirmwarePlugin : public FirmwarePlugin { @@ -47,10 +48,13 @@ public: virtual void adjustMavlinkMessage(mavlink_message_t* message); virtual void initializeVehicle(Vehicle* vehicle); virtual bool sendHomePositionToVehicle(void); + virtual ParameterLoader* getParameterLoader(AutoPilotPlugin *autopilotPlugin, Vehicle* vehicle); private: /// All access to singleton is through AutoPilotPluginManager::instance GenericFirmwarePlugin(QObject* parent = NULL); + + GenericParameterLoader* _parameterLoader; }; #endif diff --git a/src/FirmwarePlugin/Generic/GenericParameterLoader.cc b/src/FirmwarePlugin/Generic/GenericParameterLoader.cc new file mode 100644 index 0000000..20439ea --- /dev/null +++ b/src/FirmwarePlugin/Generic/GenericParameterLoader.cc @@ -0,0 +1,37 @@ +/*===================================================================== + + QGroundControl Open Source Ground Control Station + + (c) 2009 - 2014 QGROUNDCONTROL PROJECT + + This file is part of the QGROUNDCONTROL project + + QGROUNDCONTROL is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + QGROUNDCONTROL is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with QGROUNDCONTROL. If not, see . + + ======================================================================*/ + +#include "GenericParameterLoader.h" + +GenericParameterLoader::GenericParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, QObject* parent) : + ParameterLoader(autopilot, vehicle, parent) +{ + Q_ASSERT(vehicle); +} + +/// Override from ParameterLoader which connects the meta data to the fact +void GenericParameterLoader::_addMetaDataToFact(Fact* fact) +{ + // Use generic meta data + ParameterLoader::_addMetaDataToFact(fact); +} diff --git a/src/FirmwarePlugin/Generic/GenericParameterLoader.h b/src/FirmwarePlugin/Generic/GenericParameterLoader.h new file mode 100644 index 0000000..98aa7f2 --- /dev/null +++ b/src/FirmwarePlugin/Generic/GenericParameterLoader.h @@ -0,0 +1,48 @@ +/*===================================================================== + + QGroundControl Open Source Ground Control Station + + (c) 2009 - 2014 QGROUNDCONTROL PROJECT + + This file is part of the QGROUNDCONTROL project + + QGROUNDCONTROL is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + QGROUNDCONTROL is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with QGROUNDCONTROL. If not, see . + + ======================================================================*/ + +#ifndef GenericParameterLoader_H +#define GenericParameterLoader_H + +#include "ParameterLoader.h" +#include "FactSystem.h" +#include "AutoPilotPlugin.h" +#include "Vehicle.h" + +class GenericParameterLoader : public ParameterLoader +{ + Q_OBJECT + +public: + /// @param uas Uas which this set of facts is associated with + GenericParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, QObject* parent = NULL); + + /// Override from ParameterLoader + virtual QString getDefaultComponentIdParam(void) const { return QString(); } + +private: + // Overrides from ParameterLoader + virtual void _addMetaDataToFact(Fact* fact); +}; + +#endif diff --git a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc index d78c191..80d3ace 100644 --- a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc +++ b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc @@ -25,6 +25,7 @@ /// @author Don Gagne #include "PX4FirmwarePlugin.h" +#include "AutoPilotPlugins/PX4/PX4AutoPilotPlugin.h" // FIXME: Hack #include @@ -85,8 +86,9 @@ static const struct Modes2Name rgModes2Name[] = { }; -PX4FirmwarePlugin::PX4FirmwarePlugin(QObject* parent) : - FirmwarePlugin(parent) +PX4FirmwarePlugin::PX4FirmwarePlugin(QObject* parent) + : FirmwarePlugin(parent) + , _parameterLoader(NULL) { } @@ -207,3 +209,19 @@ bool PX4FirmwarePlugin::sendHomePositionToVehicle(void) // Subsequent sequence numbers must be adjusted. return false; } + +ParameterLoader* PX4FirmwarePlugin::getParameterLoader(AutoPilotPlugin* autopilotPlugin, Vehicle* vehicle) +{ + if (!_parameterLoader) { + _parameterLoader = new PX4ParameterLoader(autopilotPlugin, vehicle, this); + Q_CHECK_PTR(_parameterLoader); + + // FIXME: Why do I need SIGNAL/SLOT to make this work + connect(_parameterLoader, SIGNAL(parametersReady(bool)), autopilotPlugin, SLOT(_parametersReadyPreChecks(bool))); + connect(_parameterLoader, &PX4ParameterLoader::parameterListProgress, autopilotPlugin, &PX4AutoPilotPlugin::parameterListProgress); + + _parameterLoader->loadParameterFactMetaData(); + } + + return _parameterLoader; +} diff --git a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h index ebbd49e..a78693a 100644 --- a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h +++ b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h @@ -28,6 +28,7 @@ #define PX4FirmwarePlugin_H #include "FirmwarePlugin.h" +#include "PX4ParameterLoader.h" class PX4FirmwarePlugin : public FirmwarePlugin { @@ -47,10 +48,13 @@ public: virtual void adjustMavlinkMessage(mavlink_message_t* message); virtual void initializeVehicle(Vehicle* vehicle); virtual bool sendHomePositionToVehicle(void); + virtual ParameterLoader* getParameterLoader(AutoPilotPlugin *autopilotPlugin, Vehicle* vehicle); private: /// All access to singleton is through AutoPilotPluginManager::instance PX4FirmwarePlugin(QObject* parent = NULL); + + PX4ParameterLoader* _parameterLoader; }; #endif diff --git a/src/FirmwarePlugin/PX4/PX4ParameterLoader.cc b/src/FirmwarePlugin/PX4/PX4ParameterLoader.cc new file mode 100644 index 0000000..aea72c1 --- /dev/null +++ b/src/FirmwarePlugin/PX4/PX4ParameterLoader.cc @@ -0,0 +1,352 @@ +/*===================================================================== + + 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 "PX4ParameterLoader.h" +#include "QGCApplication.h" +#include "QGCLoggingCategory.h" + +#include +#include +#include +#include + +QGC_LOGGING_CATEGORY(PX4ParameterLoaderLog, "PX4ParameterLoaderLog") + +bool PX4ParameterLoader::_parameterMetaDataLoaded = false; +QMap PX4ParameterLoader::_mapParameterName2FactMetaData; + +PX4ParameterLoader::PX4ParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, QObject* parent) : + ParameterLoader(autopilot, vehicle, parent) +{ + Q_ASSERT(vehicle); +} + +/// Converts a string to a typed QVariant +/// @param string String to convert +/// @param type Type for Fact which dictates the QVariant type as well +/// @param convertOk Returned: true: conversion success, false: conversion failure +/// @return Returns the correctly type QVariant +QVariant PX4ParameterLoader::_stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool* convertOk) +{ + QVariant var(string); + + int convertTo = QVariant::Int; // keep compiler warning happy + switch (type) { + case FactMetaData::valueTypeUint8: + case FactMetaData::valueTypeUint16: + case FactMetaData::valueTypeUint32: + convertTo = QVariant::UInt; + break; + case FactMetaData::valueTypeInt8: + case FactMetaData::valueTypeInt16: + case FactMetaData::valueTypeInt32: + convertTo = QVariant::Int; + break; + case FactMetaData::valueTypeFloat: + convertTo = QMetaType::Float; + break; + case FactMetaData::valueTypeDouble: + convertTo = QVariant::Double; + break; + } + + *convertOk = var.convert(convertTo); + + return var; +} + +/// Load Parameter Fact meta data +/// +/// The meta data comes from firmware parameters.xml file. +void PX4ParameterLoader::loadParameterFactMetaData(void) +{ + if (_parameterMetaDataLoaded) { + return; + } + _parameterMetaDataLoaded = true; + + qCDebug(PX4ParameterLoaderLog) << "Loading PX4 parameter fact meta data"; + + Q_ASSERT(_mapParameterName2FactMetaData.count() == 0); + + QString parameterFilename; + + // We want unit test builds to always use the resource based meta data to provide repeatable results + if (!qgcApp()->runningUnitTests()) { + // First look for meta data that comes from a firmware download. Fall back to resource if not there. + QSettings settings; + QDir parameterDir = QFileInfo(settings.fileName()).dir(); + parameterFilename = parameterDir.filePath("PX4ParameterFactMetaData.xml"); + } + if (parameterFilename.isEmpty() || !QFile(parameterFilename).exists()) { + parameterFilename = ":/AutoPilotPlugins/PX4/ParameterFactMetaData.xml"; + } + + qCDebug(PX4ParameterLoaderLog) << "Loading parameter meta data:" << parameterFilename; + + QFile xmlFile(parameterFilename); + Q_ASSERT(xmlFile.exists()); + + bool success = xmlFile.open(QIODevice::ReadOnly); + Q_UNUSED(success); + Q_ASSERT(success); + + QXmlStreamReader xml(xmlFile.readAll()); + xmlFile.close(); + if (xml.hasError()) { + qWarning() << "Badly formed XML" << xml.errorString(); + return; + } + + QString factGroup; + QString errorString; + FactMetaData* metaData = NULL; + int xmlState = XmlStateNone; + bool badMetaData = true; + + while (!xml.atEnd()) { + if (xml.isStartElement()) { + QString elementName = xml.name().toString(); + + if (elementName == "parameters") { + if (xmlState != XmlStateNone) { + qWarning() << "Badly formed XML"; + return; + } + xmlState = XmlStateFoundParameters; + + } else if (elementName == "version") { + if (xmlState != XmlStateFoundParameters) { + qWarning() << "Badly formed XML"; + return; + } + xmlState = XmlStateFoundVersion; + + bool convertOk; + QString strVersion = xml.readElementText(); + int intVersion = strVersion.toInt(&convertOk); + if (!convertOk) { + qWarning() << "Badly formed XML"; + return; + } + if (intVersion <= 2) { + // We can't read these old files + qDebug() << "Parameter version stamp too old, skipping load. Found:" << intVersion << "Want: 3 File:" << parameterFilename; + return; + } + + + } else if (elementName == "group") { + if (xmlState != XmlStateFoundVersion) { + // We didn't get a version stamp, assume older version we can't read + qDebug() << "Parameter version stamp not found, skipping load" << parameterFilename; + return; + } + xmlState = XmlStateFoundGroup; + + if (!xml.attributes().hasAttribute("name")) { + qWarning() << "Badly formed XML"; + return; + } + factGroup = xml.attributes().value("name").toString(); + qCDebug(PX4ParameterLoaderLog) << "Found group: " << factGroup; + + } else if (elementName == "parameter") { + if (xmlState != XmlStateFoundGroup) { + qWarning() << "Badly formed XML"; + return; + } + xmlState = XmlStateFoundParameter; + + if (!xml.attributes().hasAttribute("name") || !xml.attributes().hasAttribute("type")) { + qWarning() << "Badly formed XML"; + return; + } + + QString name = xml.attributes().value("name").toString(); + QString type = xml.attributes().value("type").toString(); + QString strDefault = xml.attributes().value("default").toString(); + + qCDebug(PX4ParameterLoaderLog) << "Found parameter name:" << name << " type:" << type << " default:" << strDefault; + + // Convert type from string to FactMetaData::ValueType_t + + struct String2Type { + const char* strType; + FactMetaData::ValueType_t type; + }; + + static const struct String2Type rgString2Type[] = { + { "FLOAT", FactMetaData::valueTypeFloat }, + { "INT32", FactMetaData::valueTypeInt32 }, + }; + static const size_t crgString2Type = sizeof(rgString2Type) / sizeof(rgString2Type[0]); + + bool found = false; + FactMetaData::ValueType_t foundType; + for (size_t i=0; istrType) { + found = true; + foundType = info->type; + break; + } + } + if (!found) { + qWarning() << "Parameter meta data with bad type:" << type << " name:" << name; + return; + } + + // Now that we know type we can create meta data object and add it to the system + + metaData = new FactMetaData(foundType); + Q_CHECK_PTR(metaData); + if (_mapParameterName2FactMetaData.contains(name)) { + // We can't trust the meta dafa since we have dups + qCWarning(PX4ParameterLoaderLog) << "Duplicate parameter found:" << name; + badMetaData = true; + // Reset to default meta data + _mapParameterName2FactMetaData[name] = metaData; + } else { + _mapParameterName2FactMetaData[name] = metaData; + metaData->setName(name); + metaData->setGroup(factGroup); + + if (xml.attributes().hasAttribute("default") && !strDefault.isEmpty()) { + QVariant varDefault; + + if (metaData->convertAndValidate(strDefault, false, varDefault, errorString)) { + metaData->setDefaultValue(varDefault); + } else { + qCWarning(PX4ParameterLoaderLog) << "Invalid default value, name:" << name << " type:" << type << " default:" << strDefault << " error:" << errorString; + } + } + } + + } else { + // We should be getting meta data now + if (xmlState != XmlStateFoundParameter) { + qWarning() << "Badly formed XML"; + return; + } + + if (!badMetaData) { + if (elementName == "short_desc") { + Q_ASSERT(metaData); + QString text = xml.readElementText(); + text = text.replace("\n", " "); + qCDebug(PX4ParameterLoaderLog) << "Short description:" << text; + metaData->setShortDescription(text); + + } else if (elementName == "long_desc") { + Q_ASSERT(metaData); + QString text = xml.readElementText(); + text = text.replace("\n", " "); + qCDebug(PX4ParameterLoaderLog) << "Long description:" << text; + metaData->setLongDescription(text); + + } else if (elementName == "min") { + Q_ASSERT(metaData); + QString text = xml.readElementText(); + qCDebug(PX4ParameterLoaderLog) << "Min:" << text; + + QVariant varMin; + if (metaData->convertAndValidate(text, true /* convertOnly */, varMin, errorString)) { + metaData->setMin(varMin); + } else { + qCWarning(PX4ParameterLoaderLog) << "Invalid min value, name:" << metaData->name() << " type:" << metaData->type() << " min:" << text << " error:" << errorString; + } + + } else if (elementName == "max") { + Q_ASSERT(metaData); + QString text = xml.readElementText(); + qCDebug(PX4ParameterLoaderLog) << "Max:" << text; + + QVariant varMax; + if (metaData->convertAndValidate(text, true /* convertOnly */, varMax, errorString)) { + metaData->setMax(varMax); + } else { + qCWarning(PX4ParameterLoaderLog) << "Invalid max value, name:" << metaData->name() << " type:" << metaData->type() << " max:" << text << " error:" << errorString; + } + + } else if (elementName == "unit") { + Q_ASSERT(metaData); + QString text = xml.readElementText(); + qCDebug(PX4ParameterLoaderLog) << "Unit:" << text; + metaData->setUnits(text); + + } else { + qDebug() << "Unknown element in XML: " << elementName; + } + } + } + } else if (xml.isEndElement()) { + QString elementName = xml.name().toString(); + + if (elementName == "parameter") { + // Done loading this parameter, validate default value + if (metaData->defaultValueAvailable()) { + QVariant var; + + if (!metaData->convertAndValidate(metaData->defaultValue(), false /* convertOnly */, var, errorString)) { + qCWarning(PX4ParameterLoaderLog) << "Invalid default value, name:" << metaData->name() << " type:" << metaData->type() << " default:" << metaData->defaultValue() << " error:" << errorString; + } + } + + // Reset for next parameter + metaData = NULL; + badMetaData = false; + xmlState = XmlStateFoundGroup; + } else if (elementName == "group") { + xmlState = XmlStateFoundVersion; + } else if (elementName == "parameters") { + xmlState = XmlStateFoundParameters; + } + } + xml.readNext(); + } +} + +void PX4ParameterLoader::clearStaticData(void) +{ + foreach(QString parameterName, _mapParameterName2FactMetaData.keys()) { + delete _mapParameterName2FactMetaData[parameterName]; + } + _mapParameterName2FactMetaData.clear(); + _parameterMetaDataLoaded = false; +} + +/// Override from FactLoad which connects the meta data to the fact +void PX4ParameterLoader::_addMetaDataToFact(Fact* fact) +{ + if (_mapParameterName2FactMetaData.contains(fact->name())) { + fact->setMetaData(_mapParameterName2FactMetaData[fact->name()]); + } else { + // Use generic meta data + ParameterLoader::_addMetaDataToFact(fact); + } +} diff --git a/src/FirmwarePlugin/PX4/PX4ParameterLoader.h b/src/FirmwarePlugin/PX4/PX4ParameterLoader.h new file mode 100644 index 0000000..8d4b8b9 --- /dev/null +++ b/src/FirmwarePlugin/PX4/PX4ParameterLoader.h @@ -0,0 +1,78 @@ +/*===================================================================== + + QGroundControl Open Source Ground Control Station + + (c) 2009 - 2014 QGROUNDCONTROL PROJECT + + This file is part of the QGROUNDCONTROL project + + QGROUNDCONTROL is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + QGROUNDCONTROL is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with QGROUNDCONTROL. If not, see . + + ======================================================================*/ + +#ifndef PX4PARAMETERLOADER_H +#define PX4PARAMETERLOADER_H + +#include +#include +#include +#include + +#include "ParameterLoader.h" +#include "FactSystem.h" +#include "AutoPilotPlugin.h" +#include "Vehicle.h" + +/// @file +/// @author Don Gagne + +Q_DECLARE_LOGGING_CATEGORY(PX4ParameterLoaderLog) + +/// Collection of Parameter Facts for PX4 AutoPilot + +class PX4ParameterLoader : public ParameterLoader +{ + Q_OBJECT + +public: + /// @param uas Uas which this set of facts is associated with + PX4ParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, QObject* parent = NULL); + + /// Override from ParameterLoader + virtual QString getDefaultComponentIdParam(void) const { return QString("SYS_AUTOSTART"); } + + static void loadParameterFactMetaData(void); + static void clearStaticData(void); + +private: + enum { + XmlStateNone, + XmlStateFoundParameters, + XmlStateFoundVersion, + XmlStateFoundGroup, + XmlStateFoundParameter, + XmlStateDone + }; + + // Overrides from ParameterLoader + virtual void _addMetaDataToFact(Fact* fact); + + // Class methods + static QVariant _stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool* convertOk); + + static bool _parameterMetaDataLoaded; ///< true: parameter meta data already loaded + static QMap _mapParameterName2FactMetaData; ///< Maps from a parameter name to FactMetaData +}; + +#endif \ No newline at end of file From 8fdb52f5032885c8c7396ce884e8b6f07e45817c Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Sun, 25 Oct 2015 13:28:52 -0700 Subject: [PATCH 02/16] Fix signalling --- src/Vehicle/Vehicle.cc | 29 ++++++++++++++++++++++------- 1 file changed, 22 insertions(+), 7 deletions(-) diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 1991995..f97a7ed 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -202,17 +202,32 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes void Vehicle::_handleHomePosition(mavlink_message_t& message) { + bool emitHomePositionChanged = false; + bool emitHomePositionAvailableChanged = false; + mavlink_home_position_t homePos; mavlink_msg_home_position_decode(&message, &homePos); - - _homePosition.setLatitude(homePos.latitude / 10000000.0); - _homePosition.setLongitude(homePos.longitude / 10000000.0); - _homePosition.setAltitude(homePos.altitude / 1000.0); + + QGeoCoordinate newHomePosition (homePos.latitude / 10000000.0, + homePos.longitude / 10000000.0, + homePos.altitude / 1000.0); + if (newHomePosition != _homePosition) { + emitHomePositionChanged = true; + _homePosition = newHomePosition; + } + + if (!_homePositionAvailable) { + emitHomePositionAvailableChanged = true; + } _homePositionAvailable = true; - - emit homePositionChanged(_homePosition); - emit homePositionAvailableChanged(true); + + if (emitHomePositionChanged) { + emit homePositionChanged(_homePosition); + } + if (emitHomePositionAvailableChanged) { + emit homePositionAvailableChanged(true); + } } void Vehicle::_handleHeartbeat(mavlink_message_t& message) From 6025c37980f92852dcebe7a7d841cdac1a1cda51 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Sun, 25 Oct 2015 13:29:07 -0700 Subject: [PATCH 03/16] Fix home position handling --- src/MissionManager/MissionController.cc | 45 ++++++++++++++++++++------------- src/MissionManager/MissionController.h | 3 ++- 2 files changed, 29 insertions(+), 19 deletions(-) diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc index bad3024..01f9be4 100644 --- a/src/MissionManager/MissionController.cc +++ b/src/MissionManager/MissionController.cc @@ -66,21 +66,23 @@ void MissionController::start(bool editMode) connect(multiVehicleMgr, &MultiVehicleManager::activeVehicleChanged, this, &MissionController::_activeVehicleChanged); - _setupMissionItems(true /* fromVehicle */, true /* force */); + _setupMissionItems(true /* loadFromVehicle */, true /* forceLoad */); + _setupActiveVehicle(multiVehicleMgr->activeVehicle(), true /* forceLoadFromVehicle */); } void MissionController::_newMissionItemsAvailableFromVehicle(void) { qCDebug(MissionControllerLog) << "_newMissionItemsAvailableFromVehicle"; - _setupMissionItems(true /* fromVehicle */, false /* force */); + _setupMissionItems(true /* loadFromVehicle */, false /* forceLoad */); } -/// @param fromVehicle true: load items from vehicle -/// @param force true: disregard any flags which may prevent load -void MissionController::_setupMissionItems(bool fromVehicle, bool force) +/// @param loadFromVehicle true: load items from vehicle +/// @param forceLoad true: disregard any flags which may prevent load +void MissionController::_setupMissionItems(bool loadFromVehicle, bool forceLoad) { - qCDebug(MissionControllerLog) << "_setupMissionItems fromVehicle:force:_editMode:_firstItemsFromVehicle" << fromVehicle << force << _editMode << _firstItemsFromVehicle; + qCDebug(MissionControllerLog) << "_setupMissionItems loadFromVehicle:forceLoad:_editMode:_firstItemsFromVehicle" + << loadFromVehicle << forceLoad << _editMode << _firstItemsFromVehicle; MissionManager* missionManager = NULL; if (_activeVehicle) { @@ -89,8 +91,8 @@ void MissionController::_setupMissionItems(bool fromVehicle, bool force) qCDebug(MissionControllerLog) << "running offline"; } - if (!force) { - if (_editMode && fromVehicle) { + if (!forceLoad) { + if (_editMode && loadFromVehicle) { if (_firstItemsFromVehicle) { if (missionManager) { if (missionManager->inProgress()) { @@ -126,7 +128,7 @@ void MissionController::_setupMissionItems(bool fromVehicle, bool force) _missionItems->deleteLater(); } - if (!missionManager || !fromVehicle || missionManager->inProgress()) { + if (!missionManager || !loadFromVehicle || missionManager->inProgress()) { _canEdit = true; _missionItems = new QmlObjectListModel(this); qCDebug(MissionControllerLog) << "creating empty set"; @@ -440,10 +442,22 @@ void MissionController::_activeVehicleChanged(Vehicle* activeVehicle) _activeVehicle = NULL; // When the active vehicle goes away we toss the editor items - _setupMissionItems(false /* fromVehicle */, true /* force */); + _setupMissionItems(false /* loadFromVehicle */, true /* forceLoad */); _activeVehicleHomePositionAvailableChanged(false); } + _setupActiveVehicle(activeVehicle, false /* forceLoadFromVehicle */); +} + +void MissionController::_setupActiveVehicle(Vehicle* activeVehicle, bool forceLoadFromVehicle) +{ + qCDebug(MissionControllerLog) << "_setupActiveVehicle activeVehicle:forceLoadFromVehicle" + << activeVehicle << forceLoadFromVehicle; + + if (_activeVehicle) { + qCWarning(MissionControllerLog) << "_activeVehicle != NULL"; + } + _activeVehicle = activeVehicle; if (_activeVehicle) { @@ -455,7 +469,7 @@ void MissionController::_activeVehicleChanged(Vehicle* activeVehicle) connect(_activeVehicle, &Vehicle::homePositionChanged, this, &MissionController::_activeVehicleHomePositionChanged); _firstItemsFromVehicle = true; - _setupMissionItems(true /* fromVehicle */, false /* force */); + _setupMissionItems(true /* fromVehicle */, forceLoadFromVehicle); _activeVehicleHomePositionChanged(_activeVehicle->homePosition()); _activeVehicleHomePositionAvailableChanged(_activeVehicle->homePositionAvailable()); @@ -464,20 +478,15 @@ void MissionController::_activeVehicleChanged(Vehicle* activeVehicle) void MissionController::_activeVehicleHomePositionAvailableChanged(bool homePositionAvailable) { - MissionItem* homeItem = qobject_cast(_missionItems->get(0)); - - if (homePositionAvailable) { - homeItem->setCoordinate(_liveHomePosition); - } - homeItem->setHomePositionValid(homePositionAvailable); - _liveHomePositionAvailable = homePositionAvailable; + qobject_cast(_missionItems->get(0))->setHomePositionValid(homePositionAvailable); emit liveHomePositionAvailableChanged(_liveHomePositionAvailable); } void MissionController::_activeVehicleHomePositionChanged(const QGeoCoordinate& homePosition) { _liveHomePosition = homePosition; + qobject_cast(_missionItems->get(0))->setCoordinate(_liveHomePosition); emit liveHomePositionChanged(_liveHomePosition); } diff --git a/src/MissionManager/MissionController.h b/src/MissionManager/MissionController.h index 50078c9..2913268 100644 --- a/src/MissionManager/MissionController.h +++ b/src/MissionManager/MissionController.h @@ -94,7 +94,8 @@ private: void _initMissionItem(MissionItem* item); void _deinitMissionItem(MissionItem* item); void _autoSyncSend(void); - void _setupMissionItems(bool fromVehicle, bool force); + void _setupMissionItems(bool loadFromVehicle, bool forceLoad); + void _setupActiveVehicle(Vehicle* activeVehicle, bool forceLoadFromVehicle); private: bool _editMode; From 32b9124d305c1000afd13d66a9cc72aef4a0c6c8 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Sun, 25 Oct 2015 13:29:17 -0700 Subject: [PATCH 04/16] Fix item dragging --- src/MissionEditor/MissionEditor.qml | 2 -- 1 file changed, 2 deletions(-) diff --git a/src/MissionEditor/MissionEditor.qml b/src/MissionEditor/MissionEditor.qml index 83f00d5..a7e92f5 100644 --- a/src/MissionEditor/MissionEditor.qml +++ b/src/MissionEditor/MissionEditor.qml @@ -322,8 +322,6 @@ QGCView { // Move to the new position editorMap.latitude = object.coordinate.latitude editorMap.longitude = object.coordinate.longitude - } else { - itemDragger.clearItem() } } } From ba4acf82e9afe2b0ef69e4e1013395be0cd2e45e Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Sun, 25 Oct 2015 13:29:41 -0700 Subject: [PATCH 05/16] Decimal place support from meta data --- src/AutoPilotPlugins/PX4/PX4ParameterLoader.cc | 13 ++++++++ src/FactSystem/Fact.cc | 27 +++++++++++++++- src/FactSystem/Fact.h | 34 ++++++++++---------- src/FactSystem/FactMetaData.cc | 43 ++++++++++++++------------ src/FactSystem/FactMetaData.h | 27 +++++++++------- src/MissionItem.cc | 15 +++------ 6 files changed, 100 insertions(+), 59 deletions(-) diff --git a/src/AutoPilotPlugins/PX4/PX4ParameterLoader.cc b/src/AutoPilotPlugins/PX4/PX4ParameterLoader.cc index aea72c1..c7d989d 100644 --- a/src/AutoPilotPlugins/PX4/PX4ParameterLoader.cc +++ b/src/AutoPilotPlugins/PX4/PX4ParameterLoader.cc @@ -299,6 +299,19 @@ void PX4ParameterLoader::loadParameterFactMetaData(void) qCDebug(PX4ParameterLoaderLog) << "Unit:" << text; metaData->setUnits(text); + } else if (elementName == "decimal") { + Q_ASSERT(metaData); + QString text = xml.readElementText(); + qCDebug(PX4ParameterLoaderLog) << "Decimal:" << text; + + bool convertOk; + QVariant varDecimals = QVariant(text).toUInt(&convertOk); + if (convertOk) { + metaData->setDecimalPlaces(varDecimals.toInt()); + } else { + qCWarning(PX4ParameterLoaderLog) << "Invalid decimals value, name:" << metaData->name() << " type:" << metaData->type() << " decimals:" << text << " error: invalid number"; + } + } else { qDebug() << "Unknown element in XML: " << elementName; } diff --git a/src/FactSystem/Fact.cc b/src/FactSystem/Fact.cc index a69b258..09441f6 100644 --- a/src/FactSystem/Fact.cc +++ b/src/FactSystem/Fact.cc @@ -131,7 +131,22 @@ QVariant Fact::value(void) const QString Fact::valueString(void) const { - return _value.toString(); + QString valueString; + + switch (type()) { + case FactMetaData::valueTypeFloat: + qDebug() << name() << value() << decimalPlaces(); + valueString = QString("%1").arg(value().toFloat(), 0, 'g', decimalPlaces()); + break; + case FactMetaData::valueTypeDouble: + valueString = QString("%1").arg(value().toDouble(), 0, 'g', decimalPlaces()); + break; + default: + valueString = value().toString(); + break; + } + + return valueString; } QVariant Fact::defaultValue(void) const @@ -222,6 +237,16 @@ bool Fact::maxIsDefaultForType(void) const } } +int Fact::decimalPlaces(void) const +{ + if (_metaData) { + return _metaData->decimalPlaces(); + } else { + qWarning() << "Meta data pointer missing"; + return FactMetaData::defaultDecimalPlaces; + } +} + QString Fact::group(void) const { if (_metaData) { diff --git a/src/FactSystem/Fact.h b/src/FactSystem/Fact.h index da8a85e..c946b19 100644 --- a/src/FactSystem/Fact.h +++ b/src/FactSystem/Fact.h @@ -46,22 +46,23 @@ public: const Fact& operator=(const Fact& other); - Q_PROPERTY(int componentId READ componentId CONSTANT) - Q_PROPERTY(QString name READ name CONSTANT) - Q_PROPERTY(QVariant value READ value WRITE setValue NOTIFY valueChanged USER true) - Q_PROPERTY(QVariant valueString READ valueString NOTIFY valueChanged) - Q_PROPERTY(QString units READ units CONSTANT) - Q_PROPERTY(QVariant defaultValue READ defaultValue CONSTANT) - Q_PROPERTY(bool defaultValueAvailable READ defaultValueAvailable CONSTANT) - Q_PROPERTY(bool valueEqualsDefault READ valueEqualsDefault NOTIFY valueChanged) - Q_PROPERTY(FactMetaData::ValueType_t type READ type CONSTANT) - Q_PROPERTY(QString shortDescription READ shortDescription CONSTANT) - Q_PROPERTY(QString longDescription READ longDescription CONSTANT) - Q_PROPERTY(QVariant min READ min CONSTANT) - Q_PROPERTY(bool minIsDefaultForType READ minIsDefaultForType CONSTANT) - Q_PROPERTY(QVariant max READ max CONSTANT) - Q_PROPERTY(bool maxIsDefaultForType READ maxIsDefaultForType CONSTANT) - Q_PROPERTY(QString group READ group CONSTANT) + Q_PROPERTY(int componentId READ componentId CONSTANT) + Q_PROPERTY(QString group READ group CONSTANT) + Q_PROPERTY(QString name READ name CONSTANT) + Q_PROPERTY(QVariant value READ value WRITE setValue NOTIFY valueChanged USER true) + Q_PROPERTY(QVariant valueString READ valueString NOTIFY valueChanged) + Q_PROPERTY(QString units READ units CONSTANT) + Q_PROPERTY(QVariant defaultValue READ defaultValue CONSTANT) + Q_PROPERTY(bool defaultValueAvailable READ defaultValueAvailable CONSTANT) + Q_PROPERTY(bool valueEqualsDefault READ valueEqualsDefault NOTIFY valueChanged) + Q_PROPERTY(FactMetaData::ValueType_t type READ type CONSTANT) + Q_PROPERTY(QString shortDescription READ shortDescription CONSTANT) + Q_PROPERTY(QString longDescription READ longDescription CONSTANT) + Q_PROPERTY(QVariant min READ min CONSTANT) + Q_PROPERTY(bool minIsDefaultForType READ minIsDefaultForType CONSTANT) + Q_PROPERTY(QVariant max READ max CONSTANT) + Q_PROPERTY(bool maxIsDefaultForType READ maxIsDefaultForType CONSTANT) + Q_PROPERTY(int decimalPlaces READ decimalPlaces CONSTANT) /// Convert and validate value /// @param convertOnly true: validate type conversion only, false: validate against meta data as well @@ -86,6 +87,7 @@ public: QVariant max(void) const; bool maxIsDefaultForType(void) const; QString group(void) const; + int decimalPlaces(void) const; /// Sets and sends new value to vehicle even if value is the same void forceSetValue(const QVariant& value); diff --git a/src/FactSystem/FactMetaData.cc b/src/FactSystem/FactMetaData.cc index 7360e65..942d4e3 100644 --- a/src/FactSystem/FactMetaData.cc +++ b/src/FactSystem/FactMetaData.cc @@ -32,30 +32,32 @@ #include -FactMetaData::FactMetaData(QObject* parent) : - QObject(parent), - _group("*Default Group"), - _type(valueTypeInt32), - _defaultValue(0), - _defaultValueAvailable(false), - _min(_minForType()), - _max(_maxForType()), - _minIsDefaultForType(true), - _maxIsDefaultForType(true) +FactMetaData::FactMetaData(QObject* parent) + : QObject(parent) + , _group("*Default Group") + , _type(valueTypeInt32) + , _defaultValue(0) + , _defaultValueAvailable(false) + , _min(_minForType()) + , _max(_maxForType()) + , _minIsDefaultForType(true) + , _maxIsDefaultForType(true) + , _decimalPlaces(defaultDecimalPlaces) { } -FactMetaData::FactMetaData(ValueType_t type, QObject* parent) : - QObject(parent), - _group("*Default Group"), - _type(type), - _defaultValue(0), - _defaultValueAvailable(false), - _min(_minForType()), - _max(_maxForType()), - _minIsDefaultForType(true), - _maxIsDefaultForType(true) +FactMetaData::FactMetaData(ValueType_t type, QObject* parent) + : QObject(parent) + , _group("*Default Group") + , _type(type) + , _defaultValue(0) + , _defaultValueAvailable(false) + , _min(_minForType()) + , _max(_maxForType()) + , _minIsDefaultForType(true) + , _maxIsDefaultForType(true) + , _decimalPlaces(defaultDecimalPlaces) { } @@ -76,6 +78,7 @@ const FactMetaData& FactMetaData::operator=(const FactMetaData& other) _max = other._max; _minIsDefaultForType = other._minIsDefaultForType; _maxIsDefaultForType = other._maxIsDefaultForType; + _decimalPlaces = other._decimalPlaces; return *this; } diff --git a/src/FactSystem/FactMetaData.h b/src/FactSystem/FactMetaData.h index 49c72d8..03c78d2 100644 --- a/src/FactSystem/FactMetaData.h +++ b/src/FactSystem/FactMetaData.h @@ -59,18 +59,19 @@ public: const FactMetaData& operator=(const FactMetaData& other); // Property accessors - QString name(void) const { return _name; } - QString group(void) const { return _group; } - ValueType_t type(void) const { return _type; } + QString name(void) const { return _name; } + QString group(void) const { return _group; } + ValueType_t type(void) const { return _type; } QVariant defaultValue(void) const; - bool defaultValueAvailable(void) const { return _defaultValueAvailable; } - QString shortDescription(void) const { return _shortDescription; } - QString longDescription(void) const { return _longDescription;} - QString units(void) const { return _units; } - QVariant min(void) const { return _min; } - QVariant max(void) const { return _max; } - bool minIsDefaultForType(void) const { return _minIsDefaultForType; } - bool maxIsDefaultForType(void) const { return _maxIsDefaultForType; } + bool defaultValueAvailable(void) const { return _defaultValueAvailable; } + QString shortDescription(void) const { return _shortDescription; } + QString longDescription(void) const { return _longDescription;} + QString units(void) const { return _units; } + QVariant min(void) const { return _min; } + QVariant max(void) const { return _max; } + bool minIsDefaultForType(void) const { return _minIsDefaultForType; } + bool maxIsDefaultForType(void) const { return _maxIsDefaultForType; } + int decimalPlaces(void) const { return _decimalPlaces; } // Property setters void setName(const QString& name) { _name = name; } @@ -81,6 +82,7 @@ public: void setUnits(const QString& units) { _units = units; } void setMin(const QVariant& max); void setMax(const QVariant& max); + void setDecimalPlaces(int decimalPlaces) { _decimalPlaces = decimalPlaces; } /// Converts the specified value, validating against meta data /// @param value Value to convert, can be string @@ -90,6 +92,8 @@ public: /// @returns false: Convert failed, errorString set bool convertAndValidate(const QVariant& value, bool convertOnly, QVariant& typedValue, QString& errorString); + static const int defaultDecimalPlaces = 3; + private: QVariant _minForType(void) const; QVariant _maxForType(void) const; @@ -106,6 +110,7 @@ private: QVariant _max; bool _minIsDefaultForType; bool _maxIsDefaultForType; + int _decimalPlaces; }; #endif diff --git a/src/MissionItem.cc b/src/MissionItem.cc index 0d0943e..4e3f9d1 100644 --- a/src/MissionItem.cc +++ b/src/MissionItem.cc @@ -20,15 +20,6 @@ This file is part of the QGROUNDCONTROL project ======================================================================*/ -/** - * @file - * @brief MissionItem class - * - * @author Benjamin Knecht - * @author Petri Tanskanen - * - */ - #include #include @@ -115,10 +106,12 @@ MissionItem::MissionItem(QObject* parent, FactMetaData* latitudeMetaData = new FactMetaData(FactMetaData::valueTypeDouble, _latitudeFact); latitudeMetaData->setUnits("deg"); - + latitudeMetaData->setDecimalPlaces(7); + FactMetaData* longitudeMetaData = new FactMetaData(FactMetaData::valueTypeDouble, _longitudeFact); longitudeMetaData->setUnits("deg"); - + longitudeMetaData->setDecimalPlaces(7); + FactMetaData* altitudeMetaData = new FactMetaData(FactMetaData::valueTypeDouble, _altitudeFact); altitudeMetaData->setUnits("meters"); From d562a0233281210c952f51d9b1d647a7852ccdd2 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Sun, 25 Oct 2015 13:28:52 -0700 Subject: [PATCH 06/16] Fix signalling --- src/Vehicle/Vehicle.cc | 29 ++++++++++++++++++++++------- 1 file changed, 22 insertions(+), 7 deletions(-) diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 1991995..f97a7ed 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -202,17 +202,32 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes void Vehicle::_handleHomePosition(mavlink_message_t& message) { + bool emitHomePositionChanged = false; + bool emitHomePositionAvailableChanged = false; + mavlink_home_position_t homePos; mavlink_msg_home_position_decode(&message, &homePos); - - _homePosition.setLatitude(homePos.latitude / 10000000.0); - _homePosition.setLongitude(homePos.longitude / 10000000.0); - _homePosition.setAltitude(homePos.altitude / 1000.0); + + QGeoCoordinate newHomePosition (homePos.latitude / 10000000.0, + homePos.longitude / 10000000.0, + homePos.altitude / 1000.0); + if (newHomePosition != _homePosition) { + emitHomePositionChanged = true; + _homePosition = newHomePosition; + } + + if (!_homePositionAvailable) { + emitHomePositionAvailableChanged = true; + } _homePositionAvailable = true; - - emit homePositionChanged(_homePosition); - emit homePositionAvailableChanged(true); + + if (emitHomePositionChanged) { + emit homePositionChanged(_homePosition); + } + if (emitHomePositionAvailableChanged) { + emit homePositionAvailableChanged(true); + } } void Vehicle::_handleHeartbeat(mavlink_message_t& message) From acc8b92c4f09d652a6bd1de43165d5b518e3484a Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Sun, 25 Oct 2015 13:29:07 -0700 Subject: [PATCH 07/16] Fix home position handling --- src/MissionManager/MissionController.cc | 45 ++++++++++++++++++++------------- src/MissionManager/MissionController.h | 3 ++- 2 files changed, 29 insertions(+), 19 deletions(-) diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc index bad3024..01f9be4 100644 --- a/src/MissionManager/MissionController.cc +++ b/src/MissionManager/MissionController.cc @@ -66,21 +66,23 @@ void MissionController::start(bool editMode) connect(multiVehicleMgr, &MultiVehicleManager::activeVehicleChanged, this, &MissionController::_activeVehicleChanged); - _setupMissionItems(true /* fromVehicle */, true /* force */); + _setupMissionItems(true /* loadFromVehicle */, true /* forceLoad */); + _setupActiveVehicle(multiVehicleMgr->activeVehicle(), true /* forceLoadFromVehicle */); } void MissionController::_newMissionItemsAvailableFromVehicle(void) { qCDebug(MissionControllerLog) << "_newMissionItemsAvailableFromVehicle"; - _setupMissionItems(true /* fromVehicle */, false /* force */); + _setupMissionItems(true /* loadFromVehicle */, false /* forceLoad */); } -/// @param fromVehicle true: load items from vehicle -/// @param force true: disregard any flags which may prevent load -void MissionController::_setupMissionItems(bool fromVehicle, bool force) +/// @param loadFromVehicle true: load items from vehicle +/// @param forceLoad true: disregard any flags which may prevent load +void MissionController::_setupMissionItems(bool loadFromVehicle, bool forceLoad) { - qCDebug(MissionControllerLog) << "_setupMissionItems fromVehicle:force:_editMode:_firstItemsFromVehicle" << fromVehicle << force << _editMode << _firstItemsFromVehicle; + qCDebug(MissionControllerLog) << "_setupMissionItems loadFromVehicle:forceLoad:_editMode:_firstItemsFromVehicle" + << loadFromVehicle << forceLoad << _editMode << _firstItemsFromVehicle; MissionManager* missionManager = NULL; if (_activeVehicle) { @@ -89,8 +91,8 @@ void MissionController::_setupMissionItems(bool fromVehicle, bool force) qCDebug(MissionControllerLog) << "running offline"; } - if (!force) { - if (_editMode && fromVehicle) { + if (!forceLoad) { + if (_editMode && loadFromVehicle) { if (_firstItemsFromVehicle) { if (missionManager) { if (missionManager->inProgress()) { @@ -126,7 +128,7 @@ void MissionController::_setupMissionItems(bool fromVehicle, bool force) _missionItems->deleteLater(); } - if (!missionManager || !fromVehicle || missionManager->inProgress()) { + if (!missionManager || !loadFromVehicle || missionManager->inProgress()) { _canEdit = true; _missionItems = new QmlObjectListModel(this); qCDebug(MissionControllerLog) << "creating empty set"; @@ -440,10 +442,22 @@ void MissionController::_activeVehicleChanged(Vehicle* activeVehicle) _activeVehicle = NULL; // When the active vehicle goes away we toss the editor items - _setupMissionItems(false /* fromVehicle */, true /* force */); + _setupMissionItems(false /* loadFromVehicle */, true /* forceLoad */); _activeVehicleHomePositionAvailableChanged(false); } + _setupActiveVehicle(activeVehicle, false /* forceLoadFromVehicle */); +} + +void MissionController::_setupActiveVehicle(Vehicle* activeVehicle, bool forceLoadFromVehicle) +{ + qCDebug(MissionControllerLog) << "_setupActiveVehicle activeVehicle:forceLoadFromVehicle" + << activeVehicle << forceLoadFromVehicle; + + if (_activeVehicle) { + qCWarning(MissionControllerLog) << "_activeVehicle != NULL"; + } + _activeVehicle = activeVehicle; if (_activeVehicle) { @@ -455,7 +469,7 @@ void MissionController::_activeVehicleChanged(Vehicle* activeVehicle) connect(_activeVehicle, &Vehicle::homePositionChanged, this, &MissionController::_activeVehicleHomePositionChanged); _firstItemsFromVehicle = true; - _setupMissionItems(true /* fromVehicle */, false /* force */); + _setupMissionItems(true /* fromVehicle */, forceLoadFromVehicle); _activeVehicleHomePositionChanged(_activeVehicle->homePosition()); _activeVehicleHomePositionAvailableChanged(_activeVehicle->homePositionAvailable()); @@ -464,20 +478,15 @@ void MissionController::_activeVehicleChanged(Vehicle* activeVehicle) void MissionController::_activeVehicleHomePositionAvailableChanged(bool homePositionAvailable) { - MissionItem* homeItem = qobject_cast(_missionItems->get(0)); - - if (homePositionAvailable) { - homeItem->setCoordinate(_liveHomePosition); - } - homeItem->setHomePositionValid(homePositionAvailable); - _liveHomePositionAvailable = homePositionAvailable; + qobject_cast(_missionItems->get(0))->setHomePositionValid(homePositionAvailable); emit liveHomePositionAvailableChanged(_liveHomePositionAvailable); } void MissionController::_activeVehicleHomePositionChanged(const QGeoCoordinate& homePosition) { _liveHomePosition = homePosition; + qobject_cast(_missionItems->get(0))->setCoordinate(_liveHomePosition); emit liveHomePositionChanged(_liveHomePosition); } diff --git a/src/MissionManager/MissionController.h b/src/MissionManager/MissionController.h index 50078c9..2913268 100644 --- a/src/MissionManager/MissionController.h +++ b/src/MissionManager/MissionController.h @@ -94,7 +94,8 @@ private: void _initMissionItem(MissionItem* item); void _deinitMissionItem(MissionItem* item); void _autoSyncSend(void); - void _setupMissionItems(bool fromVehicle, bool force); + void _setupMissionItems(bool loadFromVehicle, bool forceLoad); + void _setupActiveVehicle(Vehicle* activeVehicle, bool forceLoadFromVehicle); private: bool _editMode; From 114f00c5b1ca0352ae0fcbeb84b17cd8b042099c Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Sun, 25 Oct 2015 13:29:17 -0700 Subject: [PATCH 08/16] Fix item dragging --- src/MissionEditor/MissionEditor.qml | 2 -- 1 file changed, 2 deletions(-) diff --git a/src/MissionEditor/MissionEditor.qml b/src/MissionEditor/MissionEditor.qml index 83f00d5..a7e92f5 100644 --- a/src/MissionEditor/MissionEditor.qml +++ b/src/MissionEditor/MissionEditor.qml @@ -322,8 +322,6 @@ QGCView { // Move to the new position editorMap.latitude = object.coordinate.latitude editorMap.longitude = object.coordinate.longitude - } else { - itemDragger.clearItem() } } } From f946f8c76bdbd84f0571e3be88c040033f834077 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Sun, 25 Oct 2015 13:29:41 -0700 Subject: [PATCH 09/16] Decimal place support from meta data --- src/FactSystem/Fact.cc | 27 ++++++++++++++++- src/FactSystem/Fact.h | 34 +++++++++++----------- src/FactSystem/FactMetaData.cc | 43 +++++++++++++++------------- src/FactSystem/FactMetaData.h | 27 ++++++++++------- src/FirmwarePlugin/PX4/PX4ParameterLoader.cc | 13 +++++++++ src/MissionItem.cc | 15 +++------- 6 files changed, 100 insertions(+), 59 deletions(-) diff --git a/src/FactSystem/Fact.cc b/src/FactSystem/Fact.cc index a69b258..09441f6 100644 --- a/src/FactSystem/Fact.cc +++ b/src/FactSystem/Fact.cc @@ -131,7 +131,22 @@ QVariant Fact::value(void) const QString Fact::valueString(void) const { - return _value.toString(); + QString valueString; + + switch (type()) { + case FactMetaData::valueTypeFloat: + qDebug() << name() << value() << decimalPlaces(); + valueString = QString("%1").arg(value().toFloat(), 0, 'g', decimalPlaces()); + break; + case FactMetaData::valueTypeDouble: + valueString = QString("%1").arg(value().toDouble(), 0, 'g', decimalPlaces()); + break; + default: + valueString = value().toString(); + break; + } + + return valueString; } QVariant Fact::defaultValue(void) const @@ -222,6 +237,16 @@ bool Fact::maxIsDefaultForType(void) const } } +int Fact::decimalPlaces(void) const +{ + if (_metaData) { + return _metaData->decimalPlaces(); + } else { + qWarning() << "Meta data pointer missing"; + return FactMetaData::defaultDecimalPlaces; + } +} + QString Fact::group(void) const { if (_metaData) { diff --git a/src/FactSystem/Fact.h b/src/FactSystem/Fact.h index da8a85e..c946b19 100644 --- a/src/FactSystem/Fact.h +++ b/src/FactSystem/Fact.h @@ -46,22 +46,23 @@ public: const Fact& operator=(const Fact& other); - Q_PROPERTY(int componentId READ componentId CONSTANT) - Q_PROPERTY(QString name READ name CONSTANT) - Q_PROPERTY(QVariant value READ value WRITE setValue NOTIFY valueChanged USER true) - Q_PROPERTY(QVariant valueString READ valueString NOTIFY valueChanged) - Q_PROPERTY(QString units READ units CONSTANT) - Q_PROPERTY(QVariant defaultValue READ defaultValue CONSTANT) - Q_PROPERTY(bool defaultValueAvailable READ defaultValueAvailable CONSTANT) - Q_PROPERTY(bool valueEqualsDefault READ valueEqualsDefault NOTIFY valueChanged) - Q_PROPERTY(FactMetaData::ValueType_t type READ type CONSTANT) - Q_PROPERTY(QString shortDescription READ shortDescription CONSTANT) - Q_PROPERTY(QString longDescription READ longDescription CONSTANT) - Q_PROPERTY(QVariant min READ min CONSTANT) - Q_PROPERTY(bool minIsDefaultForType READ minIsDefaultForType CONSTANT) - Q_PROPERTY(QVariant max READ max CONSTANT) - Q_PROPERTY(bool maxIsDefaultForType READ maxIsDefaultForType CONSTANT) - Q_PROPERTY(QString group READ group CONSTANT) + Q_PROPERTY(int componentId READ componentId CONSTANT) + Q_PROPERTY(QString group READ group CONSTANT) + Q_PROPERTY(QString name READ name CONSTANT) + Q_PROPERTY(QVariant value READ value WRITE setValue NOTIFY valueChanged USER true) + Q_PROPERTY(QVariant valueString READ valueString NOTIFY valueChanged) + Q_PROPERTY(QString units READ units CONSTANT) + Q_PROPERTY(QVariant defaultValue READ defaultValue CONSTANT) + Q_PROPERTY(bool defaultValueAvailable READ defaultValueAvailable CONSTANT) + Q_PROPERTY(bool valueEqualsDefault READ valueEqualsDefault NOTIFY valueChanged) + Q_PROPERTY(FactMetaData::ValueType_t type READ type CONSTANT) + Q_PROPERTY(QString shortDescription READ shortDescription CONSTANT) + Q_PROPERTY(QString longDescription READ longDescription CONSTANT) + Q_PROPERTY(QVariant min READ min CONSTANT) + Q_PROPERTY(bool minIsDefaultForType READ minIsDefaultForType CONSTANT) + Q_PROPERTY(QVariant max READ max CONSTANT) + Q_PROPERTY(bool maxIsDefaultForType READ maxIsDefaultForType CONSTANT) + Q_PROPERTY(int decimalPlaces READ decimalPlaces CONSTANT) /// Convert and validate value /// @param convertOnly true: validate type conversion only, false: validate against meta data as well @@ -86,6 +87,7 @@ public: QVariant max(void) const; bool maxIsDefaultForType(void) const; QString group(void) const; + int decimalPlaces(void) const; /// Sets and sends new value to vehicle even if value is the same void forceSetValue(const QVariant& value); diff --git a/src/FactSystem/FactMetaData.cc b/src/FactSystem/FactMetaData.cc index 7360e65..942d4e3 100644 --- a/src/FactSystem/FactMetaData.cc +++ b/src/FactSystem/FactMetaData.cc @@ -32,30 +32,32 @@ #include -FactMetaData::FactMetaData(QObject* parent) : - QObject(parent), - _group("*Default Group"), - _type(valueTypeInt32), - _defaultValue(0), - _defaultValueAvailable(false), - _min(_minForType()), - _max(_maxForType()), - _minIsDefaultForType(true), - _maxIsDefaultForType(true) +FactMetaData::FactMetaData(QObject* parent) + : QObject(parent) + , _group("*Default Group") + , _type(valueTypeInt32) + , _defaultValue(0) + , _defaultValueAvailable(false) + , _min(_minForType()) + , _max(_maxForType()) + , _minIsDefaultForType(true) + , _maxIsDefaultForType(true) + , _decimalPlaces(defaultDecimalPlaces) { } -FactMetaData::FactMetaData(ValueType_t type, QObject* parent) : - QObject(parent), - _group("*Default Group"), - _type(type), - _defaultValue(0), - _defaultValueAvailable(false), - _min(_minForType()), - _max(_maxForType()), - _minIsDefaultForType(true), - _maxIsDefaultForType(true) +FactMetaData::FactMetaData(ValueType_t type, QObject* parent) + : QObject(parent) + , _group("*Default Group") + , _type(type) + , _defaultValue(0) + , _defaultValueAvailable(false) + , _min(_minForType()) + , _max(_maxForType()) + , _minIsDefaultForType(true) + , _maxIsDefaultForType(true) + , _decimalPlaces(defaultDecimalPlaces) { } @@ -76,6 +78,7 @@ const FactMetaData& FactMetaData::operator=(const FactMetaData& other) _max = other._max; _minIsDefaultForType = other._minIsDefaultForType; _maxIsDefaultForType = other._maxIsDefaultForType; + _decimalPlaces = other._decimalPlaces; return *this; } diff --git a/src/FactSystem/FactMetaData.h b/src/FactSystem/FactMetaData.h index 49c72d8..03c78d2 100644 --- a/src/FactSystem/FactMetaData.h +++ b/src/FactSystem/FactMetaData.h @@ -59,18 +59,19 @@ public: const FactMetaData& operator=(const FactMetaData& other); // Property accessors - QString name(void) const { return _name; } - QString group(void) const { return _group; } - ValueType_t type(void) const { return _type; } + QString name(void) const { return _name; } + QString group(void) const { return _group; } + ValueType_t type(void) const { return _type; } QVariant defaultValue(void) const; - bool defaultValueAvailable(void) const { return _defaultValueAvailable; } - QString shortDescription(void) const { return _shortDescription; } - QString longDescription(void) const { return _longDescription;} - QString units(void) const { return _units; } - QVariant min(void) const { return _min; } - QVariant max(void) const { return _max; } - bool minIsDefaultForType(void) const { return _minIsDefaultForType; } - bool maxIsDefaultForType(void) const { return _maxIsDefaultForType; } + bool defaultValueAvailable(void) const { return _defaultValueAvailable; } + QString shortDescription(void) const { return _shortDescription; } + QString longDescription(void) const { return _longDescription;} + QString units(void) const { return _units; } + QVariant min(void) const { return _min; } + QVariant max(void) const { return _max; } + bool minIsDefaultForType(void) const { return _minIsDefaultForType; } + bool maxIsDefaultForType(void) const { return _maxIsDefaultForType; } + int decimalPlaces(void) const { return _decimalPlaces; } // Property setters void setName(const QString& name) { _name = name; } @@ -81,6 +82,7 @@ public: void setUnits(const QString& units) { _units = units; } void setMin(const QVariant& max); void setMax(const QVariant& max); + void setDecimalPlaces(int decimalPlaces) { _decimalPlaces = decimalPlaces; } /// Converts the specified value, validating against meta data /// @param value Value to convert, can be string @@ -90,6 +92,8 @@ public: /// @returns false: Convert failed, errorString set bool convertAndValidate(const QVariant& value, bool convertOnly, QVariant& typedValue, QString& errorString); + static const int defaultDecimalPlaces = 3; + private: QVariant _minForType(void) const; QVariant _maxForType(void) const; @@ -106,6 +110,7 @@ private: QVariant _max; bool _minIsDefaultForType; bool _maxIsDefaultForType; + int _decimalPlaces; }; #endif diff --git a/src/FirmwarePlugin/PX4/PX4ParameterLoader.cc b/src/FirmwarePlugin/PX4/PX4ParameterLoader.cc index aea72c1..c7d989d 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterLoader.cc +++ b/src/FirmwarePlugin/PX4/PX4ParameterLoader.cc @@ -299,6 +299,19 @@ void PX4ParameterLoader::loadParameterFactMetaData(void) qCDebug(PX4ParameterLoaderLog) << "Unit:" << text; metaData->setUnits(text); + } else if (elementName == "decimal") { + Q_ASSERT(metaData); + QString text = xml.readElementText(); + qCDebug(PX4ParameterLoaderLog) << "Decimal:" << text; + + bool convertOk; + QVariant varDecimals = QVariant(text).toUInt(&convertOk); + if (convertOk) { + metaData->setDecimalPlaces(varDecimals.toInt()); + } else { + qCWarning(PX4ParameterLoaderLog) << "Invalid decimals value, name:" << metaData->name() << " type:" << metaData->type() << " decimals:" << text << " error: invalid number"; + } + } else { qDebug() << "Unknown element in XML: " << elementName; } diff --git a/src/MissionItem.cc b/src/MissionItem.cc index 0d0943e..4e3f9d1 100644 --- a/src/MissionItem.cc +++ b/src/MissionItem.cc @@ -20,15 +20,6 @@ This file is part of the QGROUNDCONTROL project ======================================================================*/ -/** - * @file - * @brief MissionItem class - * - * @author Benjamin Knecht - * @author Petri Tanskanen - * - */ - #include #include @@ -115,10 +106,12 @@ MissionItem::MissionItem(QObject* parent, FactMetaData* latitudeMetaData = new FactMetaData(FactMetaData::valueTypeDouble, _latitudeFact); latitudeMetaData->setUnits("deg"); - + latitudeMetaData->setDecimalPlaces(7); + FactMetaData* longitudeMetaData = new FactMetaData(FactMetaData::valueTypeDouble, _longitudeFact); longitudeMetaData->setUnits("deg"); - + longitudeMetaData->setDecimalPlaces(7); + FactMetaData* altitudeMetaData = new FactMetaData(FactMetaData::valueTypeDouble, _altitudeFact); altitudeMetaData->setUnits("meters"); From 4069ab9ecab884864bd0a0fcd915a5972d9a73c5 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Sun, 25 Oct 2015 14:46:34 -0700 Subject: [PATCH 10/16] Fix binding loop --- src/AutoPilotPlugins/PX4/FlightModesComponent.qml | 12 ++++++------ src/QmlControls/ModeSwitchDisplay.qml | 4 +++- 2 files changed, 9 insertions(+), 7 deletions(-) diff --git a/src/AutoPilotPlugins/PX4/FlightModesComponent.qml b/src/AutoPilotPlugins/PX4/FlightModesComponent.qml index 5178b1c..d34f6ea 100644 --- a/src/AutoPilotPlugins/PX4/FlightModesComponent.qml +++ b/src/AutoPilotPlugins/PX4/FlightModesComponent.qml @@ -260,7 +260,7 @@ QGCView { thresholdValue: controller.manualModeThreshold thresholdDragEnabled: false - onModeChannelIndexChanged: controller.manualModeChannelIndex = modeChannelIndex + onModeChannelIndexSelected: controller.manualModeChannelIndex = index } ModeSwitchDisplay { @@ -308,7 +308,7 @@ QGCView { thresholdValue: controller.acroModeThreshold thresholdDragEnabled: true - onModeChannelIndexChanged: controller.acroModeChannelIndex = modeChannelIndex + onModeChannelIndexSelected: controller.acroModeChannelIndex = index onThresholdValueChanged: controller.acroModeThreshold = thresholdValue Behavior on y { PropertyAnimation { easing.type: Easing.InOutQuad; duration: 1000 } } @@ -341,7 +341,7 @@ QGCView { thresholdValue: controller.posCtlModeThreshold thresholdDragEnabled: true - onModeChannelIndexChanged: controller.posCtlModeChannelIndex = modeChannelIndex + onModeChannelIndexSelected: controller.posCtlModeChannelIndex = index onThresholdValueChanged: controller.posCtlModeThreshold = thresholdValue Behavior on y { PropertyAnimation { easing.type: Easing.InOutQuad; duration: 1000 } } @@ -374,7 +374,7 @@ QGCView { thresholdValue: controller.loiterModeThreshold thresholdDragEnabled: true - onModeChannelIndexChanged: controller.loiterModeChannelIndex = modeChannelIndex + onModeChannelIndexSelected: controller.loiterModeChannelIndex = index onThresholdValueChanged: controller.loiterModeThreshold = thresholdValue Behavior on y { PropertyAnimation { easing.type: Easing.InOutQuad; duration: 1000 } } @@ -391,7 +391,7 @@ QGCView { thresholdValue: controller.returnModeThreshold thresholdDragEnabled: true - onModeChannelIndexChanged: controller.returnModeChannelIndex = modeChannelIndex + onModeChannelIndexSelected: controller.returnModeChannelIndex = index onThresholdValueChanged: controller.returnModeThreshold = thresholdValue Behavior on y { PropertyAnimation { easing.type: Easing.InOutQuad; duration: 1000 } } @@ -408,7 +408,7 @@ QGCView { thresholdValue: controller.offboardModeThreshold thresholdDragEnabled: true - onModeChannelIndexChanged: controller.offboardModeChannelIndex = modeChannelIndex + onModeChannelIndexSelected: controller.offboardModeChannelIndex = index onThresholdValueChanged: controller.offboardModeThreshold = thresholdValue Behavior on y { PropertyAnimation { easing.type: Easing.InOutQuad; duration: 1000 } } diff --git a/src/QmlControls/ModeSwitchDisplay.qml b/src/QmlControls/ModeSwitchDisplay.qml index 126fd7b..376f15d 100644 --- a/src/QmlControls/ModeSwitchDisplay.qml +++ b/src/QmlControls/ModeSwitchDisplay.qml @@ -45,6 +45,8 @@ Rectangle { height: column.height + (ScreenTools.defaultFontPixelWidth * 2) color: _qgcPal.window + signal modeChannelIndexSelected(int index) + QGCPalette { id: _qgcPal; colorGroupEnabled: enabled } Item { @@ -82,7 +84,7 @@ Rectangle { currentIndex: modeChannelIndex enabled: modeChannelEnabled - onActivated: modeChannelIndex = index + onActivated: modeChannelIndexSelected(index) } QGCLabel { From 30abdb65e32f90f13fd4d1c0f35726d9109009a3 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Sun, 25 Oct 2015 15:39:02 -0700 Subject: [PATCH 11/16] Fix mode selection coloring --- src/QmlControls/ModeSwitchDisplay.qml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/QmlControls/ModeSwitchDisplay.qml b/src/QmlControls/ModeSwitchDisplay.qml index 376f15d..9e09759 100644 --- a/src/QmlControls/ModeSwitchDisplay.qml +++ b/src/QmlControls/ModeSwitchDisplay.qml @@ -65,7 +65,7 @@ Rectangle { Rectangle { width: modeLabel.width height: modeLabel.contentHeight - color: modeSelected ? _qgcPal.buttonHighlight : _qgcPal.windowShade + color: modeSelected ? _qgcPal.buttonHighlight : _qgcPal.button QGCLabel { id: modeLabel From 17cfe536a8f9a10797659900d4f1d5ce5edbbbc0 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Mon, 19 Oct 2015 22:21:05 -0400 Subject: [PATCH 12/16] travis-ci disable android debug -until we start running unit tests on android --- .travis.yml | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/.travis.yml b/.travis.yml index 1f16c4a..b7f4fbf 100644 --- a/.travis.yml +++ b/.travis.yml @@ -23,10 +23,10 @@ matrix: - os: osx osx_image: xcode7 env: SPEC=macx-clang CONFIG=installer - - os: android - language: android - env: SPEC=android-g++ CONFIG=debug - sudo: false +# - os: android +# language: android +# env: SPEC=android-g++ CONFIG=debug +# sudo: false - os: android language: android env: SPEC=android-g++ CONFIG=installer From 574ea9fedbf50e913e863c99f280d4458cd787f0 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Mon, 19 Oct 2015 22:24:36 -0400 Subject: [PATCH 13/16] travis-ci switch linux to container infrastructure -enable ccache --- .travis.yml | 25 +++++++++++++++++++------ 1 file changed, 19 insertions(+), 6 deletions(-) diff --git a/.travis.yml b/.travis.yml index b7f4fbf..4eba662 100644 --- a/.travis.yml +++ b/.travis.yml @@ -13,10 +13,10 @@ matrix: include: - os: linux env: SPEC=linux-g++-64 CONFIG=debug - sudo: true + sudo: false - os: linux env: SPEC=linux-g++-64 CONFIG=installer - sudo: true + sudo: false - os: osx osx_image: xcode7 env: SPEC=macx-clang CONFIG=debug @@ -38,8 +38,24 @@ android: - build-tools-21.1.1 - android-21 +addons: + apt: + sources: + - ubuntu-toolchain-r-test + packages: + - ccache + - espeak + - g++-4.8 + - gcc-4.8 + - libc6-i386 + - libespeak-dev + - libopenscenegraph-dev + - libsdl1.2-dev + - libudev-dev + cache: - apt + - ccache before_install: - cd ${TRAVIS_BUILD_DIR} && git fetch --unshallow && git fetch --tags @@ -49,10 +65,7 @@ before_install: install: - if [ "${TRAVIS_OS_NAME}" = "linux" ]; then - sudo apt-add-repository -y ppa:ubuntu-toolchain-r/test - && sudo apt-get -qq update - && sudo apt-get -qq install g++-4.8 espeak libespeak-dev libopenscenegraph-dev libsdl1.2-dev libudev-dev - && wget https://s3-us-west-2.amazonaws.com/qgroundcontrol/dependencies/Qt5.5.1-linux.tar.bz2 + wget https://s3-us-west-2.amazonaws.com/qgroundcontrol/dependencies/Qt5.5.1-linux.tar.bz2 && tar jxf Qt5.5.1-linux.tar.bz2 -C /tmp && export PATH=/tmp/Qt/5.5/gcc_64/bin:$PATH && export CXX="g++-4.8" From 43f586ab23d1e2168ae89ff8c868c3255ae52494 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Sun, 25 Oct 2015 19:48:53 -0400 Subject: [PATCH 14/16] travis-ci enable ccache for linux --- .travis.yml | 12 ++++++++++-- 1 file changed, 10 insertions(+), 2 deletions(-) diff --git a/.travis.yml b/.travis.yml index 4eba662..c05108a 100644 --- a/.travis.yml +++ b/.travis.yml @@ -54,8 +54,9 @@ addons: - libudev-dev cache: - - apt - - ccache + directories: + - $HOME/.ccache + before_install: - cd ${TRAVIS_BUILD_DIR} && git fetch --unshallow && git fetch --tags @@ -93,6 +94,13 @@ install: before_script: +# setup ccache + - mkdir -p ~/bin + - ln -s /usr/bin/ccache ~/bin/g++ + - ln -s /usr/bin/ccache ~/bin/g++-4.8 + - ln -s /usr/bin/ccache ~/bin/gcc + - ln -s /usr/bin/ccache ~/bin/gcc-4.8 + - export PATH=~/bin:$PATH - if [[ "${TRAVIS_OS_NAME}" = "android" && "${CONFIG}" = "installer" && -z ${ANDROID_STOREPASS} ]]; then export CONFIG=release; fi - qmake -r qgroundcontrol.pro CONFIG+=${CONFIG} CONFIG+=WarningsAsErrorsOn -spec ${SPEC} From 2ef4023b769458230a74cbb0ebdec1b8ba7ebb81 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Sun, 25 Oct 2015 21:53:42 -0400 Subject: [PATCH 15/16] qmake cleanup git version --- QGCCommon.pri | 1 + qgroundcontrol.pro | 3 --- 2 files changed, 1 insertion(+), 3 deletions(-) diff --git a/QGCCommon.pri b/QGCCommon.pri index 975040a..f67098d 100644 --- a/QGCCommon.pri +++ b/QGCCommon.pri @@ -73,6 +73,7 @@ MobileBuild { exists ($$PWD/.git) { GIT_DESCRIBE = $$system(git --git-dir $$PWD/.git --work-tree $$PWD describe --always --tags) + message(QGroundControl version $${GIT_DESCRIBE}) } else { GIT_DESCRIBE = None } diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index ba89c95..6928aad 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -30,6 +30,3 @@ message(Qt version $$[QT_VERSION]) error("Unsupported Qt version, 5.4+ is required") } -message(QGroundControl version $${GIT_DESCRIBE}) -git_ver.commands = $$QGC_GIT_VER -QMAKE_EXTRA_TARGETS += git_ver From 579206c6676dda8eac22fd73136d0012f1f0dc1c Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Sun, 25 Oct 2015 21:54:09 -0400 Subject: [PATCH 16/16] update android version --- android/AndroidManifest.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/android/AndroidManifest.xml b/android/AndroidManifest.xml index d3f51b4..6b50361 100644 --- a/android/AndroidManifest.xml +++ b/android/AndroidManifest.xml @@ -1,5 +1,5 @@ - +