diff --git a/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc b/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc index 1d45eb05abbbb949b9489ab5e723147db7f5eb36..14d54704aed17aa4a9c2bea791df56193c1daa3c 100644 --- a/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc +++ b/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc @@ -782,7 +782,7 @@ void APMSensorsComponentController::_handleMagCalProgress(mavlink_message_t& mes } } - if (magCalProgress.compass_id < 3) { + if (magCalProgress.compass_id < 3 && compassCalCount != 0) { // Each compass gets a portion of the overall progress _rgCompassCalProgress[magCalProgress.compass_id] = magCalProgress.completion_pct / compassCalCount; } diff --git a/src/AutoPilotPlugins/AutoPilotPlugin.cc b/src/AutoPilotPlugins/AutoPilotPlugin.cc index 4da3426b1da4ff4beb842423b2fadeae32852c96..40fd4713abe8d820e8d15efc2773b5fa66c841f5 100644 --- a/src/AutoPilotPlugins/AutoPilotPlugin.cc +++ b/src/AutoPilotPlugins/AutoPilotPlugin.cc @@ -33,7 +33,7 @@ void AutoPilotPlugin::_recalcSetupComplete(void) { bool newSetupComplete = true; - for(const QVariant componentVariant: vehicleComponents()) { + for(const QVariant& componentVariant: vehicleComponents()) { VehicleComponent* component = qobject_cast(qvariant_cast(componentVariant)); if (component) { if (!component->setupComplete()) { diff --git a/src/Camera/QGCCameraControl.cc b/src/Camera/QGCCameraControl.cc index f7aab027bc6816caec39d800c9692e9933c26826..a457204db21938dc9b2d02217024616a95627de4 100644 --- a/src/Camera/QGCCameraControl.cc +++ b/src/Camera/QGCCameraControl.cc @@ -1153,7 +1153,7 @@ void QGCCameraControl::_requestAllParameters() { //-- Reset receive list - for(QString paramName: _paramIO.keys()) { + for(const QString& paramName: _paramIO.keys()) { if(_paramIO[paramName]) { _paramIO[paramName]->setParamRequest(); } else { @@ -1391,7 +1391,7 @@ QGCCameraControl::_updateRanges(Fact* pFact) } //-- Parameter update requests if(_requestUpdates.contains(pFact->name())) { - for(QString param: _requestUpdates[pFact->name()]) { + for(const QString& param: _requestUpdates[pFact->name()]) { if(!_updatesToRequest.contains(param)) { _updatesToRequest << param; } @@ -1406,7 +1406,7 @@ QGCCameraControl::_updateRanges(Fact* pFact) void QGCCameraControl::_requestParamUpdates() { - for(QString param: _updatesToRequest) { + for(const QString& param: _updatesToRequest) { _paramIO[param]->paramRequest(); } _updatesToRequest.clear(); @@ -1831,7 +1831,6 @@ QGCCameraControl::_loadRanges(QDomNode option, const QString factName, QString p for(int i = 0; i < parameterRanges.size(); i++) { QString param; QString condition; - QMap rangeList; QDomNode paramRange = parameterRanges.item(i); if(!read_attribute(paramRange, kParameter, param)) { qCritical() << QString("Malformed option range for parameter %1").arg(factName); @@ -2003,7 +2002,7 @@ QGCCameraControl::_dataReady(QByteArray data) void QGCCameraControl::_paramDone() { - for(QString param: _paramIO.keys()) { + for(const QString& param: _paramIO.keys()) { if(!_paramIO[param]->paramDone()) { return; } diff --git a/src/QtLocationPlugin/QGeoTiledMappingManagerEngineQGC.cpp b/src/QtLocationPlugin/QGeoTiledMappingManagerEngineQGC.cpp index 51d2f49a30535785a5860f4b87aec24149308eaf..a58fe028caf282116a601c5b2ad450a86f5f9e81 100644 --- a/src/QtLocationPlugin/QGeoTiledMappingManagerEngineQGC.cpp +++ b/src/QtLocationPlugin/QGeoTiledMappingManagerEngineQGC.cpp @@ -217,14 +217,14 @@ QGeoTiledMappingManagerEngineQGC::_setCache(const QVariantMap ¶meters) cacheDir = parameters.value(QStringLiteral("mapping.cache.directory")).toString(); else { cacheDir = getQGCMapEngine()->getCachePath(); - if(!QFileInfo(cacheDir).exists()) { + if(!QFileInfo::exists(cacheDir)) { if(!QDir::root().mkpath(cacheDir)) { qWarning() << "Could not create mapping disk cache directory: " << cacheDir; cacheDir = QDir::homePath() + QStringLiteral("/.qgcmapscache/"); } } } - if(!QFileInfo(cacheDir).exists()) { + if(!QFileInfo::exists(cacheDir)) { if(!QDir::root().mkpath(cacheDir)) { qWarning() << "Could not create mapping disk cache directory: " << cacheDir; cacheDir.clear(); diff --git a/src/Terrain/TerrainQuery.cc b/src/Terrain/TerrainQuery.cc index 52687493587b0036794cd13261c88229b0df612a..4a25d2a0536ec2f960173eb33dd5cead69f0088e 100644 --- a/src/Terrain/TerrainQuery.cc +++ b/src/Terrain/TerrainQuery.cc @@ -501,6 +501,7 @@ void TerrainTileManager::_terrainDone(QByteArray responseBytes, QNetworkReply::N } _tilesMutex.unlock(); } else { + delete terrainTile; qCWarning(TerrainQueryLog) << "Received invalid tile"; } reply->deleteLater(); diff --git a/src/VehicleSetup/PX4FirmwareUpgradeThread.cc b/src/VehicleSetup/PX4FirmwareUpgradeThread.cc index 7b70c2922463f8ad6f562cbd15833553d89f12ee..5da788997b8859c9094b14c630adcbe3b012c36b 100644 --- a/src/VehicleSetup/PX4FirmwareUpgradeThread.cc +++ b/src/VehicleSetup/PX4FirmwareUpgradeThread.cc @@ -119,7 +119,7 @@ void PX4FirmwareUpgradeThreadWorker::_findBoardOnce(void) bool PX4FirmwareUpgradeThreadWorker::_findBoardFromPorts(QGCSerialPortInfo& portInfo, QGCSerialPortInfo::BoardType_t& boardType, QString& boardName) { - for (QGCSerialPortInfo info: QGCSerialPortInfo::availablePorts()) { + for (const QGCSerialPortInfo& info: QGCSerialPortInfo::availablePorts()) { info.getBoardInfo(boardType, boardName); qCDebug(FirmwareUpgradeVerboseLog) << "Serial Port --------------"; diff --git a/src/comm/LinkManager.cc b/src/comm/LinkManager.cc index 43e46a8c552451544649af01a2f0512caf10c36f..9724cab9c75dd71fa9f0ab81bf6e3bb14c7367a3 100644 --- a/src/comm/LinkManager.cc +++ b/src/comm/LinkManager.cc @@ -518,7 +518,7 @@ void LinkManager::_updateAutoConnectLinks(void) #endif // Iterate Comm Ports - for (QGCSerialPortInfo portInfo: portList) { + for (const QGCSerialPortInfo& portInfo: portList) { qCDebug(LinkManagerVerboseLog) << "-----------------------------------------------------"; qCDebug(LinkManagerVerboseLog) << "portName: " << portInfo.portName(); qCDebug(LinkManagerVerboseLog) << "systemLocation: " << portInfo.systemLocation(); @@ -931,7 +931,7 @@ void LinkManager::_activeLinkCheck(void) QSignalSpy spy(link, SIGNAL(bytesReceived(LinkInterface*, QByteArray))); if (spy.wait(100)) { QList arguments = spy.takeFirst(); - if (arguments[1].value().contains("nsh>")) { + if (arguments[1].toByteArray().contains("nsh>")) { foundNSHPrompt = true; } } diff --git a/src/comm/MAVLinkProtocol.cc b/src/comm/MAVLinkProtocol.cc index 2d4e08da1c2c571eb1cab8b1c39d956cf19781c9..398b013b9262fa811ad528fb54f466d34bee2fd0 100644 --- a/src/comm/MAVLinkProtocol.cc +++ b/src/comm/MAVLinkProtocol.cc @@ -461,7 +461,7 @@ void MAVLinkProtocol::checkForLostLogFiles(void) QFileInfoList fileInfoList = tempDir.entryInfoList(QStringList(filter), QDir::Files); //qDebug() << "Orphaned log file count" << fileInfoList.count(); - for(const QFileInfo fileInfo: fileInfoList) { + for(const QFileInfo& fileInfo: fileInfoList) { //qDebug() << "Orphaned log file" << fileInfo.filePath(); if (fileInfo.size() == 0) { // Delete all zero length files diff --git a/src/comm/UDPLink.cc b/src/comm/UDPLink.cc index 58fe36da5341d6ac68115be1ee787ec787acc6d9..e24b45885af1a10802dbb37c85247f24b116712a 100644 --- a/src/comm/UDPLink.cc +++ b/src/comm/UDPLink.cc @@ -55,7 +55,6 @@ static QString get_ip_address(const QString& address) if (info.error() == QHostInfo::NoError) { QList hostAddresses = info.addresses(); - QHostAddress address; for (int i = 0; i < hostAddresses.size(); i++) { // Exclude all IPv6 addresses