Skip to content
Projects
Groups
Snippets
Help
Loading...
Help
Support
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Q
qgroundcontrol
Project
Project
Details
Activity
Releases
Cycle Analytics
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Charts
Issues
0
Issues
0
List
Boards
Labels
Milestones
Merge Requests
0
Merge Requests
0
CI / CD
CI / CD
Pipelines
Jobs
Schedules
Charts
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Charts
Create a new issue
Jobs
Commits
Issue Boards
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
f1ed746d
Commit
f1ed746d
authored
Oct 23, 2018
by
Patrick José Pereira
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
MissionManager: Change from foreach to c++11 for
Signed-off-by:
Patrick José Pereira
<
patrickelectric@gmail.com
>
parent
df569bcf
Changes
18
Hide whitespace changes
Inline
Side-by-side
Showing
18 changed files
with
64 additions
and
64 deletions
+64
-64
CameraCalcTest.cc
src/MissionManager/CameraCalcTest.cc
+1
-1
CameraSectionTest.cc
src/MissionManager/CameraSectionTest.cc
+5
-5
CorridorScanComplexItem.cc
src/MissionManager/CorridorScanComplexItem.cc
+7
-7
GeoFenceController.cc
src/MissionManager/GeoFenceController.cc
+2
-2
MissionCommandList.cc
src/MissionManager/MissionCommandList.cc
+2
-2
MissionCommandTree.cc
src/MissionManager/MissionCommandTree.cc
+4
-4
MissionCommandTreeTest.cc
src/MissionManager/MissionCommandTreeTest.cc
+2
-2
MissionCommandUIInfo.cc
src/MissionManager/MissionCommandUIInfo.cc
+9
-9
MissionController.cc
src/MissionManager/MissionController.cc
+1
-1
MissionItemTest.cc
src/MissionManager/MissionItemTest.cc
+3
-3
QGCMapPolygon.cc
src/MissionManager/QGCMapPolygon.cc
+3
-3
QGCMapPolyline.cc
src/MissionManager/QGCMapPolyline.cc
+2
-2
SimpleMissionItem.cc
src/MissionManager/SimpleMissionItem.cc
+1
-1
StructureScanComplexItemTest.cc
src/MissionManager/StructureScanComplexItemTest.cc
+1
-1
SurveyComplexItem.cc
src/MissionManager/SurveyComplexItem.cc
+7
-7
SurveyComplexItemTest.cc
src/MissionManager/SurveyComplexItemTest.cc
+1
-1
TransectStyleComplexItem.cc
src/MissionManager/TransectStyleComplexItem.cc
+9
-9
TransectStyleComplexItemTest.cc
src/MissionManager/TransectStyleComplexItemTest.cc
+4
-4
No files found.
src/MissionManager/CameraCalcTest.cc
View file @
f1ed746d
...
...
@@ -68,7 +68,7 @@ void CameraCalcTest::_testDirty(void)
<<
_cameraCalc
->
sideOverlap
()
<<
_cameraCalc
->
adjustedFootprintSide
()
<<
_cameraCalc
->
adjustedFootprintFrontal
();
for
each
(
Fact
*
fact
,
rgFacts
)
{
for
(
Fact
*
fact
:
rgFacts
)
{
qDebug
()
<<
fact
->
name
();
QVERIFY
(
!
_cameraCalc
->
dirty
());
if
(
fact
->
typeIsBool
())
{
...
...
src/MissionManager/CameraSectionTest.cc
View file @
f1ed746d
...
...
@@ -421,7 +421,7 @@ void CameraSectionTest::_testItemCount(void)
QList
<
int
>
rgCameraActions
;
rgCameraActions
<<
CameraSection
::
TakePhotosIntervalTime
<<
CameraSection
::
TakePhotoIntervalDistance
<<
CameraSection
::
StopTakingPhotos
<<
CameraSection
::
TakeVideo
<<
CameraSection
::
StopTakingVideo
<<
CameraSection
::
TakePhoto
;
for
each
(
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
for
each
(
SimpleMissionItem
*
actionItem
,
rgActionItems
)
{
for
each
(
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
for
each
(
SimpleMissionItem
*
actionItem
,
rgCameraItems
)
{
for
each
(
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
);
...
...
src/MissionManager/CorridorScanComplexItem.cc
View file @
f1ed746d
...
...
@@ -149,7 +149,7 @@ void CorridorScanComplexItem::_appendLoadedMissionItems(QList<MissionItem*>& ite
int
seqNum
=
_sequenceNumber
;
for
each
(
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
MAV_FRAME
mavFrame
=
followTerrain
()
||
!
_cameraCalc
.
distanceToSurfaceRelative
()
?
MAV_FRAME_GLOBAL
:
MAV_FRAME_GLOBAL_RELATIVE_ALT
;
//qDebug() << "_buildAndAppendMissionItems";
for
each
(
const
QList
<
TransectStyleComplexItem
::
CoordInfo_t
>&
transect
,
_transects
)
{
for
(
const
QList
<
TransectStyleComplexItem
::
CoordInfo_t
>&
transect
:
_transects
)
{
bool
entryPoint
=
true
;
//qDebug() << "start transect";
for
each
(
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
<
QGeoCoordinate
>
rgCoord
;
for
each
(
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";
for
each (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
<
QList
<
TransectStyleComplexItem
::
CoordInfo_t
>>
reversedTransects
;
for
each
(
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)
if
(
reverseVertices
)
{
for
(
int
i
=
0
;
i
<
_transects
.
count
();
i
++
)
{
QList
<
TransectStyleComplexItem
::
CoordInfo_t
>
reversedVertices
;
for
each
(
const
TransectStyleComplexItem
::
CoordInfo_t
&
vertex
,
_transects
[
i
])
{
for
(
const
TransectStyleComplexItem
::
CoordInfo_t
&
vertex
:
_transects
[
i
])
{
reversedVertices
.
prepend
(
vertex
);
}
_transects
[
i
]
=
reversedVertices
;
...
...
src/MissionManager/GeoFenceController.cc
View file @
f1ed746d
...
...
@@ -143,7 +143,7 @@ bool GeoFenceController::load(const QJsonObject& json, QString& errorString)
}
QJsonArray
jsonPolygonArray
=
json
[
_jsonPolygonsKey
].
toArray
();
for
each
(
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
();
for
each
(
const
QJsonValue
&
jsonCircleValue
,
jsonCircleArray
)
{
for
(
const
QJsonValue
&
jsonCircleValue
:
jsonCircleArray
)
{
if
(
jsonCircleValue
.
type
()
!=
QJsonValue
::
Object
)
{
errorString
=
tr
(
"GeoFence circle not stored as object"
);
return
false
;
...
...
src/MissionManager/MissionCommandList.cc
View file @
f1ed746d
...
...
@@ -71,7 +71,7 @@ void MissionCommandList::_loadMavCmdInfoJson(const QString& jsonFilename, bool b
// Iterate over MissionCommandUIInfo objects
QJsonArray
jsonArray
=
jsonValue
.
toArray
();
for
each
(
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
for
each
(
MAV_CMD
id
,
_infoMap
.
keys
())
{
for
(
MAV_CMD
id
:
_infoMap
.
keys
())
{
_ids
<<
id
;
}
}
...
...
src/MissionManager/MissionCommandTree.cc
View file @
f1ed746d
...
...
@@ -47,13 +47,13 @@ void MissionCommandTree::setToolbox(QGCToolbox* toolbox)
}
else
{
#endif
// Load all levels of hierarchy
for
each
(
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
;
for
each
(
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
);
for
each
(
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
<
MAV_CMD
,
MissionCommandUIInfo
*>
commandMap
=
_availableCommands
[
baseFirmwareType
][
baseVehicleType
];
for
each
(
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.
...
...
src/MissionManager/MissionCommandTreeTest.cc
View file @
f1ed746d
...
...
@@ -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
for
each
(
MAV_AUTOPILOT
firmwareType
,
firmwareList
)
{
for
each
(
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
;
...
...
src/MissionManager/MissionCommandUIInfo.cc
View file @
f1ed746d
...
...
@@ -85,7 +85,7 @@ const MissionCommandUIInfo& MissionCommandUIInfo::operator=(const MissionCommand
_infoMap
=
other
.
_infoMap
;
_paramRemoveList
=
other
.
_paramRemoveList
;
for
each
(
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
for
each
(
const
QString
&
valueKey
,
uiInfo
->
_infoMap
.
keys
())
{
for
(
const
QString
&
valueKey
:
uiInfo
->
_infoMap
.
keys
())
{
_setInfoValue
(
valueKey
,
uiInfo
->
_infoMap
[
valueKey
]);
}
// Add to the remove params list
for
each
(
int
removeIndex
,
uiInfo
->
_paramRemoveList
)
{
for
(
int
removeIndex
:
uiInfo
->
_paramRemoveList
)
{
if
(
!
_paramRemoveList
.
contains
(
removeIndex
))
{
_paramRemoveList
.
append
(
removeIndex
);
}
}
// Override param info
for
each
(
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
for
each
(
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
(
","
));
for
each
(
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
;
for
each
(
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
for
each
(
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
);
for
each
(
const
QString
&
enumValue
,
enumValues
)
{
for
(
const
QString
&
enumValue
:
enumValues
)
{
bool
convertOk
;
double
value
=
enumValue
.
toDouble
(
&
convertOk
);
...
...
src/MissionManager/MissionController.cc
View file @
f1ed746d
...
...
@@ -1156,7 +1156,7 @@ void MissionController::_recalcWaypointLines(void)
// Create a temporary QObjectList and replace the model data
QObjectList
objs
;
objs
.
reserve
(
_linesTable
.
count
());
for
each
(
CoordinateVector
*
vect
,
_linesTable
.
values
())
{
for
(
CoordinateVector
*
vect
:
_linesTable
.
values
())
{
objs
.
append
(
vect
);
}
...
...
src/MissionManager/MissionItemTest.cc
View file @
f1ed746d
...
...
@@ -301,7 +301,7 @@ void MissionItemTest::_testLoadFromJsonV1(void)
QStringList
removeKeys
;
removeKeys
<<
MissionItem
::
_jsonParam1Key
<<
MissionItem
::
_jsonParam2Key
<<
MissionItem
::
_jsonParam3Key
<<
MissionItem
::
_jsonParam4Key
;
for
each
(
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
;
for
each
(
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
;
for
each
(
const
QString
&
removeKey
,
removeKeys
)
{
for
(
const
QString
&
removeKey
:
removeKeys
)
{
QJsonObject
badObject
=
jsonObject
;
badObject
.
remove
(
removeKey
);
QCOMPARE
(
missionItem
.
load
(
badObject
,
_seq
,
errorString
),
false
);
...
...
src/MissionManager/QGCMapPolygon.cc
View file @
f1ed746d
...
...
@@ -58,7 +58,7 @@ const QGCMapPolygon& QGCMapPolygon::operator=(const QGCMapPolygon& other)
QVariantList
vertices
=
other
.
path
();
QList
<
QGeoCoordinate
>
rgCoord
;
for
each
(
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)
{
_polygonPath
.
clear
();
_polygonModel
.
clearAndDeleteContents
();
for
each
(
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)
{
QList
<
QObject
*>
objects
;
for
each
(
const
QGeoCoordinate
&
coordinate
,
coordinates
)
{
for
(
const
QGeoCoordinate
&
coordinate
:
coordinates
)
{
objects
.
append
(
new
QGCQGeoCoordinate
(
coordinate
,
this
));
_polygonPath
.
append
(
QVariant
::
fromValue
(
coordinate
));
}
...
...
src/MissionManager/QGCMapPolyline.cc
View file @
f1ed746d
...
...
@@ -120,7 +120,7 @@ void QGCMapPolyline::setPath(const QList<QGeoCoordinate>& path)
{
_polylinePath
.
clear
();
_polylineModel
.
clearAndDeleteContents
();
for
each
(
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)
{
QList
<
QObject
*>
objects
;
for
each
(
const
QGeoCoordinate
&
coordinate
,
coordinates
)
{
for
(
const
QGeoCoordinate
&
coordinate
:
coordinates
)
{
objects
.
append
(
new
QGCQGeoCoordinate
(
coordinate
,
this
));
_polylinePath
.
append
(
QVariant
::
fromValue
(
coordinate
));
}
...
...
src/MissionManager/SimpleMissionItem.cc
View file @
f1ed746d
...
...
@@ -250,7 +250,7 @@ void SimpleMissionItem::_setupMetaData(void)
enumStrings
.
clear
();
enumValues
.
clear
();
MissionCommandTree
*
commandTree
=
qgcApp
()
->
toolbox
()
->
missionCommandTree
();
for
each
(
const
MAV_CMD
command
,
commandTree
->
allCommandIds
())
{
for
(
const
MAV_CMD
command
:
commandTree
->
allCommandIds
())
{
enumStrings
.
append
(
commandTree
->
rawName
(
command
));
enumValues
.
append
(
QVariant
((
int
)
command
));
}
...
...
src/MissionManager/StructureScanComplexItemTest.cc
View file @
f1ed746d
...
...
@@ -60,7 +60,7 @@ void StructureScanComplexItemTest::_testDirty(void)
// These facts should set dirty when changed
QList
<
Fact
*>
rgFacts
;
rgFacts
<<
_structureScanItem
->
altitude
()
<<
_structureScanItem
->
layers
();
for
each
(
Fact
*
fact
,
rgFacts
)
{
for
(
Fact
*
fact
:
rgFacts
)
{
qDebug
()
<<
fact
->
name
();
QVERIFY
(
!
_structureScanItem
->
dirty
());
if
(
fact
->
typeIsBool
())
{
...
...
src/MissionManager/SurveyComplexItem.cc
View file @
f1ed746d
...
...
@@ -819,10 +819,10 @@ void SurveyComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>& items,
MAV_FRAME
mavFrame
=
followTerrain
()
||
!
_cameraCalc
.
distanceToSurfaceRelative
()
?
MAV_FRAME_GLOBAL
:
MAV_FRAME_GLOBAL_RELATIVE_ALT
;
for
each
(
const
QList
<
TransectStyleComplexItem
::
CoordInfo_t
>&
transect
,
_transects
)
{
for
(
const
QList
<
TransectStyleComplexItem
::
CoordInfo_t
>&
transect
:
_transects
)
{
bool
entryPoint
=
true
;
for
each
(
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,
firstWaypointTrigger = true;
}
for
each (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)
// Convert from NED to Geo
QList
<
QList
<
QGeoCoordinate
>>
transects
;
for
each
(
const
QLineF
&
line
,
resultLines
)
{
for
(
const
QLineF
&
line
:
resultLines
)
{
QGeoCoordinate
coord
;
QList
<
QGeoCoordinate
>
transect
;
...
...
@@ -1234,7 +1234,7 @@ void SurveyComplexItem::_rebuildTransectsPhase1Worker(bool refly)
}
// Convert to CoordInfo transects and append to _transects
for
each
(
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)
_cameraShots
=
qCeil
(
_complexDistance
/
triggerDistance
());
}
else
{
_cameraShots
=
0
;
for
each
(
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
int
seqNum
=
_sequenceNumber
;
for
each
(
const
MissionItem
*
loadedMissionItem
,
_loadedMissionItems
)
{
for
(
const
MissionItem
*
loadedMissionItem
:
_loadedMissionItems
)
{
MissionItem
*
item
=
new
MissionItem
(
*
loadedMissionItem
,
missionItemParent
);
item
->
setSequenceNumber
(
seqNum
++
);
items
.
append
(
item
);
...
...
src/MissionManager/SurveyComplexItemTest.cc
View file @
f1ed746d
...
...
@@ -71,7 +71,7 @@ void SurveyComplexItemTest::_testDirty(void)
// These facts should set dirty when changed
QList
<
Fact
*>
rgFacts
;
rgFacts
<<
_surveyItem
->
gridAngle
()
<<
_surveyItem
->
flyAlternateTransects
();
for
each
(
Fact
*
fact
,
rgFacts
)
{
for
(
Fact
*
fact
:
rgFacts
)
{
qDebug
()
<<
fact
->
name
();
QVERIFY
(
!
_surveyItem
->
dirty
());
if
(
fact
->
typeIsBool
())
{
...
...
src/MissionManager/TransectStyleComplexItem.cc
View file @
f1ed746d
...
...
@@ -162,7 +162,7 @@ void TransectStyleComplexItem::_save(QJsonObject& complexObject)
QObject
*
missionItemParent
=
new
QObject
();
QList
<
MissionItem
*>
missionItems
;
appendMissionItems
(
missionItems
,
missionItemParent
);
for
each
(
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
();
for
each
(
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
();
for
each
(
const
QList
<
CoordInfo_t
>&
transect
,
_transects
)
{
for
each
(
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)
QList
<
QGeoCoordinate
>
transectPoints
;
for
each
(
const
QList
<
CoordInfo_t
>&
transect
,
_transects
)
{
for
each
(
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)
#if 0
qDebug() << "_adjustForTolerance";
for
each (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>&
#if 0
qDebug() << "_addInterstitialTerrainPoints";
for
each (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
;
for
each
(
const
QList
<
CoordInfo_t
>&
rgCoordInfo
,
_transects
)
{
for
(
const
QList
<
CoordInfo_t
>&
rgCoordInfo
:
_transects
)
{
itemCount
+=
rgCoordInfo
.
count
()
*
(
hoverAndCaptureEnabled
()
?
2
:
1
);
}
...
...
src/MissionManager/TransectStyleComplexItemTest.cc
View file @
f1ed746d
...
...
@@ -77,7 +77,7 @@ void TransectStyleComplexItemTest::_testDirty(void)
<<
_transectStyleItem
->
cameraTriggerInTurnAround
()
<<
_transectStyleItem
->
hoverAndCapture
()
<<
_transectStyleItem
->
refly90Degrees
();
for
each
(
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
)
{
for
each
(
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
();
for
each
(
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
();
for
each
(
Fact
*
fact
,
rgFacts
)
{
for
(
Fact
*
fact
:
rgFacts
)
{
qDebug
()
<<
fact
->
name
();
changeFactValue
(
fact
);
QVERIFY
(
_multiSpy
->
checkSignalsByMask
(
complexDistanceChangedMask
|
greatestDistanceToChangedMask
));
...
...
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment