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
ee5736e1
Commit
ee5736e1
authored
Mar 16, 2018
by
DonLakeFlyer
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Store/load generated items from Plan file
parent
9fb7a58c
Changes
6
Hide whitespace changes
Inline
Side-by-side
Showing
6 changed files
with
194 additions
and
60 deletions
+194
-60
CorridorScanComplexItem.cc
src/MissionManager/CorridorScanComplexItem.cc
+68
-24
CorridorScanComplexItem.h
src/MissionManager/CorridorScanComplexItem.h
+11
-9
TransectStyleComplexItem.cc
src/MissionManager/TransectStyleComplexItem.cc
+95
-22
TransectStyleComplexItem.h
src/MissionManager/TransectStyleComplexItem.h
+12
-3
TransectStyleComplexItemTest.cc
src/MissionManager/TransectStyleComplexItemTest.cc
+6
-1
TransectStyleComplexItemTest.h
src/MissionManager/TransectStyleComplexItemTest.h
+2
-1
No files found.
src/MissionManager/CorridorScanComplexItem.cc
View file @
ee5736e1
...
...
@@ -23,7 +23,7 @@ QGC_LOGGING_CATEGORY(CorridorScanComplexItemLog, "CorridorScanComplexItemLog")
const
char
*
CorridorScanComplexItem
::
settingsGroup
=
"CorridorScan"
;
const
char
*
CorridorScanComplexItem
::
corridorWidthName
=
"CorridorWidth"
;
const
char
*
CorridorScanComplexItem
::
_
entryPointName
=
"EntryPoint"
;
const
char
*
CorridorScanComplexItem
::
_
jsonEntryPointKey
=
"EntryPoint"
;
const
char
*
CorridorScanComplexItem
::
jsonComplexItemTypeValue
=
"CorridorScan"
;
...
...
@@ -77,16 +77,17 @@ int CorridorScanComplexItem::lastSequenceNumber(void) const
return
_sequenceNumber
+
itemCount
-
1
;
}
void
CorridorScanComplexItem
::
save
(
QJsonArray
&
missio
nItems
)
void
CorridorScanComplexItem
::
save
(
QJsonArray
&
pla
nItems
)
{
QJsonObject
saveObject
;
saveObject
[
JsonHelper
::
jsonVersionKey
]
=
1
;
_save
(
saveObject
);
saveObject
[
JsonHelper
::
jsonVersionKey
]
=
2
;
saveObject
[
VisualMissionItem
::
jsonTypeKey
]
=
VisualMissionItem
::
jsonTypeComplexItemValue
;
saveObject
[
ComplexMissionItem
::
jsonComplexItemTypeKey
]
=
jsonComplexItemTypeValue
;
saveObject
[
corridorWidthName
]
=
_corridorWidthFact
.
rawValue
().
toDouble
();
saveObject
[
turnAroundDistanceName
]
=
_turnAroundDistanceFact
.
rawValue
().
toDouble
();
saveObject
[
_entryPointName
]
=
_entryPoint
;
saveObject
[
_jsonEntryPointKey
]
=
_entryPoint
;
QJsonObject
cameraCalcObject
;
_cameraCalc
.
save
(
cameraCalcObject
);
...
...
@@ -94,28 +95,29 @@ void CorridorScanComplexItem::save(QJsonArray& missionItems)
_corridorPolyline
.
saveToJson
(
saveObject
);
_save
(
saveObject
);
missionItems
.
append
(
saveObject
);
planItems
.
append
(
saveObject
);
}
bool
CorridorScanComplexItem
::
load
(
const
QJsonObject
&
complexObject
,
int
sequenceNumber
,
QString
&
errorString
)
{
// We don't recalc while loading since all the information we need is specified in the file
_ignoreRecalc
=
true
;
QList
<
JsonHelper
::
KeyValidateInfo
>
keyInfoList
=
{
{
JsonHelper
::
jsonVersionKey
,
QJsonValue
::
Double
,
true
},
{
VisualMissionItem
::
jsonTypeKey
,
QJsonValue
::
String
,
true
},
{
ComplexMissionItem
::
jsonComplexItemTypeKey
,
QJsonValue
::
String
,
true
},
{
corridorWidthName
,
QJsonValue
::
Double
,
true
},
{
turnAroundDistanceName
,
QJsonValue
::
Double
,
true
},
{
_entryPointName
,
QJsonValue
::
Double
,
true
},
{
_jsonEntryPointKey
,
QJsonValue
::
Double
,
true
},
{
QGCMapPolyline
::
jsonPolylineKey
,
QJsonValue
::
Array
,
true
},
{
_jsonCameraCalcKey
,
QJsonValue
::
Object
,
true
},
};
if
(
!
JsonHelper
::
validateKeys
(
complexObject
,
keyInfoList
,
errorString
))
{
_ignoreRecalc
=
false
;
return
false
;
}
if
(
!
_corridorPolyline
.
loadFromJson
(
complexObject
,
true
,
errorString
))
{
_ignoreRecalc
=
false
;
return
false
;
}
...
...
@@ -123,27 +125,32 @@ bool CorridorScanComplexItem::load(const QJsonObject& complexObject, int sequenc
QString
complexType
=
complexObject
[
ComplexMissionItem
::
jsonComplexItemTypeKey
].
toString
();
if
(
itemType
!=
VisualMissionItem
::
jsonTypeComplexItemValue
||
complexType
!=
jsonComplexItemTypeValue
)
{
errorString
=
tr
(
"%1 does not support loading this complex mission item type: %2:%3"
).
arg
(
qgcApp
()
->
applicationName
()).
arg
(
itemType
).
arg
(
complexType
);
_ignoreRecalc
=
false
;
return
false
;
}
int
version
=
complexObject
[
JsonHelper
::
jsonVersionKey
].
toInt
();
if
(
version
!=
1
)
{
if
(
version
!=
2
)
{
errorString
=
tr
(
"%1 complex item version %2 not supported"
).
arg
(
jsonComplexItemTypeValue
).
arg
(
version
);
_ignoreRecalc
=
false
;
return
false
;
}
setSequenceNumber
(
sequenceNumber
);
if
(
!
_load
(
complexObject
,
errorString
))
{
_ignoreRecalc
=
false
;
return
false
;
}
_corridorWidthFact
.
setRawValue
(
complexObject
[
corridorWidthName
].
toDouble
());
_entryPoint
=
complexObject
[
_
entryPointName
].
toInt
();
_entryPoint
=
complexObject
[
_
jsonEntryPointKey
].
toInt
();
_rebuildCorridor
();
_ignoreRecalc
=
false
;
return
true
;
}
...
...
@@ -159,8 +166,23 @@ int CorridorScanComplexItem::_transectCount(void) const
return
fullWidth
>
0.0
?
qCeil
(
fullWidth
/
transectSpacing
)
:
1
;
}
void
CorridorScanComplexItem
::
appendMissionItems
(
QList
<
MissionItem
*>&
items
,
QObject
*
missionItemParent
)
void
CorridorScanComplexItem
::
_appendLoadedMissionItems
(
QList
<
MissionItem
*>&
items
,
QObject
*
missionItemParent
)
{
qCDebug
(
CorridorScanComplexItemLog
)
<<
"_appendLoadedMissionItems"
;
int
seqNum
=
_sequenceNumber
;
foreach
(
const
MissionItem
*
loadedMissionItem
,
_loadedMissionItems
)
{
MissionItem
*
item
=
new
MissionItem
(
*
loadedMissionItem
,
missionItemParent
);
item
->
setSequenceNumber
(
seqNum
++
);
items
.
append
(
item
);
}
}
void
CorridorScanComplexItem
::
_buildAndAppendMissionItems
(
QList
<
MissionItem
*>&
items
,
QObject
*
missionItemParent
)
{
qCDebug
(
CorridorScanComplexItemLog
)
<<
"_buildAndAppendMissionItems"
;
int
seqNum
=
_sequenceNumber
;
int
pointIndex
=
0
;
bool
imagesEverywhere
=
_cameraTriggerInTurnAroundFact
.
rawValue
().
toBool
();
...
...
@@ -279,6 +301,17 @@ void CorridorScanComplexItem::appendMissionItems(QList<MissionItem*>& items, QOb
}
}
void
CorridorScanComplexItem
::
appendMissionItems
(
QList
<
MissionItem
*>&
items
,
QObject
*
missionItemParent
)
{
if
(
_loadedMissionItems
.
count
())
{
// We have mission items from the loaded plan, use those
_appendLoadedMissionItems
(
items
,
missionItemParent
);
}
else
{
// Build the mission items on the fly
_buildAndAppendMissionItems
(
items
,
missionItemParent
);
}
}
void
CorridorScanComplexItem
::
applyNewAltitude
(
double
newAltitude
)
{
_cameraCalc
.
valueSetIsDistance
()
->
setRawValue
(
true
);
...
...
@@ -324,10 +357,20 @@ void CorridorScanComplexItem::_rebuildCorridorPolygon(void)
}
}
void
CorridorScanComplexItem
::
_rebuildTransects
(
void
)
void
CorridorScanComplexItem
::
_rebuildTransects
Phase1
(
void
)
{
if
(
_ignoreRecalc
)
{
return
;
}
// If the transects are getting rebuilt then any previsouly loaded mission items are now invalid
if
(
_loadedMissionItemsParent
)
{
_loadedMissionItems
.
clear
();
_loadedMissionItemsParent
->
deleteLater
();
_loadedMissionItemsParent
=
NULL
;
}
_transectPoints
.
clear
();
_cameraShots
=
0
;
double
transectSpacing
=
_cameraCalc
.
adjustedFootprintSide
()
->
rawValue
().
toDouble
();
double
fullWidth
=
_corridorWidthFact
.
rawValue
().
toDouble
();
...
...
@@ -336,13 +379,9 @@ void CorridorScanComplexItem::_rebuildTransects(void)
double
normalizedTransectPosition
=
transectSpacing
/
2.0
;
if
(
_corridorPolyline
.
count
()
>=
2
)
{
int
singleTransectImageCount
=
qCeil
(
_corridorPolyline
.
length
()
/
_cameraCalc
.
adjustedFootprintFrontal
()
->
rawValue
().
toDouble
());
// First build up the transects all going the same direction
QList
<
QList
<
QGeoCoordinate
>>
transects
;
for
(
int
i
=
0
;
i
<
transectCount
;
i
++
)
{
_cameraShots
+=
singleTransectImageCount
;
double
offsetDistance
;
if
(
transectCount
==
1
)
{
// Single transect is flown over scan line
...
...
@@ -415,8 +454,6 @@ void CorridorScanComplexItem::_rebuildTransects(void)
// Convert the list of transects to grid points
reverseVertices
=
false
;
for
(
int
i
=
0
;
i
<
transects
.
count
();
i
++
)
{
_cameraShots
+=
singleTransectImageCount
;
// We must reverse the vertices for every other transect in order to make a lawnmower pattern
QList
<
QGeoCoordinate
>
transectVertices
=
transects
[
i
];
if
(
reverseVertices
)
{
...
...
@@ -436,15 +473,21 @@ void CorridorScanComplexItem::_rebuildTransects(void)
normalizedTransectPosition
+=
transectSpacing
;
}
}
}
void
CorridorScanComplexItem
::
_rebuildTransectsPhase2
(
void
)
{
// Calculate distance flown for complex item
_complexDistance
=
0
;
for
(
int
i
=
0
;
i
<
_transectPoints
.
count
()
-
2
;
i
++
)
{
_complexDistance
+=
_transectPoints
[
i
].
value
<
QGeoCoordinate
>
().
distanceTo
(
_transectPoints
[
i
+
1
].
value
<
QGeoCoordinate
>
());
}
if
(
_cameraTriggerInTurnAroundFact
.
rawValue
().
to
Double
())
{
if
(
_cameraTriggerInTurnAroundFact
.
rawValue
().
to
Bool
())
{
_cameraShots
=
qCeil
(
_complexDistance
/
_cameraCalc
.
adjustedFootprintFrontal
()
->
rawValue
().
toDouble
());
}
else
{
int
singleTransectImageCount
=
qCeil
(
_corridorPolyline
.
length
()
/
_cameraCalc
.
adjustedFootprintFrontal
()
->
rawValue
().
toDouble
());
_cameraShots
=
singleTransectImageCount
*
_transectCount
();
}
_coordinate
=
_transectPoints
.
count
()
?
_transectPoints
.
first
().
value
<
QGeoCoordinate
>
()
:
QGeoCoordinate
();
...
...
@@ -460,5 +503,6 @@ void CorridorScanComplexItem::_rebuildTransects(void)
void
CorridorScanComplexItem
::
_rebuildCorridor
(
void
)
{
_rebuildCorridorPolygon
();
_rebuildTransects
();
_rebuildTransectsPhase1
();
_rebuildTransectsPhase2
();
}
src/MissionManager/CorridorScanComplexItem.h
View file @
ee5736e1
...
...
@@ -43,7 +43,7 @@ public:
// Overrides from TransectStyleComplexItem
void
save
(
QJsonArray
&
missio
nItems
)
final
;
void
save
(
QJsonArray
&
pla
nItems
)
final
;
bool
specifiesCoordinate
(
void
)
const
final
;
void
appendMissionItems
(
QList
<
MissionItem
*>&
items
,
QObject
*
missionItemParent
)
final
;
void
applyNewAltitude
(
double
newAltitude
)
final
;
...
...
@@ -54,17 +54,19 @@ public:
static
const
char
*
corridorWidthName
;
private
slots
:
void
_polylineDirtyChanged
(
bool
dirty
);
void
_polylineCountChanged
(
int
count
);
void
_rebuildCorridor
(
void
);
void
_polylineDirtyChanged
(
bool
dirty
);
void
_polylineCountChanged
(
int
count
);
void
_rebuildCorridor
(
void
);
// Overrides from TransectStyleComplexItem
virtual
void
_rebuildTransects
(
void
)
final
;
void
_rebuildTransectsPhase1
(
void
)
final
;
void
_rebuildTransectsPhase2
(
void
)
final
;
private:
int
_transectCount
(
void
)
const
;
void
_rebuildCorridorPolygon
(
void
);
int
_transectCount
(
void
)
const
;
void
_rebuildCorridorPolygon
(
void
);
void
_buildAndAppendMissionItems
(
QList
<
MissionItem
*>&
items
,
QObject
*
missionItemParent
);
void
_appendLoadedMissionItems
(
QList
<
MissionItem
*>&
items
,
QObject
*
missionItemParent
);
QGCMapPolyline
_corridorPolyline
;
QList
<
QList
<
QGeoCoordinate
>>
_transectSegments
;
///< Internal transect segments including grid exit, turnaround and internal camera points
...
...
@@ -75,5 +77,5 @@ private:
QMap
<
QString
,
FactMetaData
*>
_metaDataMap
;
SettingsFact
_corridorWidthFact
;
static
const
char
*
_
entryPointName
;
static
const
char
*
_
jsonEntryPointKey
;
};
src/MissionManager/TransectStyleComplexItem.cc
View file @
ee5736e1
...
...
@@ -27,19 +27,23 @@ const char* TransectStyleComplexItem::cameraTriggerInTurnAroundName = "Cam
const
char
*
TransectStyleComplexItem
::
hoverAndCaptureName
=
"HoverAndCapture"
;
const
char
*
TransectStyleComplexItem
::
refly90DegreesName
=
"Refly90Degrees"
;
const
char
*
TransectStyleComplexItem
::
_jsonCameraCalcKey
=
"CameraCalc"
;
const
char
*
TransectStyleComplexItem
::
_jsonTransectStyleComplexItemKey
=
"TransectStyleComplexItem"
;
const
char
*
TransectStyleComplexItem
::
_jsonCameraCalcKey
=
"CameraCalc"
;
const
char
*
TransectStyleComplexItem
::
_jsonTransectPointsKey
=
"TransectPoints"
;
const
char
*
TransectStyleComplexItem
::
_jsonItemsKey
=
"Items"
;
TransectStyleComplexItem
::
TransectStyleComplexItem
(
Vehicle
*
vehicle
,
QString
settingsGroup
,
QObject
*
parent
)
:
ComplexMissionItem
(
vehicle
,
parent
)
,
_settingsGroup
(
settingsGroup
)
,
_sequenceNumber
(
0
)
,
_dirty
(
false
)
,
_ignoreRecalc
(
false
)
,
_complexDistance
(
0
)
,
_cameraShots
(
0
)
,
_cameraMinTriggerInterval
(
0
)
,
_cameraCalc
(
vehicle
)
,
_metaDataMap
(
FactMetaData
::
createMapFromJsonFile
(
QStringLiteral
(
":/json/TransectStyle.SettingsGroup.json"
),
this
))
:
ComplexMissionItem
(
vehicle
,
parent
)
,
_settingsGroup
(
settingsGroup
)
,
_sequenceNumber
(
0
)
,
_dirty
(
false
)
,
_ignoreRecalc
(
false
)
,
_complexDistance
(
0
)
,
_cameraShots
(
0
)
,
_cameraMinTriggerInterval
(
0
)
,
_cameraCalc
(
vehicle
)
,
_loadedMissionItemsParent
(
NULL
)
,
_metaDataMap
(
FactMetaData
::
createMapFromJsonFile
(
QStringLiteral
(
":/json/TransectStyle.SettingsGroup.json"
),
this
))
,
_turnAroundDistanceFact
(
_settingsGroup
,
_metaDataMap
[
_vehicle
->
multiRotor
()
?
turnAroundDistanceMultiRotorName
:
turnAroundDistanceName
])
,
_cameraTriggerInTurnAroundFact
(
_settingsGroup
,
_metaDataMap
[
cameraTriggerInTurnAroundName
])
,
_hoverAndCaptureFact
(
_settingsGroup
,
_metaDataMap
[
hoverAndCaptureName
])
...
...
@@ -108,14 +112,38 @@ void TransectStyleComplexItem::setDirty(bool dirty)
void
TransectStyleComplexItem
::
_save
(
QJsonObject
&
complexObject
)
{
complexObject
[
turnAroundDistanceName
]
=
_turnAroundDistanceFact
.
rawValue
().
toDouble
();
complexObject
[
cameraTriggerInTurnAroundName
]
=
_cameraTriggerInTurnAroundFact
.
rawValue
().
toBool
();
complexObject
[
hoverAndCaptureName
]
=
_hoverAndCaptureFact
.
rawValue
().
toBool
();
complexObject
[
refly90DegreesName
]
=
_refly90DegreesFact
.
rawValue
().
toBool
();
QJsonObject
innerObject
;
innerObject
[
JsonHelper
::
jsonVersionKey
]
=
1
;
innerObject
[
turnAroundDistanceName
]
=
_turnAroundDistanceFact
.
rawValue
().
toDouble
();
innerObject
[
cameraTriggerInTurnAroundName
]
=
_cameraTriggerInTurnAroundFact
.
rawValue
().
toBool
();
innerObject
[
hoverAndCaptureName
]
=
_hoverAndCaptureFact
.
rawValue
().
toBool
();
innerObject
[
refly90DegreesName
]
=
_refly90DegreesFact
.
rawValue
().
toBool
();
QJsonObject
cameraCalcObject
;
_cameraCalc
.
save
(
cameraCalcObject
);
complexObject
[
_jsonCameraCalcKey
]
=
cameraCalcObject
;
innerObject
[
_jsonCameraCalcKey
]
=
cameraCalcObject
;
QJsonValue
transectPointsJson
;
// Save transects polyline
JsonHelper
::
saveGeoCoordinateArray
(
_transectPoints
,
false
/* writeAltitude */
,
transectPointsJson
);
innerObject
[
_jsonTransectPointsKey
]
=
transectPointsJson
;
// Save the interal mission items
QJsonArray
missionItemsJsonArray
;
QObject
*
missionItemParent
=
new
QObject
();
QList
<
MissionItem
*>
missionItems
;
appendMissionItems
(
missionItems
,
missionItemParent
);
foreach
(
const
MissionItem
*
missionItem
,
missionItems
)
{
QJsonObject
missionItemJsonObject
;
missionItem
->
save
(
missionItemJsonObject
);
missionItemsJsonArray
.
append
(
missionItemJsonObject
);
}
missionItemParent
->
deleteLater
();
innerObject
[
_jsonItemsKey
]
=
missionItemsJsonArray
;
complexObject
[
_jsonTransectStyleComplexItemKey
]
=
innerObject
;
}
void
TransectStyleComplexItem
::
setSequenceNumber
(
int
sequenceNumber
)
...
...
@@ -129,25 +157,65 @@ void TransectStyleComplexItem::setSequenceNumber(int sequenceNumber)
bool
TransectStyleComplexItem
::
_load
(
const
QJsonObject
&
complexObject
,
QString
&
errorString
)
{
QList
<
JsonHelper
::
KeyValidateInfo
>
keyInfoList
=
{
{
_jsonTransectStyleComplexItemKey
,
QJsonValue
::
Object
,
true
},
};
if
(
!
JsonHelper
::
validateKeys
(
complexObject
,
keyInfoList
,
errorString
))
{
return
false
;
}
// The TransectStyleComplexItem is a sub-object of the main complex item object
QJsonObject
innerObject
=
complexObject
[
_jsonTransectStyleComplexItemKey
].
toObject
();
QList
<
JsonHelper
::
KeyValidateInfo
>
innerKeyInfoList
=
{
{
JsonHelper
::
jsonVersionKey
,
QJsonValue
::
Double
,
true
},
{
turnAroundDistanceName
,
QJsonValue
::
Double
,
true
},
{
cameraTriggerInTurnAroundName
,
QJsonValue
::
Bool
,
true
},
{
hoverAndCaptureName
,
QJsonValue
::
Bool
,
true
},
{
refly90DegreesName
,
QJsonValue
::
Bool
,
true
},
{
_jsonCameraCalcKey
,
QJsonValue
::
Object
,
true
},
{
_jsonTransectPointsKey
,
QJsonValue
::
Array
,
true
},
{
_jsonItemsKey
,
QJsonValue
::
Array
,
true
},
};
if
(
!
JsonHelper
::
validateKeys
(
complexObject
,
k
eyInfoList
,
errorString
))
{
if
(
!
JsonHelper
::
validateKeys
(
innerObject
,
innerK
eyInfoList
,
errorString
))
{
return
false
;
}
if
(
!
_cameraCalc
.
load
(
complexObject
[
_jsonCameraCalcKey
].
toObject
(),
errorString
))
{
int
version
=
innerObject
[
JsonHelper
::
jsonVersionKey
].
toInt
();
if
(
version
!=
1
)
{
errorString
=
tr
(
"TransectStyleComplexItem version %2 not supported"
).
arg
(
version
);
return
false
;
}
_turnAroundDistanceFact
.
setRawValue
(
complexObject
[
turnAroundDistanceName
].
toDouble
());
_cameraTriggerInTurnAroundFact
.
setRawValue
(
complexObject
[
cameraTriggerInTurnAroundName
].
toBool
());
_hoverAndCaptureFact
.
setRawValue
(
complexObject
[
hoverAndCaptureName
].
toBool
());
_hoverAndCaptureFact
.
setRawValue
(
complexObject
[
refly90DegreesName
].
toBool
());
// Load transect points
if
(
!
JsonHelper
::
loadGeoCoordinateArray
(
innerObject
[
_jsonTransectPointsKey
],
false
/* altitudeRequired */
,
_transectPoints
,
errorString
))
{
return
false
;
}
// Load generated mission items
_loadedMissionItemsParent
=
new
QObject
(
this
);
QJsonArray
missionItemsJsonArray
=
innerObject
[
_jsonItemsKey
].
toArray
();
foreach
(
const
QJsonValue
&
missionItemJson
,
missionItemsJsonArray
)
{
MissionItem
*
missionItem
=
new
MissionItem
(
_loadedMissionItemsParent
);
if
(
!
missionItem
->
load
(
missionItemJson
.
toObject
(),
0
/* sequenceNumber */
,
errorString
))
{
_loadedMissionItemsParent
->
deleteLater
();
_loadedMissionItemsParent
=
NULL
;
return
false
;
}
_loadedMissionItems
.
append
(
missionItem
);
}
// Load CameraCalc data
if
(
!
_cameraCalc
.
load
(
innerObject
[
_jsonCameraCalcKey
].
toObject
(),
errorString
))
{
return
false
;
}
// Load TransectStyleComplexItem individual values
_turnAroundDistanceFact
.
setRawValue
(
innerObject
[
turnAroundDistanceName
].
toDouble
());
_cameraTriggerInTurnAroundFact
.
setRawValue
(
innerObject
[
cameraTriggerInTurnAroundName
].
toBool
());
_hoverAndCaptureFact
.
setRawValue
(
innerObject
[
hoverAndCaptureName
].
toBool
());
_hoverAndCaptureFact
.
setRawValue
(
innerObject
[
refly90DegreesName
].
toBool
());
return
true
;
}
...
...
@@ -230,3 +298,8 @@ bool TransectStyleComplexItem::hoverAndCaptureAllowed(void) const
return
_vehicle
->
multiRotor
()
||
_vehicle
->
vtol
();
}
void
TransectStyleComplexItem
::
_rebuildTransects
(
void
)
{
_rebuildTransectsPhase1
();
_rebuildTransectsPhase2
();
}
src/MissionManager/TransectStyleComplexItem.h
View file @
ee5736e1
...
...
@@ -66,7 +66,7 @@ public:
// Overrides from VisualMissionItem
void
save
(
QJsonArray
&
missio
nItems
)
override
=
0
;
void
save
(
QJsonArray
&
pla
nItems
)
override
=
0
;
bool
specifiesCoordinate
(
void
)
const
override
=
0
;
void
appendMissionItems
(
QList
<
MissionItem
*>&
items
,
QObject
*
missionItemParent
)
override
=
0
;
void
applyNewAltitude
(
double
newAltitude
)
override
=
0
;
...
...
@@ -108,7 +108,8 @@ signals:
void
coveredAreaChanged
(
void
);
protected
slots
:
virtual
void
_rebuildTransects
(
void
)
=
0
;
virtual
void
_rebuildTransectsPhase1
(
void
)
=
0
;
virtual
void
_rebuildTransectsPhase2
(
void
)
=
0
;
void
_setDirty
(
void
);
void
_setIfDirty
(
bool
dirty
);
...
...
@@ -121,7 +122,6 @@ protected:
void
_setExitCoordinate
(
const
QGeoCoordinate
&
coordinate
);
void
_setCameraShots
(
int
cameraShots
);
double
_triggerDistance
(
void
)
const
;
int
_transectCount
(
void
)
const
;
bool
_hasTurnaround
(
void
)
const
;
double
_turnaroundDistance
(
void
)
const
;
...
...
@@ -141,6 +141,9 @@ protected:
double
_cruiseSpeed
;
CameraCalc
_cameraCalc
;
QObject
*
_loadedMissionItemsParent
;
///< Parent for all items in _loadedMissionItems for simpler delete
QList
<
MissionItem
*>
_loadedMissionItems
;
///< Mission items loaded from plan file
QMap
<
QString
,
FactMetaData
*>
_metaDataMap
;
SettingsFact
_turnAroundDistanceFact
;
...
...
@@ -149,4 +152,10 @@ protected:
SettingsFact
_refly90DegreesFact
;
static
const
char
*
_jsonCameraCalcKey
;
static
const
char
*
_jsonTransectStyleComplexItemKey
;
static
const
char
*
_jsonTransectPointsKey
;
static
const
char
*
_jsonItemsKey
;
private
slots
:
void
_rebuildTransects
(
void
);
};
src/MissionManager/TransectStyleComplexItemTest.cc
View file @
ee5736e1
...
...
@@ -174,7 +174,12 @@ TransectStyleItem::TransectStyleItem(Vehicle* vehicle, QObject* parent)
}
void
TransectStyleItem
::
_rebuildTransects
(
void
)
void
TransectStyleItem
::
_rebuildTransects
Phase1
(
void
)
{
rebuildTransectsCalled
=
true
;
}
void
TransectStyleItem
::
_rebuildTransectsPhase2
(
void
)
{
}
src/MissionManager/TransectStyleComplexItemTest.h
View file @
ee5736e1
...
...
@@ -101,5 +101,6 @@ public:
private
slots
:
// Overrides from TransectStyleComplexItem
void
_rebuildTransects
(
void
)
final
;
void
_rebuildTransectsPhase1
(
void
)
final
;
void
_rebuildTransectsPhase2
(
void
)
final
;
};
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