From cae4dce2d4ed933f66050e0be73e7867f2ad06a5 Mon Sep 17 00:00:00 2001 From: Tomaz Canabrava Date: Mon, 4 Jan 2016 17:08:44 -0200 Subject: [PATCH] More Signals to new syntax Also, added a missing method on AutoPilotPlugin as a public pure virtual method (the inheritances already implemented it as a slot, so the new Signal syntax didn't worked because the base class didn't had that method) Signed-off-by: Tomaz Canabrava --- src/AutoPilotPlugins/AutoPilotPlugin.h | 2 ++ src/Vehicle/Vehicle.cc | 13 +++++++------ 2 files changed, 9 insertions(+), 6 deletions(-) diff --git a/src/AutoPilotPlugins/AutoPilotPlugin.h b/src/AutoPilotPlugins/AutoPilotPlugin.h index 649542ae9..f4d754e15 100644 --- a/src/AutoPilotPlugins/AutoPilotPlugin.h +++ b/src/AutoPilotPlugins/AutoPilotPlugin.h @@ -120,6 +120,7 @@ bool setupComplete(void); Vehicle* vehicle(void) { return _vehicle; } + virtual void _parametersReadyPreChecks(bool parametersReady) = 0; signals: void parametersReadyChanged(bool parametersReady); @@ -137,6 +138,7 @@ bool _missingParameters; bool _setupComplete; + private slots: void _uasDisconnected(void); void _parametersReadyChanged(bool parametersReady); diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 9aa7a1101..e59736b71 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -134,7 +134,7 @@ Vehicle::Vehicle(LinkInterface* link, connect(_autopilotPlugin, &AutoPilotPlugin::missingParametersChanged, this, &Vehicle::missingParametersChanged); // Refresh timer - connect(_refreshTimer, SIGNAL(timeout()), this, SLOT(_checkUpdate())); + connect(_refreshTimer, &QTimer::timeout, this, &Vehicle::_checkUpdate); _refreshTimer->setInterval(UPDATE_TIMER); _refreshTimer->start(UPDATE_TIMER); emit heartbeatTimeoutChanged(); @@ -159,10 +159,11 @@ Vehicle::Vehicle(LinkInterface* link, // Now connect the new UAS connect(_mav, SIGNAL(attitudeChanged (UASInterface*,double,double,double,quint64)), this, SLOT(_updateAttitude(UASInterface*, double, double, double, quint64))); connect(_mav, SIGNAL(attitudeChanged (UASInterface*,int,double,double,double,quint64)), this, SLOT(_updateAttitude(UASInterface*,int,double, double, double, quint64))); - connect(_mav, SIGNAL(speedChanged (UASInterface*, double, double, quint64)), this, SLOT(_updateSpeed(UASInterface*, double, double, quint64))); - connect(_mav, SIGNAL(altitudeChanged (UASInterface*, double, double, double, double, quint64)), this, SLOT(_updateAltitude(UASInterface*, double, double, double, double, quint64))); - connect(_mav, SIGNAL(navigationControllerErrorsChanged (UASInterface*, double, double, double)), this, SLOT(_updateNavigationControllerErrors(UASInterface*, double, double, double))); connect(_mav, SIGNAL(statusChanged (UASInterface*,QString,QString)), this, SLOT(_updateState(UASInterface*, QString,QString))); + + connect(_mav, &UASInterface::speedChanged, this, &Vehicle::_updateSpeed); + connect(_mav, &UASInterface::altitudeChanged, this, &Vehicle::_updateAltitude); + connect(_mav, &UASInterface::navigationControllerErrorsChanged,this, &Vehicle::_updateNavigationControllerErrors); connect(_mav, &UASInterface::NavigationControllerDataChanged, this, &Vehicle::_updateNavigationControllerData); connect(_mav, &UASInterface::heartbeatTimeout, this, &Vehicle::_heartbeatTimeout); connect(_mav, &UASInterface::batteryChanged, this, &Vehicle::_updateBatteryRemaining); @@ -183,8 +184,8 @@ Vehicle::Vehicle(LinkInterface* link, connect(_missionManager, &MissionManager::error, this, &Vehicle::_missionManagerError); _parameterLoader = new ParameterLoader(_autopilotPlugin, this /* Vehicle */, this /* parent */); - connect(_parameterLoader, SIGNAL(parametersReady(bool)), _autopilotPlugin, SLOT(_parametersReadyPreChecks(bool))); - connect(_parameterLoader, SIGNAL(parameterListProgress(float)), _autopilotPlugin, SIGNAL(parameterListProgress(float))); + connect(_parameterLoader, &ParameterLoader::parametersReady, _autopilotPlugin, &AutoPilotPlugin::_parametersReadyPreChecks); + connect(_parameterLoader, &ParameterLoader::parameterListProgress, _autopilotPlugin, &AutoPilotPlugin::parameterListProgress); _firmwarePlugin->initializeVehicle(this); -- 2.22.0