From 344acaf6abb3def4b27e88b595a13153b7458afe Mon Sep 17 00:00:00 2001 From: Tomaz Canabrava Date: Mon, 4 Jan 2016 16:12:40 -0200 Subject: [PATCH] Modernize the C++ to accept variadic templates for signals with 6+ arguments C++2003 didn't had variadic templates so different number of arguments must have been already implemented in the templates and since it's impossible to get the amount ot different methods that paople write, a variadic template was neede. now we can connect signal / slots with 6+ arguments. Signed-off-by: Tomaz Canabrava --- qgroundcontrol.pro | 3 ++- src/FactSystem/ParameterLoader.cc | 3 +-- src/FactSystem/ParameterLoader.h | 3 --- 3 files changed, 3 insertions(+), 6 deletions(-) diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index 2174a90cb..fbb3e3090 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 e9be6b724..d5f2a9919 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 74775d778..134823081 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); -- 2.22.0