diff --git a/src/AutoPilotPlugins/APM/APMRadioComponent.cc b/src/AutoPilotPlugins/APM/APMRadioComponent.cc index 5cbed197ae29d864427d7f3eaf67548546ef56f1..d7338294117d9740f7720866138efe5f2da507f5 100644 --- a/src/AutoPilotPlugins/APM/APMRadioComponent.cc +++ b/src/AutoPilotPlugins/APM/APMRadioComponent.cc @@ -59,7 +59,7 @@ bool APMRadioComponent::setupComplete(void) const // controls to be mapped. QStringList attitudeMappings; attitudeMappings << "RCMAP_ROLL" << "RCMAP_PITCH" << "RCMAP_YAW" << "RCMAP_THROTTLE"; - foreach(QString mapParam, attitudeMappings) { + foreach(const QString &mapParam, attitudeMappings) { if (_autopilot->getParameterFact(FactSystem::defaultComponentId, mapParam)->rawValue().toInt() == 0) { return false; } diff --git a/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc b/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc index c160dbf48c2427e326beab1abe160fb794556395..8e54af9e91a09c228e78239b705e7093c729ccf6 100644 --- a/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc +++ b/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc @@ -395,7 +395,7 @@ void APMSensorsComponentController::_refreshParams(void) fastRefreshList << "COMPASS_OFS_X" << "COMPASS_OFS_X" << "COMPASS_OFS_X" << "INS_ACCOFFS_X" << "INS_ACCOFFS_Y" << "INS_ACCOFFS_Z"; - foreach (QString paramName, fastRefreshList) { + foreach (const QString ¶mName, fastRefreshList) { _autopilot->refreshParameter(FactSystem::defaultComponentId, paramName); } diff --git a/src/AutoPilotPlugins/PX4/FlightModesComponentController.cc b/src/AutoPilotPlugins/PX4/FlightModesComponentController.cc index 962df646476d4a4497fce17bf0f7106679f1c346..f38602cecd76ecbe9767b530879041d4671679e3 100644 --- a/src/AutoPilotPlugins/PX4/FlightModesComponentController.cc +++ b/src/AutoPilotPlugins/PX4/FlightModesComponentController.cc @@ -119,7 +119,7 @@ void FlightModesComponentController::_init(void) QStringList attitudeParams; attitudeParams << "RC_MAP_THROTTLE" << "RC_MAP_YAW" << "RC_MAP_PITCH" << "RC_MAP_ROLL" << "RC_MAP_FLAPS" << "RC_MAP_AUX1" << "RC_MAP_AUX2"; - foreach(QString attitudeParam, attitudeParams) { + foreach(const QString &attitudeParam, attitudeParams) { int channel = getParameterFact(-1, attitudeParam)->rawValue().toInt(); if (channel != 0) { usedChannels << channel; @@ -195,7 +195,7 @@ void FlightModesComponentController::_validateConfiguration(void) thresholdParams << "RC_ASSIST_TH" << "RC_AUTO_TH" << "RC_ACRO_TH" << "RC_POSCTL_TH" << "RC_LOITER_TH" << "RC_RETURN_TH" << "RC_OFFB_TH"; - foreach(QString thresholdParam, thresholdParams) { + foreach(const QString &thresholdParam, thresholdParams) { float threshold = getParameterFact(-1, thresholdParam)->rawValue().toFloat(); if (threshold < 0.0f || threshold > 1.0f) { _validConfiguration = false; @@ -735,7 +735,7 @@ void FlightModesComponentController::generateThresholds(void) thresholdParams << "RC_ASSIST_TH" << "RC_AUTO_TH" << "RC_ACRO_TH" << "RC_POSCTL_TH" << "RC_LOITER_TH" << "RC_RETURN_TH" << "RC_OFFB_TH"; - foreach(QString thresholdParam, thresholdParams) { + foreach(const QString &thresholdParam, thresholdParams) { getParameterFact(-1, thresholdParam)->setRawValue(0.0f); } diff --git a/src/AutoPilotPlugins/PX4/PX4Component.cc b/src/AutoPilotPlugins/PX4/PX4Component.cc index 567869bf975c740b499a7e40f4d1c1a2314a65a7..a3ea75a917738853b6ad4b890009e329f8b22087 100644 --- a/src/AutoPilotPlugins/PX4/PX4Component.cc +++ b/src/AutoPilotPlugins/PX4/PX4Component.cc @@ -38,7 +38,7 @@ PX4Component::PX4Component(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject void PX4Component::setupTriggerSignals(void) { // Watch for changed on trigger list params - foreach (QString paramName, setupCompleteChangedTriggerList()) { + foreach (const QString ¶mName, setupCompleteChangedTriggerList()) { Fact* fact = _autopilot->getParameterFact(FactSystem::defaultComponentId, paramName); connect(fact, &Fact::valueChanged, this, &PX4Component::_triggerUpdated); diff --git a/src/AutoPilotPlugins/PX4/PX4RadioComponent.cc b/src/AutoPilotPlugins/PX4/PX4RadioComponent.cc index e5fb76f56e09bf259b97ccdfb96ff97d25455c6e..708cc2a322e161fb05b26cc5c65eb8f7c1426340 100644 --- a/src/AutoPilotPlugins/PX4/PX4RadioComponent.cc +++ b/src/AutoPilotPlugins/PX4/PX4RadioComponent.cc @@ -59,7 +59,7 @@ bool PX4RadioComponent::setupComplete(void) const // controls to be mapped. QStringList attitudeMappings; attitudeMappings << "RC_MAP_ROLL" << "RC_MAP_PITCH" << "RC_MAP_YAW" << "RC_MAP_THROTTLE"; - foreach(QString mapParam, attitudeMappings) { + foreach(const QString &mapParam, attitudeMappings) { if (_autopilot->getParameterFact(FactSystem::defaultComponentId, mapParam)->rawValue().toInt() == 0) { return false; } diff --git a/src/AutoPilotPlugins/PX4/SensorsComponent.cc b/src/AutoPilotPlugins/PX4/SensorsComponent.cc index 5f059eb63955f5d8f2152d7991c6fabb4f02e57d..0a712c74e8a741467a44f609ef3bf8a0230115a7 100644 --- a/src/AutoPilotPlugins/PX4/SensorsComponent.cc +++ b/src/AutoPilotPlugins/PX4/SensorsComponent.cc @@ -61,7 +61,7 @@ bool SensorsComponent::requiresSetup(void) const bool SensorsComponent::setupComplete(void) const { - foreach(QString triggerParam, setupCompleteChangedTriggerList()) { + foreach(const QString &triggerParam, setupCompleteChangedTriggerList()) { if (_autopilot->getParameterFact(FactSystem::defaultComponentId, triggerParam)->rawValue().toFloat() == 0.0f) { return false; } diff --git a/src/AutoPilotPlugins/PX4/SensorsComponentController.cc b/src/AutoPilotPlugins/PX4/SensorsComponentController.cc index 4eb5fdbd10430422a6f936c2631df37aa59b9353..602d09d01eee186d43ea1e9da36834505e8231e4 100644 --- a/src/AutoPilotPlugins/PX4/SensorsComponentController.cc +++ b/src/AutoPilotPlugins/PX4/SensorsComponentController.cc @@ -434,7 +434,7 @@ void SensorsComponentController::_refreshParams(void) // We ask for a refresh on these first so that the rotation combo show up as fast as possible fastRefreshList << "CAL_MAG0_ID" << "CAL_MAG1_ID" << "CAL_MAG2_ID" << "CAL_MAG0_ROT" << "CAL_MAG1_ROT" << "CAL_MAG2_ROT"; - foreach (QString paramName, fastRefreshList) { + foreach (const QString ¶mName, fastRefreshList) { _autopilot->refreshParameter(FactSystem::defaultComponentId, paramName); } diff --git a/src/FactSystem/FactControls/FactPanelController.cc b/src/FactSystem/FactControls/FactPanelController.cc index be1dbd070fcd91cfa9f6bd2ae6d775abc384a5c2..83e1696f1ef16132e0c78dba6b60dad9b41fe95d 100644 --- a/src/FactSystem/FactControls/FactPanelController.cc +++ b/src/FactSystem/FactControls/FactPanelController.cc @@ -61,7 +61,7 @@ void FactPanelController::setFactPanel(QQuickItem* panel) // missing fact notices that were waiting to go out _factPanel = panel; - foreach (QString missingParam, _delayedMissingParams) { + foreach (const QString &missingParam, _delayedMissingParams) { _notifyPanelMissingParameter(missingParam); } _delayedMissingParams.clear(); @@ -112,7 +112,7 @@ bool FactPanelController::_allParametersExists(int componentId, QStringList name { bool noMissingFacts = true; - foreach (QString name, names) { + foreach (const QString &name, names) { if (_autopilot && !_autopilot->parameterExists(componentId, name)) { _reportMissingParameter(componentId, name); noMissingFacts = false; diff --git a/src/FactSystem/ParameterLoader.cc b/src/FactSystem/ParameterLoader.cc index df9dcb36ddc8aa709a2a0faab2d0f149eeab6b17..f1a8cc81030b76d2cc4b047d40267f4a59fd3ace 100644 --- a/src/FactSystem/ParameterLoader.cc +++ b/src/FactSystem/ParameterLoader.cc @@ -380,7 +380,7 @@ void ParameterLoader::refreshParametersPrefix(int componentId, const QString& na componentId = _actualComponentId(componentId); qCDebug(ParameterLoaderLog) << "refreshParametersPrefix (component id:" << componentId << "name:" << namePrefix << ")"; - foreach(QString name, _mapParameterName2Variant[componentId].keys()) { + foreach(const QString &name, _mapParameterName2Variant[componentId].keys()) { if (name.startsWith(namePrefix)) { refreshParameter(componentId, name); } @@ -415,7 +415,7 @@ QStringList ParameterLoader::parameterNames(int componentId) { QStringList names; - foreach(QString paramName, _mapParameterName2Variant[_actualComponentId(componentId)].keys()) { + foreach(const QString ¶mName, _mapParameterName2Variant[_actualComponentId(componentId)].keys()) { names << paramName; } @@ -425,7 +425,7 @@ QStringList ParameterLoader::parameterNames(int componentId) void ParameterLoader::_setupGroupMap(void) { foreach (int componentId, _mapParameterName2Variant.keys()) { - foreach (QString name, _mapParameterName2Variant[componentId].keys()) { + foreach (const QString &name, _mapParameterName2Variant[componentId].keys()) { Fact* fact = _mapParameterName2Variant[componentId][name].value(); _mapGroup2ParameterName[componentId][fact->group()] += name; } @@ -471,7 +471,7 @@ void ParameterLoader::_waitingParamTimeout(void) if (!paramsRequested) { foreach(int componentId, _waitingWriteParamNameMap.keys()) { - foreach(QString paramName, _waitingWriteParamNameMap[componentId].keys()) { + foreach(const QString ¶mName, _waitingWriteParamNameMap[componentId].keys()) { paramsRequested = true; _waitingWriteParamNameMap[componentId][paramName]++; // Bump retry count _writeParameterRaw(componentId, paramName, _autopilot->getFact(FactSystem::ParameterProvider, componentId, paramName)->rawValue()); @@ -486,7 +486,7 @@ void ParameterLoader::_waitingParamTimeout(void) if (!paramsRequested) { foreach(int componentId, _waitingReadParamNameMap.keys()) { - foreach(QString paramName, _waitingReadParamNameMap[componentId].keys()) { + foreach(const QString ¶mName, _waitingReadParamNameMap[componentId].keys()) { paramsRequested = true; _waitingReadParamNameMap[componentId][paramName]++; // Bump retry count _readParameterRaw(componentId, paramName, -1); @@ -715,7 +715,7 @@ void ParameterLoader::writeParametersToStream(QTextStream &stream) stream << "# MAV ID COMPONENT ID PARAM NAME VALUE (FLOAT)\n"; foreach (int componentId, _mapParameterName2Variant.keys()) { - foreach (QString paramName, _mapParameterName2Variant[componentId].keys()) { + foreach (const QString ¶mName, _mapParameterName2Variant[componentId].keys()) { Fact* fact = _mapParameterName2Variant[componentId][paramName].value(); Q_ASSERT(fact); diff --git a/src/HomePositionManager.cc b/src/HomePositionManager.cc index a235c3117c3390b2f776578952f420d8f4c486d2..9e08ce8f173e89d7e23e4aee31a657828a369e78 100644 --- a/src/HomePositionManager.cc +++ b/src/HomePositionManager.cc @@ -97,7 +97,7 @@ void HomePositionManager::_loadSettings(void) settings.beginGroup(_settingsGroup); - foreach(QString name, settings.childGroups()) { + foreach(const QString &name, settings.childGroups()) { QGeoCoordinate coordinate; qDebug() << "Load setting" << name; diff --git a/src/Joystick/JoystickManager.cc b/src/Joystick/JoystickManager.cc index 40487a34f133fa60e8fa0e8412f6b1d422374edc..70defba4065ee9d2efa5c147d8052500c15418c2 100644 --- a/src/Joystick/JoystickManager.cc +++ b/src/Joystick/JoystickManager.cc @@ -145,7 +145,7 @@ QVariantList JoystickManager::joysticks(void) { QVariantList list; - foreach (QString name, _name2JoystickMap.keys()) { + foreach (const QString &name, _name2JoystickMap.keys()) { list += QVariant::fromValue(_name2JoystickMap[name]); } diff --git a/src/LogCompressor.cc b/src/LogCompressor.cc index 97b121146c7ef61bd6cf8e58da5a3132c1969300..f99b7fbaf6283ba384258dc31539752b741ad06a 100644 --- a/src/LogCompressor.cc +++ b/src/LogCompressor.cc @@ -172,7 +172,7 @@ void LogCompressor::run() // Fill holes if necessary if (holeFillingEnabled) { int index = 0; - foreach (QString str, list) { + foreach (const QString& str, list) { if (str == "" || str == "NaN") { list.replace(index, lastList.at(index)); } diff --git a/src/MissionManager/MissionCommands.cc b/src/MissionManager/MissionCommands.cc index dbbc0c05b81d9acb5307cfa8864e42d0d9953e9b..e9ced88ef5edf99a3791d6f7b27e92fca23d61cd 100644 --- a/src/MissionManager/MissionCommands.cc +++ b/src/MissionManager/MissionCommands.cc @@ -130,7 +130,7 @@ void MissionCommands::_loadMavCmdInfoJson(void) // Make sure we have the required keys QStringList requiredKeys; requiredKeys << _idJsonKey << _rawNameJsonKey; - foreach (QString key, requiredKeys) { + foreach (const QString &key, requiredKeys) { if (!jsonObject.contains(key)) { qWarning() << "Mission required key" << key; return; @@ -211,7 +211,7 @@ void MissionCommands::_loadMavCmdInfoJson(void) paramInfo->_units = paramObject.value(_unitsJsonKey).toString(); QStringList enumValues = paramObject.value(_enumValuesJsonKey).toString().split(",", QString::SkipEmptyParts); - foreach (QString enumValue, enumValues) { + foreach (const QString &enumValue, enumValues) { bool convertOk; double value = enumValue.toDouble(&convertOk); @@ -295,7 +295,7 @@ const QStringList MissionCommands::categories(Vehicle* vehicle) const { QStringList list; - foreach (QString category, _categoryToMavCmdInfoListMap[_firmwareTypeFromVehicle(vehicle)].keys()) { + foreach (const QString &category, _categoryToMavCmdInfoListMap[_firmwareTypeFromVehicle(vehicle)].keys()) { list << category; } diff --git a/src/QGCApplication.cc b/src/QGCApplication.cc index d5215220b6b6de0dfe09bf87c9096e3a1307d218..a76b1bc1d4802f837ebbceec041fc9e3894d89e7 100644 --- a/src/QGCApplication.cc +++ b/src/QGCApplication.cc @@ -226,7 +226,7 @@ QGCApplication::QGCApplication(int &argc, char* argv[], bool unitTesting) filterRules += ".debug=false\n"; } } else { - foreach(QString rule, logList) { + foreach(const QString &rule, logList) { filterRules += rule; filterRules += ".debug=true\n"; } @@ -261,7 +261,7 @@ QGCApplication::QGCApplication(int &argc, char* argv[], bool unitTesting) QTextStream out(&loggingFile); out << "[Rules]\n"; out << "*Log.debug=false\n"; - foreach(QString category, QGCLoggingCategoryRegister::instance()->registeredCategories()) { + foreach(const QString &category, QGCLoggingCategoryRegister::instance()->registeredCategories()) { out << category << ".debug=false\n"; } } else { @@ -737,7 +737,7 @@ void QGCApplication::_missingParamsDisplay(void) Q_ASSERT(_missingParams.count()); QString params; - foreach (QString name, _missingParams) { + foreach (const QString &name, _missingParams) { if (params.isEmpty()) { params += name; } else { diff --git a/src/QmlControls/ParameterEditorController.cc b/src/QmlControls/ParameterEditorController.cc index 6f441ec3ce621f7cd0a3bc5053009352405a6f5b..8c22847750bba6cbf5ccfdc73d83389aecda9de9 100644 --- a/src/QmlControls/ParameterEditorController.cc +++ b/src/QmlControls/ParameterEditorController.cc @@ -69,7 +69,7 @@ QStringList ParameterEditorController::searchParametersForComponent(int componen { QStringList list; - foreach(QString paramName, _autopilot->parameterNames(componentId)) { + foreach(const QString ¶mName, _autopilot->parameterNames(componentId)) { if (searchText.isEmpty()) { list += paramName; } else { diff --git a/src/VideoStreaming/VideoStreaming.cc b/src/VideoStreaming/VideoStreaming.cc index ead8e77c8a86536ab1f83cb83649338cdf2102c3..ab5da872de59828fd4892d4bf0e512795292bc95 100644 --- a/src/VideoStreaming/VideoStreaming.cc +++ b/src/VideoStreaming/VideoStreaming.cc @@ -98,7 +98,7 @@ void initializeVideoStreaming(int &argc, char* argv[]) qgcputenv("GST_PLUGIN_PATH_1_0", currentDir, "/../Frameworks/GStreamer.framework/Versions/Current/lib/gstreamer-1.0"); qgcputenv("GST_PLUGIN_PATH", currentDir, "/../Frameworks/GStreamer.framework/Versions/Current/lib/gstreamer-1.0"); // QStringList env = QProcessEnvironment::systemEnvironment().keys(); -// foreach(QString key, env) { +// foreach(const QString &key, env) { // qDebug() << key << QProcessEnvironment::systemEnvironment().value(key); // } #endif diff --git a/src/comm/MockLink.cc b/src/comm/MockLink.cc index 778345264cd8ecfeaf585c9cc6d7d9708a4e2c6b..67994f69a44bfc3ef6a25663ac753b833f98ca4c 100644 --- a/src/comm/MockLink.cc +++ b/src/comm/MockLink.cc @@ -562,7 +562,7 @@ void MockLink::_handleParamRequestList(const mavlink_message_t& msg) uint16_t paramIndex = 0; int cParameters = _mapParamName2Value[componentId].count(); - foreach(QString paramName, _mapParamName2Value[componentId].keys()) { + foreach(const QString ¶mName, _mapParamName2Value[componentId].keys()) { char paramId[MAVLINK_MSG_ID_PARAM_VALUE_LEN]; mavlink_message_t responseMsg; @@ -596,7 +596,7 @@ void MockLink::_handleParamRequestList(const mavlink_message_t& msg) int cParameters = _mapParamName2Value[componentId].count(); bool skipParam = true; - foreach(QString paramName, _mapParamName2Value[componentId].keys()) { + foreach(const QString ¶mName, _mapParamName2Value[componentId].keys()) { if (skipParam) { // We've already sent the first param skipParam = false; diff --git a/src/comm/QGCFlightGearLink.cc b/src/comm/QGCFlightGearLink.cc index 3eedde152f969e7262f840cdb111f37a6460a535..3287f571b6dbaadcb9c743959870924d40a0c375 100644 --- a/src/comm/QGCFlightGearLink.cc +++ b/src/comm/QGCFlightGearLink.cc @@ -988,7 +988,7 @@ void QGCFlightGearLink::_printFgfsOutput(void) QByteArray byteArray = _fgProcess->readAllStandardOutput(); QStringList strLines = QString(byteArray).split("\n"); - foreach (QString line, strLines){ + foreach (const QString &line, strLines){ qDebug() << line; } } @@ -1000,7 +1000,7 @@ void QGCFlightGearLink::_printFgfsError(void) QByteArray byteArray = _fgProcess->readAllStandardError(); QStringList strLines = QString(byteArray).split("\n"); - foreach (QString line, strLines){ + foreach (const QString &line, strLines){ qDebug() << line; } } diff --git a/src/comm/UDPLink.cc b/src/comm/UDPLink.cc index a7ff432aab7efd417cd08ed854e77cf8932307c7..6926f90e808a9c67070c5be2b60944422b034312 100644 --- a/src/comm/UDPLink.cc +++ b/src/comm/UDPLink.cc @@ -231,7 +231,7 @@ void UDPLink::_sendBytes(const char* data, qint64 size) } } while (_config->nextHost(host, port)); //-- Remove hosts that are no longer there - foreach (QString ghost, goneHosts) { + foreach (const QString& ghost, goneHosts) { _config->removeHost(ghost); } } diff --git a/src/qgcunittest/MavlinkLogTest.cc b/src/qgcunittest/MavlinkLogTest.cc index 310a4adcfcfadea56160ef6ac3090568dce787ab..27890648ee33195f2171ed851fc3b1dc1fee6f84 100644 --- a/src/qgcunittest/MavlinkLogTest.cc +++ b/src/qgcunittest/MavlinkLogTest.cc @@ -51,7 +51,7 @@ void MavlinkLogTest::init(void) // Make sure temp directory is clear of mavlink logs QDir tmpDir(QStandardPaths::writableLocation(QStandardPaths::TempLocation)); QStringList logFiles(tmpDir.entryList(QStringList(QString("*.%1").arg(_logFileExtension)), QDir::Files)); - foreach(QString logFile, logFiles) { + foreach(const QString &logFile, logFiles) { bool success = tmpDir.remove(logFile); Q_UNUSED(success); Q_ASSERT(success); diff --git a/src/qgcunittest/RadioConfigTest.cc b/src/qgcunittest/RadioConfigTest.cc index 6d10c93d148e2d372e025246878640f46e7c4eb8..5e876d7d64beedba94fd2ec34bcb7aca04b771b2 100644 --- a/src/qgcunittest/RadioConfigTest.cc +++ b/src/qgcunittest/RadioConfigTest.cc @@ -407,7 +407,7 @@ void RadioConfigTest::_fullCalibrationWorker(MAV_AUTOPILOT firmwareType) QStringList switchList; switchList << "RC_MAP_MODE_SW" << "RC_MAP_LOITER_SW" << "RC_MAP_RETURN_SW" << "RC_MAP_POSCTL_SW" << "RC_MAP_ACRO_SW"; - foreach (QString switchParam, switchList) { + foreach (const QString &switchParam, switchList) { Q_ASSERT(_autopilot->getParameterFact(FactSystem::defaultComponentId, switchParam)->rawValue().toInt() != channel + 1); } } diff --git a/src/ui/linechart/LinechartPlot.cc b/src/ui/linechart/LinechartPlot.cc index 604da57786182391b47bf4e6c6f9a3ffe1fc6eaa..510e0cf454236c4424c6f9aa303fb500048ae642 100644 --- a/src/ui/linechart/LinechartPlot.cc +++ b/src/ui/linechart/LinechartPlot.cc @@ -183,7 +183,7 @@ void LinechartPlot::setActive(bool active) void LinechartPlot::removeTimedOutCurves() { - foreach(QString key, lastUpdate.keys()) + foreach(const QString &key, lastUpdate.keys()) { quint64 time = lastUpdate.value(key); if (QGC::groundTimeMilliseconds() - time > 10000) @@ -499,7 +499,7 @@ bool LinechartPlot::isVisible(QString id) bool LinechartPlot::anyCurveVisible() { bool visible = false; - foreach (QString key, curves.keys()) + foreach (const QString &key, curves.keys()) { if (curves.value(key)->isVisible()) { diff --git a/src/ui/linechart/LinechartWidget.cc b/src/ui/linechart/LinechartWidget.cc index 84ba2e555a34aea47fd4b0a64b26d973a257720c..7726de0b3aa410a667a0ced45988038b7f3734ef 100644 --- a/src/ui/linechart/LinechartWidget.cc +++ b/src/ui/linechart/LinechartWidget.cc @@ -673,7 +673,7 @@ void LinechartWidget::removeCurve(QString curve) void LinechartWidget::recolor() { activePlot->styleChanged(qgcApp()->styleIsDark()); - foreach (QString key, colorIcons.keys()) + foreach (const QString &key, colorIcons.keys()) { QWidget* colorIcon = colorIcons.value(key, 0); if (colorIcon && !colorIcon->styleSheet().isEmpty()) @@ -713,7 +713,7 @@ void LinechartWidget::filterCurves(const QString &filter) { /* Hide Elements which do not match the filter pattern */ QStringMatcher stringMatcher(filter, Qt::CaseInsensitive); - foreach (QString key, colorIcons.keys()) + foreach (const QString &key, colorIcons.keys()) { if (stringMatcher.indexIn(key) < 0) { @@ -728,7 +728,7 @@ void LinechartWidget::filterCurves(const QString &filter) else { /* Show all Elements */ - foreach (QString key, colorIcons.keys()) + foreach (const QString &key, colorIcons.keys()) { filterCurve(key, true); } @@ -796,7 +796,7 @@ QString LinechartWidget::getCurveName(const QString& key, bool shortEnabled) void LinechartWidget::setShortNames(bool enable) { - foreach (QString key, curveNames.keys()) + foreach (const QString &key, curveNames.keys()) { curveNameLabels.value(key)->setText(getCurveName(key, enable)); }