From f1ed746d33f29fc1795da798a8d38c75545ec47f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Patrick=20Jos=C3=A9=20Pereira?= Date: Tue, 23 Oct 2018 22:02:20 -0300 Subject: [PATCH] MissionManager: Change from foreach to c++11 for MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Patrick José Pereira --- src/MissionManager/CameraCalcTest.cc | 2 +- src/MissionManager/CameraSectionTest.cc | 10 +++++----- src/MissionManager/CorridorScanComplexItem.cc | 14 +++++++------- src/MissionManager/GeoFenceController.cc | 4 ++-- src/MissionManager/MissionCommandList.cc | 4 ++-- src/MissionManager/MissionCommandTree.cc | 8 ++++---- src/MissionManager/MissionCommandTreeTest.cc | 4 ++-- src/MissionManager/MissionCommandUIInfo.cc | 18 +++++++++--------- src/MissionManager/MissionController.cc | 2 +- src/MissionManager/MissionItemTest.cc | 6 +++--- src/MissionManager/QGCMapPolygon.cc | 6 +++--- src/MissionManager/QGCMapPolyline.cc | 4 ++-- src/MissionManager/SimpleMissionItem.cc | 2 +- .../StructureScanComplexItemTest.cc | 2 +- src/MissionManager/SurveyComplexItem.cc | 14 +++++++------- src/MissionManager/SurveyComplexItemTest.cc | 2 +- src/MissionManager/TransectStyleComplexItem.cc | 18 +++++++++--------- .../TransectStyleComplexItemTest.cc | 8 ++++---- 18 files changed, 64 insertions(+), 64 deletions(-) diff --git a/src/MissionManager/CameraCalcTest.cc b/src/MissionManager/CameraCalcTest.cc index d6fa3dcb0..10571ce12 100644 --- a/src/MissionManager/CameraCalcTest.cc +++ b/src/MissionManager/CameraCalcTest.cc @@ -68,7 +68,7 @@ void CameraCalcTest::_testDirty(void) << _cameraCalc->sideOverlap () << _cameraCalc->adjustedFootprintSide() << _cameraCalc->adjustedFootprintFrontal(); - foreach(Fact* fact, rgFacts) { + for(Fact* fact: rgFacts) { qDebug() << fact->name(); QVERIFY(!_cameraCalc->dirty()); if (fact->typeIsBool()) { diff --git a/src/MissionManager/CameraSectionTest.cc b/src/MissionManager/CameraSectionTest.cc index 81225f4e5..a575dff16 100644 --- a/src/MissionManager/CameraSectionTest.cc +++ b/src/MissionManager/CameraSectionTest.cc @@ -421,7 +421,7 @@ void CameraSectionTest::_testItemCount(void) QList rgCameraActions; rgCameraActions << CameraSection::TakePhotosIntervalTime << CameraSection::TakePhotoIntervalDistance << CameraSection::StopTakingPhotos << CameraSection::TakeVideo << CameraSection::StopTakingVideo << CameraSection::TakePhoto; - foreach(int cameraAction, rgCameraActions) { + for(int cameraAction: rgCameraActions) { qDebug() << "camera action" << cameraAction; // Reset @@ -1063,8 +1063,8 @@ void CameraSectionTest::_testScanForMultipleItems(void) rgActionItems << _validDistanceItem << _validTimeItem << _validStartVideoItem << _validStopVideoItem << _validTakePhotoItem; // Camera action followed by gimbal/mode - foreach (SimpleMissionItem* actionItem, rgActionItems) { - foreach (SimpleMissionItem* cameraItem, rgCameraItems) { + for (SimpleMissionItem* actionItem: rgActionItems) { + for (SimpleMissionItem* cameraItem: rgCameraItems) { SimpleMissionItem* item1 = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this); item1->missionItem() = actionItem->missionItem(); SimpleMissionItem* item2 = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this); @@ -1084,8 +1084,8 @@ void CameraSectionTest::_testScanForMultipleItems(void) } // Gimbal/Mode followed by camera action - foreach (SimpleMissionItem* actionItem, rgCameraItems) { - foreach (SimpleMissionItem* cameraItem, rgActionItems) { + for (SimpleMissionItem* actionItem: rgCameraItems) { + for (SimpleMissionItem* cameraItem: rgActionItems) { SimpleMissionItem* item1 = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this); item1->missionItem() = actionItem->missionItem(); SimpleMissionItem* item2 = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this); diff --git a/src/MissionManager/CorridorScanComplexItem.cc b/src/MissionManager/CorridorScanComplexItem.cc index 827ba910e..dafe3ed90 100644 --- a/src/MissionManager/CorridorScanComplexItem.cc +++ b/src/MissionManager/CorridorScanComplexItem.cc @@ -149,7 +149,7 @@ void CorridorScanComplexItem::_appendLoadedMissionItems(QList& ite int seqNum = _sequenceNumber; - foreach (const MissionItem* loadedMissionItem, _loadedMissionItems) { + for (const MissionItem* loadedMissionItem: _loadedMissionItems) { MissionItem* item = new MissionItem(*loadedMissionItem, missionItemParent); item->setSequenceNumber(seqNum++); items.append(item); @@ -171,11 +171,11 @@ void CorridorScanComplexItem::_buildAndAppendMissionItems(QList& i MAV_FRAME mavFrame = followTerrain() || !_cameraCalc.distanceToSurfaceRelative() ? MAV_FRAME_GLOBAL : MAV_FRAME_GLOBAL_RELATIVE_ALT; //qDebug() << "_buildAndAppendMissionItems"; - foreach (const QList& transect, _transects) { + for (const QList& transect: _transects) { bool entryPoint = true; //qDebug() << "start transect"; - foreach (const CoordInfo_t& transectCoordInfo, transect) { + for (const CoordInfo_t& transectCoordInfo: transect) { //qDebug() << transectCoordInfo.coordType; item = new MissionItem(seqNum++, @@ -309,7 +309,7 @@ void CorridorScanComplexItem::_rebuildCorridorPolygon(void) _surveyAreaPolygon.clear(); QList rgCoord; - foreach (const QGeoCoordinate& vertex, firstSideVertices) { + for (const QGeoCoordinate& vertex: firstSideVertices) { rgCoord.append(vertex); } for (int i=secondSideVertices.count() - 1; i >= 0; i--) { @@ -386,7 +386,7 @@ void CorridorScanComplexItem::_rebuildTransectsPhase1(void) #if 0 qDebug() << "transect debug"; - foreach (const TransectStyleComplexItem::CoordInfo_t& coordInfo, transect) { + for (const TransectStyleComplexItem::CoordInfo_t& coordInfo: transect) { qDebug() << coordInfo.coordType; } #endif @@ -423,7 +423,7 @@ void CorridorScanComplexItem::_rebuildTransectsPhase1(void) } if (reverseTransects) { QList> reversedTransects; - foreach (const QList& transect, _transects) { + for (const QList& transect: _transects) { reversedTransects.prepend(transect); } _transects = reversedTransects; @@ -431,7 +431,7 @@ void CorridorScanComplexItem::_rebuildTransectsPhase1(void) if (reverseVertices) { for (int i=0; i<_transects.count(); i++) { QList reversedVertices; - foreach (const TransectStyleComplexItem::CoordInfo_t& vertex, _transects[i]) { + for (const TransectStyleComplexItem::CoordInfo_t& vertex: _transects[i]) { reversedVertices.prepend(vertex); } _transects[i] = reversedVertices; diff --git a/src/MissionManager/GeoFenceController.cc b/src/MissionManager/GeoFenceController.cc index 254790b3d..5d3733ea1 100644 --- a/src/MissionManager/GeoFenceController.cc +++ b/src/MissionManager/GeoFenceController.cc @@ -143,7 +143,7 @@ bool GeoFenceController::load(const QJsonObject& json, QString& errorString) } QJsonArray jsonPolygonArray = json[_jsonPolygonsKey].toArray(); - foreach (const QJsonValue& jsonPolygonValue, jsonPolygonArray) { + for (const QJsonValue& jsonPolygonValue: jsonPolygonArray) { if (jsonPolygonValue.type() != QJsonValue::Object) { errorString = tr("GeoFence polygon not stored as object"); return false; @@ -157,7 +157,7 @@ bool GeoFenceController::load(const QJsonObject& json, QString& errorString) } QJsonArray jsonCircleArray = json[_jsonCirclesKey].toArray(); - foreach (const QJsonValue& jsonCircleValue, jsonCircleArray) { + for (const QJsonValue& jsonCircleValue: jsonCircleArray) { if (jsonCircleValue.type() != QJsonValue::Object) { errorString = tr("GeoFence circle not stored as object"); return false; diff --git a/src/MissionManager/MissionCommandList.cc b/src/MissionManager/MissionCommandList.cc index 32a9080ac..7c0e537e6 100644 --- a/src/MissionManager/MissionCommandList.cc +++ b/src/MissionManager/MissionCommandList.cc @@ -71,7 +71,7 @@ void MissionCommandList::_loadMavCmdInfoJson(const QString& jsonFilename, bool b // Iterate over MissionCommandUIInfo objects QJsonArray jsonArray = jsonValue.toArray(); - foreach(QJsonValue info, jsonArray) { + for(QJsonValue info: jsonArray) { if (!info.isObject()) { qWarning() << jsonFilename << "mavCmdArray should contain objects"; return; @@ -96,7 +96,7 @@ void MissionCommandList::_loadMavCmdInfoJson(const QString& jsonFilename, bool b } // Build id list - foreach (MAV_CMD id, _infoMap.keys()) { + for (MAV_CMD id: _infoMap.keys()) { _ids << id; } } diff --git a/src/MissionManager/MissionCommandTree.cc b/src/MissionManager/MissionCommandTree.cc index c2db1a1fc..8d4bce9d4 100644 --- a/src/MissionManager/MissionCommandTree.cc +++ b/src/MissionManager/MissionCommandTree.cc @@ -47,13 +47,13 @@ void MissionCommandTree::setToolbox(QGCToolbox* toolbox) } else { #endif // Load all levels of hierarchy - foreach (MAV_AUTOPILOT firmwareType, _toolbox->firmwarePluginManager()->supportedFirmwareTypes()) { + for (MAV_AUTOPILOT firmwareType: _toolbox->firmwarePluginManager()->supportedFirmwareTypes()) { FirmwarePlugin* plugin = _toolbox->firmwarePluginManager()->firmwarePluginForAutopilot(firmwareType, MAV_TYPE_QUADROTOR); QList vehicleTypes; vehicleTypes << MAV_TYPE_GENERIC << MAV_TYPE_FIXED_WING << MAV_TYPE_QUADROTOR << MAV_TYPE_VTOL_QUADROTOR << MAV_TYPE_GROUND_ROVER << MAV_TYPE_SUBMARINE; - foreach(MAV_TYPE vehicleType, vehicleTypes) { + for(MAV_TYPE vehicleType: vehicleTypes) { QString overrideFile = plugin->missionCommandOverrides(vehicleType); if (!overrideFile.isEmpty()) { _staticCommandTree[firmwareType][vehicleType] = new MissionCommandList(overrideFile, firmwareType == MAV_AUTOPILOT_GENERIC && vehicleType == MAV_TYPE_GENERIC /* baseCommandList */, this); @@ -105,7 +105,7 @@ void MissionCommandTree::_collapseHierarchy(Vehicle* _baseVehicleInfo(vehicle, baseFirmwareType, baseVehicleType); - foreach (MAV_CMD command, cmdList->commandIds()) { + for (MAV_CMD command: cmdList->commandIds()) { // Only add supported command to tree (MAV_CMD_NAV_LAST is used for planned home position) if (!qgcApp()->runningUnitTests() && !vehicle->firmwarePlugin()->supportedMissionCommands().isEmpty() @@ -238,7 +238,7 @@ QVariantList MissionCommandTree::getCommandsForCategory(Vehicle* vehicle, const QVariantList list; QMap commandMap = _availableCommands[baseFirmwareType][baseVehicleType]; - foreach (MAV_CMD command, commandMap.keys()) { + for (MAV_CMD command: commandMap.keys()) { if (command == MAV_CMD_NAV_LAST) { // MAV_CMD_NAV_LAST is used for Mission Settings item. Although we want to be able to get command info for it. // The user should not be able to use it as a command. diff --git a/src/MissionManager/MissionCommandTreeTest.cc b/src/MissionManager/MissionCommandTreeTest.cc index 9407d9f8b..4a414fc87 100644 --- a/src/MissionManager/MissionCommandTreeTest.cc +++ b/src/MissionManager/MissionCommandTreeTest.cc @@ -206,8 +206,8 @@ void MissionCommandTreeTest::testAllTrees(void) vehicleList << MAV_TYPE_GENERIC << MAV_TYPE_QUADROTOR << MAV_TYPE_FIXED_WING << MAV_TYPE_GROUND_ROVER << MAV_TYPE_SUBMARINE << MAV_TYPE_VTOL_QUADROTOR; // This will cause all of the variants of collapsed trees to be built - foreach(MAV_AUTOPILOT firmwareType, firmwareList) { - foreach (MAV_TYPE vehicleType, vehicleList) { + for(MAV_AUTOPILOT firmwareType: firmwareList) { + for (MAV_TYPE vehicleType: vehicleList) { if (firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA && vehicleType == MAV_TYPE_VTOL_QUADROTOR) { // VTOL in ArduPilot shows up as plane so we can test this pair continue; diff --git a/src/MissionManager/MissionCommandUIInfo.cc b/src/MissionManager/MissionCommandUIInfo.cc index c12b7aaa8..3c2747d81 100644 --- a/src/MissionManager/MissionCommandUIInfo.cc +++ b/src/MissionManager/MissionCommandUIInfo.cc @@ -85,7 +85,7 @@ const MissionCommandUIInfo& MissionCommandUIInfo::operator=(const MissionCommand _infoMap = other._infoMap; _paramRemoveList = other._paramRemoveList; - foreach (int index, other._paramInfoMap.keys()) { + for (int index: other._paramInfoMap.keys()) { _paramInfoMap[index] = new MissionCmdParamInfo(*other._paramInfoMap[index], this); } @@ -167,19 +167,19 @@ bool MissionCommandUIInfo::specifiesAltitudeOnly(void) const void MissionCommandUIInfo::_overrideInfo(MissionCommandUIInfo* uiInfo) { // Override info values - foreach (const QString& valueKey, uiInfo->_infoMap.keys()) { + for (const QString& valueKey: uiInfo->_infoMap.keys()) { _setInfoValue(valueKey, uiInfo->_infoMap[valueKey]); } // Add to the remove params list - foreach (int removeIndex, uiInfo->_paramRemoveList) { + for (int removeIndex: uiInfo->_paramRemoveList) { if (!_paramRemoveList.contains(removeIndex)) { _paramRemoveList.append(removeIndex); } } // Override param info - foreach (const int paramIndex, uiInfo->_paramInfoMap.keys()) { + for (const int paramIndex: uiInfo->_paramInfoMap.keys()) { _paramRemoveList.removeOne(paramIndex); // MissionCmdParamInfo objects are owned by MissionCommandTree are are in existence for the entire run so // we can just use the same pointer reference. @@ -202,7 +202,7 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ << _paramRemoveJsonKey << _categoryJsonKey << _specifiesAltitudeOnlyJsonKey; // Look for unknown keys in top level object - foreach (const QString& key, jsonObject.keys()) { + for (const QString& key: jsonObject.keys()) { if (!allKeys.contains(key) && key != _commentJsonKey) { errorString = _loadErrorString(QString("Unknown key: %1").arg(key)); return false; @@ -267,7 +267,7 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ } if (jsonObject.contains(_paramRemoveJsonKey)) { QStringList indexList = jsonObject.value(_paramRemoveJsonKey).toString().split(QStringLiteral(",")); - foreach (const QString& indexString, indexList) { + for (const QString& indexString: indexList) { _paramRemoveList.append(indexString.toInt()); } } @@ -308,7 +308,7 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ } QString debugOutput; - foreach (const QString& infoKey, _infoMap.keys()) { + for (const QString& infoKey: _infoMap.keys()) { debugOutput.append(QString("MavCmdInfo %1: %2 ").arg(infoKey).arg(_infoMap[infoKey].toString())); } qCDebug(MissionCommandsLog) << debugOutput; @@ -325,7 +325,7 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ allParamKeys << _defaultJsonKey << _decimalPlacesJsonKey << _enumStringsJsonKey << _enumValuesJsonKey << _labelJsonKey << _unitsJsonKey << _nanUnchangedJsonKey; // Look for unknown keys in param object - foreach (const QString& key, paramObject.keys()) { + for (const QString& key: paramObject.keys()) { if (!allParamKeys.contains(key) && key != _commentJsonKey) { errorString = _loadErrorString(QString("Unknown param key: %1").arg(key)); return false; @@ -372,7 +372,7 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ } QStringList enumValues = paramObject.value(_enumValuesJsonKey).toString().split(",", QString::SkipEmptyParts); - foreach (const QString &enumValue, enumValues) { + for (const QString &enumValue: enumValues) { bool convertOk; double value = enumValue.toDouble(&convertOk); diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc index 524514121..6f26b67c8 100644 --- a/src/MissionManager/MissionController.cc +++ b/src/MissionManager/MissionController.cc @@ -1156,7 +1156,7 @@ void MissionController::_recalcWaypointLines(void) // Create a temporary QObjectList and replace the model data QObjectList objs; objs.reserve(_linesTable.count()); - foreach(CoordinateVector *vect, _linesTable.values()) { + for(CoordinateVector *vect: _linesTable.values()) { objs.append(vect); } diff --git a/src/MissionManager/MissionItemTest.cc b/src/MissionManager/MissionItemTest.cc index f4ed23e4f..cac8d3bb5 100644 --- a/src/MissionManager/MissionItemTest.cc +++ b/src/MissionManager/MissionItemTest.cc @@ -301,7 +301,7 @@ void MissionItemTest::_testLoadFromJsonV1(void) QStringList removeKeys; removeKeys << MissionItem::_jsonParam1Key << MissionItem::_jsonParam2Key << MissionItem::_jsonParam3Key << MissionItem::_jsonParam4Key; - foreach (const QString& removeKey, removeKeys) { + for (const QString& removeKey: removeKeys) { QJsonObject badObject = jsonObject; badObject.remove(removeKey); QCOMPARE(missionItem.load(badObject, _seq, errorString), false); @@ -329,7 +329,7 @@ void MissionItemTest::_testLoadFromJsonV2(void) QStringList removeKeys; removeKeys << MissionItem::_jsonCoordinateKey; - foreach(const QString& removeKey, removeKeys) { + for(const QString& removeKey: removeKeys) { QJsonObject badObject = jsonObject; badObject.remove(removeKey); QCOMPARE(missionItem.load(badObject, _seq, errorString), false); @@ -399,7 +399,7 @@ void MissionItemTest::_testLoadFromJsonV3(void) MissionItem::_jsonFrameKey << MissionItem::_jsonParamsKey << VisualMissionItem::jsonTypeKey; - foreach(const QString& removeKey, removeKeys) { + for(const QString& removeKey: removeKeys) { QJsonObject badObject = jsonObject; badObject.remove(removeKey); QCOMPARE(missionItem.load(badObject, _seq, errorString), false); diff --git a/src/MissionManager/QGCMapPolygon.cc b/src/MissionManager/QGCMapPolygon.cc index feec11d0f..ba3619a38 100644 --- a/src/MissionManager/QGCMapPolygon.cc +++ b/src/MissionManager/QGCMapPolygon.cc @@ -58,7 +58,7 @@ const QGCMapPolygon& QGCMapPolygon::operator=(const QGCMapPolygon& other) QVariantList vertices = other.path(); QList rgCoord; - foreach (const QVariant& vertexVar, vertices) { + for (const QVariant& vertexVar: vertices) { rgCoord.append(vertexVar.value()); } appendVertices(rgCoord); @@ -162,7 +162,7 @@ void QGCMapPolygon::setPath(const QList& path) { _polygonPath.clear(); _polygonModel.clearAndDeleteContents(); - foreach(const QGeoCoordinate& coord, path) { + for(const QGeoCoordinate& coord: path) { _polygonPath.append(QVariant::fromValue(coord)); _polygonModel.append(new QGCQGeoCoordinate(coord, this)); } @@ -265,7 +265,7 @@ void QGCMapPolygon::appendVertices(const QList& coordinates) { QList objects; - foreach (const QGeoCoordinate& coordinate, coordinates) { + for (const QGeoCoordinate& coordinate: coordinates) { objects.append(new QGCQGeoCoordinate(coordinate, this)); _polygonPath.append(QVariant::fromValue(coordinate)); } diff --git a/src/MissionManager/QGCMapPolyline.cc b/src/MissionManager/QGCMapPolyline.cc index 9d6eda2b9..c4a308593 100644 --- a/src/MissionManager/QGCMapPolyline.cc +++ b/src/MissionManager/QGCMapPolyline.cc @@ -120,7 +120,7 @@ void QGCMapPolyline::setPath(const QList& path) { _polylinePath.clear(); _polylineModel.clearAndDeleteContents(); - foreach (const QGeoCoordinate& coord, path) { + for (const QGeoCoordinate& coord: path) { _polylinePath.append(QVariant::fromValue(coord)); _polylineModel.append(new QGCQGeoCoordinate(coord, this)); } @@ -382,7 +382,7 @@ void QGCMapPolyline::appendVertices(const QList& coordinates) { QList objects; - foreach (const QGeoCoordinate& coordinate, coordinates) { + for (const QGeoCoordinate& coordinate: coordinates) { objects.append(new QGCQGeoCoordinate(coordinate, this)); _polylinePath.append(QVariant::fromValue(coordinate)); } diff --git a/src/MissionManager/SimpleMissionItem.cc b/src/MissionManager/SimpleMissionItem.cc index 6fb45ca27..40ca7d04e 100644 --- a/src/MissionManager/SimpleMissionItem.cc +++ b/src/MissionManager/SimpleMissionItem.cc @@ -250,7 +250,7 @@ void SimpleMissionItem::_setupMetaData(void) enumStrings.clear(); enumValues.clear(); MissionCommandTree* commandTree = qgcApp()->toolbox()->missionCommandTree(); - foreach (const MAV_CMD command, commandTree->allCommandIds()) { + for (const MAV_CMD command: commandTree->allCommandIds()) { enumStrings.append(commandTree->rawName(command)); enumValues.append(QVariant((int)command)); } diff --git a/src/MissionManager/StructureScanComplexItemTest.cc b/src/MissionManager/StructureScanComplexItemTest.cc index 88352c9ad..17fc257bd 100644 --- a/src/MissionManager/StructureScanComplexItemTest.cc +++ b/src/MissionManager/StructureScanComplexItemTest.cc @@ -60,7 +60,7 @@ void StructureScanComplexItemTest::_testDirty(void) // These facts should set dirty when changed QList rgFacts; rgFacts << _structureScanItem->altitude() << _structureScanItem->layers(); - foreach(Fact* fact, rgFacts) { + for(Fact* fact: rgFacts) { qDebug() << fact->name(); QVERIFY(!_structureScanItem->dirty()); if (fact->typeIsBool()) { diff --git a/src/MissionManager/SurveyComplexItem.cc b/src/MissionManager/SurveyComplexItem.cc index 231729529..420fab39a 100644 --- a/src/MissionManager/SurveyComplexItem.cc +++ b/src/MissionManager/SurveyComplexItem.cc @@ -819,10 +819,10 @@ void SurveyComplexItem::_buildAndAppendMissionItems(QList& items, MAV_FRAME mavFrame = followTerrain() || !_cameraCalc.distanceToSurfaceRelative() ? MAV_FRAME_GLOBAL : MAV_FRAME_GLOBAL_RELATIVE_ALT; - foreach (const QList& transect, _transects) { + for (const QList& transect: _transects) { bool entryPoint = true; - foreach (const CoordInfo_t& transectCoordInfo, transect) { + for (const CoordInfo_t& transectCoordInfo: transect) { item = new MissionItem(seqNum++, MAV_CMD_NAV_WAYPOINT, mavFrame, @@ -940,7 +940,7 @@ bool SurveyComplexItem::_buildAndAppendMissionItems(QList& items, firstWaypointTrigger = true; } - foreach (const QList& transect, _transects) { + for (const QList& transect: _transects) { int pointIndex = 0; QGeoCoordinate coord; CameraTriggerCode cameraTrigger; @@ -1182,7 +1182,7 @@ void SurveyComplexItem::_rebuildTransectsPhase1Worker(bool refly) // Convert from NED to Geo QList> transects; - foreach (const QLineF& line, resultLines) { + for (const QLineF& line: resultLines) { QGeoCoordinate coord; QList transect; @@ -1234,7 +1234,7 @@ void SurveyComplexItem::_rebuildTransectsPhase1Worker(bool refly) } // Convert to CoordInfo transects and append to _transects - foreach (const QList& transect, transects) { + for (const QList& transect: transects) { QGeoCoordinate coord; QList coordInfoTransect; TransectStyleComplexItem::CoordInfo_t coordInfo; @@ -1293,7 +1293,7 @@ void SurveyComplexItem::_rebuildTransectsPhase2(void) _cameraShots = qCeil(_complexDistance / triggerDistance()); } else { _cameraShots = 0; - foreach (const QList& transect, _transects) { + for (const QList& transect: _transects) { QGeoCoordinate firstCameraCoord, lastCameraCoord; if (_hasTurnaround()) { firstCameraCoord = transect[1].coord; @@ -1345,7 +1345,7 @@ void SurveyComplexItem::_appendLoadedMissionItems(QList& items, QO int seqNum = _sequenceNumber; - foreach (const MissionItem* loadedMissionItem, _loadedMissionItems) { + for (const MissionItem* loadedMissionItem: _loadedMissionItems) { MissionItem* item = new MissionItem(*loadedMissionItem, missionItemParent); item->setSequenceNumber(seqNum++); items.append(item); diff --git a/src/MissionManager/SurveyComplexItemTest.cc b/src/MissionManager/SurveyComplexItemTest.cc index ca86135c3..0666bda98 100644 --- a/src/MissionManager/SurveyComplexItemTest.cc +++ b/src/MissionManager/SurveyComplexItemTest.cc @@ -71,7 +71,7 @@ void SurveyComplexItemTest::_testDirty(void) // These facts should set dirty when changed QList rgFacts; rgFacts << _surveyItem->gridAngle() << _surveyItem->flyAlternateTransects(); - foreach(Fact* fact, rgFacts) { + for(Fact* fact: rgFacts) { qDebug() << fact->name(); QVERIFY(!_surveyItem->dirty()); if (fact->typeIsBool()) { diff --git a/src/MissionManager/TransectStyleComplexItem.cc b/src/MissionManager/TransectStyleComplexItem.cc index 22126e744..7005d9a5e 100644 --- a/src/MissionManager/TransectStyleComplexItem.cc +++ b/src/MissionManager/TransectStyleComplexItem.cc @@ -162,7 +162,7 @@ void TransectStyleComplexItem::_save(QJsonObject& complexObject) QObject* missionItemParent = new QObject(); QList missionItems; appendMissionItems(missionItems, missionItemParent); - foreach (const MissionItem* missionItem, missionItems) { + for (const MissionItem* missionItem: missionItems) { QJsonObject missionItemJsonObject; missionItem->save(missionItemJsonObject); missionItemsJsonArray.append(missionItemJsonObject); @@ -228,7 +228,7 @@ bool TransectStyleComplexItem::_load(const QJsonObject& complexObject, QString& // Load generated mission items _loadedMissionItemsParent = new QObject(this); QJsonArray missionItemsJsonArray = innerObject[_jsonItemsKey].toArray(); - foreach (const QJsonValue& missionItemJson, missionItemsJsonArray) { + for (const QJsonValue& missionItemJson: missionItemsJsonArray) { MissionItem* missionItem = new MissionItem(_loadedMissionItemsParent); if (!missionItem->load(missionItemJson.toObject(), 0 /* sequenceNumber */, errorString)) { _loadedMissionItemsParent->deleteLater(); @@ -371,8 +371,8 @@ void TransectStyleComplexItem::_rebuildTransects(void) double top = 0.; // Generate the visuals transect representation _visualTransectPoints.clear(); - foreach (const QList& transect, _transects) { - foreach (const CoordInfo_t& coordInfo, transect) { + for (const QList& transect: _transects) { + for (const CoordInfo_t& coordInfo: transect) { _visualTransectPoints.append(QVariant::fromValue(coordInfo.coord)); double lat = coordInfo.coord.latitude() + 90.0; double lon = coordInfo.coord.longitude() + 180.0; @@ -440,8 +440,8 @@ void TransectStyleComplexItem::_reallyQueryTransectsPathHeightInfo(void) QList transectPoints; - foreach (const QList& transect, _transects) { - foreach (const CoordInfo_t& coordInfo, transect) { + for (const QList& transect: _transects) { + for (const CoordInfo_t& coordInfo: transect) { transectPoints.append(coordInfo.coord); } } @@ -645,7 +645,7 @@ void TransectStyleComplexItem::_adjustForTolerance(QList& transect) #if 0 qDebug() << "_adjustForTolerance"; - foreach (const TransectStyleComplexItem::CoordInfo_t& coordInfo, adjustedPoints) { + for (const TransectStyleComplexItem::CoordInfo_t& coordInfo: adjustedPoints) { qDebug() << coordInfo.coordType; } #endif @@ -698,7 +698,7 @@ void TransectStyleComplexItem::_addInterstitialTerrainPoints(QList& #if 0 qDebug() << "_addInterstitialTerrainPoints"; - foreach (const TransectStyleComplexItem::CoordInfo_t& coordInfo, adjustedTransect) { + for (const TransectStyleComplexItem::CoordInfo_t& coordInfo: adjustedTransect) { qDebug() << coordInfo.coordType; } #endif @@ -723,7 +723,7 @@ int TransectStyleComplexItem::lastSequenceNumber(void) const // We have to determine from transects int itemCount = 0; - foreach (const QList& rgCoordInfo, _transects) { + for (const QList& rgCoordInfo: _transects) { itemCount += rgCoordInfo.count() * (hoverAndCaptureEnabled() ? 2 : 1); } diff --git a/src/MissionManager/TransectStyleComplexItemTest.cc b/src/MissionManager/TransectStyleComplexItemTest.cc index 99caca578..97242c6e7 100644 --- a/src/MissionManager/TransectStyleComplexItemTest.cc +++ b/src/MissionManager/TransectStyleComplexItemTest.cc @@ -77,7 +77,7 @@ void TransectStyleComplexItemTest::_testDirty(void) << _transectStyleItem->cameraTriggerInTurnAround() << _transectStyleItem->hoverAndCapture() << _transectStyleItem->refly90Degrees(); - foreach(Fact* fact, rgFacts) { + for(Fact* fact: rgFacts) { qDebug() << fact->name(); QVERIFY(!_transectStyleItem->dirty()); changeFactValue(fact); @@ -102,7 +102,7 @@ void TransectStyleComplexItemTest::_testDirty(void) void TransectStyleComplexItemTest::_setSurveyAreaPolygon(void) { - foreach (const QGeoCoordinate vertex, _polygonVertices) { + for (const QGeoCoordinate vertex: _polygonVertices) { _transectStyleItem->surveyAreaPolygon()->appendVertex(vertex); } } @@ -132,7 +132,7 @@ void TransectStyleComplexItemTest::_testRebuildTransects(void) << _transectStyleItem->refly90Degrees() << _transectStyleItem->cameraCalc()->frontalOverlap() << _transectStyleItem->cameraCalc()->sideOverlap(); - foreach(Fact* fact, rgFacts) { + for(Fact* fact: rgFacts) { qDebug() << fact->name(); changeFactValue(fact); QVERIFY(_transectStyleItem->rebuildTransectsPhase1Called); @@ -175,7 +175,7 @@ void TransectStyleComplexItemTest::_testDistanceSignalling(void) rgFacts << _transectStyleItem->turnAroundDistance() << _transectStyleItem->hoverAndCapture() << _transectStyleItem->refly90Degrees(); - foreach(Fact* fact, rgFacts) { + for(Fact* fact: rgFacts) { qDebug() << fact->name(); changeFactValue(fact); QVERIFY(_multiSpy->checkSignalsByMask(complexDistanceChangedMask | greatestDistanceToChangedMask)); -- 2.22.0