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
985c72e5
Commit
985c72e5
authored
Apr 30, 2018
by
DonLakeFlyer
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
SurveyMissionItem -> SurveyComplexItem
parent
8962f261
Changes
11
Hide whitespace changes
Inline
Side-by-side
Showing
11 changed files
with
198 additions
and
207 deletions
+198
-207
qgroundcontrol.pro
qgroundcontrol.pro
+4
-4
CorridorScanComplexItemTest.cc
src/MissionManager/CorridorScanComplexItemTest.cc
+4
-4
MissionController.cc
src/MissionManager/MissionController.cc
+9
-9
MissionItem.h
src/MissionManager/MissionItem.h
+2
-2
QGCMapPolygonTest.h
src/MissionManager/QGCMapPolygonTest.h
+0
-1
SectionTest.cc
src/MissionManager/SectionTest.cc
+2
-2
SurveyComplexItem.cc
src/MissionManager/SurveyComplexItem.cc
+148
-148
SurveyComplexItem.h
src/MissionManager/SurveyComplexItem.h
+4
-8
SurveyComplexItemTest.cc
src/MissionManager/SurveyComplexItemTest.cc
+17
-17
SurveyComplexItemTest.h
src/MissionManager/SurveyComplexItemTest.h
+6
-10
UnitTestList.cc
src/qgcunittest/UnitTestList.cc
+2
-2
No files found.
qgroundcontrol.pro
View file @
985c72e5
...
...
@@ -433,7 +433,7 @@ DebugBuild { PX4FirmwarePlugin { PX4FirmwarePluginFactory { APMFirmwarePlugin {
src
/
MissionManager
/
SimpleMissionItemTest
.
h
\
src
/
MissionManager
/
SpeedSectionTest
.
h
\
src
/
MissionManager
/
StructureScanComplexItemTest
.
h
\
src
/
MissionManager
/
Survey
Mission
ItemTest
.
h
\
src
/
MissionManager
/
Survey
Complex
ItemTest
.
h
\
src
/
MissionManager
/
TransectStyleComplexItemTest
.
h
\
src
/
MissionManager
/
VisualMissionItemTest
.
h
\
src
/
qgcunittest
/
FileDialogTest
.
h
\
...
...
@@ -474,7 +474,7 @@ DebugBuild { PX4FirmwarePlugin { PX4FirmwarePluginFactory { APMFirmwarePlugin {
src
/
MissionManager
/
SimpleMissionItemTest
.
cc
\
src
/
MissionManager
/
SpeedSectionTest
.
cc
\
src
/
MissionManager
/
StructureScanComplexItemTest
.
cc
\
src
/
MissionManager
/
Survey
Mission
ItemTest
.
cc
\
src
/
MissionManager
/
Survey
Complex
ItemTest
.
cc
\
src
/
MissionManager
/
TransectStyleComplexItemTest
.
cc
\
src
/
MissionManager
/
VisualMissionItemTest
.
cc
\
src
/
qgcunittest
/
FileDialogTest
.
cc
\
...
...
@@ -546,7 +546,7 @@ HEADERS += \
src
/
MissionManager
/
Section
.
h
\
src
/
MissionManager
/
SpeedSection
.
h
\
src
/
MissionManager
/
StructureScanComplexItem
.
h
\
src
/
MissionManager
/
Survey
Mission
Item
.
h
\
src
/
MissionManager
/
Survey
Complex
Item
.
h
\
src
/
MissionManager
/
TransectStyleComplexItem
.
h
\
src
/
MissionManager
/
VisualMissionItem
.
h
\
src
/
PositionManager
/
PositionManager
.
h
\
...
...
@@ -740,7 +740,7 @@ SOURCES += \
src
/
MissionManager
/
SimpleMissionItem
.
cc
\
src
/
MissionManager
/
SpeedSection
.
cc
\
src
/
MissionManager
/
StructureScanComplexItem
.
cc
\
src
/
MissionManager
/
Survey
Mission
Item
.
cc
\
src
/
MissionManager
/
Survey
Complex
Item
.
cc
\
src
/
MissionManager
/
TransectStyleComplexItem
.
cc
\
src
/
MissionManager
/
VisualMissionItem
.
cc
\
src
/
PositionManager
/
PositionManager
.
cpp
\
...
...
src/MissionManager/CorridorScanComplexItemTest.cc
View file @
985c72e5
...
...
@@ -117,10 +117,10 @@ void CorridorScanComplexItemTest::_testEntryLocation(void)
QList<QGeoCoordinate> rgSeenEntryCoords;
QList<int> rgEntryLocation;
rgEntryLocation << Survey
Mission
Item::EntryLocationTopLeft
<< Survey
Mission
Item::EntryLocationTopRight
<< Survey
Mission
Item::EntryLocationBottomLeft
<< Survey
Mission
Item::EntryLocationBottomRight;
rgEntryLocation << Survey
Complex
Item::EntryLocationTopLeft
<< Survey
Complex
Item::EntryLocationTopRight
<< Survey
Complex
Item::EntryLocationBottomLeft
<< Survey
Complex
Item::EntryLocationBottomRight;
// Validate that each entry location is unique
for (int i=0; i<rgEntryLocation.count(); i++) {
...
...
src/MissionManager/MissionController.cc
View file @
985c72e5
...
...
@@ -16,7 +16,7 @@
#include "FirmwarePlugin.h"
#include "QGCApplication.h"
#include "SimpleMissionItem.h"
#include "Survey
Mission
Item.h"
#include "Survey
Complex
Item.h"
#include "FixedWingLandingComplexItem.h"
#include "StructureScanComplexItem.h"
#include "CorridorScanComplexItem.h"
...
...
@@ -394,7 +394,7 @@ int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate
int
sequenceNumber
=
_nextSequenceNumber
();
if
(
itemName
==
_surveyMissionItemName
)
{
newItem
=
new
Survey
Mission
Item
(
_controllerVehicle
,
_visualItems
);
newItem
=
new
Survey
Complex
Item
(
_controllerVehicle
,
_visualItems
);
newItem
->
setCoordinate
(
mapCenterCoordinate
);
surveyStyleItem
=
true
;
}
else
if
(
itemName
==
_fwLandingMissionItemName
)
{
...
...
@@ -452,7 +452,7 @@ void MissionController::removeMissionItem(int index)
return
;
}
bool
removeSurveyStyle
=
_visualItems
->
value
<
Survey
Mission
Item
*>
(
index
)
||
_visualItems
->
value
<
CorridorScanComplexItem
*>
(
index
);
bool
removeSurveyStyle
=
_visualItems
->
value
<
Survey
Complex
Item
*>
(
index
)
||
_visualItems
->
value
<
CorridorScanComplexItem
*>
(
index
);
VisualMissionItem
*
item
=
qobject_cast
<
VisualMissionItem
*>
(
_visualItems
->
removeAt
(
index
));
_deinitVisualItem
(
item
);
...
...
@@ -462,7 +462,7 @@ void MissionController::removeMissionItem(int index)
// Determine if the mission still has another survey style item in it
bool
foundSurvey
=
false
;
for
(
int
i
=
1
;
i
<
_visualItems
->
count
();
i
++
)
{
if
(
_visualItems
->
value
<
Survey
Mission
Item
*>
(
i
)
||
_visualItems
->
value
<
CorridorScanComplexItem
*>
(
i
))
{
if
(
_visualItems
->
value
<
Survey
Complex
Item
*>
(
i
)
||
_visualItems
->
value
<
CorridorScanComplexItem
*>
(
i
))
{
foundSurvey
=
true
;
break
;
}
...
...
@@ -519,7 +519,7 @@ bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjec
}
// Read complex items
QList
<
Survey
Mission
Item
*>
surveyItems
;
QList
<
Survey
Complex
Item
*>
surveyItems
;
QJsonArray
complexArray
(
json
[
_jsonComplexItemsKey
].
toArray
());
qCDebug
(
MissionControllerLog
)
<<
"Json load: complex item count"
<<
complexArray
.
count
();
for
(
int
i
=
0
;
i
<
complexArray
.
count
();
i
++
)
{
...
...
@@ -530,7 +530,7 @@ bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjec
return
false
;
}
Survey
MissionItem
*
item
=
new
SurveyMission
Item
(
_controllerVehicle
,
visualItems
);
Survey
ComplexItem
*
item
=
new
SurveyComplex
Item
(
_controllerVehicle
,
visualItems
);
const
QJsonObject
itemObject
=
itemValue
.
toObject
();
if
(
item
->
load
(
itemObject
,
itemObject
[
"id"
].
toInt
(),
errorString
))
{
surveyItems
.
append
(
item
);
...
...
@@ -552,7 +552,7 @@ bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjec
// If there is a complex item that should be next in sequence add it in
if
(
nextComplexItemIndex
<
surveyItems
.
count
())
{
Survey
Mission
Item
*
complexItem
=
surveyItems
[
nextComplexItemIndex
];
Survey
Complex
Item
*
complexItem
=
surveyItems
[
nextComplexItemIndex
];
if
(
complexItem
->
sequenceNumber
()
==
nextSequenceNumber
)
{
qCDebug
(
MissionControllerLog
)
<<
"Json load: injecting complex item expectedSequence:actualSequence:"
<<
nextSequenceNumber
<<
complexItem
->
sequenceNumber
();
...
...
@@ -686,9 +686,9 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec
}
QString
complexItemType
=
itemObject
[
ComplexMissionItem
::
jsonComplexItemTypeKey
].
toString
();
if
(
complexItemType
==
Survey
Mission
Item
::
jsonComplexItemTypeValue
)
{
if
(
complexItemType
==
Survey
Complex
Item
::
jsonComplexItemTypeValue
)
{
qCDebug
(
MissionControllerLog
)
<<
"Loading Survey: nextSequenceNumber"
<<
nextSequenceNumber
;
Survey
MissionItem
*
surveyItem
=
new
SurveyMission
Item
(
_controllerVehicle
,
visualItems
);
Survey
ComplexItem
*
surveyItem
=
new
SurveyComplex
Item
(
_controllerVehicle
,
visualItems
);
if
(
!
surveyItem
->
load
(
itemObject
,
nextSequenceNumber
++
,
errorString
))
{
return
false
;
}
...
...
src/MissionManager/MissionItem.h
View file @
985c72e5
...
...
@@ -25,7 +25,7 @@
#include "QGCLoggingCategory.h"
#include "QmlObjectListModel.h"
class
Survey
Mission
Item
;
class
Survey
Complex
Item
;
class
SimpleMissionItem
;
class
MissionController
;
#ifdef UNITTEST_BUILD
...
...
@@ -151,7 +151,7 @@ private:
static
const
char
*
_jsonParam3Key
;
static
const
char
*
_jsonParam4Key
;
friend
class
Survey
Mission
Item
;
friend
class
Survey
Complex
Item
;
friend
class
SimpleMissionItem
;
friend
class
MissionController
;
#ifdef UNITTEST_BUILD
...
...
src/MissionManager/QGCMapPolygonTest.h
View file @
985c72e5
...
...
@@ -14,7 +14,6 @@
#include "QGCMapPolygon.h"
#include "QmlObjectListModel.h"
/// Unit test for SurveyMissionItem
class
QGCMapPolygonTest
:
public
UnitTest
{
Q_OBJECT
...
...
src/MissionManager/SectionTest.cc
View file @
985c72e5
...
...
@@ -8,7 +8,7 @@
****************************************************************************/
#include "SectionTest.h"
#include "Survey
Mission
Item.h"
#include "Survey
Complex
Item.h"
SectionTest
::
SectionTest
(
void
)
:
_simpleItem
(
NULL
)
...
...
@@ -83,7 +83,7 @@ void SectionTest::_commonScanTest(Section* section)
waypointVisualItems
.
append
(
&
simpleItem
);
QmlObjectListModel
complexVisualItems
;
Survey
Mission
Item
surveyItem
(
_offlineVehicle
);
Survey
Complex
Item
surveyItem
(
_offlineVehicle
);
complexVisualItems
.
append
(
&
surveyItem
);
// This tests the common cases which should not lead to scan succeess
...
...
src/MissionManager/Survey
Mission
Item.cc
→
src/MissionManager/Survey
Complex
Item.cc
View file @
985c72e5
...
...
@@ -8,7 +8,7 @@
****************************************************************************/
#include "Survey
Mission
Item.h"
#include "Survey
Complex
Item.h"
#include "JsonHelper.h"
#include "MissionController.h"
#include "QGCGeo.h"
...
...
@@ -19,61 +19,61 @@
#include <QPolygonF>
QGC_LOGGING_CATEGORY
(
Survey
MissionItemLog
,
"SurveyMission
ItemLog"
)
const
char
*
Survey
Mission
Item
::
jsonComplexItemTypeValue
=
"survey"
;
const
char
*
Survey
Mission
Item
::
_jsonGridObjectKey
=
"grid"
;
const
char
*
Survey
Mission
Item
::
_jsonGridAltitudeKey
=
"altitude"
;
const
char
*
Survey
Mission
Item
::
_jsonGridAltitudeRelativeKey
=
"relativeAltitude"
;
const
char
*
Survey
Mission
Item
::
_jsonGridAngleKey
=
"angle"
;
const
char
*
Survey
Mission
Item
::
_jsonGridSpacingKey
=
"spacing"
;
const
char
*
Survey
Mission
Item
::
_jsonGridEntryLocationKey
=
"entryLocation"
;
const
char
*
Survey
Mission
Item
::
_jsonTurnaroundDistKey
=
"turnAroundDistance"
;
const
char
*
Survey
Mission
Item
::
_jsonCameraTriggerDistanceKey
=
"cameraTriggerDistance"
;
const
char
*
Survey
Mission
Item
::
_jsonCameraTriggerInTurnaroundKey
=
"cameraTriggerInTurnaround"
;
const
char
*
Survey
Mission
Item
::
_jsonHoverAndCaptureKey
=
"hoverAndCapture"
;
const
char
*
Survey
Mission
Item
::
_jsonGroundResolutionKey
=
"groundResolution"
;
const
char
*
Survey
Mission
Item
::
_jsonFrontalOverlapKey
=
"imageFrontalOverlap"
;
const
char
*
Survey
Mission
Item
::
_jsonSideOverlapKey
=
"imageSideOverlap"
;
const
char
*
Survey
Mission
Item
::
_jsonCameraSensorWidthKey
=
"sensorWidth"
;
const
char
*
Survey
Mission
Item
::
_jsonCameraSensorHeightKey
=
"sensorHeight"
;
const
char
*
Survey
Mission
Item
::
_jsonCameraResolutionWidthKey
=
"resolutionWidth"
;
const
char
*
Survey
Mission
Item
::
_jsonCameraResolutionHeightKey
=
"resolutionHeight"
;
const
char
*
Survey
Mission
Item
::
_jsonCameraFocalLengthKey
=
"focalLength"
;
const
char
*
Survey
Mission
Item
::
_jsonCameraMinTriggerIntervalKey
=
"minTriggerInterval"
;
const
char
*
Survey
Mission
Item
::
_jsonCameraObjectKey
=
"camera"
;
const
char
*
Survey
Mission
Item
::
_jsonCameraNameKey
=
"name"
;
const
char
*
Survey
Mission
Item
::
_jsonManualGridKey
=
"manualGrid"
;
const
char
*
Survey
Mission
Item
::
_jsonCameraOrientationLandscapeKey
=
"orientationLandscape"
;
const
char
*
Survey
Mission
Item
::
_jsonFixedValueIsAltitudeKey
=
"fixedValueIsAltitude"
;
const
char
*
Survey
Mission
Item
::
_jsonRefly90DegreesKey
=
"refly90Degrees"
;
const
char
*
Survey
Mission
Item
::
settingsGroup
=
"Survey"
;
const
char
*
Survey
Mission
Item
::
manualGridName
=
"ManualGrid"
;
const
char
*
Survey
Mission
Item
::
gridAltitudeName
=
"GridAltitude"
;
const
char
*
Survey
Mission
Item
::
gridAltitudeRelativeName
=
"GridAltitudeRelative"
;
const
char
*
Survey
Mission
Item
::
gridAngleName
=
"GridAngle"
;
const
char
*
Survey
Mission
Item
::
gridSpacingName
=
"GridSpacing"
;
const
char
*
Survey
Mission
Item
::
gridEntryLocationName
=
"GridEntryLocation"
;
const
char
*
Survey
Mission
Item
::
turnaroundDistName
=
"TurnaroundDist"
;
const
char
*
Survey
Mission
Item
::
cameraTriggerDistanceName
=
"CameraTriggerDistance"
;
const
char
*
Survey
Mission
Item
::
cameraTriggerInTurnaroundName
=
"CameraTriggerInTurnaround"
;
const
char
*
Survey
Mission
Item
::
hoverAndCaptureName
=
"HoverAndCapture"
;
const
char
*
Survey
Mission
Item
::
groundResolutionName
=
"GroundResolution"
;
const
char
*
Survey
Mission
Item
::
frontalOverlapName
=
"FrontalOverlap"
;
const
char
*
Survey
Mission
Item
::
sideOverlapName
=
"SideOverlap"
;
const
char
*
Survey
Mission
Item
::
cameraSensorWidthName
=
"CameraSensorWidth"
;
const
char
*
Survey
Mission
Item
::
cameraSensorHeightName
=
"CameraSensorHeight"
;
const
char
*
Survey
Mission
Item
::
cameraResolutionWidthName
=
"CameraResolutionWidth"
;
const
char
*
Survey
Mission
Item
::
cameraResolutionHeightName
=
"CameraResolutionHeight"
;
const
char
*
Survey
Mission
Item
::
cameraFocalLengthName
=
"CameraFocalLength"
;
const
char
*
Survey
Mission
Item
::
cameraTriggerName
=
"CameraTrigger"
;
const
char
*
Survey
Mission
Item
::
cameraOrientationLandscapeName
=
"CameraOrientationLandscape"
;
const
char
*
Survey
Mission
Item
::
fixedValueIsAltitudeName
=
"FixedValueIsAltitude"
;
const
char
*
Survey
Mission
Item
::
cameraName
=
"Camera"
;
Survey
MissionItem
::
SurveyMission
Item
(
Vehicle
*
vehicle
,
QObject
*
parent
)
QGC_LOGGING_CATEGORY
(
Survey
ComplexItemLog
,
"SurveyComplex
ItemLog"
)
const
char
*
Survey
Complex
Item
::
jsonComplexItemTypeValue
=
"survey"
;
const
char
*
Survey
Complex
Item
::
_jsonGridObjectKey
=
"grid"
;
const
char
*
Survey
Complex
Item
::
_jsonGridAltitudeKey
=
"altitude"
;
const
char
*
Survey
Complex
Item
::
_jsonGridAltitudeRelativeKey
=
"relativeAltitude"
;
const
char
*
Survey
Complex
Item
::
_jsonGridAngleKey
=
"angle"
;
const
char
*
Survey
Complex
Item
::
_jsonGridSpacingKey
=
"spacing"
;
const
char
*
Survey
Complex
Item
::
_jsonGridEntryLocationKey
=
"entryLocation"
;
const
char
*
Survey
Complex
Item
::
_jsonTurnaroundDistKey
=
"turnAroundDistance"
;
const
char
*
Survey
Complex
Item
::
_jsonCameraTriggerDistanceKey
=
"cameraTriggerDistance"
;
const
char
*
Survey
Complex
Item
::
_jsonCameraTriggerInTurnaroundKey
=
"cameraTriggerInTurnaround"
;
const
char
*
Survey
Complex
Item
::
_jsonHoverAndCaptureKey
=
"hoverAndCapture"
;
const
char
*
Survey
Complex
Item
::
_jsonGroundResolutionKey
=
"groundResolution"
;
const
char
*
Survey
Complex
Item
::
_jsonFrontalOverlapKey
=
"imageFrontalOverlap"
;
const
char
*
Survey
Complex
Item
::
_jsonSideOverlapKey
=
"imageSideOverlap"
;
const
char
*
Survey
Complex
Item
::
_jsonCameraSensorWidthKey
=
"sensorWidth"
;
const
char
*
Survey
Complex
Item
::
_jsonCameraSensorHeightKey
=
"sensorHeight"
;
const
char
*
Survey
Complex
Item
::
_jsonCameraResolutionWidthKey
=
"resolutionWidth"
;
const
char
*
Survey
Complex
Item
::
_jsonCameraResolutionHeightKey
=
"resolutionHeight"
;
const
char
*
Survey
Complex
Item
::
_jsonCameraFocalLengthKey
=
"focalLength"
;
const
char
*
Survey
Complex
Item
::
_jsonCameraMinTriggerIntervalKey
=
"minTriggerInterval"
;
const
char
*
Survey
Complex
Item
::
_jsonCameraObjectKey
=
"camera"
;
const
char
*
Survey
Complex
Item
::
_jsonCameraNameKey
=
"name"
;
const
char
*
Survey
Complex
Item
::
_jsonManualGridKey
=
"manualGrid"
;
const
char
*
Survey
Complex
Item
::
_jsonCameraOrientationLandscapeKey
=
"orientationLandscape"
;
const
char
*
Survey
Complex
Item
::
_jsonFixedValueIsAltitudeKey
=
"fixedValueIsAltitude"
;
const
char
*
Survey
Complex
Item
::
_jsonRefly90DegreesKey
=
"refly90Degrees"
;
const
char
*
Survey
Complex
Item
::
settingsGroup
=
"Survey"
;
const
char
*
Survey
Complex
Item
::
manualGridName
=
"ManualGrid"
;
const
char
*
Survey
Complex
Item
::
gridAltitudeName
=
"GridAltitude"
;
const
char
*
Survey
Complex
Item
::
gridAltitudeRelativeName
=
"GridAltitudeRelative"
;
const
char
*
Survey
Complex
Item
::
gridAngleName
=
"GridAngle"
;
const
char
*
Survey
Complex
Item
::
gridSpacingName
=
"GridSpacing"
;
const
char
*
Survey
Complex
Item
::
gridEntryLocationName
=
"GridEntryLocation"
;
const
char
*
Survey
Complex
Item
::
turnaroundDistName
=
"TurnaroundDist"
;
const
char
*
Survey
Complex
Item
::
cameraTriggerDistanceName
=
"CameraTriggerDistance"
;
const
char
*
Survey
Complex
Item
::
cameraTriggerInTurnaroundName
=
"CameraTriggerInTurnaround"
;
const
char
*
Survey
Complex
Item
::
hoverAndCaptureName
=
"HoverAndCapture"
;
const
char
*
Survey
Complex
Item
::
groundResolutionName
=
"GroundResolution"
;
const
char
*
Survey
Complex
Item
::
frontalOverlapName
=
"FrontalOverlap"
;
const
char
*
Survey
Complex
Item
::
sideOverlapName
=
"SideOverlap"
;
const
char
*
Survey
Complex
Item
::
cameraSensorWidthName
=
"CameraSensorWidth"
;
const
char
*
Survey
Complex
Item
::
cameraSensorHeightName
=
"CameraSensorHeight"
;
const
char
*
Survey
Complex
Item
::
cameraResolutionWidthName
=
"CameraResolutionWidth"
;
const
char
*
Survey
Complex
Item
::
cameraResolutionHeightName
=
"CameraResolutionHeight"
;
const
char
*
Survey
Complex
Item
::
cameraFocalLengthName
=
"CameraFocalLength"
;
const
char
*
Survey
Complex
Item
::
cameraTriggerName
=
"CameraTrigger"
;
const
char
*
Survey
Complex
Item
::
cameraOrientationLandscapeName
=
"CameraOrientationLandscape"
;
const
char
*
Survey
Complex
Item
::
fixedValueIsAltitudeName
=
"FixedValueIsAltitude"
;
const
char
*
Survey
Complex
Item
::
cameraName
=
"Camera"
;
Survey
ComplexItem
::
SurveyComplex
Item
(
Vehicle
*
vehicle
,
QObject
*
parent
)
:
ComplexMissionItem
(
vehicle
,
parent
)
,
_sequenceNumber
(
0
)
,
_dirty
(
false
)
...
...
@@ -125,37 +125,37 @@ SurveyMissionItem::SurveyMissionItem(Vehicle* vehicle, QObject* parent)
_gridAltitudeFact
.
setRawValue
(
qgcApp
()
->
toolbox
()
->
settingsManager
()
->
appSettings
()
->
defaultMissionItemAltitude
()
->
rawValue
());
}
connect
(
&
_gridSpacingFact
,
&
Fact
::
valueChanged
,
this
,
&
Survey
Mission
Item
::
_generateGrid
);
connect
(
&
_gridAngleFact
,
&
Fact
::
valueChanged
,
this
,
&
Survey
Mission
Item
::
_generateGrid
);
connect
(
&
_gridEntryLocationFact
,
&
Fact
::
valueChanged
,
this
,
&
Survey
Mission
Item
::
_generateGrid
);
connect
(
&
_turnaroundDistFact
,
&
Fact
::
valueChanged
,
this
,
&
Survey
Mission
Item
::
_generateGrid
);
connect
(
&
_cameraTriggerDistanceFact
,
&
Fact
::
valueChanged
,
this
,
&
Survey
Mission
Item
::
_generateGrid
);
connect
(
&
_cameraTriggerInTurnaroundFact
,
&
Fact
::
valueChanged
,
this
,
&
Survey
Mission
Item
::
_generateGrid
);
connect
(
&
_hoverAndCaptureFact
,
&
Fact
::
valueChanged
,
this
,
&
Survey
Mission
Item
::
_generateGrid
);
connect
(
this
,
&
Survey
MissionItem
::
refly90DegreesChanged
,
this
,
&
SurveyMission
Item
::
_generateGrid
);
connect
(
&
_gridSpacingFact
,
&
Fact
::
valueChanged
,
this
,
&
Survey
Complex
Item
::
_generateGrid
);
connect
(
&
_gridAngleFact
,
&
Fact
::
valueChanged
,
this
,
&
Survey
Complex
Item
::
_generateGrid
);
connect
(
&
_gridEntryLocationFact
,
&
Fact
::
valueChanged
,
this
,
&
Survey
Complex
Item
::
_generateGrid
);
connect
(
&
_turnaroundDistFact
,
&
Fact
::
valueChanged
,
this
,
&
Survey
Complex
Item
::
_generateGrid
);
connect
(
&
_cameraTriggerDistanceFact
,
&
Fact
::
valueChanged
,
this
,
&
Survey
Complex
Item
::
_generateGrid
);
connect
(
&
_cameraTriggerInTurnaroundFact
,
&
Fact
::
valueChanged
,
this
,
&
Survey
Complex
Item
::
_generateGrid
);
connect
(
&
_hoverAndCaptureFact
,
&
Fact
::
valueChanged
,
this
,
&
Survey
Complex
Item
::
_generateGrid
);
connect
(
this
,
&
Survey
ComplexItem
::
refly90DegreesChanged
,
this
,
&
SurveyComplex
Item
::
_generateGrid
);
connect
(
&
_gridAltitudeFact
,
&
Fact
::
valueChanged
,
this
,
&
Survey
Mission
Item
::
_updateCoordinateAltitude
);
connect
(
&
_gridAltitudeFact
,
&
Fact
::
valueChanged
,
this
,
&
Survey
Complex
Item
::
_updateCoordinateAltitude
);
connect
(
&
_gridAltitudeRelativeFact
,
&
Fact
::
valueChanged
,
this
,
&
Survey
Mission
Item
::
_setDirty
);
connect
(
&
_gridAltitudeRelativeFact
,
&
Fact
::
valueChanged
,
this
,
&
Survey
Complex
Item
::
_setDirty
);
// Signal to Qml when camera value changes so it can recalc
connect
(
&
_groundResolutionFact
,
&
Fact
::
valueChanged
,
this
,
&
Survey
Mission
Item
::
_cameraValueChanged
);
connect
(
&
_frontalOverlapFact
,
&
Fact
::
valueChanged
,
this
,
&
Survey
Mission
Item
::
_cameraValueChanged
);
connect
(
&
_sideOverlapFact
,
&
Fact
::
valueChanged
,
this
,
&
Survey
Mission
Item
::
_cameraValueChanged
);
connect
(
&
_cameraSensorWidthFact
,
&
Fact
::
valueChanged
,
this
,
&
Survey
Mission
Item
::
_cameraValueChanged
);
connect
(
&
_cameraSensorHeightFact
,
&
Fact
::
valueChanged
,
this
,
&
Survey
Mission
Item
::
_cameraValueChanged
);
connect
(
&
_cameraResolutionWidthFact
,
&
Fact
::
valueChanged
,
this
,
&
Survey
Mission
Item
::
_cameraValueChanged
);
connect
(
&
_cameraResolutionHeightFact
,
&
Fact
::
valueChanged
,
this
,
&
Survey
Mission
Item
::
_cameraValueChanged
);
connect
(
&
_cameraFocalLengthFact
,
&
Fact
::
valueChanged
,
this
,
&
Survey
Mission
Item
::
_cameraValueChanged
);
connect
(
&
_cameraOrientationLandscapeFact
,
&
Fact
::
valueChanged
,
this
,
&
Survey
Mission
Item
::
_cameraValueChanged
);
connect
(
&
_cameraTriggerDistanceFact
,
&
Fact
::
valueChanged
,
this
,
&
Survey
Mission
Item
::
timeBetweenShotsChanged
);
connect
(
&
_mapPolygon
,
&
QGCMapPolygon
::
dirtyChanged
,
this
,
&
Survey
Mission
Item
::
_polygonDirtyChanged
);
connect
(
&
_mapPolygon
,
&
QGCMapPolygon
::
pathChanged
,
this
,
&
Survey
Mission
Item
::
_generateGrid
);
connect
(
&
_groundResolutionFact
,
&
Fact
::
valueChanged
,
this
,
&
Survey
Complex
Item
::
_cameraValueChanged
);
connect
(
&
_frontalOverlapFact
,
&
Fact
::
valueChanged
,
this
,
&
Survey
Complex
Item
::
_cameraValueChanged
);
connect
(
&
_sideOverlapFact
,
&
Fact
::
valueChanged
,
this
,
&
Survey
Complex
Item
::
_cameraValueChanged
);
connect
(
&
_cameraSensorWidthFact
,
&
Fact
::
valueChanged
,
this
,
&
Survey
Complex
Item
::
_cameraValueChanged
);
connect
(
&
_cameraSensorHeightFact
,
&
Fact
::
valueChanged
,
this
,
&
Survey
Complex
Item
::
_cameraValueChanged
);
connect
(
&
_cameraResolutionWidthFact
,
&
Fact
::
valueChanged
,
this
,
&
Survey
Complex
Item
::
_cameraValueChanged
);
connect
(
&
_cameraResolutionHeightFact
,
&
Fact
::
valueChanged
,
this
,
&
Survey
Complex
Item
::
_cameraValueChanged
);
connect
(
&
_cameraFocalLengthFact
,
&
Fact
::
valueChanged
,
this
,
&
Survey
Complex
Item
::
_cameraValueChanged
);
connect
(
&
_cameraOrientationLandscapeFact
,
&
Fact
::
valueChanged
,
this
,
&
Survey
Complex
Item
::
_cameraValueChanged
);
connect
(
&
_cameraTriggerDistanceFact
,
&
Fact
::
valueChanged
,
this
,
&
Survey
Complex
Item
::
timeBetweenShotsChanged
);
connect
(
&
_mapPolygon
,
&
QGCMapPolygon
::
dirtyChanged
,
this
,
&
Survey
Complex
Item
::
_polygonDirtyChanged
);
connect
(
&
_mapPolygon
,
&
QGCMapPolygon
::
pathChanged
,
this
,
&
Survey
Complex
Item
::
_generateGrid
);
}
void
Survey
Mission
Item
::
_setSurveyDistance
(
double
surveyDistance
)
void
Survey
Complex
Item
::
_setSurveyDistance
(
double
surveyDistance
)
{
if
(
!
qFuzzyCompare
(
_surveyDistance
,
surveyDistance
))
{
_surveyDistance
=
surveyDistance
;
...
...
@@ -163,7 +163,7 @@ void SurveyMissionItem::_setSurveyDistance(double surveyDistance)
}
}
void
Survey
Mission
Item
::
_setCameraShots
(
int
cameraShots
)
void
Survey
Complex
Item
::
_setCameraShots
(
int
cameraShots
)
{
if
(
_cameraShots
!=
cameraShots
)
{
_cameraShots
=
cameraShots
;
...
...
@@ -171,7 +171,7 @@ void SurveyMissionItem::_setCameraShots(int cameraShots)
}
}
void
Survey
Mission
Item
::
_setCoveredArea
(
double
coveredArea
)
void
Survey
Complex
Item
::
_setCoveredArea
(
double
coveredArea
)
{
if
(
!
qFuzzyCompare
(
_coveredArea
,
coveredArea
))
{
_coveredArea
=
coveredArea
;
...
...
@@ -179,7 +179,7 @@ void SurveyMissionItem::_setCoveredArea(double coveredArea)
}
}
void
Survey
Mission
Item
::
_clearInternal
(
void
)
void
Survey
Complex
Item
::
_clearInternal
(
void
)
{
// Bug workaround
while
(
_simpleGridPoints
.
count
()
>
1
)
{
...
...
@@ -197,12 +197,12 @@ void SurveyMissionItem::_clearInternal(void)
emit
lastSequenceNumberChanged
(
lastSequenceNumber
());
}
int
Survey
Mission
Item
::
lastSequenceNumber
(
void
)
const
int
Survey
Complex
Item
::
lastSequenceNumber
(
void
)
const
{
return
_sequenceNumber
+
_missionCommandCount
;
}
void
Survey
Mission
Item
::
setCoordinate
(
const
QGeoCoordinate
&
coordinate
)
void
Survey
Complex
Item
::
setCoordinate
(
const
QGeoCoordinate
&
coordinate
)
{
if
(
_coordinate
!=
coordinate
)
{
_coordinate
=
coordinate
;
...
...
@@ -210,7 +210,7 @@ void SurveyMissionItem::setCoordinate(const QGeoCoordinate& coordinate)
}
}
void
Survey
Mission
Item
::
setDirty
(
bool
dirty
)
void
Survey
Complex
Item
::
setDirty
(
bool
dirty
)
{
if
(
_dirty
!=
dirty
)
{
_dirty
=
dirty
;
...
...
@@ -218,7 +218,7 @@ void SurveyMissionItem::setDirty(bool dirty)
}
}
void
Survey
Mission
Item
::
save
(
QJsonArray
&
missionItems
)
void
Survey
Complex
Item
::
save
(
QJsonArray
&
missionItems
)
{
QJsonObject
saveObject
;
...
...
@@ -265,7 +265,7 @@ void SurveyMissionItem::save(QJsonArray& missionItems)
missionItems
.
append
(
saveObject
);
}
void
Survey
Mission
Item
::
setSequenceNumber
(
int
sequenceNumber
)
void
Survey
Complex
Item
::
setSequenceNumber
(
int
sequenceNumber
)
{
if
(
_sequenceNumber
!=
sequenceNumber
)
{
_sequenceNumber
=
sequenceNumber
;
...
...
@@ -274,7 +274,7 @@ void SurveyMissionItem::setSequenceNumber(int sequenceNumber)
}
}
bool
Survey
Mission
Item
::
load
(
const
QJsonObject
&
complexObject
,
int
sequenceNumber
,
QString
&
errorString
)
bool
Survey
Complex
Item
::
load
(
const
QJsonObject
&
complexObject
,
int
sequenceNumber
,
QString
&
errorString
)
{
QJsonObject
v2Object
=
complexObject
;
...
...
@@ -424,7 +424,7 @@ bool SurveyMissionItem::load(const QJsonObject& complexObject, int sequenceNumbe
return
true
;
}
double
Survey
Mission
Item
::
greatestDistanceTo
(
const
QGeoCoordinate
&
other
)
const
double
Survey
Complex
Item
::
greatestDistanceTo
(
const
QGeoCoordinate
&
other
)
const
{
double
greatestDistance
=
0.0
;
for
(
int
i
=
0
;
i
<
_simpleGridPoints
.
count
();
i
++
)
{
...
...
@@ -437,7 +437,7 @@ double SurveyMissionItem::greatestDistanceTo(const QGeoCoordinate &other) const
return
greatestDistance
;
}
void
Survey
Mission
Item
::
_setExitCoordinate
(
const
QGeoCoordinate
&
coordinate
)
void
Survey
Complex
Item
::
_setExitCoordinate
(
const
QGeoCoordinate
&
coordinate
)
{
if
(
_exitCoordinate
!=
coordinate
)
{
_exitCoordinate
=
coordinate
;
...
...
@@ -445,7 +445,7 @@ void SurveyMissionItem::_setExitCoordinate(const QGeoCoordinate& coordinate)
}
}
bool
Survey
Mission
Item
::
specifiesCoordinate
(
void
)
const
bool
Survey
Complex
Item
::
specifiesCoordinate
(
void
)
const
{
return
_mapPolygon
.
count
()
>
2
;
}
...
...
@@ -455,7 +455,7 @@ void _calcCameraShots()
}
void
Survey
Mission
Item
::
_convertTransectToGeo
(
const
QList
<
QList
<
QPointF
>>&
transectSegmentsNED
,
const
QGeoCoordinate
&
tangentOrigin
,
QList
<
QList
<
QGeoCoordinate
>>&
transectSegmentsGeo
)
void
Survey
Complex
Item
::
_convertTransectToGeo
(
const
QList
<
QList
<
QPointF
>>&
transectSegmentsNED
,
const
QGeoCoordinate
&
tangentOrigin
,
QList
<
QList
<
QGeoCoordinate
>>&
transectSegmentsGeo
)
{
transectSegmentsGeo
.
clear
();
...
...
@@ -474,7 +474,7 @@ void SurveyMissionItem::_convertTransectToGeo(const QList<QList<QPointF>>& trans
}
/// Reverse the order of the transects. First transect becomes last and so forth.
void
Survey
Mission
Item
::
_reverseTransectOrder
(
QList
<
QList
<
QGeoCoordinate
>>&
transects
)
void
Survey
Complex
Item
::
_reverseTransectOrder
(
QList
<
QList
<
QGeoCoordinate
>>&
transects
)
{
QList
<
QList
<
QGeoCoordinate
>>
rgReversedTransects
;
for
(
int
i
=
transects
.
count
()
-
1
;
i
>=
0
;
i
--
)
{
...
...
@@ -484,7 +484,7 @@ void SurveyMissionItem::_reverseTransectOrder(QList<QList<QGeoCoordinate>>& tran
}
/// Reverse the order of all points withing each transect, First point becomes last and so forth.
void
Survey
Mission
Item
::
_reverseInternalTransectPoints
(
QList
<
QList
<
QGeoCoordinate
>>&
transects
)
void
Survey
Complex
Item
::
_reverseInternalTransectPoints
(
QList
<
QList
<
QGeoCoordinate
>>&
transects
)
{
for
(
int
i
=
0
;
i
<
transects
.
count
();
i
++
)
{
QList
<
QGeoCoordinate
>
rgReversedCoords
;
...
...
@@ -500,7 +500,7 @@ void SurveyMissionItem::_reverseInternalTransectPoints(QList<QList<QGeoCoordinat
/// and the first point within that transect is the shortest distance to the specified coordinate.
/// @param distanceCoord Coordinate to measure distance against
/// @param transects Transects to test and reorder
void
Survey
Mission
Item
::
_optimizeTransectsForShortestDistance
(
const
QGeoCoordinate
&
distanceCoord
,
QList
<
QList
<
QGeoCoordinate
>>&
transects
)
void
Survey
Complex
Item
::
_optimizeTransectsForShortestDistance
(
const
QGeoCoordinate
&
distanceCoord
,
QList
<
QList
<
QGeoCoordinate
>>&
transects
)
{
double
rgTransectDistance
[
4
];
rgTransectDistance
[
0
]
=
transects
.
first
().
first
().
distanceTo
(
distanceCoord
);
...
...
@@ -527,9 +527,9 @@ void SurveyMissionItem::_optimizeTransectsForShortestDistance(const QGeoCoordina
}
}
void
Survey
Mission
Item
::
_appendGridPointsFromTransects
(
QList
<
QList
<
QGeoCoordinate
>>&
rgTransectSegments
)
void
Survey
Complex
Item
::
_appendGridPointsFromTransects
(
QList
<
QList
<
QGeoCoordinate
>>&
rgTransectSegments
)
{
qCDebug
(
Survey
Mission
ItemLog
)
<<
"Entry point _appendGridPointsFromTransects"
<<
rgTransectSegments
.
first
().
first
();
qCDebug
(
Survey
Complex
ItemLog
)
<<
"Entry point _appendGridPointsFromTransects"
<<
rgTransectSegments
.
first
().
first
();
for
(
int
i
=
0
;
i
<
rgTransectSegments
.
count
();
i
++
)
{
_simpleGridPoints
.
append
(
QVariant
::
fromValue
(
rgTransectSegments
[
i
].
first
()));
...
...
@@ -537,17 +537,17 @@ void SurveyMissionItem::_appendGridPointsFromTransects(QList<QList<QGeoCoordinat
}
}
qreal
Survey
Mission
Item
::
_ccw
(
QPointF
pt1
,
QPointF
pt2
,
QPointF
pt3
)
qreal
Survey
Complex
Item
::
_ccw
(
QPointF
pt1
,
QPointF
pt2
,
QPointF
pt3
)
{
return
(
pt2
.
x
()
-
pt1
.
x
())
*
(
pt3
.
y
()
-
pt1
.
y
())
-
(
pt2
.
y
()
-
pt1
.
y
())
*
(
pt3
.
x
()
-
pt1
.
x
());
}
qreal
Survey
Mission
Item
::
_dp
(
QPointF
pt1
,
QPointF
pt2
)
qreal
Survey
Complex
Item
::
_dp
(
QPointF
pt1
,
QPointF
pt2
)
{
return
(
pt2
.
x
()
-
pt1
.
x
())
/
qSqrt
((
pt2
.
x
()
-
pt1
.
x
())
*
(
pt2
.
x
()
-
pt1
.
x
())
+
(
pt2
.
y
()
-
pt1
.
y
())
*
(
pt2
.
y
()
-
pt1
.
y
()));
}
void
Survey
Mission
Item
::
_swapPoints
(
QList
<
QPointF
>&
points
,
int
index1
,
int
index2
)
void
Survey
Complex
Item
::
_swapPoints
(
QList
<
QPointF
>&
points
,
int
index1
,
int
index2
)
{
QPointF
temp
=
points
[
index1
];
points
[
index1
]
=
points
[
index2
];
...
...
@@ -555,14 +555,14 @@ void SurveyMissionItem::_swapPoints(QList<QPointF>& points, int index1, int inde
}
/// Returns true if the current grid angle generates north/south oriented transects
bool
Survey
Mission
Item
::
_gridAngleIsNorthSouthTransects
()
bool
Survey
Complex
Item
::
_gridAngleIsNorthSouthTransects
()
{
// Grid angle ranges from -360<->360
double
gridAngle
=
qAbs
(
_gridAngleFact
.
rawValue
().
toDouble
());
return
gridAngle
<
45.0
||
(
gridAngle
>
360.0
-
45.0
)
||
(
gridAngle
>
90.0
+
45.0
&&
gridAngle
<
270.0
-
45.0
);
}
void
Survey
Mission
Item
::
_adjustTransectsToEntryPointLocation
(
QList
<
QList
<
QGeoCoordinate
>>&
transects
)
void
Survey
Complex
Item
::
_adjustTransectsToEntryPointLocation
(
QList
<
QList
<
QGeoCoordinate
>>&
transects
)
{
if
(
transects
.
count
()
==
0
)
{
return
;
...
...
@@ -580,18 +580,18 @@ void SurveyMissionItem::_adjustTransectsToEntryPointLocation(QList<QList<QGeoCoo
}
if
(
reversePoints
)
{
qCDebug
(
Survey
Mission
ItemLog
)
<<
"Reverse Points"
;
qCDebug
(
Survey
Complex
ItemLog
)
<<
"Reverse Points"
;
_reverseInternalTransectPoints
(
transects
);
}
if
(
reverseTransects
)
{
qCDebug
(
Survey
Mission
ItemLog
)
<<
"Reverse Transects"
;
qCDebug
(
Survey
Complex
ItemLog
)
<<
"Reverse Transects"
;
_reverseTransectOrder
(
transects
);
}
qCDebug
(
Survey
Mission
ItemLog
)
<<
"Modified entry point"
<<
transects
.
first
().
first
();
qCDebug
(
Survey
Complex
ItemLog
)
<<
"Modified entry point"
<<
transects
.
first
().
first
();
}
int
Survey
Mission
Item
::
_calcMissionCommandCount
(
QList
<
QList
<
QGeoCoordinate
>>&
transectSegments
)
int
Survey
Complex
Item
::
_calcMissionCommandCount
(
QList
<
QList
<
QGeoCoordinate
>>&
transectSegments
)
{
int
missionCommandCount
=
0
;
for
(
int
i
=
0
;
i
<
transectSegments
.
count
();
i
++
)
{
...
...
@@ -613,7 +613,7 @@ int SurveyMissionItem::_calcMissionCommandCount(QList<QList<QGeoCoordinate>>& tr
return
missionCommandCount
;
}
void
Survey
Mission
Item
::
_generateGrid
(
void
)
void
Survey
Complex
Item
::
_generateGrid
(
void
)
{
if
(
_ignoreRecalc
)
{
return
;
...
...
@@ -634,7 +634,7 @@ void SurveyMissionItem::_generateGrid(void)
// Convert polygon to NED
QGeoCoordinate
tangentOrigin
=
_mapPolygon
.
pathModel
().
value
<
QGCQGeoCoordinate
*>
(
0
)
->
coordinate
();
qCDebug
(
Survey
Mission
ItemLog
)
<<
"Convert polygon to NED - tangentOrigin"
<<
tangentOrigin
;
qCDebug
(
Survey
Complex
ItemLog
)
<<
"Convert polygon to NED - tangentOrigin"
<<
tangentOrigin
;
for
(
int
i
=
0
;
i
<
_mapPolygon
.
count
();
i
++
)
{
double
y
,
x
,
down
;
QGeoCoordinate
vertex
=
_mapPolygon
.
pathModel
().
value
<
QGCQGeoCoordinate
*>
(
i
)
->
coordinate
();
...
...
@@ -645,7 +645,7 @@ void SurveyMissionItem::_generateGrid(void)
convertGeoToNed
(
vertex
,
tangentOrigin
,
&
y
,
&
x
,
&
down
);
}
polygonPoints
+=
QPointF
(
x
,
y
);
qCDebug
(
Survey
Mission
ItemLog
)
<<
"vertex:x:y"
<<
vertex
<<
polygonPoints
.
last
().
x
()
<<
polygonPoints
.
last
().
y
();
qCDebug
(
Survey
Complex
ItemLog
)
<<
"vertex:x:y"
<<
vertex
<<
polygonPoints
.
last
().
x
()
<<
polygonPoints
.
last
().
y
();
}
double
coveredArea
=
0.0
;
...
...
@@ -713,7 +713,7 @@ void SurveyMissionItem::_generateGrid(void)
setDirty
(
true
);
}
void
Survey
Mission
Item
::
_updateCoordinateAltitude
(
void
)
void
Survey
Complex
Item
::
_updateCoordinateAltitude
(
void
)
{
_coordinate
.
setAltitude
(
_gridAltitudeFact
.
rawValue
().
toDouble
());
_exitCoordinate
.
setAltitude
(
_gridAltitudeFact
.
rawValue
().
toDouble
());
...
...
@@ -722,7 +722,7 @@ void SurveyMissionItem::_updateCoordinateAltitude(void)
setDirty
(
true
);
}
QPointF
Survey
Mission
Item
::
_rotatePoint
(
const
QPointF
&
point
,
const
QPointF
&
origin
,
double
angle
)
QPointF
Survey
Complex
Item
::
_rotatePoint
(
const
QPointF
&
point
,
const
QPointF
&
origin
,
double
angle
)
{
QPointF
rotated
;
double
radians
=
(
M_PI
/
180.0
)
*
-
angle
;
...
...
@@ -733,7 +733,7 @@ QPointF SurveyMissionItem::_rotatePoint(const QPointF& point, const QPointF& ori
return
rotated
;
}
void
Survey
Mission
Item
::
_intersectLinesWithRect
(
const
QList
<
QLineF
>&
lineList
,
const
QRectF
&
boundRect
,
QList
<
QLineF
>&
resultLines
)
void
Survey
Complex
Item
::
_intersectLinesWithRect
(
const
QList
<
QLineF
>&
lineList
,
const
QRectF
&
boundRect
,
QList
<
QLineF
>&
resultLines
)
{
QLineF
topLine
(
boundRect
.
topLeft
(),
boundRect
.
topRight
());
QLineF
bottomLine
(
boundRect
.
bottomLeft
(),
boundRect
.
bottomRight
());
...
...
@@ -790,7 +790,7 @@ void SurveyMissionItem::_intersectLinesWithRect(const QList<QLineF>& lineList, c
}
}
void
Survey
Mission
Item
::
_intersectLinesWithPolygon
(
const
QList
<
QLineF
>&
lineList
,
const
QPolygonF
&
polygon
,
QList
<
QLineF
>&
resultLines
)
void
Survey
Complex
Item
::
_intersectLinesWithPolygon
(
const
QList
<
QLineF
>&
lineList
,
const
QPolygonF
&
polygon
,
QList
<
QLineF
>&
resultLines
)
{
resultLines
.
clear
();
...
...
@@ -833,7 +833,7 @@ void SurveyMissionItem::_intersectLinesWithPolygon(const QList<QLineF>& lineList
}
/// Adjust the line segments such that they are all going the same direction with respect to going from P1->P2
void
Survey
Mission
Item
::
_adjustLineDirection
(
const
QList
<
QLineF
>&
lineList
,
QList
<
QLineF
>&
resultLines
)
void
Survey
Complex
Item
::
_adjustLineDirection
(
const
QList
<
QLineF
>&
lineList
,
QList
<
QLineF
>&
resultLines
)
{
qreal
firstAngle
=
0
;
for
(
int
i
=
0
;
i
<
lineList
.
count
();
i
++
)
{
...
...
@@ -855,7 +855,7 @@ void SurveyMissionItem::_adjustLineDirection(const QList<QLineF>& lineList, QLis
}
}
double
Survey
Mission
Item
::
_clampGridAngle90
(
double
gridAngle
)
double
Survey
Complex
Item
::
_clampGridAngle90
(
double
gridAngle
)
{
// Clamp grid angle to -90<->90. This prevents transects from being rotated to a reversed order.
if
(
gridAngle
>
90.0
)
{
...
...
@@ -866,7 +866,7 @@ double SurveyMissionItem::_clampGridAngle90(double gridAngle)
return
gridAngle
;
}
int
Survey
Mission
Item
::
_gridGenerator
(
const
QList
<
QPointF
>&
polygonPoints
,
QList
<
QList
<
QPointF
>>&
transectSegments
,
bool
refly
)
int
Survey
Complex
Item
::
_gridGenerator
(
const
QList
<
QPointF
>&
polygonPoints
,
QList
<
QList
<
QPointF
>>&
transectSegments
,
bool
refly
)
{
int
cameraShots
=
0
;
...
...
@@ -875,24 +875,24 @@ int SurveyMissionItem::_gridGenerator(const QList<QPointF>& polygonPoints, QLis
gridAngle
=
_clampGridAngle90
(
gridAngle
);
gridAngle
+=
refly
?
90
:
0
;
qCDebug
(
Survey
Mission
ItemLog
)
<<
"Clamped grid angle"
<<
gridAngle
;
qCDebug
(
Survey
Complex
ItemLog
)
<<
"Clamped grid angle"
<<
gridAngle
;
qCDebug
(
Survey
MissionItemLog
)
<<
"SurveyMission
Item::_gridGenerator gridSpacing:gridAngle:refly"
<<
gridSpacing
<<
gridAngle
<<
refly
;
qCDebug
(
Survey
ComplexItemLog
)
<<
"SurveyComplex
Item::_gridGenerator gridSpacing:gridAngle:refly"
<<
gridSpacing
<<
gridAngle
<<
refly
;
transectSegments
.
clear
();
// Convert polygon to bounding rect
qCDebug
(
Survey
Mission
ItemLog
)
<<
"Polygon"
;
qCDebug
(
Survey
Complex
ItemLog
)
<<
"Polygon"
;
QPolygonF
polygon
;
for
(
int
i
=
0
;
i
<
polygonPoints
.
count
();
i
++
)
{
qCDebug
(
Survey
Mission
ItemLog
)
<<
polygonPoints
[
i
];
qCDebug
(
Survey
Complex
ItemLog
)
<<
polygonPoints
[
i
];
polygon
<<
polygonPoints
[
i
];
}
polygon
<<
polygonPoints
[
0
];
QRectF
boundingRect
=
polygon
.
boundingRect
();
QPointF
boundingCenter
=
boundingRect
.
center
();
qCDebug
(
Survey
Mission
ItemLog
)
<<
"Bounding rect"
<<
boundingRect
.
topLeft
().
x
()
<<
boundingRect
.
topLeft
().
y
()
<<
boundingRect
.
bottomRight
().
x
()
<<
boundingRect
.
bottomRight
().
y
();
qCDebug
(
Survey
Complex
ItemLog
)
<<
"Bounding rect"
<<
boundingRect
.
topLeft
().
x
()
<<
boundingRect
.
topLeft
().
y
()
<<
boundingRect
.
bottomRight
().
x
()
<<
boundingRect
.
bottomRight
().
y
();
// Create set of rotated parallel lines within the expanded bounding rect. Make the lines larger than the
// bounding box to guarantee intersection.
...
...
@@ -979,7 +979,7 @@ int SurveyMissionItem::_gridGenerator(const QList<QPointF>& polygonPoints, QLis
if
(
_triggerCamera
()
&&
_hoverAndCaptureEnabled
())
{
if
(
_triggerDistance
()
<
transectLine
.
length
())
{
int
innerPoints
=
floor
(
transectLine
.
length
()
/
_triggerDistance
());
qCDebug
(
Survey
Mission
ItemLog
)
<<
"innerPoints"
<<
innerPoints
;
qCDebug
(
Survey
Complex
ItemLog
)
<<
"innerPoints"
<<
innerPoints
;
float
transectPositionIncrement
=
_triggerDistance
()
/
transectLine
.
length
();
for
(
int
i
=
0
;
i
<
innerPoints
;
i
++
)
{
transectPoints
.
append
(
transectLine
.
pointAt
(
transectPositionIncrement
*
(
i
+
1
)));
...
...
@@ -1000,12 +1000,12 @@ int SurveyMissionItem::_gridGenerator(const QList<QPointF>& polygonPoints, QLis
return
cameraShots
;
}
int
Survey
Mission
Item
::
_appendWaypointToMission
(
QList
<
MissionItem
*>&
items
,
int
seqNum
,
QGeoCoordinate
&
coord
,
CameraTriggerCode
cameraTrigger
,
QObject
*
missionItemParent
)
int
Survey
Complex
Item
::
_appendWaypointToMission
(
QList
<
MissionItem
*>&
items
,
int
seqNum
,
QGeoCoordinate
&
coord
,
CameraTriggerCode
cameraTrigger
,
QObject
*
missionItemParent
)
{
double
altitude
=
_gridAltitudeFact
.
rawValue
().
toDouble
();
bool
altitudeRelative
=
_gridAltitudeRelativeFact
.
rawValue
().
toBool
();
qCDebug
(
Survey
Mission
ItemLog
)
<<
"_appendWaypointToMission seq:trigger"
<<
seqNum
<<
(
cameraTrigger
!=
CameraTriggerNone
);
qCDebug
(
Survey
Complex
ItemLog
)
<<
"_appendWaypointToMission seq:trigger"
<<
seqNum
<<
(
cameraTrigger
!=
CameraTriggerNone
);
MissionItem
*
item
=
new
MissionItem
(
seqNum
++
,
MAV_CMD_NAV_WAYPOINT
,
...
...
@@ -1068,7 +1068,7 @@ int SurveyMissionItem::_appendWaypointToMission(QList<MissionItem*>& items, int
return
seqNum
;
}
bool
Survey
Mission
Item
::
_nextTransectCoord
(
const
QList
<
QGeoCoordinate
>&
transectPoints
,
int
pointIndex
,
QGeoCoordinate
&
coord
)
bool
Survey
Complex
Item
::
_nextTransectCoord
(
const
QList
<
QGeoCoordinate
>&
transectPoints
,
int
pointIndex
,
QGeoCoordinate
&
coord
)
{
if
(
pointIndex
>
transectPoints
.
count
())
{
qWarning
()
<<
"Bad grid generation"
;
...
...
@@ -1086,11 +1086,11 @@ bool SurveyMissionItem::_nextTransectCoord(const QList<QGeoCoordinate>& transect
/// @param hasRefly true: misison has a refly section
/// @param buildRefly: true: build the refly section, false: build the first section
/// @return false: Generation failed
bool
Survey
Mission
Item
::
_appendMissionItemsWorker
(
QList
<
MissionItem
*>&
items
,
QObject
*
missionItemParent
,
int
&
seqNum
,
bool
hasRefly
,
bool
buildRefly
)
bool
Survey
Complex
Item
::
_appendMissionItemsWorker
(
QList
<
MissionItem
*>&
items
,
QObject
*
missionItemParent
,
int
&
seqNum
,
bool
hasRefly
,
bool
buildRefly
)
{
bool
firstWaypointTrigger
=
false
;
qCDebug
(
Survey
Mission
ItemLog
)
<<
QStringLiteral
(
"hasTurnaround(%1) triggerCamera(%2) hoverAndCapture(%3) imagesEverywhere(%4) hasRefly(%5) buildRefly(%6) "
).
arg
(
_hasTurnaround
()).
arg
(
_triggerCamera
()).
arg
(
_hoverAndCaptureEnabled
()).
arg
(
_imagesEverywhere
()).
arg
(
hasRefly
).
arg
(
buildRefly
);
qCDebug
(
Survey
Complex
ItemLog
)
<<
QStringLiteral
(
"hasTurnaround(%1) triggerCamera(%2) hoverAndCapture(%3) imagesEverywhere(%4) hasRefly(%5) buildRefly(%6) "
).
arg
(
_hasTurnaround
()).
arg
(
_triggerCamera
()).
arg
(
_hoverAndCaptureEnabled
()).
arg
(
_imagesEverywhere
()).
arg
(
hasRefly
).
arg
(
buildRefly
);
QList
<
QList
<
QGeoCoordinate
>>&
transectSegments
=
buildRefly
?
_reflyTransectSegments
:
_transectSegments
;
...
...
@@ -1104,7 +1104,7 @@ bool SurveyMissionItem::_appendMissionItemsWorker(QList<MissionItem*>& items, QO
CameraTriggerCode
cameraTrigger
;
const
QList
<
QGeoCoordinate
>&
segment
=
transectSegments
[
segmentIndex
];
qCDebug
(
Survey
Mission
ItemLog
)
<<
"segment.count"
<<
segment
.
count
();
qCDebug
(
Survey
Complex
ItemLog
)
<<
"segment.count"
<<
segment
.
count
();
if
(
_hasTurnaround
())
{
// Add entry turnaround point
...
...
@@ -1130,7 +1130,7 @@ bool SurveyMissionItem::_appendMissionItemsWorker(QList<MissionItem*>& items, QO
// Add internal hover and capture points
if
(
_hoverAndCaptureEnabled
())
{
int
lastHoverAndCaptureIndex
=
segment
.
count
()
-
1
-
(
_hasTurnaround
()
?
1
:
0
);
qCDebug
(
Survey
Mission
ItemLog
)
<<
"lastHoverAndCaptureIndex"
<<
lastHoverAndCaptureIndex
;
qCDebug
(
Survey
Complex
ItemLog
)
<<
"lastHoverAndCaptureIndex"
<<
lastHoverAndCaptureIndex
;
for
(;
pointIndex
<
lastHoverAndCaptureIndex
;
pointIndex
++
)
{
if
(
!
_nextTransectCoord
(
segment
,
pointIndex
,
coord
))
{
return
false
;
...
...
@@ -1154,7 +1154,7 @@ bool SurveyMissionItem::_appendMissionItemsWorker(QList<MissionItem*>& items, QO
seqNum
=
_appendWaypointToMission
(
items
,
seqNum
,
coord
,
CameraTriggerNone
,
missionItemParent
);
}
qCDebug
(
Survey
Mission
ItemLog
)
<<
"last PointIndex"
<<
pointIndex
;
qCDebug
(
Survey
Complex
ItemLog
)
<<
"last PointIndex"
<<
pointIndex
;
}
if
(((
hasRefly
&&
buildRefly
)
||
!
hasRefly
)
&&
_imagesEverywhere
())
{
...
...
@@ -1173,7 +1173,7 @@ bool SurveyMissionItem::_appendMissionItemsWorker(QList<MissionItem*>& items, QO
return
true
;
}
void
Survey
Mission
Item
::
appendMissionItems
(
QList
<
MissionItem
*>&
items
,
QObject
*
missionItemParent
)
void
Survey
Complex
Item
::
appendMissionItems
(
QList
<
MissionItem
*>&
items
,
QObject
*
missionItemParent
)
{
int
seqNum
=
_sequenceNumber
;
...
...
@@ -1186,22 +1186,22 @@ void SurveyMissionItem::appendMissionItems(QList<MissionItem*>& items, QObject*
}
}
int
Survey
Mission
Item
::
cameraShots
(
void
)
const
int
Survey
Complex
Item
::
cameraShots
(
void
)
const
{
return
_triggerCamera
()
?
_cameraShots
:
0
;
}
void
Survey
Mission
Item
::
_cameraValueChanged
(
void
)
void
Survey
Complex
Item
::
_cameraValueChanged
(
void
)
{
emit
cameraValueChanged
();
}
double
Survey
Mission
Item
::
timeBetweenShots
(
void
)
const
double
Survey
Complex
Item
::
timeBetweenShots
(
void
)
const
{
return
_cruiseSpeed
==
0
?
0
:
_triggerDistance
()
/
_cruiseSpeed
;
}
void
Survey
Mission
Item
::
setMissionFlightStatus
(
MissionController
::
MissionFlightStatus_t
&
missionFlightStatus
)
void
Survey
Complex
Item
::
setMissionFlightStatus
(
MissionController
::
MissionFlightStatus_t
&
missionFlightStatus
)
{
ComplexMissionItem
::
setMissionFlightStatus
(
missionFlightStatus
);
if
(
!
qFuzzyCompare
(
_cruiseSpeed
,
missionFlightStatus
.
vehicleSpeed
))
{
...
...
@@ -1210,52 +1210,52 @@ void SurveyMissionItem::setMissionFlightStatus(MissionController::MissionFlightS
}
}
void
Survey
Mission
Item
::
_setDirty
(
void
)
void
Survey
Complex
Item
::
_setDirty
(
void
)
{
setDirty
(
true
);
}
bool
Survey
Mission
Item
::
hoverAndCaptureAllowed
(
void
)
const
bool
Survey
Complex
Item
::
hoverAndCaptureAllowed
(
void
)
const
{
return
_vehicle
->
multiRotor
()
||
_vehicle
->
vtol
();
}
double
Survey
Mission
Item
::
_triggerDistance
(
void
)
const
{
double
Survey
Complex
Item
::
_triggerDistance
(
void
)
const
{
return
_cameraTriggerDistanceFact
.
rawValue
().
toDouble
();
}
bool
Survey
Mission
Item
::
_triggerCamera
(
void
)
const
bool
Survey
Complex
Item
::
_triggerCamera
(
void
)
const
{
return
_triggerDistance
()
>
0
;
}
bool
Survey
Mission
Item
::
_imagesEverywhere
(
void
)
const
bool
Survey
Complex
Item
::
_imagesEverywhere
(
void
)
const
{
return
_triggerCamera
()
&&
_cameraTriggerInTurnaroundFact
.
rawValue
().
toBool
();
}
bool
Survey
Mission
Item
::
_hoverAndCaptureEnabled
(
void
)
const
bool
Survey
Complex
Item
::
_hoverAndCaptureEnabled
(
void
)
const
{
return
hoverAndCaptureAllowed
()
&&
!
_imagesEverywhere
()
&&
_triggerCamera
()
&&
_hoverAndCaptureFact
.
rawValue
().
toBool
();
}
bool
Survey
Mission
Item
::
_hasTurnaround
(
void
)
const
bool
Survey
Complex
Item
::
_hasTurnaround
(
void
)
const
{
return
_turnaroundDistance
()
>
0
;
}
double
Survey
Mission
Item
::
_turnaroundDistance
(
void
)
const
double
Survey
Complex
Item
::
_turnaroundDistance
(
void
)
const
{
return
_turnaroundDistFact
.
rawValue
().
toDouble
();
}
void
Survey
Mission
Item
::
applyNewAltitude
(
double
newAltitude
)
void
Survey
Complex
Item
::
applyNewAltitude
(
double
newAltitude
)
{
_fixedValueIsAltitudeFact
.
setRawValue
(
true
);
_gridAltitudeFact
.
setRawValue
(
newAltitude
);
}
void
Survey
Mission
Item
::
setRefly90Degrees
(
bool
refly90Degrees
)
void
Survey
Complex
Item
::
setRefly90Degrees
(
bool
refly90Degrees
)
{
if
(
refly90Degrees
!=
_refly90Degrees
)
{
_refly90Degrees
=
refly90Degrees
;
...
...
@@ -1263,7 +1263,7 @@ void SurveyMissionItem::setRefly90Degrees(bool refly90Degrees)
}
}
void
Survey
Mission
Item
::
_polygonDirtyChanged
(
bool
dirty
)
void
Survey
Complex
Item
::
_polygonDirtyChanged
(
bool
dirty
)
{
if
(
dirty
)
{
setDirty
(
true
);
...
...
src/MissionManager/Survey
Mission
Item.h
→
src/MissionManager/Survey
Complex
Item.h
View file @
985c72e5
...
...
@@ -7,9 +7,7 @@
*
****************************************************************************/
#ifndef SurveyMissionItem_H
#define SurveyMissionItem_H
#pragma once
#include "ComplexMissionItem.h"
#include "MissionItem.h"
...
...
@@ -17,14 +15,14 @@
#include "QGCLoggingCategory.h"
#include "QGCMapPolygon.h"
Q_DECLARE_LOGGING_CATEGORY
(
Survey
Mission
ItemLog
)
Q_DECLARE_LOGGING_CATEGORY
(
Survey
Complex
ItemLog
)
class
Survey
Mission
Item
:
public
ComplexMissionItem
class
Survey
Complex
Item
:
public
ComplexMissionItem
{
Q_OBJECT
public:
Survey
Mission
Item
(
Vehicle
*
vehicle
,
QObject
*
parent
=
NULL
);
Survey
Complex
Item
(
Vehicle
*
vehicle
,
QObject
*
parent
=
NULL
);
Q_PROPERTY
(
Fact
*
gridAltitude
READ
gridAltitude
CONSTANT
)
Q_PROPERTY
(
Fact
*
gridAltitudeRelative
READ
gridAltitudeRelative
CONSTANT
)
...
...
@@ -297,5 +295,3 @@ private:
static
const
int
_hoverAndCaptureDelaySeconds
=
4
;
};
#endif
src/MissionManager/Survey
Mission
ItemTest.cc
→
src/MissionManager/Survey
Complex
ItemTest.cc
View file @
985c72e5
...
...
@@ -7,17 +7,17 @@
*
****************************************************************************/
#include "Survey
Mission
ItemTest.h"
#include "Survey
Complex
ItemTest.h"
#include "QGCApplication.h"
Survey
MissionItemTest
::
SurveyMission
ItemTest
(
void
)
Survey
ComplexItemTest
::
SurveyComplex
ItemTest
(
void
)
:
_offlineVehicle
(
NULL
)
{
_polyPoints
<<
QGeoCoordinate
(
47.633550640000003
,
-
122.08982199
)
<<
QGeoCoordinate
(
47.634129020000003
,
-
122.08887249
)
<<
QGeoCoordinate
(
47.633619320000001
,
-
122.08811074
)
<<
QGeoCoordinate
(
47.633189139999999
,
-
122.08900124
);
}
void
Survey
Mission
ItemTest
::
init
(
void
)
void
Survey
Complex
ItemTest
::
init
(
void
)
{
UnitTest
::
init
();
...
...
@@ -32,7 +32,7 @@ void SurveyMissionItemTest::init(void)
_rgSurveySignals
[
dirtyChangedIndex
]
=
SIGNAL
(
dirtyChanged
(
bool
));
_offlineVehicle
=
new
Vehicle
(
MAV_AUTOPILOT_PX4
,
MAV_TYPE_QUADROTOR
,
qgcApp
()
->
toolbox
()
->
firmwarePluginManager
(),
this
);
_surveyItem
=
new
Survey
Mission
Item
(
_offlineVehicle
,
this
);
_surveyItem
=
new
Survey
Complex
Item
(
_offlineVehicle
,
this
);
_surveyItem
->
setTurnaroundDist
(
0
);
// Unit test written for no turnaround distance
_surveyItem
->
setDirty
(
false
);
_mapPolygon
=
_surveyItem
->
mapPolygon
();
...
...
@@ -46,14 +46,14 @@ void SurveyMissionItemTest::init(void)
QCOMPARE
(
_multiSpy
->
init
(
_surveyItem
,
_rgSurveySignals
,
_cSurveySignals
),
true
);
}
void
Survey
Mission
ItemTest
::
cleanup
(
void
)
void
Survey
Complex
ItemTest
::
cleanup
(
void
)
{
delete
_surveyItem
;
delete
_offlineVehicle
;
delete
_multiSpy
;
}
void
Survey
Mission
ItemTest
::
_testDirty
(
void
)
void
Survey
Complex
ItemTest
::
_testDirty
(
void
)
{
QVERIFY
(
!
_surveyItem
->
dirty
());
_surveyItem
->
setDirty
(
false
);
...
...
@@ -110,7 +110,7 @@ void SurveyMissionItemTest::_testDirty(void)
rgFacts
.
clear
();
}
void
Survey
Mission
ItemTest
::
_testCameraValueChanged
(
void
)
void
Survey
Complex
ItemTest
::
_testCameraValueChanged
(
void
)
{
// These facts should trigger cameraValueChanged when changed
QList
<
Fact
*>
rgFacts
;
...
...
@@ -145,7 +145,7 @@ void SurveyMissionItemTest::_testCameraValueChanged(void)
rgFacts
.
clear
();
}
void
Survey
Mission
ItemTest
::
_testCameraTrigger
(
void
)
void
Survey
Complex
ItemTest
::
_testCameraTrigger
(
void
)
{
#if 0
QCOMPARE(_surveyItem->property("cameraTrigger").toBool(), true);
...
...
@@ -182,7 +182,7 @@ void SurveyMissionItemTest::_testCameraTrigger(void)
}
// Clamp expected grid angle from 0<->180. We don't care about opposite angles like 90/270
double
Survey
Mission
ItemTest
::
_clampGridAngle180
(
double
gridAngle
)
double
Survey
Complex
ItemTest
::
_clampGridAngle180
(
double
gridAngle
)
{
if
(
gridAngle
>=
0.0
)
{
if
(
gridAngle
==
360.0
)
{
...
...
@@ -200,7 +200,7 @@ double SurveyMissionItemTest::_clampGridAngle180(double gridAngle)
return
gridAngle
;
}
void
Survey
Mission
ItemTest
::
_setPolygon
(
void
)
void
Survey
Complex
ItemTest
::
_setPolygon
(
void
)
{
for
(
int
i
=
0
;
i
<
_polyPoints
.
count
();
i
++
)
{
QGeoCoordinate
&
vertex
=
_polyPoints
[
i
];
...
...
@@ -208,7 +208,7 @@ void SurveyMissionItemTest::_setPolygon(void)
}
}
void
Survey
Mission
ItemTest
::
_testGridAngle
(
void
)
void
Survey
Complex
ItemTest
::
_testGridAngle
(
void
)
{
_setPolygon
();
...
...
@@ -224,7 +224,7 @@ void SurveyMissionItemTest::_testGridAngle(void)
}
}
void
Survey
Mission
ItemTest
::
_testEntryLocation
(
void
)
void
Survey
Complex
ItemTest
::
_testEntryLocation
(
void
)
{
_setPolygon
();
...
...
@@ -233,10 +233,10 @@ void SurveyMissionItemTest::_testEntryLocation(void)
QList
<
QGeoCoordinate
>
rgSeenEntryCoords
;
QList
<
int
>
rgEntryLocation
;
rgEntryLocation
<<
Survey
Mission
Item
::
EntryLocationTopLeft
<<
Survey
Mission
Item
::
EntryLocationTopRight
<<
Survey
Mission
Item
::
EntryLocationBottomLeft
<<
Survey
Mission
Item
::
EntryLocationBottomRight
;
rgEntryLocation
<<
Survey
Complex
Item
::
EntryLocationTopLeft
<<
Survey
Complex
Item
::
EntryLocationTopRight
<<
Survey
Complex
Item
::
EntryLocationBottomLeft
<<
Survey
Complex
Item
::
EntryLocationBottomRight
;
// Validate that each entry location is unique
for
(
int
i
=
0
;
i
<
rgEntryLocation
.
count
();
i
++
)
{
...
...
@@ -251,7 +251,7 @@ void SurveyMissionItemTest::_testEntryLocation(void)
}
void
Survey
Mission
ItemTest
::
_testItemCount
(
void
)
void
Survey
Complex
ItemTest
::
_testItemCount
(
void
)
{
QList
<
MissionItem
*>
items
;
...
...
src/MissionManager/Survey
Mission
ItemTest.h
→
src/MissionManager/Survey
Complex
ItemTest.h
View file @
985c72e5
...
...
@@ -7,24 +7,22 @@
*
****************************************************************************/
#ifndef SurveyMissionItemTest_H
#define SurveyMissionItemTest_H
#pragma once
#include "UnitTest.h"
#include "TCPLink.h"
#include "MultiSignalSpy.h"
#include "Survey
Mission
Item.h"
#include "Survey
Complex
Item.h"
#include <QGeoCoordinate>
/// Unit test for Survey
Mission
Item
class
Survey
Mission
ItemTest
:
public
UnitTest
/// Unit test for Survey
Complex
Item
class
Survey
Complex
ItemTest
:
public
UnitTest
{
Q_OBJECT
public:
Survey
Mission
ItemTest
(
void
);
Survey
Complex
ItemTest
(
void
);
protected:
void
init
(
void
)
final
;
...
...
@@ -72,9 +70,7 @@ private:
Vehicle
*
_offlineVehicle
;
MultiSignalSpy
*
_multiSpy
;
Survey
Mission
Item
*
_surveyItem
;
Survey
Complex
Item
*
_surveyItem
;
QGCMapPolygon
*
_mapPolygon
;
QList
<
QGeoCoordinate
>
_polyPoints
;
};
#endif
src/qgcunittest/UnitTestList.cc
View file @
985c72e5
...
...
@@ -20,7 +20,7 @@
#include "MessageBoxTest.h"
#include "MissionItemTest.h"
#include "SimpleMissionItemTest.h"
#include "Survey
Mission
ItemTest.h"
#include "Survey
Complex
ItemTest.h"
#include "MissionControllerTest.h"
#include "MissionManagerTest.h"
#include "RadioConfigTest.h"
...
...
@@ -63,7 +63,7 @@ UT_REGISTER_TEST(ParameterManagerTest)
UT_REGISTER_TEST
(
MissionCommandTreeTest
)
UT_REGISTER_TEST
(
LogDownloadTest
)
UT_REGISTER_TEST
(
SendMavCommandTest
)
UT_REGISTER_TEST
(
Survey
Mission
ItemTest
)
UT_REGISTER_TEST
(
Survey
Complex
ItemTest
)
UT_REGISTER_TEST
(
CameraSectionTest
)
UT_REGISTER_TEST
(
SpeedSectionTest
)
UT_REGISTER_TEST
(
PlanMasterControllerTest
)
...
...
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