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
3355fcfe
Commit
3355fcfe
authored
Mar 10, 2020
by
DoinLakeFlyer
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
parent
9574328f
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
with
174 additions
and
12 deletions
+174
-12
SurveyComplexItemTest.cc
src/MissionManager/SurveyComplexItemTest.cc
+163
-8
SurveyComplexItemTest.h
src/MissionManager/SurveyComplexItemTest.h
+11
-4
No files found.
src/MissionManager/SurveyComplexItemTest.cc
View file @
3355fcfe
...
...
@@ -9,11 +9,16 @@
#include "SurveyComplexItemTest.h"
#include "QGCApplication.h"
#include "JsonHelper.h"
SurveyComplexItemTest
::
SurveyComplexItemTest
(
void
)
{
_polyPoints
<<
QGeoCoordinate
(
47.633550640000003
,
-
122.08982199
)
<<
QGeoCoordinate
(
47.634129020000003
,
-
122.08887249
)
<<
QGeoCoordinate
(
47.633619320000001
,
-
122.08811074
)
<<
QGeoCoordinate
(
47.633189139999999
,
-
122.08900124
);
// We use a 100m by 100m square test polygon
const
double
edgeDistance
=
100
;
_polyVertices
.
append
(
QGeoCoordinate
(
47.633550640000003
,
-
122.08982199
));
_polyVertices
.
append
(
_polyVertices
[
0
].
atDistanceAndAzimuth
(
edgeDistance
,
90
));
_polyVertices
.
append
(
_polyVertices
[
1
].
atDistanceAndAzimuth
(
edgeDistance
,
180
));
_polyVertices
.
append
(
_polyVertices
[
2
].
atDistanceAndAzimuth
(
edgeDistance
,
-
90.0
));
}
void
SurveyComplexItemTest
::
init
(
void
)
...
...
@@ -27,12 +32,26 @@ void SurveyComplexItemTest::init(void)
_rgSurveySignals
[
surveyRefly90DegreesChangedIndex
]
=
SIGNAL
(
refly90DegreesChanged
(
bool
));
_rgSurveySignals
[
surveyDirtyChangedIndex
]
=
SIGNAL
(
dirtyChanged
(
bool
));
_planViewSettings
=
qgcApp
()
->
toolbox
()
->
settingsManager
()
->
planViewSettings
();
_masterController
=
new
PlanMasterController
(
this
);
_controllerVehicle
=
_masterController
->
controllerVehicle
();
_surveyItem
=
new
SurveyComplexItem
(
_masterController
,
false
/* flyView */
,
QString
()
/* kmlFile */
,
this
/* parent */
);
_surveyItem
->
turnAroundDistance
()
->
setRawValue
(
0
);
// Unit test written for no turnaround distance
_surveyItem
->
setDirty
(
false
);
_mapPolygon
=
_surveyItem
->
surveyAreaPolygon
();
_mapPolygon
->
appendVertices
(
_polyVertices
);
QVERIFY
(
_surveyItem
->
cameraCalc
()
->
isManualCamera
());
// Set grid spacing to match expected transect count
double
polyWidthDistance
=
_polyVertices
[
0
].
distanceTo
(
_polyVertices
[
1
]);
double
polyHeightDistance
=
_polyVertices
[
0
].
distanceTo
(
_polyVertices
[
3
]);
_surveyItem
->
cameraCalc
()
->
adjustedFootprintSide
()
->
setRawValue
((
polyWidthDistance
*
0.5
)
-
1.0
);
_surveyItem
->
cameraCalc
()
->
adjustedFootprintFrontal
()
->
setRawValue
(
polyHeightDistance
*
0.25
);
_surveyItem
->
gridAngle
()
->
setRawValue
(
0
);
int
expectedTransectCount
=
_expectedTransectCount
;
QCOMPARE
(
_surveyItem
->
_transectCount
(),
expectedTransectCount
);
_surveyItem
->
setDirty
(
false
);
// It's important to check that the right signals are emitted at the right time since that drives ui change.
// It's also important to check that things are not being over-signalled when they should not be, since that can lead
...
...
@@ -107,10 +126,7 @@ double SurveyComplexItemTest::_clampGridAngle180(double gridAngle)
void
SurveyComplexItemTest
::
_setPolygon
(
void
)
{
for
(
int
i
=
0
;
i
<
_polyPoints
.
count
();
i
++
)
{
QGeoCoordinate
&
vertex
=
_polyPoints
[
i
];
_mapPolygon
->
appendVertex
(
vertex
);
}
_mapPolygon
->
appendVertices
(
_polyVertices
);
}
void
SurveyComplexItemTest
::
_testGridAngle
(
void
)
...
...
@@ -184,3 +200,142 @@ void SurveyComplexItemTest::_testItemCount(void)
QCOMPARE
(
items
.
count
()
-
1
,
_surveyItem
->
lastSequenceNumber
());
items
.
clear
();
}
QList
<
MAV_CMD
>
SurveyComplexItemTest
::
_createExpectedCommands
(
bool
hasTurnaround
,
bool
useConditionGate
)
{
static
const
QList
<
MAV_CMD
>
singleFullTransect
=
{
MAV_CMD_NAV_WAYPOINT
,
// Turnaround
MAV_CMD_CONDITION_GATE
,
// Survey area entry edge
MAV_CMD_DO_SET_CAM_TRIGG_DIST
,
MAV_CMD_CONDITION_GATE
,
// Survey area exit edge
MAV_CMD_DO_SET_CAM_TRIGG_DIST
,
MAV_CMD_NAV_WAYPOINT
,
};
QList
<
MAV_CMD
>
singleTransect
=
singleFullTransect
;
QList
<
MAV_CMD
>
expectedCommands
;
if
(
!
useConditionGate
)
{
for
(
MAV_CMD
&
cmd
:
singleTransect
)
{
cmd
=
cmd
==
MAV_CMD_CONDITION_GATE
?
MAV_CMD_NAV_WAYPOINT
:
cmd
;
}
}
if
(
!
hasTurnaround
)
{
singleTransect
.
takeFirst
();
singleTransect
.
takeLast
();
}
for
(
int
i
=
0
;
i
<
_expectedTransectCount
;
i
++
)
{
expectedCommands
.
append
(
singleTransect
);
}
return
expectedCommands
;
}
void
SurveyComplexItemTest
::
_testItemGenerationWorker
(
bool
imagesInTurnaround
,
bool
hasTurnaround
,
bool
useConditionGate
,
const
QList
<
MAV_CMD
>&
expectedCommands
)
{
qDebug
()
<<
QStringLiteral
(
"_testItemGenerationWorker imagesInTuraround:%1 turnaround:%2 gate:%3"
).
arg
(
imagesInTurnaround
).
arg
(
hasTurnaround
).
arg
(
useConditionGate
);
_surveyItem
->
turnAroundDistance
()
->
setRawValue
(
hasTurnaround
?
50
:
0
);
_surveyItem
->
cameraTriggerInTurnAround
()
->
setRawValue
(
imagesInTurnaround
);
_planViewSettings
->
useConditionGate
()
->
setRawValue
(
useConditionGate
);
QList
<
MissionItem
*>
items
;
_surveyItem
->
appendMissionItems
(
items
,
this
);
#if 0
// Handy for debugging failures
for (const MissionItem* item : items) {
qDebug() << "Cmd" << item->command();
}
#endif
QCOMPARE
(
items
.
count
(),
expectedCommands
.
count
());
for
(
int
i
=
0
;
i
<
expectedCommands
.
count
();
i
++
)
{
int
actualCommand
=
items
[
i
]
->
command
();
int
expectedCommand
=
expectedCommands
[
i
];
#if 0
// Handy for debugging failures
qDebug() << "Index" << i;
#endif
QCOMPARE
(
actualCommand
,
expectedCommand
);
}
}
void
SurveyComplexItemTest
::
_testItemGeneration
(
void
)
{
// Test all the combinations of: cameraTriggerInTurnAround: false, hasTurnAround: *, useConditionGate: *
typedef
struct
{
bool
hasTurnaround
;
bool
useConditionGate
;
}
TestCase_t
;
static
const
TestCase_t
rgTestCases
[]
=
{
{
false
,
false
},
{
false
,
true
},
{
true
,
false
},
{
true
,
true
},
};
for
(
const
TestCase_t
&
testCase
:
rgTestCases
)
{
_testItemGenerationWorker
(
false
/* imagesInTurnaround */
,
testCase
.
hasTurnaround
,
testCase
.
useConditionGate
,
_createExpectedCommands
(
testCase
.
hasTurnaround
,
testCase
.
useConditionGate
));
}
// Test cameraTriggerInTurnAround = true cases
QList
<
MAV_CMD
>
imagesInTurnaroundCommands
=
{
// Transect 1
MAV_CMD_CONDITION_GATE
,
// First turaround
MAV_CMD_DO_SET_CAM_TRIGG_DIST
,
MAV_CMD_CONDITION_GATE
,
// Survey entry
MAV_CMD_DO_SET_CAM_TRIGG_DIST
,
// Survey entry also has trigger start
MAV_CMD_NAV_WAYPOINT
,
// Survey exit
MAV_CMD_NAV_WAYPOINT
,
// Turnaround
// Transect 2
MAV_CMD_NAV_WAYPOINT
,
// Turnaround
MAV_CMD_CONDITION_GATE
,
// Survey entry
MAV_CMD_DO_SET_CAM_TRIGG_DIST
,
// Survey entry also has trigger start
MAV_CMD_NAV_WAYPOINT
,
// Survey exit
MAV_CMD_CONDITION_GATE
,
// Final turnaround
MAV_CMD_DO_SET_CAM_TRIGG_DIST
,
};
_testItemGenerationWorker
(
true
/* imagesInTurnaround */
,
true
/* hasTurnaround */
,
true
/* useConditionGate */
,
imagesInTurnaroundCommands
);
// Switch to non CONDITION_GATE usage
for
(
MAV_CMD
&
cmd
:
imagesInTurnaroundCommands
)
{
cmd
=
cmd
==
MAV_CMD_CONDITION_GATE
?
MAV_CMD_NAV_WAYPOINT
:
cmd
;
}
_testItemGenerationWorker
(
true
/* imagesInTurnaround */
,
true
/* hasTurnaround */
,
false
/* useConditionGate */
,
imagesInTurnaroundCommands
);
}
void
SurveyComplexItemTest
::
_testHoverCaptureItemGeneration
(
void
)
{
static
const
QList
<
MAV_CMD
>
singleFullTransect
=
{
MAV_CMD_NAV_WAYPOINT
,
// Turnaround
MAV_CMD_NAV_WAYPOINT
,
// Survey area entry edge
MAV_CMD_IMAGE_START_CAPTURE
,
MAV_CMD_NAV_WAYPOINT
,
// Interior trigger
MAV_CMD_IMAGE_START_CAPTURE
,
MAV_CMD_NAV_WAYPOINT
,
// Interior trigger
MAV_CMD_IMAGE_START_CAPTURE
,
MAV_CMD_NAV_WAYPOINT
,
// Survey area exit edge
MAV_CMD_IMAGE_START_CAPTURE
,
MAV_CMD_NAV_WAYPOINT
,
// Turnaround
};
QList
<
MAV_CMD
>
expectedCommands
;
for
(
int
i
=
0
;
i
<
_expectedTransectCount
;
i
++
)
{
expectedCommands
.
append
(
singleFullTransect
);
}
// Set trigger distance to generates two interior capture points
double
polyHeightDistance
=
_polyVertices
[
0
].
distanceTo
(
_polyVertices
[
3
]);
double
triggerDistance
=
(
polyHeightDistance
/
3.0
)
+
1.0
;
_surveyItem
->
cameraCalc
()
->
adjustedFootprintFrontal
()
->
setRawValue
(
triggerDistance
);
qDebug
()
<<
"_testHoverCaptureItemGeneration"
;
_surveyItem
->
hoverAndCapture
()
->
setRawValue
(
true
);
_testItemGenerationWorker
(
false
/* imagesInTurnaround */
,
true
/* hasTurnaround */
,
true
/* useConditionGate */
,
expectedCommands
);
_testItemGenerationWorker
(
false
/* imagesInTurnaround */
,
true
/* hasTurnaround */
,
false
/* useConditionGate */
,
expectedCommands
);
}
src/MissionManager/SurveyComplexItemTest.h
View file @
3355fcfe
...
...
@@ -14,6 +14,7 @@
#include "MultiSignalSpy.h"
#include "SurveyComplexItem.h"
#include "PlanMasterController.h"
#include "PlanViewSettings.h"
#include <QGeoCoordinate>
...
...
@@ -30,15 +31,18 @@ protected:
void
cleanup
(
void
)
final
;
private
slots
:
void
_testHoverCaptureItemGeneration
(
void
);
private:
void
_testDirty
(
void
);
void
_testGridAngle
(
void
);
void
_testEntryLocation
(
void
);
void
_testItemCount
(
void
);
private:
void
_testItemGeneration
(
void
);
double
_clampGridAngle180
(
double
gridAngle
);
void
_setPolygon
(
void
);
QList
<
MAV_CMD
>
_createExpectedCommands
(
bool
hasTurnaround
,
bool
useConditionGate
);
void
_testItemGenerationWorker
(
bool
imagesInTurnaround
,
bool
hasTurnaround
,
bool
useConditionGate
,
const
QList
<
MAV_CMD
>&
expectedCommands
);
// SurveyComplexItem signals
...
...
@@ -69,5 +73,8 @@ private:
MultiSignalSpy
*
_multiSpy
=
nullptr
;
SurveyComplexItem
*
_surveyItem
=
nullptr
;
QGCMapPolygon
*
_mapPolygon
=
nullptr
;
QList
<
QGeoCoordinate
>
_polyPoints
;
PlanViewSettings
*
_planViewSettings
=
nullptr
;
QList
<
QGeoCoordinate
>
_polyVertices
;
static
const
int
_expectedTransectCount
=
2
;
};
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