Browse Source

MissionManager: Change from foreach to c++11 for

Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
QGC4.4
Patrick José Pereira 7 years ago
parent
commit
f1ed746d33
  1. 2
      src/MissionManager/CameraCalcTest.cc
  2. 10
      src/MissionManager/CameraSectionTest.cc
  3. 14
      src/MissionManager/CorridorScanComplexItem.cc
  4. 4
      src/MissionManager/GeoFenceController.cc
  5. 4
      src/MissionManager/MissionCommandList.cc
  6. 8
      src/MissionManager/MissionCommandTree.cc
  7. 4
      src/MissionManager/MissionCommandTreeTest.cc
  8. 18
      src/MissionManager/MissionCommandUIInfo.cc
  9. 2
      src/MissionManager/MissionController.cc
  10. 6
      src/MissionManager/MissionItemTest.cc
  11. 6
      src/MissionManager/QGCMapPolygon.cc
  12. 4
      src/MissionManager/QGCMapPolyline.cc
  13. 2
      src/MissionManager/SimpleMissionItem.cc
  14. 2
      src/MissionManager/StructureScanComplexItemTest.cc
  15. 14
      src/MissionManager/SurveyComplexItem.cc
  16. 2
      src/MissionManager/SurveyComplexItemTest.cc
  17. 18
      src/MissionManager/TransectStyleComplexItem.cc
  18. 8
      src/MissionManager/TransectStyleComplexItemTest.cc

2
src/MissionManager/CameraCalcTest.cc

@ -68,7 +68,7 @@ void CameraCalcTest::_testDirty(void) @@ -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()) {

10
src/MissionManager/CameraSectionTest.cc

@ -421,7 +421,7 @@ void CameraSectionTest::_testItemCount(void) @@ -421,7 +421,7 @@ void CameraSectionTest::_testItemCount(void)
QList<int> 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) @@ -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) @@ -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);

14
src/MissionManager/CorridorScanComplexItem.cc

@ -149,7 +149,7 @@ void CorridorScanComplexItem::_appendLoadedMissionItems(QList<MissionItem*>& ite @@ -149,7 +149,7 @@ void CorridorScanComplexItem::_appendLoadedMissionItems(QList<MissionItem*>& 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<MissionItem*>& i @@ -171,11 +171,11 @@ void CorridorScanComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>& i
MAV_FRAME mavFrame = followTerrain() || !_cameraCalc.distanceToSurfaceRelative() ? MAV_FRAME_GLOBAL : MAV_FRAME_GLOBAL_RELATIVE_ALT;
//qDebug() << "_buildAndAppendMissionItems";
foreach (const QList<TransectStyleComplexItem::CoordInfo_t>& transect, _transects) {
for (const QList<TransectStyleComplexItem::CoordInfo_t>& 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) @@ -309,7 +309,7 @@ void CorridorScanComplexItem::_rebuildCorridorPolygon(void)
_surveyAreaPolygon.clear();
QList<QGeoCoordinate> 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) @@ -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) @@ -423,7 +423,7 @@ void CorridorScanComplexItem::_rebuildTransectsPhase1(void)
}
if (reverseTransects) {
QList<QList<TransectStyleComplexItem::CoordInfo_t>> reversedTransects;
foreach (const QList<TransectStyleComplexItem::CoordInfo_t>& transect, _transects) {
for (const QList<TransectStyleComplexItem::CoordInfo_t>& transect: _transects) {
reversedTransects.prepend(transect);
}
_transects = reversedTransects;
@ -431,7 +431,7 @@ void CorridorScanComplexItem::_rebuildTransectsPhase1(void) @@ -431,7 +431,7 @@ void CorridorScanComplexItem::_rebuildTransectsPhase1(void)
if (reverseVertices) {
for (int i=0; i<_transects.count(); i++) {
QList<TransectStyleComplexItem::CoordInfo_t> reversedVertices;
foreach (const TransectStyleComplexItem::CoordInfo_t& vertex, _transects[i]) {
for (const TransectStyleComplexItem::CoordInfo_t& vertex: _transects[i]) {
reversedVertices.prepend(vertex);
}
_transects[i] = reversedVertices;

4
src/MissionManager/GeoFenceController.cc

@ -143,7 +143,7 @@ bool GeoFenceController::load(const QJsonObject& json, QString& errorString) @@ -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) @@ -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;

4
src/MissionManager/MissionCommandList.cc

@ -71,7 +71,7 @@ void MissionCommandList::_loadMavCmdInfoJson(const QString& jsonFilename, bool b @@ -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 @@ -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;
}
}

8
src/MissionManager/MissionCommandTree.cc

@ -47,13 +47,13 @@ void MissionCommandTree::setToolbox(QGCToolbox* toolbox) @@ -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<MAV_TYPE> 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* @@ -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 @@ -238,7 +238,7 @@ QVariantList MissionCommandTree::getCommandsForCategory(Vehicle* vehicle, const
QVariantList list;
QMap<MAV_CMD, MissionCommandUIInfo*> 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.

4
src/MissionManager/MissionCommandTreeTest.cc

@ -206,8 +206,8 @@ void MissionCommandTreeTest::testAllTrees(void) @@ -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;

18
src/MissionManager/MissionCommandUIInfo.cc

@ -85,7 +85,7 @@ const MissionCommandUIInfo& MissionCommandUIInfo::operator=(const MissionCommand @@ -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 @@ -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 @@ -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 @@ -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 @@ -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 @@ -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 @@ -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);

2
src/MissionManager/MissionController.cc

@ -1156,7 +1156,7 @@ void MissionController::_recalcWaypointLines(void) @@ -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);
}

6
src/MissionManager/MissionItemTest.cc

@ -301,7 +301,7 @@ void MissionItemTest::_testLoadFromJsonV1(void) @@ -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) @@ -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) @@ -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);

