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
8e661ea0
Commit
8e661ea0
authored
Apr 28, 2020
by
DoinLakeFlyer
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
parent
e9bbd5eb
Changes
60
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
60 changed files
with
2552 additions
and
1066 deletions
+2552
-1066
qgroundcontrol.pro
qgroundcontrol.pro
+6
-3
qgroundcontrol.qrc
qgroundcontrol.qrc
+1
-0
FlightDisplayView.qml
src/FlightDisplay/FlightDisplayView.qml
+1
-0
MissionLineView.qml
src/FlightMap/MapItems/MissionLineView.qml
+6
-1
ComplexMissionItem.cc
src/MissionManager/ComplexMissionItem.cc
+33
-0
ComplexMissionItem.h
src/MissionManager/ComplexMissionItem.h
+42
-7
CorridorScanComplexItem.cc
src/MissionManager/CorridorScanComplexItem.cc
+2
-19
CorridorScanComplexItem.h
src/MissionManager/CorridorScanComplexItem.h
+3
-2
CorridorScanPlanCreator.cc
src/MissionManager/CorridorScanPlanCreator.cc
+3
-3
FixedWingLandingComplexItem.cc
src/MissionManager/FixedWingLandingComplexItem.cc
+56
-10
FixedWingLandingComplexItem.h
src/MissionManager/FixedWingLandingComplexItem.h
+55
-50
MissionController.cc
src/MissionManager/MissionController.cc
+206
-188
MissionController.h
src/MissionManager/MissionController.h
+97
-93
MissionControllerTest.cc
src/MissionManager/MissionControllerTest.cc
+6
-3
MissionSettingsItem.cc
src/MissionManager/MissionSettingsItem.cc
+5
-0
MissionSettingsItem.h
src/MissionManager/MissionSettingsItem.h
+34
-33
QGCMapPolygon.cc
src/MissionManager/QGCMapPolygon.cc
+16
-0
QGCMapPolygon.h
src/MissionManager/QGCMapPolygon.h
+24
-17
QGCMapPolygonVisuals.qml
src/MissionManager/QGCMapPolygonVisuals.qml
+6
-9
SimpleMissionItem.cc
src/MissionManager/SimpleMissionItem.cc
+58
-24
SimpleMissionItem.h
src/MissionManager/SimpleMissionItem.h
+25
-26
SimpleMissionItemTest.cc
src/MissionManager/SimpleMissionItemTest.cc
+2
-3
SimpleMissionItemTest.h
src/MissionManager/SimpleMissionItemTest.h
+0
-2
StructureScanComplexItem.cc
src/MissionManager/StructureScanComplexItem.cc
+165
-20
StructureScanComplexItem.h
src/MissionManager/StructureScanComplexItem.h
+59
-53
StructureScanPlanCreator.cc
src/MissionManager/StructureScanPlanCreator.cc
+3
-3
SurveyComplexItem.cc
src/MissionManager/SurveyComplexItem.cc
+2
-21
SurveyComplexItem.h
src/MissionManager/SurveyComplexItem.h
+3
-2
SurveyPlanCreator.cc
src/MissionManager/SurveyPlanCreator.cc
+3
-4
TakeoffMissionItem.cc
src/MissionManager/TakeoffMissionItem.cc
+1
-1
TransectStyleComplexItem.cc
src/MissionManager/TransectStyleComplexItem.cc
+216
-59
TransectStyleComplexItem.h
src/MissionManager/TransectStyleComplexItem.h
+55
-52
TransectStyleComplexItemTest.cc
src/MissionManager/TransectStyleComplexItemTest.cc
+8
-9
TransectStyleComplexItemTest.h
src/MissionManager/TransectStyleComplexItemTest.h
+1
-2
VTOLLandingComplexItem.cc
src/MissionManager/VTOLLandingComplexItem.cc
+78
-31
VTOLLandingComplexItem.h
src/MissionManager/VTOLLandingComplexItem.h
+53
-48
VisualMissionItem.cc
src/MissionManager/VisualMissionItem.cc
+32
-6
VisualMissionItem.h
src/MissionManager/VisualMissionItem.h
+38
-21
VisualMissionItemTest.cc
src/MissionManager/VisualMissionItemTest.cc
+0
-2
VisualMissionItemTest.h
src/MissionManager/VisualMissionItemTest.h
+0
-4
FWLandingPatternMapVisual.qml
src/PlanView/FWLandingPatternMapVisual.qml
+1
-1
PlanView.qml
src/PlanView/PlanView.qml
+33
-12
StructureScanMapVisual.qml
src/PlanView/StructureScanMapVisual.qml
+1
-0
TerrainStatus.qml
src/PlanView/TerrainStatus.qml
+214
-0
TransectStyleMapVisuals.qml
src/PlanView/TransectStyleMapVisuals.qml
+1
-0
QGCApplication.cc
src/QGCApplication.cc
+6
-2
QGCApplication.h
src/QGCApplication.h
+100
-0
QGCPalette.cc
src/QGCPalette.cc
+5
-4
QGCPalette.h
src/QGCPalette.h
+37
-36
CoordinateVector.cc
src/QmlControls/CoordinateVector.cc
+0
-54
CoordinateVector.h
src/QmlControls/CoordinateVector.h
+0
-50
FlightPathSegment.cc
src/QmlControls/FlightPathSegment.cc
+170
-0
FlightPathSegment.h
src/QmlControls/FlightPathSegment.h
+91
-0
MissionItemIndexLabel.qml
src/QmlControls/MissionItemIndexLabel.qml
+4
-2
qmldir
src/QmlControls/QGroundControl/Controls/qmldir
+1
-0
TerrainProfile.cc
src/QmlControls/TerrainProfile.cc
+324
-0
TerrainProfile.h
src/QmlControls/TerrainProfile.h
+83
-0
TerrainQuery.cc
src/Terrain/TerrainQuery.cc
+45
-36
TerrainQuery.h
src/Terrain/TerrainQuery.h
+30
-36
Vehicle.cc
src/Vehicle/Vehicle.cc
+2
-2
No files found.
qgroundcontrol.pro
View file @
8e661ea0
...
...
@@ -255,7 +255,8 @@ QT += \
svg
\
widgets
\
xml
\
texttospeech
texttospeech
\
core
-
private
#
Multimedia
only
used
if
QVC
is
enabled
!
contains
(
DEFINES
,
QGC_DISABLE_UVC
)
{
...
...
@@ -641,8 +642,8 @@ HEADERS += \
src
/
QGCTemporaryFile
.
h
\
src
/
QGCToolbox
.
h
\
src
/
QmlControls
/
AppMessages
.
h
\
src
/
QmlControls
/
CoordinateVector
.
h
\
src
/
QmlControls
/
EditPositionDialogController
.
h
\
src
/
QmlControls
/
FlightPathSegment
.
h
\
src
/
QmlControls
/
InstrumentValueData
.
h
\
src
/
QmlControls
/
InstrumentValueArea
.
h
\
src
/
QmlControls
/
ParameterEditorController
.
h
\
...
...
@@ -654,6 +655,7 @@ HEADERS += \
src
/
QmlControls
/
RCChannelMonitorController
.
h
\
src
/
QmlControls
/
RCToParamDialogController
.
h
\
src
/
QmlControls
/
ScreenToolsController
.
h
\
src
/
QmlControls
/
TerrainProfile
.
h
\
src
/
QtLocationPlugin
/
QMLControl
/
QGCMapEngineManager
.
h
\
src
/
Settings
/
ADSBVehicleManagerSettings
.
h
\
src
/
Settings
/
AppSettings
.
h
\
...
...
@@ -847,8 +849,8 @@ SOURCES += \
src
/
QGCTemporaryFile
.
cc
\
src
/
QGCToolbox
.
cc
\
src
/
QmlControls
/
AppMessages
.
cc
\
src
/
QmlControls
/
CoordinateVector
.
cc
\
src
/
QmlControls
/
EditPositionDialogController
.
cc
\
src
/
QmlControls
/
FlightPathSegment
.
cc
\
src
/
QmlControls
/
InstrumentValueData
.
cc
\
src
/
QmlControls
/
InstrumentValueArea
.
cc
\
src
/
QmlControls
/
ParameterEditorController
.
cc
\
...
...
@@ -860,6 +862,7 @@ SOURCES += \
src
/
QmlControls
/
RCChannelMonitorController
.
cc
\
src
/
QmlControls
/
RCToParamDialogController
.
cc
\
src
/
QmlControls
/
ScreenToolsController
.
cc
\
src
/
QmlControls
/
TerrainProfile
.
cc
\
src
/
QtLocationPlugin
/
QMLControl
/
QGCMapEngineManager
.
cc
\
src
/
Settings
/
ADSBVehicleManagerSettings
.
cc
\
src
/
Settings
/
AppSettings
.
cc
\
...
...
qgroundcontrol.qrc
View file @
8e661ea0
...
...
@@ -172,6 +172,7 @@
<file alias="QGroundControl/Controls/StructureScanMapVisual.qml">src/PlanView/StructureScanMapVisual.qml</file>
<file alias="QGroundControl/Controls/SubMenuButton.qml">src/QmlControls/SubMenuButton.qml</file>
<file alias="QGroundControl/Controls/SurveyMapVisual.qml">src/PlanView/SurveyMapVisual.qml</file>
<file alias="QGroundControl/Controls/TerrainStatus.qml">src/PlanView/TerrainStatus.qml</file>
<file alias="QGroundControl/Controls/TakeoffItemMapVisual.qml">src/PlanView/TakeoffItemMapVisual.qml</file>
<file alias="QGroundControl/Controls/ToolStrip.qml">src/QmlControls/ToolStrip.qml</file>
<file alias="QGroundControl/Controls/TransectStyleComplexItemStats.qml">src/PlanView/TransectStyleComplexItemStats.qml</file>
...
...
src/FlightDisplay/FlightDisplayView.qml
View file @
8e661ea0
...
...
@@ -640,6 +640,7 @@ Item {
name
:
qsTr
(
"
Action
"
),
iconSource
:
"
/res/action.svg
"
,
buttonVisible
:
_anyActionAvailable
,
buttonEnabled
:
true
,
action
:
-
1
}
]
...
...
src/FlightMap/MapItems/MissionLineView.qml
View file @
8e661ea0
...
...
@@ -19,8 +19,13 @@ MapItemView {
property
bool
showSpecialVisual
:
false
delegate
:
MapPolyline
{
line.width
:
3
line.color
:
object
&&
showSpecialVisual
&&
object
.
specialVisual
?
"
green
"
:
QGroundControl
.
globalPalette
.
mapMissionTrajectory
line.color
:
_terrainCollision
?
"
red
"
:
(
showSpecialVisual
?
"
green
"
:
QGroundControl
.
globalPalette
.
mapMissionTrajectory
)
z
:
QGroundControl
.
zOrderWaypointLines
path
:
object
&&
object
.
coordinate1
.
isValid
&&
object
.
coordinate2
.
isValid
?
[
object
.
coordinate1
,
object
.
coordinate2
]
:
[]
property
bool
_terrainCollision
:
object
&&
object
.
terrainCollision
property
bool
_showSpecialVisual
:
object
&&
showSpecialVisual
&&
object
.
specialVisual
}
}
src/MissionManager/ComplexMissionItem.cc
View file @
8e661ea0
...
...
@@ -12,6 +12,8 @@
#include "QGCCorePlugin.h"
#include "QGCOptions.h"
#include "PlanMasterController.h"
#include "FlightPathSegment.h"
#include "MissionController.h"
#include <QSettings>
...
...
@@ -112,3 +114,34 @@ void ComplexMissionItem::addKMLVisuals(KMLPlanDomDocument& /* domDocument */)
{
// Default implementation has no visuals
}
void
ComplexMissionItem
::
_appendFlightPathSegment
(
const
QGeoCoordinate
&
coord1
,
double
coord1AMSLAlt
,
const
QGeoCoordinate
&
coord2
,
double
coord2AMSLAlt
)
{
FlightPathSegment
*
segment
=
new
FlightPathSegment
(
coord1
,
coord1AMSLAlt
,
coord2
,
coord2AMSLAlt
,
true
/* queryTerrainData */
,
this
/* parent */
);
connect
(
segment
,
&
FlightPathSegment
::
terrainCollisionChanged
,
this
,
&
ComplexMissionItem
::
_segmentTerrainCollisionChanged
);
connect
(
segment
,
&
FlightPathSegment
::
terrainCollisionChanged
,
_missionController
,
&
MissionController
::
recalcTerrainProfile
,
Qt
::
QueuedConnection
);
connect
(
segment
,
&
FlightPathSegment
::
amslTerrainHeightsChanged
,
_missionController
,
&
MissionController
::
recalcTerrainProfile
,
Qt
::
QueuedConnection
);
// Signals may have been emitted in contructor so we need to deal with that now since they were missed
_flightPathSegments
.
append
(
segment
);
if
(
segment
->
terrainCollision
())
{
emit
_segmentTerrainCollisionChanged
(
true
);
}
if
(
segment
->
amslTerrainHeights
().
count
())
{
_missionController
->
recalcTerrainProfile
();
}
}
void
ComplexMissionItem
::
_segmentTerrainCollisionChanged
(
bool
terrainCollision
)
{
if
(
terrainCollision
)
{
_cTerrainCollisionSegments
++
;
}
else
{
_cTerrainCollisionSegments
--
;
}
emit
terrainCollisionChanged
(
_cTerrainCollisionSegments
!=
0
);
}
src/MissionManager/ComplexMissionItem.h
View file @
8e661ea0
...
...
@@ -14,10 +14,12 @@
#include "QGCToolbox.h"
#include "SettingsManager.h"
#include "KMLPlanDomDocument.h"
#include "QmlObjectListModel.h"
#include <QSettings>
class
PlanMasterController
;
class
MissionController
;
class
ComplexMissionItem
:
public
VisualMissionItem
{
...
...
@@ -28,10 +30,29 @@ public:
const
ComplexMissionItem
&
operator
=
(
const
ComplexMissionItem
&
other
);
Q_PROPERTY
(
double
complexDistance
READ
complexDistance
NOTIFY
complexDistanceChanged
)
Q_PROPERTY
(
bool
presetsSupported
READ
presetsSupported
CONSTANT
)
Q_PROPERTY
(
QStringList
presetNames
READ
presetNames
NOTIFY
presetNamesChanged
)
Q_PROPERTY
(
bool
isIncomplete
READ
isIncomplete
NOTIFY
isIncompleteChanged
)
Q_PROPERTY
(
QString
patternName
READ
patternName
CONSTANT
)
Q_PROPERTY
(
double
complexDistance
READ
complexDistance
NOTIFY
complexDistanceChanged
)
Q_PROPERTY
(
bool
presetsSupported
READ
presetsSupported
CONSTANT
)
Q_PROPERTY
(
QStringList
presetNames
READ
presetNames
NOTIFY
presetNamesChanged
)
Q_PROPERTY
(
bool
isIncomplete
READ
isIncomplete
NOTIFY
isIncompleteChanged
)
Q_PROPERTY
(
double
minAMSLAltitude
READ
minAMSLAltitude
NOTIFY
minAMSLAltitudeChanged
)
///< Minimum altitude of all coordinates in item
Q_PROPERTY
(
double
maxAMSLAltitude
READ
maxAMSLAltitude
NOTIFY
maxAMSLAltitudeChanged
)
///< Maximum altitude of all coordinates in item
Q_PROPERTY
(
bool
isSingleItem
READ
isSingleItem
CONSTANT
)
Q_PROPERTY
(
QmlObjectListModel
*
flightPathSegments
READ
flightPathSegments
CONSTANT
)
Q_PROPERTY
(
bool
terrainCollision
READ
terrainCollision
NOTIFY
terrainCollisionChanged
)
QmlObjectListModel
*
flightPathSegments
(
void
)
{
return
&
_flightPathSegments
;
}
virtual
QString
patternName
(
void
)
const
=
0
;
/// @return true: This complex item is colliding with terrain
virtual
bool
terrainCollision
(
void
)
const
{
return
_cTerrainCollisionSegments
!=
0
;
}
/// @return Minimum altitude for the items within this complex items.
virtual
double
minAMSLAltitude
(
void
)
const
=
0
;
/// @return Maximum altitude for the items within this complex items.
virtual
double
maxAMSLAltitude
(
void
)
const
=
0
;
/// @return The distance covered the complex mission item in meters.
/// Signals complexDistanceChanged
...
...
@@ -44,6 +65,9 @@ public:
/// @return true: load success, false: load failed, errorString set
virtual
bool
load
(
const
QJsonObject
&
complexObject
,
int
sequenceNumber
,
QString
&
errorString
)
=
0
;
/// @return true: Represents a single coordinate (ex: MissionSettingsItem), false: Represents multiple items (ex: Survey)
virtual
bool
isSingleItem
(
void
)
const
{
return
false
;
}
/// Loads the specified preset into the complex item.
/// @param name Preset name.
Q_INVOKABLE
virtual
void
loadPreset
(
const
QString
&
name
);
...
...
@@ -83,12 +107,21 @@ signals:
void
greatestDistanceToChanged
(
void
);
void
presetNamesChanged
(
void
);
void
isIncompleteChanged
(
void
);
void
minAMSLAltitudeChanged
(
double
minAMSLAltitude
);
void
maxAMSLAltitudeChanged
(
double
maxAMSLAltitude
);
void
terrainCollisionChanged
(
bool
terrainCollision
);
protected
slots
:
virtual
void
_segmentTerrainCollisionChanged
(
bool
terrainCollision
);
protected:
void
_savePresetJson
(
const
QString
&
name
,
QJsonObject
&
presetObject
);
QJsonObject
_loadPresetJson
(
const
QString
&
name
);
void
_savePresetJson
(
const
QString
&
name
,
QJsonObject
&
presetObject
);
QJsonObject
_loadPresetJson
(
const
QString
&
name
);
void
_appendFlightPathSegment
(
const
QGeoCoordinate
&
coord1
,
double
coord1AMSLAlt
,
const
QGeoCoordinate
&
coord2
,
double
coord2AMSLAlt
);
bool
_isIncomplete
=
true
;
bool
_isIncomplete
=
true
;
int
_cTerrainCollisionSegments
=
0
;
QmlObjectListModel
_flightPathSegments
;
// Contains FlightPathSegment items
QMap
<
QString
,
FactMetaData
*>
_metaDataMap
;
...
...
@@ -96,4 +129,6 @@ protected:
QGCToolbox
*
_toolbox
;
SettingsManager
*
_settingsManager
;
private:
};
src/MissionManager/CorridorScanComplexItem.cc
View file @
8e661ea0
...
...
@@ -22,6 +22,8 @@
QGC_LOGGING_CATEGORY
(
CorridorScanComplexItemLog
,
"CorridorScanComplexItemLog"
)
const
QString
CorridorScanComplexItem
::
name
(
tr
(
"Corridor Scan"
));
const
char
*
CorridorScanComplexItem
::
settingsGroup
=
"CorridorScan"
;
const
char
*
CorridorScanComplexItem
::
corridorWidthName
=
"CorridorWidth"
;
const
char
*
CorridorScanComplexItem
::
_jsonEntryPointKey
=
"EntryPoint"
;
...
...
@@ -44,9 +46,6 @@ CorridorScanComplexItem::CorridorScanComplexItem(PlanMasterController* masterCon
connect
(
&
_corridorWidthFact
,
&
Fact
::
valueChanged
,
this
,
&
CorridorScanComplexItem
::
_setDirty
);
connect
(
&
_corridorPolyline
,
&
QGCMapPolyline
::
pathChanged
,
this
,
&
CorridorScanComplexItem
::
_setDirty
);
connect
(
&
_cameraCalc
,
&
CameraCalc
::
distanceToSurfaceRelativeChanged
,
this
,
&
CorridorScanComplexItem
::
coordinateHasRelativeAltitudeChanged
);
connect
(
&
_cameraCalc
,
&
CameraCalc
::
distanceToSurfaceRelativeChanged
,
this
,
&
CorridorScanComplexItem
::
exitCoordinateHasRelativeAltitudeChanged
);
connect
(
&
_corridorPolyline
,
&
QGCMapPolyline
::
dirtyChanged
,
this
,
&
CorridorScanComplexItem
::
_polylineDirtyChanged
);
connect
(
&
_corridorPolyline
,
&
QGCMapPolyline
::
pathChanged
,
this
,
&
CorridorScanComplexItem
::
_rebuildCorridorPolygon
);
...
...
@@ -150,13 +149,6 @@ int CorridorScanComplexItem::_calcTransectCount(void) const
return
fullWidth
>
0.0
?
qCeil
(
fullWidth
/
_calcTransectSpacing
())
:
1
;
}
void
CorridorScanComplexItem
::
applyNewAltitude
(
double
newAltitude
)
{
_cameraCalc
.
valueSetIsDistance
()
->
setRawValue
(
true
);
_cameraCalc
.
distanceToSurface
()
->
setRawValue
(
newAltitude
);
_cameraCalc
.
setDistanceToSurfaceRelative
(
true
);
}
void
CorridorScanComplexItem
::
_polylineDirtyChanged
(
bool
dirty
)
{
if
(
dirty
)
{
...
...
@@ -338,15 +330,6 @@ void CorridorScanComplexItem::_rebuildTransectsPhase1(void)
}
}
void
CorridorScanComplexItem
::
_recalcComplexDistance
(
void
)
{
_complexDistance
=
0
;
for
(
int
i
=
0
;
i
<
_visualTransectPoints
.
count
()
-
1
;
i
++
)
{
_complexDistance
+=
_visualTransectPoints
[
i
].
value
<
QGeoCoordinate
>
().
distanceTo
(
_visualTransectPoints
[
i
+
1
].
value
<
QGeoCoordinate
>
());
}
emit
complexDistanceChanged
();
}
void
CorridorScanComplexItem
::
_recalcCameraShots
(
void
)
{
double
triggerDistance
=
_cameraCalc
.
adjustedFootprintFrontal
()
->
rawValue
().
toDouble
();
...
...
src/MissionManager/CorridorScanComplexItem.h
View file @
8e661ea0
...
...
@@ -36,9 +36,9 @@ public:
Q_INVOKABLE
void
rotateEntryPoint
(
void
);
// Overrides from TransectStyleComplexItem
QString
patternName
(
void
)
const
final
{
return
name
;
}
void
save
(
QJsonArray
&
planItems
)
final
;
bool
specifiesCoordinate
(
void
)
const
final
;
void
applyNewAltitude
(
double
newAltitude
)
final
;
double
timeBetweenShots
(
void
)
final
;
// Overrides from ComplexMissionItem
...
...
@@ -52,6 +52,8 @@ public:
ReadyForSaveState
readyForSaveState
(
void
)
const
final
;
double
additionalTimeDelay
(
void
)
const
final
{
return
0
;
}
static
const
QString
name
;
static
const
char
*
jsonComplexItemTypeValue
;
static
const
char
*
settingsGroup
;
...
...
@@ -64,7 +66,6 @@ private slots:
// Overrides from TransectStyleComplexItem
void
_rebuildTransectsPhase1
(
void
)
final
;
void
_recalcComplexDistance
(
void
)
final
;
void
_recalcCameraShots
(
void
)
final
;
private:
...
...
src/MissionManager/CorridorScanPlanCreator.cc
View file @
8e661ea0
...
...
@@ -10,10 +10,10 @@
#include "CorridorScanPlanCreator.h"
#include "PlanMasterController.h"
#include "MissionSettingsItem.h"
#include "
FixedWingLanding
ComplexItem.h"
#include "
CorridorScan
ComplexItem.h"
CorridorScanPlanCreator
::
CorridorScanPlanCreator
(
PlanMasterController
*
planMasterController
,
QObject
*
parent
)
:
PlanCreator
(
planMasterController
,
MissionController
::
patternCorridorScanN
ame
,
QStringLiteral
(
"/qmlimages/PlanCreator/CorridorScanPlanCreator.png"
),
parent
)
:
PlanCreator
(
planMasterController
,
CorridorScanComplexItem
::
n
ame
,
QStringLiteral
(
"/qmlimages/PlanCreator/CorridorScanPlanCreator.png"
),
parent
)
{
}
...
...
@@ -22,7 +22,7 @@ void CorridorScanPlanCreator::createPlan(const QGeoCoordinate& mapCenterCoord)
{
_planMasterController
->
removeAll
();
VisualMissionItem
*
takeoffItem
=
_missionController
->
insertTakeoffItem
(
mapCenterCoord
,
-
1
);
_missionController
->
insertComplexMissionItem
(
MissionController
::
patternCorridorScanN
ame
,
mapCenterCoord
,
-
1
);
_missionController
->
insertComplexMissionItem
(
CorridorScanComplexItem
::
n
ame
,
mapCenterCoord
,
-
1
);
_missionController
->
insertLandItem
(
mapCenterCoord
,
-
1
);
_missionController
->
setCurrentPlanViewSeqNum
(
takeoffItem
->
sequenceNumber
(),
true
);
}
src/MissionManager/FixedWingLandingComplexItem.cc
View file @
8e661ea0
...
...
@@ -13,11 +13,14 @@
#include "QGCGeo.h"
#include "SimpleMissionItem.h"
#include "PlanMasterController.h"
#include "FlightPathSegment.h"
#include <QPolygonF>
QGC_LOGGING_CATEGORY
(
FixedWingLandingComplexItemLog
,
"FixedWingLandingComplexItemLog"
)
const
QString
FixedWingLandingComplexItem
::
name
(
tr
(
"Fixed Wing Landing"
));
const
char
*
FixedWingLandingComplexItem
::
settingsGroup
=
"FixedWingLanding"
;
const
char
*
FixedWingLandingComplexItem
::
jsonComplexItemTypeValue
=
"fwLandingPattern"
;
...
...
@@ -47,10 +50,6 @@ const char* FixedWingLandingComplexItem::_jsonLoiterAltitudeRelativeKey = "loi
FixedWingLandingComplexItem
::
FixedWingLandingComplexItem
(
PlanMasterController
*
masterController
,
bool
flyView
,
QObject
*
parent
)
:
ComplexMissionItem
(
masterController
,
flyView
,
parent
)
,
_sequenceNumber
(
0
)
,
_dirty
(
false
)
,
_landingCoordSet
(
false
)
,
_ignoreRecalcSignals
(
false
)
,
_metaDataMap
(
FactMetaData
::
createMapFromJsonFile
(
QStringLiteral
(
":/json/FWLandingPattern.FactMetaData.json"
),
this
))
,
_landingDistanceFact
(
settingsGroup
,
_metaDataMap
[
loiterToLandDistanceName
])
,
_loiterAltitudeFact
(
settingsGroup
,
_metaDataMap
[
loiterAltitudeName
])
...
...
@@ -61,8 +60,6 @@ FixedWingLandingComplexItem::FixedWingLandingComplexItem(PlanMasterController* m
,
_stopTakingPhotosFact
(
settingsGroup
,
_metaDataMap
[
stopTakingPhotosName
])
,
_stopTakingVideoFact
(
settingsGroup
,
_metaDataMap
[
stopTakingVideoName
])
,
_valueSetIsDistanceFact
(
settingsGroup
,
_metaDataMap
[
valueSetIsDistanceName
])
,
_loiterClockwise
(
true
)
,
_altitudesAreRelative
(
true
)
{
_editorQml
=
"qrc:/qml/FWLandingPatternEditor.qml"
;
_isIncomplete
=
false
;
...
...
@@ -98,12 +95,29 @@ FixedWingLandingComplexItem::FixedWingLandingComplexItem(PlanMasterController* m
connect
(
this
,
&
FixedWingLandingComplexItem
::
altitudesAreRelativeChanged
,
this
,
&
FixedWingLandingComplexItem
::
_setDirty
);
connect
(
this
,
&
FixedWingLandingComplexItem
::
valueSetIsDistanceChanged
,
this
,
&
FixedWingLandingComplexItem
::
_setDirty
);
connect
(
this
,
&
FixedWingLandingComplexItem
::
altitudesAreRelativeChanged
,
this
,
&
FixedWingLandingComplexItem
::
coordinateHasRelativeAltitudeChanged
);
connect
(
this
,
&
FixedWingLandingComplexItem
::
altitudesAreRelativeChanged
,
this
,
&
FixedWingLandingComplexItem
::
exitCoordinateHasRelativeAltitudeChanged
);
connect
(
this
,
&
FixedWingLandingComplexItem
::
altitudesAreRelativeChanged
,
this
,
&
FixedWingLandingComplexItem
::
_amslEntryAltChanged
);
connect
(
this
,
&
FixedWingLandingComplexItem
::
altitudesAreRelativeChanged
,
this
,
&
FixedWingLandingComplexItem
::
_amslExitAltChanged
);
connect
(
_missionController
,
&
MissionController
::
plannedHomePositionChanged
,
this
,
&
FixedWingLandingComplexItem
::
_amslEntryAltChanged
);
connect
(
_missionController
,
&
MissionController
::
plannedHomePositionChanged
,
this
,
&
FixedWingLandingComplexItem
::
_amslExitAltChanged
);
connect
(
&
_loiterAltitudeFact
,
&
Fact
::
valueChanged
,
this
,
&
FixedWingLandingComplexItem
::
_amslEntryAltChanged
);
connect
(
&
_landingAltitudeFact
,
&
Fact
::
valueChanged
,
this
,
&
FixedWingLandingComplexItem
::
_amslExitAltChanged
);
connect
(
this
,
&
FixedWingLandingComplexItem
::
amslEntryAltChanged
,
this
,
&
FixedWingLandingComplexItem
::
maxAMSLAltitudeChanged
);
connect
(
this
,
&
FixedWingLandingComplexItem
::
amslExitAltChanged
,
this
,
&
FixedWingLandingComplexItem
::
minAMSLAltitudeChanged
);
connect
(
this
,
&
FixedWingLandingComplexItem
::
landingCoordSetChanged
,
this
,
&
FixedWingLandingComplexItem
::
readyForSaveStateChanged
);
connect
(
this
,
&
FixedWingLandingComplexItem
::
wizardModeChanged
,
this
,
&
FixedWingLandingComplexItem
::
readyForSaveStateChanged
);
connect
(
this
,
&
FixedWingLandingComplexItem
::
loiterTangentCoordinateChanged
,
this
,
&
FixedWingLandingComplexItem
::
_updateFlightPathSegmentsSignal
);
connect
(
this
,
&
FixedWingLandingComplexItem
::
landingCoordinateChanged
,
this
,
&
FixedWingLandingComplexItem
::
_updateFlightPathSegmentsSignal
);
connect
(
&
_loiterAltitudeFact
,
&
Fact
::
valueChanged
,
this
,
&
FixedWingLandingComplexItem
::
_updateFlightPathSegmentsSignal
);
connect
(
&
_landingAltitudeFact
,
&
Fact
::
valueChanged
,
this
,
&
FixedWingLandingComplexItem
::
_updateFlightPathSegmentsSignal
);
connect
(
this
,
&
FixedWingLandingComplexItem
::
altitudesAreRelativeChanged
,
this
,
&
FixedWingLandingComplexItem
::
_updateFlightPathSegmentsSignal
);
connect
(
_missionController
,
&
MissionController
::
plannedHomePositionChanged
,
this
,
&
FixedWingLandingComplexItem
::
_updateFlightPathSegmentsSignal
);
// The follow is used to compress multiple recalc calls in a row to into a single call.
connect
(
this
,
&
FixedWingLandingComplexItem
::
_updateFlightPathSegmentsSignal
,
this
,
&
FixedWingLandingComplexItem
::
_updateFlightPathSegmentsDontCallDirectly
,
Qt
::
QueuedConnection
);
qgcApp
()
->
addCompressedSignal
(
QMetaMethod
::
fromSignal
(
&
FixedWingLandingComplexItem
::
_updateFlightPathSegmentsSignal
));
if
(
_masterController
->
controllerVehicle
()
->
apmFirmware
())
{
// ArduPilot does not support camera commands
_stopTakingVideoFact
.
setRawValue
(
false
);
...
...
@@ -217,8 +231,8 @@ bool FixedWingLandingComplexItem::load(const QJsonObject& complexObject, int seq
bool
landingAltitudeRelative
=
complexObject
[
_jsonLandingAltitudeRelativeKey
].
toBool
();
if
(
loiterAltitudeRelative
!=
landingAltitudeRelative
)
{
qgcApp
()
->
showAppMessage
(
tr
(
"Fixed Wing Landing Pattern: "
"Setting the loiter and landing altitudes with different settings for altitude relative is no longer supported. "
"Both have been set to altitude relative. Be sure to adjust/check your plan prior to flight."
));
"Setting the loiter and landing altitudes with different settings for altitude relative is no longer supported. "
"Both have been set to altitude relative. Be sure to adjust/check your plan prior to flight."
));
_altitudesAreRelative
=
true
;
}
else
{
_altitudesAreRelative
=
loiterAltitudeRelative
;
...
...
@@ -727,3 +741,35 @@ void FixedWingLandingComplexItem::moveLandingPosition(const QGeoCoordinate& coor
landingHeading
()
->
setRawValue
(
savedHeading
);
landingDistance
()
->
setRawValue
(
savedDistance
);
}
double
FixedWingLandingComplexItem
::
amslEntryAlt
(
void
)
const
{
return
_loiterAltitudeFact
.
rawValue
().
toDouble
()
+
(
_altitudesAreRelative
?
_missionController
->
plannedHomePosition
().
altitude
()
:
0
);
}
double
FixedWingLandingComplexItem
::
amslExitAlt
(
void
)
const
{
return
_landingAltitudeFact
.
rawValue
().
toDouble
()
+
(
_altitudesAreRelative
?
_missionController
->
plannedHomePosition
().
altitude
()
:
0
);
}
// Never call this method directly. If you want to update the flight segments you emit _updateFlightPathSegmentsSignal()
void
FixedWingLandingComplexItem
::
_updateFlightPathSegmentsDontCallDirectly
(
void
)
{
if
(
_cTerrainCollisionSegments
!=
0
)
{
_cTerrainCollisionSegments
=
0
;
emit
terrainCollisionChanged
(
false
);
}
_flightPathSegments
.
beginReset
();
_flightPathSegments
.
clearAndDeleteContents
();
_appendFlightPathSegment
(
_loiterTangentCoordinate
,
amslEntryAlt
(),
_landingCoordinate
,
amslExitAlt
());
// Loiter to land
_appendFlightPathSegment
(
_landingCoordinate
,
amslEntryAlt
(),
_landingCoordinate
,
amslExitAlt
());
// Land to ground
_flightPathSegments
.
endReset
();
if
(
_cTerrainCollisionSegments
!=
0
)
{
emit
terrainCollisionChanged
(
true
);
}
_masterController
->
missionController
()
->
recalcTerrainProfile
();
}
src/MissionManager/FixedWingLandingComplexItem.h
View file @
8e661ea0
...
...
@@ -69,40 +69,43 @@ public:
static
MissionItem
*
createLandItem
(
int
seqNum
,
bool
altRel
,
double
lat
,
double
lon
,
double
alt
,
QObject
*
parent
);
// Overrides from ComplexMissionItem
double
complexDistance
(
void
)
const
final
;
int
lastSequenceNumber
(
void
)
const
final
;
bool
load
(
const
QJsonObject
&
complexObject
,
int
sequenceNumber
,
QString
&
errorString
)
final
;
double
greatestDistanceTo
(
const
QGeoCoordinate
&
other
)
const
final
;
QString
mapVisualQML
(
void
)
const
final
{
return
QStringLiteral
(
"FWLandingPatternMapVisual.qml"
);
}
QString
patternName
(
void
)
const
final
{
return
name
;
}
double
complexDistance
(
void
)
const
final
;
int
lastSequenceNumber
(
void
)
const
final
;
bool
load
(
const
QJsonObject
&
complexObject
,
int
sequenceNumber
,
QString
&
errorString
)
final
;
double
greatestDistanceTo
(
const
QGeoCoordinate
&
other
)
const
final
;
QString
mapVisualQML
(
void
)
const
final
{
return
QStringLiteral
(
"FWLandingPatternMapVisual.qml"
);
}
// Overrides from VisualMissionItem
bool
dirty
(
void
)
const
final
{
return
_dirty
;
}
bool
isSimpleItem
(
void
)
const
final
{
return
false
;
}
bool
isStandaloneCoordinate
(
void
)
const
final
{
return
false
;
}
bool
specifiesCoordinate
(
void
)
const
final
;
bool
specifiesAltitudeOnly
(
void
)
const
final
{
return
false
;
}
QString
commandDescription
(
void
)
const
final
{
return
"Landing Pattern"
;
}
QString
commandName
(
void
)
const
final
{
return
"Landing Pattern"
;
}
QString
abbreviation
(
void
)
const
final
{
return
"L"
;
}
QGeoCoordinate
coordinate
(
void
)
const
final
{
return
_loiterCoordinate
;
}
QGeoCoordinate
exitCoordinate
(
void
)
const
final
{
return
_landingCoordinate
;
}
int
sequenceNumber
(
void
)
const
final
{
return
_sequenceNumber
;
}
double
specifiedFlightSpeed
(
void
)
final
{
return
std
::
numeric_limits
<
double
>::
quiet_NaN
();
}
double
specifiedGimbalYaw
(
void
)
final
{
return
std
::
numeric_limits
<
double
>::
quiet_NaN
();
}
double
specifiedGimbalPitch
(
void
)
final
{
return
std
::
numeric_limits
<
double
>::
quiet_NaN
();
}
void
appendMissionItems
(
QList
<
MissionItem
*>&
items
,
QObject
*
missionItemParent
)
final
;
void
applyNewAltitude
(
double
newAltitude
)
final
;
double
additionalTimeDelay
(
void
)
const
final
{
return
0
;
}
ReadyForSaveState
readyForSaveState
(
void
)
const
final
;
bool
coordinateHasRelativeAltitude
(
void
)
const
final
{
return
_altitudesAreRelative
;
}
bool
exitCoordinateHasRelativeAltitude
(
void
)
const
final
{
return
_altitudesAreRelative
;
}
bool
exitCoordinateSameAsEntry
(
void
)
const
final
{
return
false
;
}
void
setDirty
(
bool
dirty
)
final
;
void
setCoordinate
(
const
QGeoCoordinate
&
coordinate
)
final
{
setLoiterCoordinate
(
coordinate
);
}
void
setSequenceNumber
(
int
sequenceNumber
)
final
;
void
save
(
QJsonArray
&
missionItems
)
final
;
bool
dirty
(
void
)
const
final
{
return
_dirty
;
}
bool
isSimpleItem
(
void
)
const
final
{
return
false
;
}
bool
isStandaloneCoordinate
(
void
)
const
final
{
return
false
;
}
bool
specifiesCoordinate
(
void
)
const
final
;
bool
specifiesAltitudeOnly
(
void
)
const
final
{
return
false
;
}
QString
commandDescription
(
void
)
const
final
{
return
"Landing Pattern"
;
}
QString
commandName
(
void
)
const
final
{
return
"Landing Pattern"
;
}
QString
abbreviation
(
void
)
const
final
{
return
"L"
;
}
QGeoCoordinate
coordinate
(
void
)
const
final
{
return
_loiterCoordinate
;
}
QGeoCoordinate
exitCoordinate
(
void
)
const
final
{
return
_landingCoordinate
;
}
int
sequenceNumber
(
void
)
const
final
{
return
_sequenceNumber
;
}
double
specifiedFlightSpeed
(
void
)
final
{
return
std
::
numeric_limits
<
double
>::
quiet_NaN
();
}
double
specifiedGimbalYaw
(
void
)
final
{
return
std
::
numeric_limits
<
double
>::
quiet_NaN
();
}
double
specifiedGimbalPitch
(
void
)
final
{
return
std
::
numeric_limits
<
double
>::
quiet_NaN
();
}
void
appendMissionItems
(
QList
<
MissionItem
*>&
items
,
QObject
*
missionItemParent
)
final
;
void
applyNewAltitude
(
double
newAltitude
)
final
;
double
additionalTimeDelay
(
void
)
const
final
{
return
0
;
}
ReadyForSaveState
readyForSaveState
(
void
)
const
final
;
bool
exitCoordinateSameAsEntry
(
void
)
const
final
{
return
false
;
}
void
setDirty
(
bool
dirty
)
final
;
void
setCoordinate
(
const
QGeoCoordinate
&
coordinate
)
final
{
setLoiterCoordinate
(
coordinate
);
}
void
setSequenceNumber
(
int
sequenceNumber
)
final
;
void
save
(
QJsonArray
&
missionItems
)
final
;
double
amslEntryAlt
(
void
)
const
final
;
double
amslExitAlt
(
void
)
const
final
;
double
minAMSLAltitude
(
void
)
const
final
{
return
amslExitAlt
();
}
double
maxAMSLAltitude
(
void
)
const
final
{
return
amslEntryAlt
();
}
static
const
QString
name
;
static
const
char
*
jsonComplexItemTypeValue
;
...
...
@@ -125,30 +128,34 @@ signals:
void
loiterClockwiseChanged
(
bool
loiterClockwise
);
void
altitudesAreRelativeChanged
(
bool
altitudesAreRelative
);
void
valueSetIsDistanceChanged
(
bool
valueSetIsDistance
);
void
_updateFlightPathSegmentsSignal
(
void
);
private
slots
:
void
_recalcFromHeadingAndDistanceChange
(
void
);
void
_recalcFromCoordinateChange
(
void
);
void
_recalcFromRadiusChange
(
void
);
void
_updateLoiterCoodinateAltitudeFromFact
(
void
);
void
_updateLandingCoodinateAltitudeFromFact
(
void
);
double
_mathematicAngleToHeading
(
double
angle
);
double
_headingToMathematicAngle
(
double
heading
);
void
_setDirty
(
void
);
void
_glideSlopeChanged
(
void
);
void
_signalLastSequenceNumberChanged
(
void
);
void
_recalcFromHeadingAndDistanceChange
(
void
);
void
_recalcFromCoordinateChange
(
void
);
void
_recalcFromRadiusChange
(
void
);
void
_updateLoiterCoodinateAltitudeFromFact
(
void
);
void
_updateLandingCoodinateAltitudeFromFact
(
void
);
double
_mathematicAngleToHeading
(
double
angle
);
double
_headingToMathematicAngle
(
double
heading
);
void
_setDirty
(
void
);
void
_glideSlopeChanged
(
void
);
void
_signalLastSequenceNumberChanged
(
void
);
void
_updateFlightPathSegmentsDontCallDirectly
(
void
);
private:
QPointF
_rotatePoint
(
const
QPointF
&
point
,
const
QPointF
&
origin
,
double
angle
);
void
_calcGlideSlope
(
void
);
QPointF
_rotatePoint
(
const
QPointF
&
point
,
const
QPointF
&
origin
,
double
angle
);
void
_calcGlideSlope
(
void
);
int
_sequenceNumber
;
bool
_dirty
;
int
_sequenceNumber
=
0
;
bool
_dirty
=
false
;
QGeoCoordinate
_loiterCoordinate
;
QGeoCoordinate
_loiterTangentCoordinate
;
QGeoCoordinate
_landingCoordinate
;
bool
_landingCoordSet
;
bool
_ignoreRecalcSignals
;
bool
_landingCoordSet
=
false
;
bool
_ignoreRecalcSignals
=
false
;
bool
_loiterClockwise
=
true
;
bool
_altitudesAreRelative
=
true
;
QMap
<
QString
,
FactMetaData
*>
_metaDataMap
;
...
...
@@ -162,8 +169,6 @@ private:
Fact
_stopTakingVideoFact
;
Fact
_valueSetIsDistanceFact
;
bool
_loiterClockwise
;
bool
_altitudesAreRelative
;
static
const
char
*
_jsonLoiterCoordinateKey
;
static
const
char
*
_jsonLoiterRadiusKey
;
...
...
src/MissionManager/MissionController.cc
View file @
8e661ea0
This diff is collapsed.
Click to expand it.
src/MissionManager/MissionController.h
View file @
8e661ea0
This diff is collapsed.
Click to expand it.
src/MissionManager/MissionControllerTest.cc
View file @
8e661ea0
...
...
@@ -81,9 +81,9 @@ void MissionControllerTest::_initForFirmwareType(MAV_AUTOPILOT firmwareType)
QCOMPARE
(
settingsItem
->
childItems
()
->
count
(),
0
);
// No waypoint lines
QmlObjectListModel
*
waypointLines
=
_missionController
->
waypointLine
s
();
QVERIFY
(
waypointLine
s
);
QCOMPARE
(
waypointLine
s
->
count
(),
0
);
QmlObjectListModel
*
simpleFlightPathSegments
=
_missionController
->
simpleFlightPathSegment
s
();
QVERIFY
(
simpleFlightPathSegment
s
);
QCOMPARE
(
simpleFlightPathSegment
s
->
count
(),
0
);
}
void
MissionControllerTest
::
_testEmptyVehicleWorker
(
MAV_AUTOPILOT
firmwareType
)
...
...
@@ -166,6 +166,8 @@ void MissionControllerTest::_testGimbalRecalc(void)
QVERIFY
(
qIsNaN
(
visualItem
->
missionGimbalYaw
()));
}
#if 0
// FIXME: No longer works due to signal compression
// Specify gimbal yaw on settings item should generate yaw on all items
MissionSettingsItem* settingsItem = _missionController->visualItems()->value<MissionSettingsItem*>(0);
settingsItem->cameraSection()->setSpecifyGimbal(true);
...
...
@@ -174,6 +176,7 @@ void MissionControllerTest::_testGimbalRecalc(void)
VisualMissionItem* visualItem = _missionController->visualItems()->value<VisualMissionItem*>(i);
QCOMPARE(visualItem->missionGimbalYaw(), 0.0);
}
#endif
}
void
MissionControllerTest
::
_testLoadJsonSectionAvailable
(
void
)
...
...
src/MissionManager/MissionSettingsItem.cc
View file @
8e661ea0
...
...
@@ -55,6 +55,11 @@ MissionSettingsItem::MissionSettingsItem(PlanMasterController* masterController,
connect
(
&
_cameraSection
,
&
CameraSection
::
specifiedGimbalYawChanged
,
this
,
&
MissionSettingsItem
::
specifiedGimbalYawChanged
);
connect
(
&
_cameraSection
,
&
CameraSection
::
specifiedGimbalPitchChanged
,
this
,
&
MissionSettingsItem
::
specifiedGimbalPitchChanged
);
connect
(
&
_speedSection
,
&
SpeedSection
::
specifiedFlightSpeedChanged
,
this
,
&
MissionSettingsItem
::
specifiedFlightSpeedChanged
);
connect
(
this
,
&
MissionSettingsItem
::
coordinateChanged
,
this
,
&
MissionSettingsItem
::
_amslEntryAltChanged
);
connect
(
this
,
&
MissionSettingsItem
::
amslEntryAltChanged
,
this
,
&
MissionSettingsItem
::
amslExitAltChanged
);
connect
(
this
,
&
MissionSettingsItem
::
amslEntryAltChanged
,
this
,
&
MissionSettingsItem
::
minAMSLAltitudeChanged
);
connect
(
this
,
&
MissionSettingsItem
::
amslEntryAltChanged
,
this
,
&
MissionSettingsItem
::
maxAMSLAltitudeChanged
);
connect
(
&
_plannedHomePositionAltitudeFact
,
&
Fact
::
rawValueChanged
,
this
,
&
MissionSettingsItem
::
_updateAltitudeInCoordinate
);
connect
(
_managerVehicle
,
&
Vehicle
::
homePositionChanged
,
this
,
&
MissionSettingsItem
::
_updateHomePosition
);
...
...
src/MissionManager/MissionSettingsItem.h
View file @
8e661ea0
...
...
@@ -56,41 +56,42 @@ public:
void
setInitialHomePositionFromUser
(
const
QGeoCoordinate
&
coordinate
);
// Overrides from ComplexMissionItem
double
complexDistance
(
void
)
const
final
;
int
lastSequenceNumber
(
void
)
const
final
;
bool
load
(
const
QJsonObject
&
complexObject
,
int
sequenceNumber
,
QString
&
errorString
)
final
;
double
greatestDistanceTo
(
const
QGeoCoordinate
&
other
)
const
final
;
QString
mapVisualQML
(
void
)
const
final
{
return
QStringLiteral
(
"SimpleItemMapVisual.qml"
);
}
QString
patternName
(
void
)
const
final
{
return
QString
();
}
double
complexDistance
(
void
)
const
final
;
int
lastSequenceNumber
(
void
)
const
final
;
bool
load
(
const
QJsonObject
&
complexObject
,
int
sequenceNumber
,
QString
&
errorString
)
final
;
double
greatestDistanceTo
(
const
QGeoCoordinate
&
other
)
const
final
;
QString
mapVisualQML
(
void
)
const
final
{
return
QStringLiteral
(
"SimpleItemMapVisual.qml"
);
}
bool
isSingleItem
(
void
)
const
final
{
return
true
;
}
bool
terrainCollision
(
void
)
const
final
{
return
false
;
}
// Overrides from VisualMissionItem
bool
dirty
(
void
)
const
final
{
return
_dirty
;
}
bool
isSimpleItem
(
void
)
const
final
{
return
false
;
}
bool
isStandaloneCoordinate
(
void
)
const
final
{
return
false
;
}
bool
specifiesCoordinate
(
void
)
const
final
;
bool
specifiesAltitudeOnly
(
void
)
const
final
{
return
false
;
}
QString
commandDescription
(
void
)
const
final
{
return
"Mission Start"
;
}
QString
commandName
(
void
)
const
final
{
return
"Mission Start"
;
}
QString
abbreviation
(
void
)
const
final
;
QGeoCoordinate
coordinate
(
void
)
const
final
{
return
_plannedHomePositionCoordinate
;
}
QGeoCoordinate
exitCoordinate
(
void
)
const
final
{
return
_plannedHomePositionCoordinate
;
}
int
sequenceNumber
(
void
)
const
final
{
return
_sequenceNumber
;
}
double
specifiedGimbalYaw
(
void
)
final
;
double
specifiedGimbalPitch
(
void
)
final
;
void
appendMissionItems
(
QList
<
MissionItem
*>&
items
,
QObject
*
missionItemParent
)
final
;
void
applyNewAltitude
(
double
/*newAltitude*/
)
final
{
/* no action */
}
double
specifiedFlightSpeed
(
void
)
final
;
double
additionalTimeDelay
(
void
)
const
final
{
return
0
;
}
bool
coordinateHasRelativeAltitude
(
void
)
const
final
{
return
false
;
}
bool
exitCoordinateHasRelativeAltitude
(
void
)
const
final
{
return
false
;
}
bool
exitCoordinateSameAsEntry
(
void
)
const
final
{
return
true
;
}
void
setDirty
(
bool
dirty
)
final
;
void
setCoordinate
(
const
QGeoCoordinate
&
coordinate
)
final
;
// Should only be called if the end user is moving
void
setSequenceNumber
(
int
sequenceNumber
)
final
;
void
save
(
QJsonArray
&
missionItems
)
final
;
bool
dirty
(
void
)
const
final
{
return
_dirty
;
}
bool
isSimpleItem
(
void
)
const
final
{
return
false
;
}
bool
isStandaloneCoordinate
(
void
)
const
final
{
return
false
;
}
bool
specifiesCoordinate
(
void
)
const
final
;
bool
specifiesAltitudeOnly
(
void
)
const
final
{
return
false
;
}
QString
commandDescription
(
void
)
const
final
{
return
"Mission Start"
;
}
QString
commandName
(
void
)
const
final
{
return
"Mission Start"
;
}
QString
abbreviation
(
void
)
const
final
;
QGeoCoordinate
coordinate
(
void
)
const
final
{
return
_plannedHomePositionCoordinate
;
}
// Includes altitude
QGeoCoordinate
exitCoordinate
(
void
)
const
final
{
return
_plannedHomePositionCoordinate
;
}
int
sequenceNumber
(
void
)
const
final
{
return
_sequenceNumber
;
}
double
specifiedGimbalYaw
(
void
)
final
;
double
specifiedGimbalPitch
(
void
)
final
;
void
appendMissionItems
(
QList
<
MissionItem
*>&
items
,
QObject
*
missionItemParent
)
final
;