diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index 2174a90cbca104795d9d5ead7645e20e90612192..fbb3e30906dcee462fbc795aa77afe188f1b16f7 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -63,7 +63,8 @@ LinuxBuild { # Qt configuration CONFIG += qt \ - thread + thread \ + c++11 QT += \ concurrent \ diff --git a/src/FactSystem/ParameterLoader.cc b/src/FactSystem/ParameterLoader.cc index e9be6b724f97c21ecd2510b08c5e56607962071f..d5f2a99193fc333711e5d0deed8fe4bd422a1e7f 100644 --- a/src/FactSystem/ParameterLoader.cc +++ b/src/FactSystem/ParameterLoader.cc @@ -74,8 +74,7 @@ ParameterLoader::ParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, Q _cacheTimeoutTimer.setInterval(2500); connect(&_cacheTimeoutTimer, &QTimer::timeout, this, &ParameterLoader::refreshAllParameters); - // FIXME: Why not direct connect? - connect(_vehicle->uas(), SIGNAL(parameterUpdate(int, int, QString, int, int, int, QVariant)), this, SLOT(_parameterUpdate(int, int, QString, int, int, int, QVariant))); + connect(_vehicle->uas(), &UASInterface::parameterUpdate, this, &ParameterLoader::_parameterUpdate); /* Initially attempt a local cache load, refresh over the link if it fails */ _tryCacheLookup(); diff --git a/src/FactSystem/ParameterLoader.h b/src/FactSystem/ParameterLoader.h index 74775d77808f0c41b35f9ccde61c1a9d538f057f..1348230813ecb05440a7f9ed8ff55b2061cd4fb5 100644 --- a/src/FactSystem/ParameterLoader.h +++ b/src/FactSystem/ParameterLoader.h @@ -56,11 +56,9 @@ public: /// Returns true if the full set of facts are ready bool parametersAreReady(void) { return _parametersReady; } -public slots: /// Re-request the full set of parameters from the autopilot void refreshAllParameters(void); -public: /// Request a refresh on the specific parameter void refreshParameter(int componentId, const QString& name); @@ -102,7 +100,6 @@ protected: Vehicle* _vehicle; MAVLinkProtocol* _mavlink; -private slots: void _parameterUpdate(int uasId, int componentId, QString parameterName, int parameterCount, int parameterId, int mavType, QVariant value); void _valueUpdated(const QVariant& value); void _restartWaitingParamTimer(void);