6
src/MissionManager/QGCMapPolygon.cc

@ -58,7 +58,7 @@ const QGCMapPolygon& QGCMapPolygon::operator=(const QGCMapPolygon& other) @@ -58,7 +58,7 @@ const QGCMapPolygon& QGCMapPolygon::operator=(const QGCMapPolygon& other)
QVariantList vertices = other.path();
QList<QGeoCoordinate> rgCoord;
foreach (const QVariant& vertexVar, vertices) {
for (const QVariant& vertexVar: vertices) {
rgCoord.append(vertexVar.value<QGeoCoordinate>());
}
appendVertices(rgCoord);
@ -162,7 +162,7 @@ void QGCMapPolygon::setPath(const QList<QGeoCoordinate>& path) @@ -162,7 +162,7 @@ void QGCMapPolygon::setPath(const QList<QGeoCoordinate>& 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<QGeoCoordinate>& coordinates) @@ -265,7 +265,7 @@ void QGCMapPolygon::appendVertices(const QList<QGeoCoordinate>& coordinates)
{
QList<QObject*> objects;
foreach (const QGeoCoordinate& coordinate, coordinates) {
for (const QGeoCoordinate& coordinate: coordinates) {
objects.append(new QGCQGeoCoordinate(coordinate, this));
_polygonPath.append(QVariant::fromValue(coordinate));
}

4
src/MissionManager/QGCMapPolyline.cc

@ -120,7 +120,7 @@ void QGCMapPolyline::setPath(const QList<QGeoCoordinate>& path) @@ -120,7 +120,7 @@ void QGCMapPolyline::setPath(const QList<QGeoCoordinate>& 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<QGeoCoordinate>& coordinates) @@ -382,7 +382,7 @@ void QGCMapPolyline::appendVertices(const QList<QGeoCoordinate>& coordinates)
{
QList<QObject*> objects;
foreach (const QGeoCoordinate& coordinate, coordinates) {
for (const QGeoCoordinate& coordinate: coordinates) {
objects.append(new QGCQGeoCoordinate(coordinate, this));
_polylinePath.append(QVariant::fromValue(coordinate));
}

2
src/MissionManager/SimpleMissionItem.cc

@ -250,7 +250,7 @@ void SimpleMissionItem::_setupMetaData(void) @@ -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));
}

2
src/MissionManager/StructureScanComplexItemTest.cc

@ -60,7 +60,7 @@ void StructureScanComplexItemTest::_testDirty(void) @@ -60,7 +60,7 @@ void StructureScanComplexItemTest::_testDirty(void)
// These facts should set dirty when changed
QList<Fact*> rgFacts;
rgFacts << _structureScanItem->altitude() << _structureScanItem->layers();
foreach(Fact* fact, rgFacts) {
for(Fact* fact: rgFacts) {
qDebug() << fact->name();
QVERIFY(!_structureScanItem->dirty());
if (fact->typeIsBool()) {

14
src/MissionManager/SurveyComplexItem.cc

@ -819,10 +819,10 @@ void SurveyComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>& items, @@ -819,10 +819,10 @@ void SurveyComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>& items,
MAV_FRAME mavFrame = followTerrain() || !_cameraCalc.distanceToSurfaceRelative() ? MAV_FRAME_GLOBAL : MAV_FRAME_GLOBAL_RELATIVE_ALT;
foreach (const QList<TransectStyleComplexItem::CoordInfo_t>& transect, _transects) {
for (const QList<TransectStyleComplexItem::CoordInfo_t>& 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<MissionItem*>& items, @@ -940,7 +940,7 @@ bool SurveyComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>& items,
firstWaypointTrigger = true;
}
foreach (const QList<TransectStyleComplexItem::CoordInfo_t>& transect, _transects) {
for (const QList<TransectStyleComplexItem::CoordInfo_t>& transect: _transects) {
int pointIndex = 0;
QGeoCoordinate coord;
CameraTriggerCode cameraTrigger;
@ -1182,7 +1182,7 @@ void SurveyComplexItem::_rebuildTransectsPhase1Worker(bool refly) @@ -1182,7 +1182,7 @@ void SurveyComplexItem::_rebuildTransectsPhase1Worker(bool refly)
// Convert from NED to Geo
QList<QList<QGeoCoordinate>> transects;
foreach (const QLineF& line, resultLines) {
for (const QLineF& line: resultLines) {
QGeoCoordinate coord;
QList<QGeoCoordinate> transect;
@ -1234,7 +1234,7 @@ void SurveyComplexItem::_rebuildTransectsPhase1Worker(bool refly) @@ -1234,7 +1234,7 @@ void SurveyComplexItem::_rebuildTransectsPhase1Worker(bool refly)
}
// Convert to CoordInfo transects and append to _transects
foreach (const QList<QGeoCoordinate>& transect, transects) {
for (const QList<QGeoCoordinate>& transect: transects) {
QGeoCoordinate coord;
QList<TransectStyleComplexItem::CoordInfo_t> coordInfoTransect;
TransectStyleComplexItem::CoordInfo_t coordInfo;
@ -1293,7 +1293,7 @@ void SurveyComplexItem::_rebuildTransectsPhase2(void) @@ -1293,7 +1293,7 @@ void SurveyComplexItem::_rebuildTransectsPhase2(void)
_cameraShots = qCeil(_complexDistance / triggerDistance());
} else {
_cameraShots = 0;
foreach (const QList<TransectStyleComplexItem::CoordInfo_t>& transect, _transects) {
for (const QList<TransectStyleComplexItem::CoordInfo_t>& transect: _transects) {
QGeoCoordinate firstCameraCoord, lastCameraCoord;
if (_hasTurnaround()) {
firstCameraCoord = transect[1].coord;
@ -1345,7 +1345,7 @@ void SurveyComplexItem::_appendLoadedMissionItems(QList<MissionItem*>& items, QO @@ -1345,7 +1345,7 @@ void SurveyComplexItem::_appendLoadedMissionItems(QList<MissionItem*>& 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);

2
src/MissionManager/SurveyComplexItemTest.cc

@ -71,7 +71,7 @@ void SurveyComplexItemTest::_testDirty(void) @@ -71,7 +71,7 @@ void SurveyComplexItemTest::_testDirty(void)
// These facts should set dirty when changed
QList<Fact*> rgFacts;
rgFacts << _surveyItem->gridAngle() << _surveyItem->flyAlternateTransects();
foreach(Fact* fact, rgFacts) {
for(Fact* fact: rgFacts) {
qDebug() << fact->name();
QVERIFY(!_surveyItem->dirty());
if (fact->typeIsBool()) {

18
src/MissionManager/TransectStyleComplexItem.cc

@ -162,7 +162,7 @@ void TransectStyleComplexItem::_save(QJsonObject& complexObject) @@ -162,7 +162,7 @@ void TransectStyleComplexItem::_save(QJsonObject& complexObject)
QObject* missionItemParent = new QObject();
QList<MissionItem*> 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& @@ -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) @@ -371,8 +371,8 @@ void TransectStyleComplexItem::_rebuildTransects(void)
double top = 0.;
// Generate the visuals transect representation
_visualTransectPoints.clear();
foreach (const QList<CoordInfo_t>& transect, _transects) {
foreach (const CoordInfo_t& coordInfo, transect) {
for (const QList<CoordInfo_t>& 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) @@ -440,8 +440,8 @@ void TransectStyleComplexItem::_reallyQueryTransectsPathHeightInfo(void)
QList<QGeoCoordinate> transectPoints;
foreach (const QList<CoordInfo_t>& transect, _transects) {
foreach (const CoordInfo_t& coordInfo, transect) {
for (const QList<CoordInfo_t>& transect: _transects) {
for (const CoordInfo_t& coordInfo: transect) {
transectPoints.append(coordInfo.coord);
}
}
@ -645,7 +645,7 @@ void TransectStyleComplexItem::_adjustForTolerance(QList<CoordInfo_t>& transect) @@ -645,7 +645,7 @@ void TransectStyleComplexItem::_adjustForTolerance(QList<CoordInfo_t>& 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<CoordInfo_t>& @@ -698,7 +698,7 @@ void TransectStyleComplexItem::_addInterstitialTerrainPoints(QList<CoordInfo_t>&
#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 @@ -723,7 +723,7 @@ int TransectStyleComplexItem::lastSequenceNumber(void) const
// We have to determine from transects
int itemCount = 0;
foreach (const QList<CoordInfo_t>& rgCoordInfo, _transects) {
for (const QList<CoordInfo_t>& rgCoordInfo: _transects) {
itemCount += rgCoordInfo.count() * (hoverAndCaptureEnabled() ? 2 : 1);
}

8
src/MissionManager/TransectStyleComplexItemTest.cc

@ -77,7 +77,7 @@ void TransectStyleComplexItemTest::_testDirty(void) @@ -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) @@ -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) @@ -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) @@ -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));

Loading…
Cancel
Save