Commit 5a4e8197 authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #5708 from DonLakeFlyer/StructureScan

Initial Structure Scan support
parents ad1dbf03 801221a8
......@@ -522,6 +522,7 @@ HEADERS += \
src/MissionManager/SimpleMissionItem.h \
src/MissionManager/Section.h \
src/MissionManager/SpeedSection.h \
src/MissionManager/StructureScanComplexItem.h \
src/MissionManager/SurveyMissionItem.h \
src/MissionManager/VisualMissionItem.h \
src/PositionManager/PositionManager.h \
......@@ -707,6 +708,7 @@ SOURCES += \
src/MissionManager/RallyPointManager.cc \
src/MissionManager/SimpleMissionItem.cc \
src/MissionManager/SpeedSection.cc \
src/MissionManager/StructureScanComplexItem.cc \
src/MissionManager/SurveyMissionItem.cc \
src/MissionManager/VisualMissionItem.cc \
src/PositionManager/PositionManager.cpp \
......
......@@ -115,6 +115,7 @@
<file alias="QGroundControl/Controls/SignalStrength.qml">src/ui/toolbar/SignalStrength.qml</file>
<file alias="QGroundControl/Controls/SimpleItemMapVisual.qml">src/PlanView/SimpleItemMapVisual.qml</file>
<file alias="QGroundControl/Controls/SliderSwitch.qml">src/QmlControls/SliderSwitch.qml</file>
<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/VehicleRotationCal.qml">src/QmlControls/VehicleRotationCal.qml</file>
......@@ -179,7 +180,7 @@
<file alias="SetupParameterEditor.qml">src/VehicleSetup/SetupParameterEditor.qml</file>
<file alias="SetupView.qml">src/VehicleSetup/SetupView.qml</file>
<file alias="SimpleItemEditor.qml">src/PlanView/SimpleItemEditor.qml</file>
<file alias="SurveyItemEditor.qml">src/PlanView/SurveyItemEditor.qml</file>
<file alias="StructureScanEditor.qml">src/PlanView/StructureScanEditor.qml</file>
<file alias="FWLandingPatternEditor.qml">src/PlanView/FWLandingPatternEditor.qml</file>
<file alias="MissionSettingsEditor.qml">src/PlanView/MissionSettingsEditor.qml</file>
<file alias="TcpSettings.qml">src/ui/preferences/TcpSettings.qml</file>
......@@ -206,6 +207,7 @@
<file alias="QGCMapCircle.Facts.json">src/MissionManager/QGCMapCircle.Facts.json</file>
<file alias="RTK.SettingsGroup.json">src/Settings/RTK.SettingsGroup.json</file>
<file alias="Survey.SettingsGroup.json">src/MissionManager/Survey.SettingsGroup.json</file>
<file alias="StructureScan.SettingsGroup.json">src/MissionManager/StructureScan.SettingsGroup.json</file>
<file alias="Units.SettingsGroup.json">src/Settings/Units.SettingsGroup.json</file>
<file alias="Video.SettingsGroup.json">src/Settings/Video.SettingsGroup.json</file>
<file alias="RallyPoint.FactMetaData.json">src/MissionManager/RallyPoint.FactMetaData.json</file>
......
......@@ -24,6 +24,7 @@ public:
Q_PROPERTY(double complexDistance READ complexDistance NOTIFY complexDistanceChanged)
/// @return The distance covered the complex mission item in meters.
/// Signals complexDistanceChanged
virtual double complexDistance(void) const = 0;
/// @return Amount of additional time delay in seconds needed to fly the complex item
......@@ -39,6 +40,7 @@ public:
/// Get the point of complex mission item furthest away from a coordinate
/// @param other QGeoCoordinate to which distance is calculated
/// @return the greatest distance from any point of the complex item to some coordinate
/// Signals greatestDistanceToChanged
virtual double greatestDistanceTo(const QGeoCoordinate &other) const = 0;
/// This mission item attribute specifies the type of the complex item.
......@@ -46,6 +48,7 @@ public:
signals:
void complexDistanceChanged (double complexDistance);
void greatestDistanceToChanged (void);
void additionalTimeDelayChanged (double additionalTimeDelay);
};
......
......@@ -18,6 +18,7 @@
#include "SimpleMissionItem.h"
#include "SurveyMissionItem.h"
#include "FixedWingLandingComplexItem.h"
#include "StructureScanComplexItem.h"
#include "JsonHelper.h"
#include "ParameterManager.h"
#include "QGroundControlQmlGlobal.h"
......@@ -60,6 +61,7 @@ MissionController::MissionController(PlanMasterController* masterController, QOb
, _itemsRequested(false)
, _surveyMissionItemName(tr("Survey"))
, _fwLandingMissionItemName(tr("Fixed Wing Landing"))
, _structureScanMissionItemName(tr("Structure Scan"))
, _appSettings(qgcApp()->toolbox()->settingsManager()->appSettings())
, _progressPct(0)
{
......@@ -379,6 +381,8 @@ int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate
}
} else if (itemName == _fwLandingMissionItemName) {
newItem = new FixedWingLandingComplexItem(_controllerVehicle, _visualItems);
} else if (itemName == _structureScanMissionItemName) {
newItem = new StructureScanComplexItem(_controllerVehicle, _visualItems);
} else {
qWarning() << "Internal error: Unknown complex item:" << itemName;
return sequenceNumber;
......@@ -1475,6 +1479,7 @@ void MissionController::_initVisualItem(VisualMissionItem* visualItem)
ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
if (complexItem) {
connect(complexItem, &ComplexMissionItem::complexDistanceChanged, this, &MissionController::_recalcMissionFlightStatus);
connect(complexItem, &ComplexMissionItem::greatestDistanceToChanged, this, &MissionController::_recalcMissionFlightStatus);
connect(complexItem, &ComplexMissionItem::additionalTimeDelayChanged, this, &MissionController::_recalcMissionFlightStatus);
} else {
qWarning() << "ComplexMissionItem not found";
......@@ -1769,6 +1774,9 @@ QStringList MissionController::complexMissionItemNames(void) const
if (_controllerVehicle->fixedWing()) {
complexItems.append(_fwLandingMissionItemName);
}
if (_controllerVehicle->multiRotor() || _controllerVehicle->vtol()) {
complexItems.append(_structureScanMissionItemName);
}
return complexItems;
}
......
......@@ -231,6 +231,7 @@ private:
MissionFlightStatus_t _missionFlightStatus;
QString _surveyMissionItemName;
QString _fwLandingMissionItemName;
QString _structureScanMissionItemName;
AppSettings* _appSettings;
double _progressPct;
......
......@@ -354,3 +354,13 @@ void QGCMapPolygon::setInteractive(bool interactive)
emit interactiveChanged(interactive);
}
}
QGeoCoordinate QGCMapPolygon::vertexCoordinate(int vertex) const
{
if (vertex >= 0 && vertex < _polygonPath.count()) {
return _polygonPath[vertex].value<QGeoCoordinate>();
} else {
qWarning() << "QGCMapPolygon::vertexCoordinate bad vertex requested";
return QGeoCoordinate();
}
}
......@@ -55,6 +55,9 @@ public:
/// Returns the path in a list of QGeoCoordinate's format
QList<QGeoCoordinate> coordinateList(void) const;
/// Returns the QGeoCoordinate for the vertex specified
QGeoCoordinate vertexCoordinate(int vertex) const;
/// Saves the polygon to the json object.
/// @param json Json object to save to
void saveToJson(QJsonObject& json);
......
[
{
"name": "Altitude",
"shortDescription": "Altitude for the bottom layer of the structure scan.",
"type": "double",
"units": "m",
"decimalPlaces": 1,
"defaultValue": 50
},
{
"name": "Layers",
"shortDescription": "Number of scan layers.",
"type": "uint32",
"min": 1,
"defaultValue": 1
},
{
"name": "Layer distance",
"shortDescription": "Distance between each layer.",
"type": "double",
"decimalPlaces": 2,
"min": 0,
"units": "m",
"defaultValue": 25
},
{
"name": "Trigger distance",
"shortDescription": "Distance between each triggering of the camera. 0 specifies not camera trigger.",
"type": "double",
"decimalPlaces": 2,
"min": 0,
"units": "m",
"defaultValue": 25
}
]
This diff is collapsed.
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#ifndef StructureScanComplexItem_H
#define StructureScanComplexItem_H
#include "ComplexMissionItem.h"
#include "MissionItem.h"
#include "SettingsFact.h"
#include "QGCLoggingCategory.h"
#include "QGCMapPolygon.h"
Q_DECLARE_LOGGING_CATEGORY(StructureScanComplexItemLog)
class StructureScanComplexItem : public ComplexMissionItem
{
Q_OBJECT
public:
StructureScanComplexItem(Vehicle* vehicle, QObject* parent = NULL);
Q_PROPERTY(Fact* altitude READ altitude CONSTANT)
Q_PROPERTY(Fact* layers READ layers CONSTANT)
Q_PROPERTY(Fact* layerDistance READ layerDistance CONSTANT)
Q_PROPERTY(Fact* cameraTriggerDistance READ cameraTriggerDistance CONSTANT)
Q_PROPERTY(bool altitudeRelative MEMBER _altitudeRelative NOTIFY altitudeRelativeChanged)
Q_PROPERTY(int cameraShots READ cameraShots NOTIFY cameraShotsChanged)
Q_PROPERTY(double timeBetweenShots READ timeBetweenShots NOTIFY timeBetweenShotsChanged)
Q_PROPERTY(double cameraMinTriggerInterval MEMBER _cameraMinTriggerInterval NOTIFY cameraMinTriggerIntervalChanged)
Q_PROPERTY(QGCMapPolygon* mapPolygon READ mapPolygon CONSTANT)
Fact* altitude (void) { return &_altitudeFact; }
Fact* layers (void) { return &_layersFact; }
Fact* layerDistance (void) { return &_layerDistanceFact; }
Fact* cameraTriggerDistance (void) { return &_cameraTriggerDistanceFact; }
int cameraShots (void) const;
double timeBetweenShots(void) const;
QGCMapPolygon* mapPolygon (void) { return &_mapPolygon; }
Q_INVOKABLE void rotateEntryPoint(void);
// Overrides from ComplexMissionItem
double complexDistance (void) const final { return _scanDistance; }
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("StructureScanMapVisual.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 tr("Structure Scan"); }
QString commandName (void) const final { return tr("Structure Scan"); }
QString abbreviation (void) const final { return "S"; }
QGeoCoordinate coordinate (void) const final;
QGeoCoordinate exitCoordinate (void) const final;
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(); }
void appendMissionItems (QList<MissionItem*>& items, QObject* missionItemParent) final;
void setMissionFlightStatus (MissionController::MissionFlightStatus_t& missionFlightStatus) final;
void applyNewAltitude (double newAltitude) final;
bool coordinateHasRelativeAltitude (void) const final { return _altitudeRelative; }
bool exitCoordinateHasRelativeAltitude (void) const final { return _altitudeRelative; }
bool exitCoordinateSameAsEntry (void) const final { return true; }
void setDirty (bool dirty) final;
void setCoordinate (const QGeoCoordinate& coordinate) final { Q_UNUSED(coordinate); }
void setSequenceNumber (int sequenceNumber) final;
void save (QJsonArray& missionItems) final;
static const char* jsonComplexItemTypeValue;
signals:
void cameraShotsChanged (int cameraShots);
void timeBetweenShotsChanged (void);
void cameraMinTriggerIntervalChanged(double cameraMinTriggerInterval);
void altitudeRelativeChanged (bool altitudeRelative);
private slots:
void _setDirty(void);
void _polygonDirtyChanged(bool dirty);
void _polygonCountChanged(int count);
void _polygonPathChanged(void);
void _clearInternal(void);
void _updateCoordinateAltitudes(void);
private:
void _setExitCoordinate(const QGeoCoordinate& coordinate);
void _setScanDistance(double scanDistance);
void _setCameraShots(int cameraShots);
double _triggerDistance(void) const;
int _sequenceNumber;
bool _dirty;
QGCMapPolygon _mapPolygon;
bool _altitudeRelative;
int _entryVertex; // Polygon vertext which is used as the mission entry point
bool _ignoreRecalc;
double _scanDistance;
int _cameraShots;
double _timeBetweenShots;
double _cameraMinTriggerInterval;
double _cruiseSpeed;
static QMap<QString, FactMetaData*> _metaDataMap;
Fact _altitudeFact;
Fact _layersFact;
Fact _layerDistanceFact;
Fact _cameraTriggerDistanceFact;
static const char* _altitudeFactName;
static const char* _layersFactName;
static const char* _layerDistanceFactName;
static const char* _cameraTriggerDistanceFactName;
static const char* _jsonGridObjectKey;
static const char* _jsonGridAltitudeKey;
static const char* _jsonGridAltitudeRelativeKey;
static const char* _jsonGridAngleKey;
static const char* _jsonGridSpacingKey;
static const char* _jsonGridEntryLocationKey;
static const char* _jsonTurnaroundDistKey;
static const char* _jsonCameraTriggerDistanceKey;
static const char* _jsonCameraTriggerInTurnaroundKey;
static const char* _jsonHoverAndCaptureKey;
static const char* _jsonGroundResolutionKey;
static const char* _jsonFrontalOverlapKey;
static const char* _jsonSideOverlapKey;
static const char* _jsonCameraSensorWidthKey;
static const char* _jsonCameraSensorHeightKey;
static const char* _jsonCameraResolutionWidthKey;
static const char* _jsonCameraResolutionHeightKey;
static const char* _jsonCameraFocalLengthKey;
static const char* _jsonCameraMinTriggerIntervalKey;
static const char* _jsonManualGridKey;
static const char* _jsonCameraObjectKey;
static const char* _jsonCameraNameKey;
static const char* _jsonCameraOrientationLandscapeKey;
static const char* _jsonFixedValueIsAltitudeKey;
static const char* _jsonRefly90DegreesKey;
static const int _hoverAndCaptureDelaySeconds = 1;
};
#endif
......@@ -1322,7 +1322,7 @@ double SurveyMissionItem::timeBetweenShots(void) const
return _cruiseSpeed == 0 ? 0 : _triggerDistance() / _cruiseSpeed;
}
void SurveyMissionItem::setMissionFlightStatus (MissionController::MissionFlightStatus_t& missionFlightStatus)
void SurveyMissionItem::setMissionFlightStatus(MissionController::MissionFlightStatus_t& missionFlightStatus)
{
ComplexMissionItem::setMissionFlightStatus(missionFlightStatus);
if (!qFuzzyCompare(_cruiseSpeed, missionFlightStatus.vehicleSpeed)) {
......
import QtQuick 2.3
import QtQuick.Controls 1.2
import QtQuick.Controls.Styles 1.4
import QtQuick.Dialogs 1.2
import QtQuick.Extras 1.4
import QtQuick.Layouts 1.2
import QGroundControl 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Vehicle 1.0
import QGroundControl.Controls 1.0
import QGroundControl.FactControls 1.0
import QGroundControl.Palette 1.0
import QGroundControl.FlightMap 1.0
// Editor for Survery mission items
Rectangle {
id: _root
height: visible ? (editorColumn.height + (_margin * 2)) : 0
width: availableWidth
color: qgcPal.windowShadeDark
radius: _radius
// The following properties must be available up the hierarchy chain
//property real availableWidth ///< Width for control
//property var missionItem ///< Mission Item for editor
property real _margin: ScreenTools.defaultFontPixelWidth / 2
property real _fieldWidth: ScreenTools.defaultFontPixelWidth * 10.5
property var _vehicle: QGroundControl.multiVehicleManager.activeVehicle ? QGroundControl.multiVehicleManager.activeVehicle : QGroundControl.multiVehicleManager.offlineEditingVehicle
function polygonCaptureStarted() {
missionItem.clearPolygon()
}
function polygonCaptureFinished(coordinates) {
for (var i=0; i<coordinates.length; i++) {
missionItem.addPolygonCoordinate(coordinates[i])
}
}
function polygonAdjustVertex(vertexIndex, vertexCoordinate) {
missionItem.adjustPolygonCoordinate(vertexIndex, vertexCoordinate)
}
function polygonAdjustStarted() { }
function polygonAdjustFinished() { }
QGCPalette { id: qgcPal; colorGroupEnabled: true }
Column {
id: editorColumn
anchors.margins: _margin
anchors.top: parent.top
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
QGCLabel {
anchors.left: parent.left
anchors.right: parent.right
text: qsTr("WARNING: WORK IN PROGRESS. USE AT YOUR OWN RISK.")
wrapMode: Text.WordWrap
color: qgcPal.warningText
}
QGCLabel {
anchors.left: parent.left
anchors.right: parent.right
text: qsTr("WARNING: Photo interval is below minimum interval (%1 secs) supported by camera.").arg(missionItem.cameraMinTriggerInterval.toFixed(1))
wrapMode: Text.WordWrap
color: qgcPal.warningText
visible: missionItem.cameraShots > 0 && missionItem.cameraMinTriggerInterval !== 0 && missionItem.cameraMinTriggerInterval > missionItem.timeBetweenShots
}
GridLayout {
anchors.left: parent.left
anchors.right: parent.right
columnSpacing: _margin
rowSpacing: _margin
columns: 2
QGCLabel { text: qsTr("Altitude") }
FactTextField {
fact: missionItem.altitude
Layout.fillWidth: true
}
QGCLabel { text: qsTr("Layers") }
FactTextField {
fact: missionItem.layers
Layout.fillWidth: true
}
QGCLabel { text: qsTr("Layer distance") }
FactTextField {
fact: missionItem.layerDistance
Layout.fillWidth: true
}
QGCLabel { text: qsTr("Trigger Distance") }
FactTextField {
fact: missionItem.cameraTriggerDistance
Layout.fillWidth: true
}
QGCCheckBox {
text: qsTr("Relative altitude")
checked: missionItem.altitudeRelative
Layout.columnSpan: 2
onClicked: missionItem.altitudeRelative = checked
}
}
QGCLabel { text: qsTr("Point camera to structure using:") }
QGCRadioButton { text: qsTr("Vehicle yaw"); enabled: false }
QGCRadioButton { text: qsTr("Gimbal yaw"); checked: true; enabled: false }
QGCButton {
text: qsTr("Rotate entry point")
onClicked: missionItem.rotateEntryPoint()
}
SectionHeader {
id: statsHeader
text: qsTr("Statistics")
}
Grid {
columns: 2
columnSpacing: ScreenTools.defaultFontPixelWidth
visible: statsHeader.checked
QGCLabel { text: qsTr("Photo count") }
QGCLabel { text: missionItem.cameraShots }
QGCLabel { text: qsTr("Photo interval") }
QGCLabel { text: missionItem.timeBetweenShots.toFixed(1) + " " + qsTr("secs") }
}
}
}
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
import QtQuick 2.3
import QtQuick.Controls 1.2
import QtLocation 5.3
import QtPositioning 5.3
import QGroundControl 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Palette 1.0
import QGroundControl.Controls 1.0
import QGroundControl.FlightMap 1.0
/// Survey Complex Mission Item visuals
Item {
id: _root
property var map ///< Map control to place item in
property var _missionItem: object
property var _mapPolygon: object.mapPolygon
property var _gridComponent
property var _entryCoordinate
property var _exitCoordinate
signal clicked(int sequenceNumber)
function _addVisualElements() {
_gridComponent = gridComponent.createObject(map)
_entryCoordinate = entryPointComponent.createObject(map)
_exitCoordinate = exitPointComponent.createObject(map)
map.addMapItem(_gridComponent)
map.addMapItem(_entryCoordinate)
map.addMapItem(_exitCoordinate)
}
function _destroyVisualElements() {
_gridComponent.destroy()
_entryCoordinate.destroy()
_exitCoordinate.destroy()
}
/// Add an initial 4 sided polygon if there is none
function _addInitialPolygon() {
if (_mapPolygon.count < 3) {
// Initial polygon is inset to take 2/3rds space
var rect = Qt.rect(map.centerViewport.x, map.centerViewport.y, map.centerViewport.width, map.centerViewport.height)
rect.x += (rect.width * 0.25) / 2
rect.y += (rect.height * 0.25) / 2
rect.width *= 0.75
rect.height *= 0.75
var centerCoord = map.toCoordinate(Qt.point(rect.x + (rect.width / 2), rect.y + (rect.height / 2)), false /* clipToViewPort */)
var topLeftCoord = map.toCoordinate(Qt.point(rect.x, rect.y), false /* clipToViewPort */)
var topRightCoord = map.toCoordinate(Qt.point(rect.x + rect.width, rect.y), false /* clipToViewPort */)
var bottomLeftCoord = map.toCoordinate(Qt.point(rect.x, rect.y + rect.height), false /* clipToViewPort */)
var bottomRightCoord = map.toCoordinate(Qt.point(rect.x + rect.width, rect.y + rect.height), false /* clipToViewPort */)
// Initial polygon has max width and height of 3000 meters
var halfWidthMeters = Math.min(topLeftCoord.distanceTo(topRightCoord), 3000) / 2
var halfHeightMeters = Math.min(topLeftCoord.distanceTo(bottomLeftCoord), 3000) / 2
topLeftCoord = centerCoord.atDistanceAndAzimuth(halfWidthMeters, -90).atDistanceAndAzimuth(halfHeightMeters, 0)
topRightCoord = centerCoord.atDistanceAndAzimuth(halfWidthMeters, 90).atDistanceAndAzimuth(halfHeightMeters, 0)
bottomLeftCoord = centerCoord.atDistanceAndAzimuth(halfWidthMeters, -90).atDistanceAndAzimuth(halfHeightMeters, 180)
bottomRightCoord = centerCoord.atDistanceAndAzimuth(halfWidthMeters, 90).atDistanceAndAzimuth(halfHeightMeters, 180)
_mapPolygon.appendVertex(topLeftCoord)
_mapPolygon.appendVertex(topRightCoord)
_mapPolygon.appendVertex(bottomRightCoord)
_mapPolygon.appendVertex(bottomLeftCoord)
}
}
Component.onCompleted: {
_addInitialPolygon()
_addVisualElements()
}
Component.onDestruction: {
_destroyVisualElements()
}
QGCMapPolygonVisuals {
id: mapPolygonVisuals
mapControl: map
mapPolygon: _mapPolygon
interactive: _missionItem.isCurrentItem
borderWidth: 1
borderColor: "black"
interiorColor: "green"
interiorOpacity: 0.5
}
// Survey grid lines
Component {
id: gridComponent
MapPolyline {
line.color: "white"
line.width: 2
path: _missionItem.gridPoints
}
}
// Entry point
Component {
id: entryPointComponent
MapQuickItem {
anchorPoint.x: sourceItem.anchorPointX
anchorPoint.y: sourceItem.anchorPointY
z: QGroundControl.zOrderMapItems
coordinate: _missionItem.coordinate
visible: _missionItem.exitCoordinate.isValid
sourceItem: MissionItemIndexLabel {
index: _missionItem.sequenceNumber
label: "Entry"
checked: _missionItem.isCurrentItem
onClicked: _root.clicked(_missionItem.sequenceNumber)
}
}
}
// Exit point
Component {
id: exitPointComponent
MapQuickItem {
anchorPoint.x: sourceItem.anchorPointX
anchorPoint.y: sourceItem.anchorPointY
z: QGroundControl.zOrderMapItems
coordinate: _missionItem.exitCoordinate
visible: _missionItem.exitCoordinate.isValid
sourceItem: MissionItemIndexLabel {
index: _missionItem.lastSequenceNumber
label: "Exit"
checked: _missionItem.isCurrentItem
onClicked: _root.clicked(_missionItem.sequenceNumber)
}
}
}
}
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment