diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc
index 59895cab56872f5e9b177d73216a8ae2bb54aada..62267c300b3111862fea1c8f27fb3d6131b09c8e 100644
--- a/qgroundcontrol.qrc
+++ b/qgroundcontrol.qrc
@@ -101,6 +101,7 @@
src/QmlControls/QGroundControl.Controls.qmldir
src/PlanView/RallyPointEditorHeader.qml
src/PlanView/RallyPointItemEditor.qml
+ src/PlanView/RallyPointMapVisuals.qml
src/QmlControls/RCChannelMonitor.qml
src/QmlControls/RoundButton.qml
src/PlanView/SectionHeader.qml
@@ -152,7 +153,6 @@
src/FlightMap/Widgets/QGCCompassWidget.qml
src/FlightMap/Widgets/QGCInstrumentWidget.qml
src/FlightMap/Widgets/QGCInstrumentWidgetAlternate.qml
- src/PlanView/QGCMapPolygonControls.qml
src/FlightMap/Widgets/QGCPitchIndicator.qml
src/FlightMap/QGCVideoBackground.qml
src/FlightMap/qmldir
@@ -215,7 +215,4 @@
src/comm/APMArduSubMockLink.params
src/comm/PX4MockLink.params
-
- src/FirmwarePlugin/NoGeoFenceEditor.qml
-
diff --git a/src/FirmwarePlugin/APM/APMGeoFenceManager.cc b/src/FirmwarePlugin/APM/APMGeoFenceManager.cc
index be7540e1af620b4b8723e23852c5a01e5ff4a3ec..181929caddac22e368c94a2be97e5d49a22e9cab 100644
--- a/src/FirmwarePlugin/APM/APMGeoFenceManager.cc
+++ b/src/FirmwarePlugin/APM/APMGeoFenceManager.cc
@@ -23,9 +23,10 @@ const char* APMGeoFenceManager::_fenceEnableParam = "FENCE_ENABLE";
APMGeoFenceManager::APMGeoFenceManager(Vehicle* vehicle)
: GeoFenceManager(vehicle)
, _fenceSupported(false)
- , _breachReturnEnabled(vehicle->fixedWing())
, _circleEnabled(false)
+ , _polygonSupported(false)
, _polygonEnabled(false)
+ , _breachReturnSupported(vehicle->fixedWing())
, _firstParamLoadComplete(false)
, _readTransactionInProgress(false)
, _writeTransactionInProgress(false)
@@ -223,27 +224,43 @@ bool APMGeoFenceManager::inProgress(void) const
return _readTransactionInProgress || _writeTransactionInProgress;
}
-void APMGeoFenceManager::_updateEnabledFlags(void)
+void APMGeoFenceManager::_setCircleEnabled(bool circleEnabled)
{
- bool fenceEnabled;
- if (_fenceEnableFact) {
- fenceEnabled = _fenceEnableFact->rawValue().toBool();
- } else {
- fenceEnabled = true;
+ if (circleEnabled != _circleEnabled) {
+ _circleEnabled = circleEnabled;
+ emit circleEnabledChanged(circleEnabled);
}
+}
- bool newCircleEnabled = _fenceSupported && fenceEnabled && _fenceTypeFact && (_fenceTypeFact->rawValue().toInt() & 2);
- if (newCircleEnabled != _circleEnabled) {
- _circleEnabled = newCircleEnabled;
- emit circleEnabledChanged(newCircleEnabled);
+void APMGeoFenceManager::_setPolygonEnabled(bool polygonEnabled)
+{
+ if (polygonEnabled != _polygonEnabled) {
+ _polygonEnabled = polygonEnabled;
+ emit polygonEnabledChanged(polygonEnabled);
}
+}
+
+void APMGeoFenceManager::_updateEnabledFlags(void)
+{
+ bool fenceEnabled = false;
+
+ if (_fenceSupported) {
+ if (_fenceEnableFact) {
+ fenceEnabled = _fenceEnableFact->rawValue().toBool();
+ } else {
+ fenceEnabled = true;
+ }
- bool newPolygonEnabled = _fenceSupported && fenceEnabled &&
- ((_vehicle->multiRotor() && _fenceTypeFact && (_fenceTypeFact->rawValue().toInt() & 4)) ||
- _vehicle->fixedWing());
- if (newPolygonEnabled != _polygonEnabled) {
- _polygonEnabled = newPolygonEnabled;
- emit polygonEnabledChanged(newPolygonEnabled);
+ bool newCircleEnabled = fenceEnabled && _fenceTypeFact && (_fenceTypeFact->rawValue().toInt() & 2);
+ _setCircleEnabled(newCircleEnabled);
+
+ bool newPolygonEnabled = _fenceSupported && fenceEnabled &&
+ ((_vehicle->multiRotor() && _fenceTypeFact && (_fenceTypeFact->rawValue().toInt() & 4)) ||
+ _vehicle->fixedWing());
+ _setPolygonEnabled(newPolygonEnabled);
+ } else {
+ _setCircleEnabled(false);
+ _setPolygonEnabled(false);
}
}
@@ -260,24 +277,26 @@ void APMGeoFenceManager::_parametersReady(void)
QStringList paramNames;
QStringList paramLabels;
+ _polygonSupported = true;
+
if (_vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, _fenceEnableParam)) {
_fenceEnableFact = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, _fenceEnableParam);
connect(_fenceEnableFact, &Fact::rawValueChanged, this, &APMGeoFenceManager::_updateEnabledFlags);
}
if (_vehicle->multiRotor()) {
+ _breachReturnSupported = false;
_fenceTypeFact = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, QStringLiteral("FENCE_TYPE"));
connect(_fenceTypeFact, &Fact::rawValueChanged, this, &APMGeoFenceManager::_updateEnabledFlags);
_circleRadiusFact = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, QStringLiteral("FENCE_RADIUS"));
- connect(_circleRadiusFact, &Fact::rawValueChanged, this, &APMGeoFenceManager::_circleRadiusRawValueChanged);
- emit circleRadiusChanged(circleRadius());
paramNames << QStringLiteral("FENCE_ENABLE") << QStringLiteral("FENCE_TYPE") << QStringLiteral("FENCE_ACTION") << QStringLiteral("FENCE_ALT_MAX")
<< QStringLiteral("FENCE_RADIUS") << QStringLiteral("FENCE_MARGIN");
paramLabels << QStringLiteral("Enabled:") << QStringLiteral("Type:") << QStringLiteral("Breach Action:") << QStringLiteral("Max Altitude:")
<< QStringLiteral("Radius:") << QStringLiteral("Margin:");
} if (_vehicle->fixedWing()) {
+ _breachReturnSupported = true;
paramNames << QStringLiteral("FENCE_ACTION") << QStringLiteral("FENCE_MINALT") << QStringLiteral("FENCE_MAXALT") << QStringLiteral("FENCE_RETALT")
<< QStringLiteral("FENCE_AUTOENABLE") << QStringLiteral("FENCE_RET_RALLY");
paramLabels << QStringLiteral("Breach Action:") << QStringLiteral("Min Altitude:") << QStringLiteral("Max Altitude:") << QStringLiteral("Return Altitude:")
@@ -297,36 +316,11 @@ void APMGeoFenceManager::_parametersReady(void)
emit paramsChanged(_params);
emit paramLabelsChanged(_paramLabels);
- _updateEnabledFlags();
+ emit breachReturnSupportedChanged(_breachReturnSupported);
+ emit polygonSupportedChanged(_polygonSupported);
}
- qCDebug(GeoFenceManagerLog) << "fenceSupported:circleEnabled:polygonEnabled:breachReturnEnabled" <<
- _fenceSupported << _circleEnabled << _polygonEnabled << _breachReturnEnabled;
- }
-}
-
-float APMGeoFenceManager::circleRadius(void) const
-{
- if (_circleRadiusFact) {
- return _circleRadiusFact->rawValue().toFloat();
- } else {
- return 0.0;
- }
-}
-
-void APMGeoFenceManager::_circleRadiusRawValueChanged(QVariant value)
-{
- emit circleRadiusChanged(value.toFloat());
-}
-
-QString APMGeoFenceManager::editorQml(void) const
-{
- if (_fenceSupported) {
- return _vehicle->multiRotor() ?
- QStringLiteral("qrc:/FirmwarePlugin/APM/CopterGeoFenceEditor.qml") :
- QStringLiteral("qrc:/FirmwarePlugin/APM/PlaneGeoFenceEditor.qml");
- } else {
- return QStringLiteral("qrc:/FirmwarePlugin/NoGeoFenceEditor.qml");
+ _updateEnabledFlags();
}
}
diff --git a/src/FirmwarePlugin/APM/APMGeoFenceManager.h b/src/FirmwarePlugin/APM/APMGeoFenceManager.h
index ccdd198b387e80312c4581e7212a9df6c4e8b2ea..a092e412f8e5737135c44e9249af460b74c17d1c 100644
--- a/src/FirmwarePlugin/APM/APMGeoFenceManager.h
+++ b/src/FirmwarePlugin/APM/APMGeoFenceManager.h
@@ -25,33 +25,35 @@ public:
~APMGeoFenceManager();
// Overrides from GeoFenceManager
- bool inProgress (void) const final;
- void loadFromVehicle (void) final;
- void sendToVehicle (const QGeoCoordinate& breachReturn, QmlObjectListModel& polygon) final;
- bool circleEnabled (void) const final { return _circleEnabled; }
- bool polygonEnabled (void) const final { return _polygonEnabled; }
- bool breachReturnEnabled (void) const final { return _breachReturnEnabled; }
- float circleRadius (void) const final;
- QVariantList params (void) const final { return _params; }
- QStringList paramLabels (void) const final { return _paramLabels; }
- QString editorQml (void) const final;
- void removeAll (void) final;
+ bool inProgress (void) const final;
+ void loadFromVehicle (void) final;
+ void sendToVehicle (const QGeoCoordinate& breachReturn, QmlObjectListModel& polygon) final;
+ bool polygonSupported (void) const final { return _polygonSupported; }
+ bool polygonEnabled (void) const final { return _polygonEnabled; }
+ bool breachReturnSupported (void) const final { return _breachReturnSupported; }
+ bool circleEnabled (void) const { return _circleEnabled; }
+ Fact* circleRadiusFact (void) const { return _circleRadiusFact; }
+ QVariantList params (void) const final { return _params; }
+ QStringList paramLabels (void) const final { return _paramLabels; }
+ void removeAll (void) final;
private slots:
- void _mavlinkMessageReceived(const mavlink_message_t& message);
- void _updateEnabledFlags(void);
- void _circleRadiusRawValueChanged(QVariant value);
- void _parametersReady(void);
+ void _mavlinkMessageReceived (const mavlink_message_t& message);
+ void _parametersReady (void);
private:
- void _requestFencePoint(uint8_t pointIndex);
- void _sendFencePoint(uint8_t pointIndex);
+ void _requestFencePoint (uint8_t pointIndex);
+ void _sendFencePoint (uint8_t pointIndex);
+ void _updateEnabledFlags(void);
+ void _setCircleEnabled (bool circleEnabled);
+ void _setPolygonEnabled (bool polygonEnabled);
private:
bool _fenceSupported;
- bool _breachReturnEnabled;
bool _circleEnabled;
+ bool _polygonSupported;
bool _polygonEnabled;
+ bool _breachReturnSupported;
bool _firstParamLoadComplete;
QVariantList _params;
diff --git a/src/FirmwarePlugin/APM/APMResources.qrc b/src/FirmwarePlugin/APM/APMResources.qrc
index 82e2bfc895dd89b42964196ea402bdf9fba608f6..8f08af94795f5152a08e021a8340260063acb484 100644
--- a/src/FirmwarePlugin/APM/APMResources.qrc
+++ b/src/FirmwarePlugin/APM/APMResources.qrc
@@ -51,8 +51,6 @@
APMParameterFactMetaData.Rover.3.2.xml
APMParameterFactMetaData.Sub.3.4.xml
APMParameterFactMetaData.Sub.3.5.xml
- CopterGeoFenceEditor.qml
- PlaneGeoFenceEditor.qml
Copter3.4.OfflineEditing.params
Plane3.7.OfflineEditing.params
diff --git a/src/FirmwarePlugin/APM/CopterGeoFenceEditor.qml b/src/FirmwarePlugin/APM/CopterGeoFenceEditor.qml
deleted file mode 100644
index e55535a81ab169bd0aefefe0f1192a46bc62d39d..0000000000000000000000000000000000000000
--- a/src/FirmwarePlugin/APM/CopterGeoFenceEditor.qml
+++ /dev/null
@@ -1,86 +0,0 @@
-import QtQuick 2.3
-import QtQuick.Controls 1.2
-
-import QGroundControl 1.0
-import QGroundControl.ScreenTools 1.0
-import QGroundControl.Controls 1.0
-import QGroundControl.FactControls 1.0
-import QGroundControl.Palette 1.0
-import QGroundControl.FlightMap 1.0
-import QGroundControl.FactSystem 1.0
-
-Column {
- id: editorColumn
- width: availableWidth
- spacing: _margin
-
- //property real availableWidth - Available width for control - Must be passed in from Loader
-
- readonly property real _margin: ScreenTools.defaultFontPixelWidth / 2
- readonly property real _editFieldWidth: Math.min(width - _margin * 2, ScreenTools.defaultFontPixelWidth * 15)
-
- QGCLabel {
- anchors.left: parent.left
- anchors.right: parent.right
- wrapMode: Text.WordWrap
- text: qsTr("Click in map to set breach return point.")
- }
-
- QGCLabel { text: qsTr("Fence Settings:") }
-
- Rectangle {
- anchors.left: parent.left
- anchors.right: parent.right
- height: 1
- color: qgcPal.text
- }
-
- Repeater {
- model: geoFenceController.params
-
- Item {
- width: editorColumn.width
- height: textField.height
-
- property bool showCombo: modelData.enumStrings.length > 0
-
- QGCLabel {
- id: textFieldLabel
- anchors.baseline: textField.baseline
- text: geoFenceController.paramLabels[index]
- }
-
- FactTextField {
- id: textField
- anchors.right: parent.right
- width: _editFieldWidth
- showUnits: true
- fact: modelData
- visible: !parent.showCombo
- }
-
- FactComboBox {
- id: comboField
- anchors.right: parent.right
- width: _editFieldWidth
- indexModel: false
- fact: showCombo ? modelData : _nullFact
- visible: parent.showCombo
-
- property var _nullFact: Fact { }
- }
- }
- }
-
- QGCButton {
- text: qsTr("Add fence")
- visible: geoFenceController.mapPolygon.count < 3
- onClicked: geoFenceController.addFence()
- }
-
- QGCButton {
- text: qsTr("Remove fence")
- visible: geoFenceController.mapPolygon.count >= 3
- onClicked: geoFenceController.removeFence()
- }
-}
diff --git a/src/FirmwarePlugin/APM/PlaneGeoFenceEditor.qml b/src/FirmwarePlugin/APM/PlaneGeoFenceEditor.qml
deleted file mode 100644
index 5449a2868460eb5078914b3245a700405107b078..0000000000000000000000000000000000000000
--- a/src/FirmwarePlugin/APM/PlaneGeoFenceEditor.qml
+++ /dev/null
@@ -1,210 +0,0 @@
-import QtQuick 2.3
-import QtQuick.Controls 1.2
-import QtQuick.Layouts 1.2
-
-import QGroundControl 1.0
-import QGroundControl.ScreenTools 1.0
-import QGroundControl.Controls 1.0
-import QGroundControl.FactControls 1.0
-import QGroundControl.Palette 1.0
-import QGroundControl.FlightMap 1.0
-import QGroundControl.FactSystem 1.0
-
-Column {
- id: editorColumn
- width: availableWidth
- spacing: _margin
-
- //property real availableWidth - Available width for control - Must be passed in from Loader
-
- readonly property real _margin: ScreenTools.defaultFontPixelWidth / 2
- readonly property real _editFieldWidth: Math.min(width - _margin * 2, ScreenTools.defaultFontPixelWidth * 15)
-
- property Fact fenceAction: factController.getParameterFact(-1, "FENCE_ACTION")
- property Fact fenceMinAlt: factController.getParameterFact(-1, "FENCE_MINALT")
- property Fact fenceMaxAlt: factController.getParameterFact(-1, "FENCE_MAXALT")
- property Fact fenceRetAlt: factController.getParameterFact(-1, "FENCE_RETALT")
- property Fact fenceAutoEnable: factController.getParameterFact(-1, "FENCE_AUTOENABLE")
- property Fact fenceRetRally: factController.getParameterFact(-1, "FENCE_RET_RALLY")
-
- FactPanelController {
- id: factController
- factPanel: qgcView.viewPanel
- }
-
- QGCLabel { text: qsTr("Fence Settings:") }
-
- Rectangle {
- anchors.left: parent.left
- anchors.right: parent.right
- height: 1
- color: qgcPal.text
- }
-
- QGCLabel { text: qsTr("Action on fence breach:") }
-
- QGCComboBox {
- id: actionCombo
- anchors.leftMargin: ScreenTools.defaultFontPixelWidth
- anchors.left: parent.left
- anchors.right: parent.right
- model: ListModel {
- id: actionModel
- ListElement { text: qsTr("None"); actionValue: 0 }
- ListElement { text: qsTr("Report only"); actionValue: 2 }
- ListElement { text: qsTr("Fly to return point"); actionValue: 1 }
- ListElement { text: qsTr("Fly to return point (throttle control)"); actionValue: 3 }
- }
-
- onActivated: fenceAction.rawValue = actionModel.get(index).actionValue
- Component.onCompleted: recalcSelection()
-
- Connections {
- target: fenceAction
- onValueChanged: actionCombo.recalcSelection()
- }
-
- function recalcSelection() {
- for (var i=0; i 0
- onClicked: fenceMinAlt.value = checked ? 10 : 0
- }
-
- FactTextField {
- id: fenceAltMinField
- Layout.fillWidth: true
- showUnits: true
- fact: fenceMinAlt
- enabled: minAltFenceCheckBox.checked
- }
-
- QGCCheckBox {
- id: maxAltFenceCheckBox
- text: qsTr("Max altitude:")
- checked: fenceMaxAlt.value > 0
- onClicked: fenceMaxAlt.value = checked ? 100 : 0
- }
-
- FactTextField {
- id: fenceAltMaxField
- Layout.fillWidth: true
- showUnits: true
- fact: fenceMaxAlt
- enabled: maxAltFenceCheckBox.checked
- }
- }
-
- Item { width: 1; height: 1 }
-
- QGCLabel { text: qsTr("Breach return point:") }
-
- QGCLabel {
- anchors.margins: ScreenTools.defaultFontPixelWidth
- anchors.left: parent.left
- anchors.right: parent.right
- wrapMode: Text.WordWrap
- text: qsTr("Click in map to set breach return location.")
- font.pointSize: ScreenTools.smallFontPointSize
- }
-
- Row {
- anchors.margins: ScreenTools.defaultFontPixelWidth
- anchors.left: parent.left
- spacing: _margin
-
- QGCLabel {
- anchors.baseline: retAltField.baseline
- text: qsTr("Return Alt:")
- }
-
- FactTextField {
- id: retAltField
- showUnits: true
- fact: fenceRetAlt
- width: _editFieldWidth
- }
- }
-
- Item { width: 1; height: 1 }
-
- FactCheckBox {
- text: qsTr("Auto-Enable after takeoff")
- fact: fenceAutoEnable
- }
-
- QGCLabel {
- anchors.margins: ScreenTools.defaultFontPixelWidth
- anchors.left: parent.left
- anchors.right: parent.right
- wrapMode: Text.WordWrap
- font.pointSize: ScreenTools.smallFontPointSize
- text: qsTr("If checked, the aircraft will start with the fence disabled. After an autonomous takeoff completes the fences will automatically enable. When the autonomous mission arrives at a landing waypoint the fence automatically disables.")
- }
-
- /*
- FENCE_ACTION - the action to take on fence breach. This defaults to zero which disables geo-fencing. Set it to 1 to enable geo-fencing and fly to the return point on fence breach. Set to 2 to report a breach to the GCS but take no other action. Set to 3 to have the plane head to the return point on breach, but the pilot will maintain manual throttle control in this case.
- FENCE_MINALT - the minimum altitude in meters. If this is zero then you will not have a minimum altitude.
- FENCE_MAXALT - the maximum altitude in meters. If this is zero then you will not have a maximum altitude.
- FENCE_CHANNEL - the RC input channel to watch for enabling the geo-fence. This defaults to zero, which disables geo-fencing. You should set it to a spare RC input channel that is connected to a two position switch on your transmitter. Fencing will be enabled when this channel goes above a PWM value of 1750. If your transmitter supports it it is also a good idea to enable audible feedback when this channel is enabled (a beep every few seconds), so you can tell if the fencing is enabled without looking down.
- FENCE_TOTAL - the number of points in your fence (the return point plus the enclosed boundary). This should be set for you by the planner when you create the fence.
- FENCE_RETALT - the altitude the aircraft will fly at when flying to the return point and when loitering at the return point (in meters). Note that when FENCE_RET_RALLY is set to 1 this parameter is ignored and the loiter altitude of the closest Rally Point is used instead. If this parameter is zero and FENCE_RET_RALLY is also zero, the midpoint of the FENCE_MAXALT and FENCE_MINALT parameters is used as the return altitude.
- FENCE_AUTOENABLE - if set to 1, the aircraft will boot with the fence disabled. After an autonomous takeoff completes the fences will automatically enable. When the autonomous mission arrives at a landing waypoint the fence automatically disables.
- FENCE_RET_RALLY - if set to 1 the aircraft will head to the nearest Rally Point rather than the fence return point when the fence is breached. Note that the loiter altitude of the Rally Point is used as the return altitude.
- */
-
- QGCButton {
- text: qsTr("Add fence")
- visible: geoFenceController.mapPolygon.count < 3
- onClicked: geoFenceController.addFence()
- }
-
- QGCButton {
- text: qsTr("Remove fence")
- visible: geoFenceController.mapPolygon.count >= 3
- onClicked: geoFenceController.removeFence()
- }
-}
diff --git a/src/FirmwarePlugin/NoGeoFenceEditor.qml b/src/FirmwarePlugin/NoGeoFenceEditor.qml
deleted file mode 100644
index e324f7779429fd87ab834273442a0b7b92926b31..0000000000000000000000000000000000000000
--- a/src/FirmwarePlugin/NoGeoFenceEditor.qml
+++ /dev/null
@@ -1,19 +0,0 @@
-import QtQuick 2.3
-import QtQuick.Controls 1.2
-
-import QGroundControl 1.0
-import QGroundControl.ScreenTools 1.0
-import QGroundControl.Controls 1.0
-import QGroundControl.FactControls 1.0
-import QGroundControl.Palette 1.0
-import QGroundControl.FlightMap 1.0
-import QGroundControl.FactSystem 1.0
-
-QGCLabel {
- width: availableWidth
- wrapMode: Text.WordWrap
- text: qsTr("This vehicle does not support GeoFence.")
-
- //property var contoller - controller - Must be passed in from Loader
- //property real availableWidth - Available width for control - Must be passed in from Loader
-}
diff --git a/src/FirmwarePlugin/PX4/PX4GeoFenceEditor.qml b/src/FirmwarePlugin/PX4/PX4GeoFenceEditor.qml
deleted file mode 100644
index cc556100aa585ebe7588e6a022df47638c263d5f..0000000000000000000000000000000000000000
--- a/src/FirmwarePlugin/PX4/PX4GeoFenceEditor.qml
+++ /dev/null
@@ -1,105 +0,0 @@
-import QtQuick 2.3
-import QtQuick.Controls 1.2
-
-import QGroundControl 1.0
-import QGroundControl.ScreenTools 1.0
-import QGroundControl.Controls 1.0
-import QGroundControl.FactControls 1.0
-import QGroundControl.Palette 1.0
-import QGroundControl.FlightMap 1.0
-import QGroundControl.FactSystem 1.0
-import QGroundControl.Controllers 1.0
-
-Column {
- id: editorColumn
- width: availableWidth
- spacing: _margin
-
- //property real availableWidth - Available width for control - Must be passed in from Loader
-
- readonly property real _margin: ScreenTools.defaultFontPixelWidth / 2
- readonly property real _editFieldWidth: Math.min(width - _margin * 2, ScreenTools.defaultFontPixelWidth * 15)
-
- property Fact _fenceAction: factController.getParameterFact(-1, "GF_ACTION")
- property Fact _fenceRadius: factController.getParameterFact(-1, "GF_MAX_HOR_DIST")
- property Fact _fenceMaxAlt: factController.getParameterFact(-1, "GF_MAX_VER_DIST")
-
- FactPanelController {
- id: factController
- factPanel: qgcView.viewPanel
- }
-
- QGCLabel { text: qsTr("Fence Settings:") }
-
- Rectangle {
- anchors.left: parent.left
- anchors.right: parent.right
- height: 1
- color: qgcPal.text
- }
-
- QGCLabel { text: qsTr("Action on fence breach:") }
- FactComboBox {
- anchors.margins: ScreenTools.defaultFontPixelWidth
- anchors.left: parent.left
- width: _editFieldWidth
- fact: _fenceAction
- indexModel: false
- }
-
- Item { width: 1; height: 1 }
-
- QGCCheckBox {
- id: circleFenceCheckBox
- text: qsTr("Circular fence around home pos")
- checked: _fenceRadius.value > 0
- onClicked: _fenceRadius.value = checked ? 100 : 0
- }
-
- Row {
- anchors.margins: ScreenTools.defaultFontPixelWidth
- anchors.left: parent.left
- spacing: _margin
-
- QGCLabel {
- anchors.baseline: fenceRadiusField.baseline
- text: qsTr("Radius:")
- }
-
- FactTextField {
- id: fenceRadiusField
- showUnits: true
- fact: _fenceRadius
- enabled: circleFenceCheckBox.checked
- width: _editFieldWidth
- }
- }
-
- Item { width: 1; height: 1 }
-
- QGCCheckBox {
- id: maxAltFenceCheckBox
- text: qsTr("Maximum altitude fence")
- checked: _fenceMaxAlt.value > 0
- onClicked: _fenceMaxAlt.value = checked ? 100 : 0
- }
-
- Row {
- anchors.margins: ScreenTools.defaultFontPixelWidth
- anchors.left: parent.left
- spacing: _margin
-
- QGCLabel {
- anchors.baseline: fenceAltMaxField.baseline
- text: qsTr("Altitude:")
- }
-
- FactTextField {
- id: fenceAltMaxField
- showUnits: true
- fact: _fenceMaxAlt
- enabled: maxAltFenceCheckBox.checked
- width: _editFieldWidth
- }
- }
-}
diff --git a/src/FirmwarePlugin/PX4/PX4GeoFenceManager.cc b/src/FirmwarePlugin/PX4/PX4GeoFenceManager.cc
index c1be41589ddec4903d14fa4c735d0ce0da3dbae5..fec0bfd2fb52e999b54cc73b25740af0fcaf0a80 100644
--- a/src/FirmwarePlugin/PX4/PX4GeoFenceManager.cc
+++ b/src/FirmwarePlugin/PX4/PX4GeoFenceManager.cc
@@ -15,7 +15,6 @@
PX4GeoFenceManager::PX4GeoFenceManager(Vehicle* vehicle)
: GeoFenceManager(vehicle)
, _firstParamLoadComplete(false)
- , _circleEnabled(false)
, _circleRadiusFact(NULL)
{
connect(_vehicle->parameterManager(), &ParameterManager::parametersReadyChanged, this, &PX4GeoFenceManager::_parametersReady);
@@ -36,14 +35,13 @@ void PX4GeoFenceManager::_parametersReady(void)
_firstParamLoadComplete = true;
_circleRadiusFact = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, QStringLiteral("GF_MAX_HOR_DIST"));
- connect(_circleRadiusFact, &Fact::rawValueChanged, this, &PX4GeoFenceManager::_circleRadiusRawValueChanged);
- emit circleRadiusChanged(circleRadius());
+ emit circleRadiusFactChanged(_circleRadiusFact);
QStringList paramNames;
QStringList paramLabels;
paramNames << QStringLiteral("GF_ACTION") << QStringLiteral("GF_MAX_HOR_DIST") << QStringLiteral("GF_MAX_VER_DIST");
- paramLabels << QStringLiteral("Action:") << QStringLiteral("Radius:") << QStringLiteral("Max Altitude:");
+ paramLabels << QStringLiteral("Breach Action:") << QStringLiteral("Radius:") << QStringLiteral("Max Altitude:");
_params.clear();
_paramLabels.clear();
@@ -55,32 +53,8 @@ void PX4GeoFenceManager::_parametersReady(void)
_paramLabels << paramLabels[i];
}
}
+
emit paramsChanged(_params);
emit paramLabelsChanged(_paramLabels);
-
- _circleEnabled = true;
- emit circleEnabledChanged(true);
-
- qCDebug(GeoFenceManagerLog) << "fenceSupported:circleSupported:polygonSupported:breachReturnSupported" <<
- _circleEnabled << polygonEnabled() << breachReturnEnabled();
- }
-}
-
-float PX4GeoFenceManager::circleRadius(void) const
-{
- if (_circleRadiusFact) {
- return _circleRadiusFact->rawValue().toFloat();
- } else {
- return 0.0;
}
}
-
-void PX4GeoFenceManager::_circleRadiusRawValueChanged(QVariant value)
-{
- emit circleRadiusChanged(value.toFloat());
-}
-
-void PX4GeoFenceManager::removeAll(void)
-{
- // Only params so nothing to do
-}
diff --git a/src/FirmwarePlugin/PX4/PX4GeoFenceManager.h b/src/FirmwarePlugin/PX4/PX4GeoFenceManager.h
index edfe955e6ad33a550bbf7c6f375763f86e6aa426..7a87f2cbf234ed348ad342c4c6b1b3cc25de3361 100644
--- a/src/FirmwarePlugin/PX4/PX4GeoFenceManager.h
+++ b/src/FirmwarePlugin/PX4/PX4GeoFenceManager.h
@@ -23,25 +23,19 @@ public:
~PX4GeoFenceManager();
// Overrides from GeoFenceManager
- bool circleEnabled (void) const final { return _circleEnabled; }
- float circleRadius (void) const final;
- QVariantList params (void) const final { return _params; }
- QStringList paramLabels (void) const final { return _paramLabels; }
- QString editorQml (void) const final { return QStringLiteral("qrc:/FirmwarePlugin/PX4/PX4GeoFenceEditor.qml"); }
- void removeAll (void) final;
+ bool circleEnabled (void) const { return true; }
+ Fact* circleRadiusFact (void) const { return _circleRadiusFact; }
+ QVariantList params (void) const final { return _params; }
+ QStringList paramLabels (void) const final { return _paramLabels; }
private slots:
- void _circleRadiusRawValueChanged(QVariant value);
void _parametersReady(void);
private:
- bool _firstParamLoadComplete;
-
+ bool _firstParamLoadComplete;
+ Fact* _circleRadiusFact;
QVariantList _params;
QStringList _paramLabels;
- bool _circleEnabled;
-
- Fact* _circleRadiusFact;
};
#endif
diff --git a/src/FirmwarePlugin/PX4/PX4Resources.qrc b/src/FirmwarePlugin/PX4/PX4Resources.qrc
index de0775e1c697981ff1af8fe535732869a0aefacd..bceb094d56c8748da3c915bfc523113985b12f9b 100644
--- a/src/FirmwarePlugin/PX4/PX4Resources.qrc
+++ b/src/FirmwarePlugin/PX4/PX4Resources.qrc
@@ -21,7 +21,6 @@
PX4ParameterFactMetaData.xml
- PX4GeoFenceEditor.qml
V1.4.OfflineEditing.params
diff --git a/src/FlightDisplay/FlightDisplayViewMap.qml b/src/FlightDisplay/FlightDisplayViewMap.qml
index 2a6243f10d8bbfb3ffd54646f5693c8507ec3048..6fab1c4a32c93b9d9666dace08239eb913ac4232 100644
--- a/src/FlightDisplay/FlightDisplayViewMap.qml
+++ b/src/FlightDisplay/FlightDisplayViewMap.qml
@@ -40,6 +40,8 @@ FlightMap {
property var rightPanelWidth
property var qgcView ///< QGCView control which contains this map
+ property rect centerViewport: Qt.rect(0, 0, width, height)
+
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
property var _activeVehicleCoordinate: _activeVehicle ? _activeVehicle.coordinate : QtPositioning.coordinate()
property var _gotoHereCoordinate: QtPositioning.coordinate()
@@ -201,6 +203,7 @@ FlightMap {
map: flightMap
myGeoFenceController: geoFenceController
interactive: false
+ planView: false
homePosition: _activeVehicle && _activeVehicle.homePosition.isValid ? _activeVehicle.homePosition : undefined
}
diff --git a/src/MissionManager/GeoFenceController.cc b/src/MissionManager/GeoFenceController.cc
index cfc493ee8ad8cc6fcc78cf87ce0020ba5c87e999..740d6c6bc36cd9ffbff8796b8b980b69597e2919 100644
--- a/src/MissionManager/GeoFenceController.cc
+++ b/src/MissionManager/GeoFenceController.cc
@@ -80,14 +80,12 @@ void GeoFenceController::setBreachReturnPoint(const QGeoCoordinate& breachReturn
void GeoFenceController::_signalAll(void)
{
+ emit breachReturnSupportedChanged(breachReturnSupported());
+ emit breachReturnPointChanged(breachReturnPoint());
emit circleEnabledChanged(circleEnabled());
+ emit circleRadiusFactChanged(circleRadiusFact());
emit polygonEnabledChanged(polygonEnabled());
- emit breachReturnEnabledChanged(breachReturnEnabled());
- emit breachReturnPointChanged(breachReturnPoint());
- emit circleRadiusChanged(circleRadius());
- emit paramsChanged(params());
- emit paramLabelsChanged(paramLabels());
- emit editorQmlChanged(editorQml());
+ emit polygonSupportedChanged(polygonSupported());
emit dirtyChanged(dirty());
}
@@ -99,15 +97,13 @@ void GeoFenceController::_activeVehicleBeingRemoved(void)
void GeoFenceController::_activeVehicleSet(void)
{
GeoFenceManager* geoFenceManager = _activeVehicle->geoFenceManager();
- connect(geoFenceManager, &GeoFenceManager::polygonEnabledChanged, this, &GeoFenceController::_setDirty);
- connect(geoFenceManager, &GeoFenceManager::circleEnabledChanged, this, &GeoFenceController::circleEnabledChanged);
- connect(geoFenceManager, &GeoFenceManager::polygonEnabledChanged, this, &GeoFenceController::polygonEnabledChanged);
- connect(geoFenceManager, &GeoFenceManager::breachReturnEnabledChanged, this, &GeoFenceController::breachReturnEnabledChanged);
- connect(geoFenceManager, &GeoFenceManager::circleRadiusChanged, this, &GeoFenceController::circleRadiusChanged);
- connect(geoFenceManager, &GeoFenceManager::paramsChanged, this, &GeoFenceController::paramsChanged);
- connect(geoFenceManager, &GeoFenceManager::paramLabelsChanged, this, &GeoFenceController::paramLabelsChanged);
- connect(geoFenceManager, &GeoFenceManager::loadComplete, this, &GeoFenceController::_loadComplete);
- connect(geoFenceManager, &GeoFenceManager::inProgressChanged, this, &GeoFenceController::syncInProgressChanged);
+ connect(geoFenceManager, &GeoFenceManager::breachReturnSupportedChanged, this, &GeoFenceController::breachReturnSupportedChanged);
+ connect(geoFenceManager, &GeoFenceManager::circleEnabledChanged, this, &GeoFenceController::circleEnabledChanged);
+ connect(geoFenceManager, &GeoFenceManager::circleRadiusFactChanged, this, &GeoFenceController::circleRadiusFactChanged);
+ connect(geoFenceManager, &GeoFenceManager::polygonEnabledChanged, this, &GeoFenceController::polygonEnabledChanged);
+ connect(geoFenceManager, &GeoFenceManager::polygonSupportedChanged, this, &GeoFenceController::polygonSupportedChanged);
+ connect(geoFenceManager, &GeoFenceManager::loadComplete, this, &GeoFenceController::_loadComplete);
+ connect(geoFenceManager, &GeoFenceManager::inProgressChanged, this, &GeoFenceController::syncInProgressChanged);
if (!geoFenceManager->inProgress()) {
_loadComplete(geoFenceManager->breachReturnPoint(), geoFenceManager->polygon());
@@ -134,77 +130,18 @@ bool GeoFenceController::_loadJsonFile(QJsonDocument& jsonDoc, QString& errorStr
return false;
}
- if (breachReturnEnabled()) {
- if (json.contains(_jsonBreachReturnKey)
- && !JsonHelper::loadGeoCoordinate(json[_jsonBreachReturnKey], false /* altitudeRequired */, _breachReturnPoint, errorString)) {
- return false;
- }
- } else {
- _breachReturnPoint = QGeoCoordinate();
- }
-
- if (polygonEnabled()) {
- if (!_mapPolygon.loadFromJson(json, true, errorString)) {
- return false;
- }
- }
- _mapPolygon.setDirty(false);
-
- return true;
-}
-
-#if 0
-// NYI
-bool GeoFenceController::_loadTextFile(QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString)
-{
- bool addPlannedHomePosition = false;
-
- QString firstLine = stream.readLine();
- const QStringList& version = firstLine.split(" ");
-
- bool versionOk = false;
- if (version.size() == 3 && version[0] == "QGC" && version[1] == "WPL") {
- if (version[2] == "110") {
- // ArduPilot file, planned home position is already in position 0
- versionOk = true;
- } else if (version[2] == "120") {
- // Old QGC file, no planned home position
- versionOk = true;
- addPlannedHomePosition = true;
- }
- }
-
- if (versionOk) {
- while (!stream.atEnd()) {
- SimpleMissionItem* item = new SimpleMissionItem(_activeVehicle, this);
-
- if (item->load(stream)) {
- visualItems->append(item);
- } else {
- errorString = QStringLiteral("The mission file is corrupted.");
- return false;
- }
- }
- } else {
- errorString = QStringLiteral("The mission file is not compatible with this version of %1.").arg(qgcApp()->applicationName()));
+ if (json.contains(_jsonBreachReturnKey)
+ && !JsonHelper::loadGeoCoordinate(json[_jsonBreachReturnKey], false /* altitudeRequired */, _breachReturnPoint, errorString)) {
return false;
}
- if (addPlannedHomePosition || visualItems->count() == 0) {
- _addPlannedHomePosition(visualItems, true /* addToCenter */);
-
- // Update sequence numbers in DO_JUMP commands to take into account added home position in index 0
- for (int i=1; icount(); i++) {
- SimpleMissionItem* item = qobject_cast(visualItems->get(i));
- if (item && item->command() == MavlinkQmlSingleton::MAV_CMD_DO_JUMP) {
- item->missionItem().setParam1((int)item->missionItem().param1() + 1);
- }
- }
+ if (!_mapPolygon.loadFromJson(json, true, errorString)) {
+ return false;
}
+ _mapPolygon.setDirty(false);
return true;
}
-#endif
void GeoFenceController::loadFromFile(const QString& filename)
{
@@ -222,13 +159,7 @@ void GeoFenceController::loadFromFile(const QString& filename)
QJsonDocument jsonDoc;
QByteArray bytes = file.readAll();
- if (JsonHelper::isJsonFile(bytes, jsonDoc)) {
- _loadJsonFile(jsonDoc, errorString);
- } else {
- // FIXME: No MP file format support
- qgcApp()->showMessage("GeoFence file is in incorrect format.");
- return;
- }
+ _loadJsonFile(jsonDoc, errorString);
}
if (!errorString.isEmpty()) {
@@ -261,27 +192,11 @@ void GeoFenceController::saveToFile(const QString& filename)
fenceFileObject[JsonHelper::jsonVersionKey] = 1;
fenceFileObject[JsonHelper::jsonGroundStationKey] = JsonHelper::jsonGroundStationValue;
- QStringList paramNames;
- ParameterManager* paramMgr = _activeVehicle->parameterManager();
- GeoFenceManager* fenceMgr = _activeVehicle->geoFenceManager();
- QVariantList params = fenceMgr->params();
+ QJsonValue jsonBreachReturn;
+ JsonHelper::saveGeoCoordinate(_breachReturnPoint, false /* writeAltitude */, jsonBreachReturn);
+ fenceFileObject[_jsonBreachReturnKey] = jsonBreachReturn;
- for (int i=0; i< params.count(); i++) {
- paramNames.append(params[i].value()->name());
- }
- if (paramNames.count() > 0) {
- paramMgr->saveToJson(_activeVehicle->defaultComponentId(), paramNames, fenceFileObject);
- }
-
- if (breachReturnEnabled()) {
- QJsonValue jsonBreachReturn;
- JsonHelper::saveGeoCoordinate(_breachReturnPoint, false /* writeAltitude */, jsonBreachReturn);
- fenceFileObject[_jsonBreachReturnKey] = jsonBreachReturn;
- }
-
- if (polygonEnabled()) {
- _mapPolygon.saveToJson(fenceFileObject);
- }
+ _mapPolygon.saveToJson(fenceFileObject);
QJsonDocument saveDoc(fenceFileObject);
file.write(saveDoc.toJson());
@@ -345,19 +260,39 @@ void GeoFenceController::_polygonDirtyChanged(bool dirty)
}
}
+bool GeoFenceController::breachReturnSupported(void) const
+{
+ return _activeVehicle->geoFenceManager()->breachReturnSupported();
+}
+
bool GeoFenceController::circleEnabled(void) const
{
return _activeVehicle->geoFenceManager()->circleEnabled();
}
+Fact* GeoFenceController::circleRadiusFact(void) const
+{
+ return _activeVehicle->geoFenceManager()->circleRadiusFact();
+}
+
+bool GeoFenceController::polygonSupported(void) const
+{
+ return _activeVehicle->geoFenceManager()->polygonSupported();
+}
+
bool GeoFenceController::polygonEnabled(void) const
{
return _activeVehicle->geoFenceManager()->polygonEnabled();
}
-bool GeoFenceController::breachReturnEnabled(void) const
+QVariantList GeoFenceController::params(void) const
{
- return _activeVehicle->geoFenceManager()->breachReturnEnabled();
+ return _activeVehicle->geoFenceManager()->params();
+}
+
+QStringList GeoFenceController::paramLabels(void) const
+{
+ return _activeVehicle->geoFenceManager()->paramLabels();
}
void GeoFenceController::_setDirty(void)
@@ -380,26 +315,6 @@ void GeoFenceController::_setReturnPointFromManager(QGeoCoordinate breachReturnP
emit breachReturnPointChanged(_breachReturnPoint);
}
-float GeoFenceController::circleRadius(void) const
-{
- return _activeVehicle->geoFenceManager()->circleRadius();
-}
-
-QVariantList GeoFenceController::params(void) const
-{
- return _activeVehicle->geoFenceManager()->params();
-}
-
-QStringList GeoFenceController::paramLabels(void) const
-{
- return _activeVehicle->geoFenceManager()->paramLabels();
-}
-
-QString GeoFenceController::editorQml(void) const
-{
- return _activeVehicle->geoFenceManager()->editorQml();
-}
-
void GeoFenceController::_loadComplete(const QGeoCoordinate& breachReturn, const QList& polygon)
{
_setReturnPointFromManager(breachReturn);
@@ -427,15 +342,3 @@ void GeoFenceController::removeAllFromVehicle(void)
{
_activeVehicle->geoFenceManager()->removeAll();
}
-
-void GeoFenceController::addFence(void)
-{
- // GeoFenceMapVisuals control is resposible for this
- emit addFencePolygon();
-}
-
-void GeoFenceController::removeFence(void)
-{
- _mapPolygon.clear();
-}
-
diff --git a/src/MissionManager/GeoFenceController.h b/src/MissionManager/GeoFenceController.h
index 523c0434100c315af4ff67b3367eda5d673177d1..ac4c311be9bb5e1175be5dfedbbf6b6b41069c4a 100644
--- a/src/MissionManager/GeoFenceController.h
+++ b/src/MissionManager/GeoFenceController.h
@@ -29,21 +29,20 @@ public:
GeoFenceController(QObject* parent = NULL);
~GeoFenceController();
- Q_PROPERTY(bool circleEnabled READ circleEnabled NOTIFY circleEnabledChanged)
- Q_PROPERTY(float circleRadius READ circleRadius NOTIFY circleRadiusChanged)
+ Q_PROPERTY(QGCMapPolygon* mapPolygon READ mapPolygon CONSTANT)
+ Q_PROPERTY(QGeoCoordinate breachReturnPoint READ breachReturnPoint WRITE setBreachReturnPoint NOTIFY breachReturnPointChanged)
- Q_PROPERTY(bool polygonEnabled READ polygonEnabled NOTIFY polygonEnabledChanged)
- Q_PROPERTY(QGCMapPolygon* mapPolygon READ mapPolygon CONSTANT)
+ // The following properties are reflections of properties from GeoFenceManager
+ Q_PROPERTY(bool circleEnabled READ circleEnabled NOTIFY circleEnabledChanged)
+ Q_PROPERTY(Fact* circleRadiusFact READ circleRadiusFact NOTIFY circleRadiusFactChanged)
+ Q_PROPERTY(bool polygonSupported READ polygonSupported NOTIFY polygonSupportedChanged)
+ Q_PROPERTY(bool polygonEnabled READ polygonEnabled NOTIFY polygonEnabledChanged)
+ Q_PROPERTY(bool breachReturnSupported READ breachReturnSupported NOTIFY breachReturnSupportedChanged)
+ Q_PROPERTY(QVariantList params READ params NOTIFY paramsChanged)
+ Q_PROPERTY(QStringList paramLabels READ paramLabels NOTIFY paramLabelsChanged)
- Q_PROPERTY(bool breachReturnEnabled READ breachReturnEnabled NOTIFY breachReturnEnabledChanged)
- Q_PROPERTY(QGeoCoordinate breachReturnPoint READ breachReturnPoint WRITE setBreachReturnPoint NOTIFY breachReturnPointChanged)
-
- Q_PROPERTY(QVariantList params READ params NOTIFY paramsChanged)
- Q_PROPERTY(QStringList paramLabels READ paramLabels NOTIFY paramLabelsChanged)
- Q_PROPERTY(QString editorQml READ editorQml NOTIFY editorQmlChanged)
-
- Q_INVOKABLE void addFence(void);
- Q_INVOKABLE void removeFence(void);
+ Q_INVOKABLE void addPolygon (void) { emit addInitialFencePolygon(); }
+ Q_INVOKABLE void removePolygon (void) { _mapPolygon.clear(); }
void start (bool editMode) final;
void startStaticActiveVehicle (Vehicle* vehicle) final;
@@ -60,29 +59,30 @@ public:
QString fileExtension(void) const final;
- bool circleEnabled (void) const;
- bool polygonEnabled (void) const;
- bool breachReturnEnabled (void) const;
- float circleRadius (void) const;
- QGCMapPolygon* mapPolygon (void) { return &_mapPolygon; }
- QGeoCoordinate breachReturnPoint (void) const { return _breachReturnPoint; }
- QVariantList params (void) const;
- QStringList paramLabels (void) const;
- QString editorQml (void) const;
+ bool circleEnabled (void) const;
+ Fact* circleRadiusFact (void) const;
+ bool polygonSupported (void) const;
+ bool polygonEnabled (void) const;
+ bool breachReturnSupported (void) const;
+ QVariantList params (void) const;
+ QStringList paramLabels (void) const;
+ QGCMapPolygon* mapPolygon (void) { return &_mapPolygon; }
+ QGeoCoordinate breachReturnPoint (void) const { return _breachReturnPoint; }
void setBreachReturnPoint(const QGeoCoordinate& breachReturnPoint);
signals:
- void addFencePolygon (void);
- void circleEnabledChanged (bool circleEnabled);
- void polygonEnabledChanged (bool polygonEnabled);
- void breachReturnEnabledChanged (bool breachReturnEnabled);
- void circleRadiusChanged (float circleRadius);
- void breachReturnPointChanged (QGeoCoordinate breachReturnPoint);
- void paramsChanged (QVariantList params);
- void paramLabelsChanged (QStringList paramLabels);
- void editorQmlChanged (QString editorQml);
- void loadComplete (void);
+ void breachReturnPointChanged (QGeoCoordinate breachReturnPoint);
+ void editorQmlChanged (QString editorQml);
+ void loadComplete (void);
+ void addInitialFencePolygon (void);
+ void circleEnabledChanged (bool circleEnabled);
+ void circleRadiusFactChanged (Fact* circleRadiusFact);
+ void polygonSupportedChanged (bool polygonSupported);
+ void polygonEnabledChanged (bool polygonEnabled);
+ void breachReturnSupportedChanged (bool breachReturnSupported);
+ void paramsChanged (QVariantList params);
+ void paramLabelsChanged (QStringList paramLabels);
private slots:
void _polygonDirtyChanged(bool dirty);
@@ -100,10 +100,9 @@ private:
void _activeVehicleBeingRemoved(void) final;
void _activeVehicleSet(void) final;
- bool _dirty;
- QGCMapPolygon _mapPolygon;
- QGeoCoordinate _breachReturnPoint;
- QVariantList _params;
+ bool _dirty;
+ QGCMapPolygon _mapPolygon;
+ QGeoCoordinate _breachReturnPoint;
static const char* _jsonFileTypeValue;
static const char* _jsonBreachReturnKey;
diff --git a/src/MissionManager/GeoFenceManager.h b/src/MissionManager/GeoFenceManager.h
index f63b3402d13ee7e3143dbc33786e0d7a509224c5..ffa82f0e365eb7108ac669c89ba0ce0454363ebf 100644
--- a/src/MissionManager/GeoFenceManager.h
+++ b/src/MissionManager/GeoFenceManager.h
@@ -14,6 +14,7 @@
#include
#include "QGCLoggingCategory.h"
+#include "FactSystem.h"
class Vehicle;
class QmlObjectListModel;
@@ -39,20 +40,39 @@ public:
/// Send the current settings to the vehicle
virtual void sendToVehicle(const QGeoCoordinate& breachReturn, QmlObjectListModel& polygon);
- virtual void removeAll(void) { };
+ /// Remove all fence related items from vehicle (does not affect paramters)
+ virtual void removeAll(void) { }
- virtual bool circleEnabled (void) const { return false; }
- virtual bool polygonEnabled (void) const { return false; }
- virtual bool breachReturnEnabled (void) const { return false; }
+ /// Returns true if this vehicle support polygon fence
+ /// Signal: polygonSupportedChanged
+ virtual bool polygonSupported(void) const { return false; }
- virtual float circleRadius (void) const { return 0.0; }
- QList polygon (void) const { return _polygon; }
- QGeoCoordinate breachReturnPoint (void) const { return _breachReturnPoint; }
+ /// Returns true if polygon fence is currently enabled on this vehicle
+ /// Signal: polygonEnabledChanged
+ virtual bool polygonEnabled(void) const { return false; }
+
+ /// Returns true if breach return is supported by this vehicle
+ /// Signal: breachReturnSupportedChanged
+ virtual bool breachReturnSupported(void) const { return false; }
+
+ /// Returns a list of parameter facts that relate to geofence support for the vehicle
+ /// Signal: paramsChanged
+ virtual QVariantList params(void) const { return QVariantList(); }
+
+ /// Returns the user visible labels for the paremeters returned by params method
+ /// Signal: paramLabelsChanged
+ virtual QStringList paramLabels(void) const { return QStringList(); }
- virtual QVariantList params (void) const { return QVariantList(); }
- virtual QStringList paramLabels (void) const { return QStringList(); }
+ /// Returns true if circular fence is currently enabled on vehicle
+ /// Signal: circleEnabledChanged
+ virtual bool circleEnabled(void) const { return false; }
- virtual QString editorQml(void) const { return QStringLiteral("qrc:/FirmwarePlugin/NoGeoFenceEditor.qml"); }
+ /// Returns the fact which controls the fence circle radius. NULL if not supported
+ /// Signal: circleRadiusFactChanged
+ virtual Fact* circleRadiusFact(void) const { return NULL; }
+
+ QList polygon (void) const { return _polygon; }
+ QGeoCoordinate breachReturnPoint (void) const { return _breachReturnPoint; }
/// Error codes returned in error signal
typedef enum {
@@ -63,16 +83,17 @@ public:
} ErrorCode_t;
signals:
- void loadComplete (const QGeoCoordinate& breachReturn, const QList& polygon);
- void circleEnabledChanged (bool circleEnabled);
- void polygonEnabledChanged (bool polygonEnabled);
- void breachReturnEnabledChanged (bool fenceEnabled);
- void circleRadiusChanged (float circleRadius);
- void inProgressChanged (bool inProgress);
- void error (int errorCode, const QString& errorMsg);
- void paramsChanged (QVariantList params);
- void paramLabelsChanged (QStringList paramLabels);
-
+ void loadComplete (const QGeoCoordinate& breachReturn, const QList& polygon);
+ void inProgressChanged (bool inProgress);
+ void error (int errorCode, const QString& errorMsg);
+ void paramsChanged (QVariantList params);
+ void paramLabelsChanged (QStringList paramLabels);
+ void circleEnabledChanged (bool circleEnabled);
+ void circleRadiusFactChanged (Fact* circleRadiusFact);
+ void polygonSupportedChanged (bool polygonSupported);
+ void polygonEnabledChanged (bool polygonEnabled);
+ void breachReturnSupportedChanged (bool breachReturnSupported);
+
protected:
void _sendError(ErrorCode_t errorCode, const QString& errorMsg);
diff --git a/src/MissionManager/QGCMapPolygonVisuals.qml b/src/MissionManager/QGCMapPolygonVisuals.qml
index 760099103ec9773a0dcd773b9b2a564b675a0a46..0a06f12379b95b68558434555e43619cb4829a56 100644
--- a/src/MissionManager/QGCMapPolygonVisuals.qml
+++ b/src/MissionManager/QGCMapPolygonVisuals.qml
@@ -22,8 +22,13 @@ import QGroundControl.FlightMap 1.0
Item {
id: _root
- property var mapControl ///< Map control to place item in
- property var mapPolygon ///< QGCMapPolygon object
+ property var mapControl ///< Map control to place item in
+ property var mapPolygon ///< QGCMapPolygon object
+ property bool interactive: true /// true: user can manipulate polygon
+ property color interiorColor: "transparent"
+ property real interiorOpacity: 1
+ property int borderWidth: 0
+ property color borderColor: "black"
property var _polygonComponent
property var _dragHandlesComponent
@@ -40,9 +45,11 @@ Item {
}
function addHandles() {
- _dragHandlesComponent = dragHandlesComponent.createObject(mapControl)
- _splitHandlesComponent = splitHandlesComponent.createObject(mapControl)
- _centerDragHandleComponent = centerDragHandleComponent.createObject(mapControl)
+ if (!_dragHandlesComponent) {
+ _dragHandlesComponent = dragHandlesComponent.createObject(mapControl)
+ _splitHandlesComponent = splitHandlesComponent.createObject(mapControl)
+ _centerDragHandleComponent = centerDragHandleComponent.createObject(mapControl)
+ }
}
function removeHandles() {
@@ -60,6 +67,52 @@ Item {
}
}
+ /// Add an initial 4 sided polygon
+ 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)
+ }
+ }
+
+ onInteractiveChanged: {
+ if (interactive) {
+ addHandles()
+ } else {
+ removeHandles()
+ }
+ }
+
+ Component.onCompleted: {
+ mapPolygonVisuals.addVisuals()
+ if (interactive) {
+ addHandles()
+ }
+ }
+
Component.onDestruction: {
removeVisuals()
removeHandles()
@@ -69,9 +122,11 @@ Item {
id: polygonComponent
MapPolygon {
- color: "green"
- opacity: 0.5
- path: mapPolygon.path
+ color: interiorColor
+ opacity: interiorOpacity
+ border.color: borderColor
+ border.width: borderWidth
+ path: mapPolygon.path
}
}
@@ -250,4 +305,3 @@ Item {
}
}
-
diff --git a/src/PlanView/GeoFenceEditor.qml b/src/PlanView/GeoFenceEditor.qml
index 9a65116c3bfec3906c62dea42a6b45367bb6475f..b34ec3e7feaaae74035e0182eb57674124548c1f 100644
--- a/src/PlanView/GeoFenceEditor.qml
+++ b/src/PlanView/GeoFenceEditor.qml
@@ -4,6 +4,8 @@ import QtQuick.Controls 1.2
import QGroundControl 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Controls 1.0
+import QGroundControl.FactSystem 1.0
+import QGroundControl.FactControls 1.0
QGCFlickable {
id: root
@@ -45,31 +47,74 @@ QGCFlickable {
anchors.left: parent.left
anchors.right: parent.right
anchors.top: geoFenceLabel.bottom
- height: editorLoader.y + editorLoader.height + (_margin * 2)
+ height: fenceColumn.y + fenceColumn.height + (_margin * 2)
color: qgcPal.windowShadeDark
radius: _radius
- QGCLabel {
- id: geoLabel
+ Column {
+ id: fenceColumn
anchors.margins: _margin
- anchors.top: parent.top
anchors.left: parent.left
anchors.right: parent.right
- wrapMode: Text.WordWrap
- font.pointSize: ScreenTools.smallFontPointSize
- text: qsTr("GeoFencing allows you to set a virtual ‘fence’ around the area you want to fly in.")
- }
+ spacing: ScreenTools.defaultFontPixelHeight / 2
- Loader {
- id: editorLoader
- anchors.margins: _margin
- anchors.top: geoLabel.bottom
- anchors.left: parent.left
- source: myGeoFenceController.editorQml
+ QGCLabel {
+ id: geoLabel
+ anchors.left: parent.left
+ anchors.right: parent.right
+ wrapMode: Text.WordWrap
+ font.pointSize: ScreenTools.smallFontPointSize
+ text: qsTr("GeoFencing allows you to set a virtual ‘fence’ around the area you want to fly in.")
+ }
+
+ Repeater {
+ model: myGeoFenceController.params
+
+ Item {
+ width: fenceColumn.width
+ height: textField.height
+
+ property bool showCombo: modelData.enumStrings.length > 0
+
+ QGCLabel {
+ id: textFieldLabel
+ anchors.baseline: textField.baseline
+ text: myGeoFenceController.paramLabels[index]
+ }
+
+ FactTextField {
+ id: textField
+ anchors.right: parent.right
+ width: _editFieldWidth
+ showUnits: true
+ fact: modelData
+ visible: !parent.showCombo
+ }
+
+ FactComboBox {
+ id: comboField
+ anchors.right: parent.right
+ width: _editFieldWidth
+ indexModel: false
+ fact: showCombo ? modelData : _nullFact
+ visible: parent.showCombo
+
+ property var _nullFact: Fact { }
+ }
+ }
+ }
+
+ QGCButton {
+ text: qsTr("Add fence polygon")
+ visible: myGeoFenceController.polygonSupported && myGeoFenceController.mapPolygon.count === 0
+ onClicked: myGeoFenceController.addPolygon()
+ }
- property real availableWidth: parent.width - (_margin * 2)
- property var geoFenceController: myGeoFenceController
- property var myFlightMap: flightMap
+ QGCButton {
+ text: qsTr("Remove fence polygon")
+ visible: myGeoFenceController.polygonSupported && myGeoFenceController.mapPolygon.count > 0
+ onClicked: myGeoFenceController.removePolygon()
+ }
}
}
}
diff --git a/src/PlanView/GeoFenceMapVisuals.qml b/src/PlanView/GeoFenceMapVisuals.qml
index 0988080daccc1c9e533549e4318a4dd4aac51453..e66cbd666233f14cca4f6d36a81d637e27c33ac1 100644
--- a/src/PlanView/GeoFenceMapVisuals.qml
+++ b/src/PlanView/GeoFenceMapVisuals.qml
@@ -18,7 +18,7 @@ import QGroundControl.Palette 1.0
import QGroundControl.Controls 1.0
import QGroundControl.FlightMap 1.0
-/// Survey Complex Mission Item visuals
+/// GeoFence map visuals
Item {
z: QGroundControl.zOrderMapItems
@@ -28,17 +28,18 @@ Item {
property bool planView: false ///< true: visuals showing in plan view
property var homePosition
- property var _polygonComponent
- property var _dragHandles
- property var _splitHandles
- property var _breachReturnPointComponent
- property var _mouseAreaComponent
- property var _circleComponent
- property var _mapPolygon: myGeoFenceController.mapPolygon
+ property var _breachReturnPointComponent
+ property var _mouseAreaComponent
+ property var _circleComponent
+ property var _mapPolygon: myGeoFenceController.mapPolygon
+ property bool _interactive: interactive
+ property bool _circleSupported: myGeoFenceController.circleRadiusFact !== null
+ property bool _circleEnabled: myGeoFenceController.circleEnabled
+ property real _circleRadius: _circleSupported ? myGeoFenceController.circleRadiusFact.rawValue : 0
+ property bool _polygonSupported: myGeoFenceController.polygonSupported
+ property bool _polygonEnabled: myGeoFenceController.polygonEnabled
- function _addVisualElements() {
- _polygonComponent = polygonComponent.createObject(map)
- map.addMapItem(_polygonComponent)
+ Component.onCompleted: {
_circleComponent = circleComponent.createObject(map)
map.addMapItem(_circleComponent)
_breachReturnPointComponent = breachReturnPointComponent.createObject(map)
@@ -46,71 +47,17 @@ Item {
_mouseAreaComponent = mouseAreaComponent.createObject(map)
}
- function _destroyVisualElements() {
- _polygonComponent.destroy()
+ Component.onDestruction: {
_circleComponent.destroy()
_breachReturnPointComponent.destroy()
_mouseAreaComponent.destroy()
}
- function _addDragHandles() {
- if (!_dragHandles) {
- _dragHandles = dragHandlesComponent.createObject(map)
- }
- if (!_splitHandles) {
- _splitHandles = splitHandlesComponent.createObject(map)
- }
- }
-
- function _destroyDragHandles() {
- if (_dragHandles) {
- _dragHandles.destroy()
- _dragHandles = undefined
- }
- if (_splitHandles) {
- _splitHandles.destroy()
- _splitHandles = undefined
- }
- }
-
- /// Add an initial 4 sided polygon if there is none
- function _addInitialPolygon() {
- // Initial polygon is inset to take 2/3rds space
- var rect = map.centerViewport
- rect.x += (rect.width * 0.25) / 2
- rect.y += (rect.height * 0.25) / 2
- rect.width *= 0.75
- rect.height *= 0.75
- var topLeft = Qt.point(rect.x, rect.y)
- var topRight = Qt.point(rect.x + rect.width, rect.y)
- var bottomLeft = Qt.point(rect.x, rect.y + rect.height)
- var bottomRight = Qt.point(rect.x + rect.width, rect.y + rect.height)
- _mapPolygon.clear()
- _mapPolygon.appendVertex(map.toCoordinate(topLeft, false /* clipToViewPort */))
- _mapPolygon.appendVertex(map.toCoordinate(topRight, false /* clipToViewPort */))
- _mapPolygon.appendVertex(map.toCoordinate(bottomRight, false /* clipToViewPort */))
- _mapPolygon.appendVertex(map.toCoordinate(bottomLeft, false /* clipToViewPort */))
- }
-
- Component.onCompleted: {
- _addVisualElements()
- _addDragHandles()
- }
-
- Component.onDestruction: {
- _destroyVisualElements()
- _destroyDragHandles()
- }
-
Connections {
- target: myGeoFenceController
-
- onAddFencePolygon: {
- _addInitialPolygon()
- }
+ target: myGeoFenceController
+ onAddInitialFencePolygon: mapPolygonVisuals.addInitialPolygon()
}
-
// Mouse area to capture breach return point coordinate
Component {
id: mouseAreaComponent
@@ -122,19 +69,14 @@ Item {
}
}
- // GeoFence polygon
- Component {
- id: polygonComponent
-
- MapPolygon {
- z: QGroundControl.zOrderMapItems
- border.width: 2
- border.color: "orange"
- color: "transparent"
- opacity: 0.5
- path: _mapPolygon.path
- visible: planView || geoFenceController.polygonEnabled
- }
+ QGCMapPolygonVisuals {
+ id: mapPolygonVisuals
+ mapControl: map
+ mapPolygon: _mapPolygon
+ interactive: _interactive
+ borderWidth: 2
+ borderColor: "orange"
+ visible: _polygonSupported && (planView || _polygonEnabled)
}
// GeoFence circle
@@ -147,152 +89,8 @@ Item {
border.color: "orange"
color: "transparent"
center: homePosition ? homePosition : QtPositioning.coordinate()
- radius: myGeoFenceController.circleRadius
- visible: planView || geoFenceController.circleEnabled
- }
- }
-
- Component {
- id: splitHandleComponent
-
- MapQuickItem {
- id: mapQuickItem
- anchorPoint.x: dragHandle.width / 2
- anchorPoint.y: dragHandle.height / 2
- z: QGroundControl.zOrderMapItems + 1
- visible: interactive
-
- property int vertexIndex
-
- sourceItem: Rectangle {
- id: dragHandle
- width: ScreenTools.defaultFontPixelHeight * 1.5
- height: width
- radius: width / 2
- color: "white"
- opacity: .50
-
- QGCLabel {
- anchors.horizontalCenter: parent.horizontalCenter
- anchors.verticalCenter: parent.verticalCenter
- text: "+"
- }
-
- QGCMouseArea {
- fillItem: parent
- onClicked: _mapPolygon.splitPolygonSegment(mapQuickItem.vertexIndex)
- }
- }
- }
- }
-
- Component {
- id: splitHandlesComponent
-
- Repeater {
- model: _mapPolygon.path.length > 2 ? _mapPolygon.path : 0
-
- delegate: Item {
- property var _splitHandle
- property var _vertices: _mapPolygon.path
-
- function _setHandlePosition() {
- var nextIndex = index + 1
- if (nextIndex > _vertices.length - 1) {
- nextIndex = 0
- }
- var distance = _vertices[index].distanceTo(_vertices[nextIndex])
- var azimuth = _vertices[index].azimuthTo(_vertices[nextIndex])
- _splitHandle.coordinate = _vertices[index].atDistanceAndAzimuth(distance / 2, azimuth)
- }
-
- Component.onCompleted: {
- _splitHandle = splitHandleComponent.createObject(map)
- _splitHandle.vertexIndex = index
- _setHandlePosition()
- map.addMapItem(_splitHandle)
- }
-
- Component.onDestruction: {
- _splitHandle.destroy()
- }
- }
- }
- }
-
- // Control which is used to drag polygon vertices
- Component {
- id: dragAreaComponent
-
- MissionItemIndicatorDrag {
- id: dragArea
- visible: interactive
-
- property int polygonVertex
-
- property bool _creationComplete: false
-
- Component.onCompleted: _creationComplete = true
-
- onItemCoordinateChanged: {
- if (_creationComplete) {
- // During component creation some bad coordinate values got through which screws up polygon draw
- _mapPolygon.adjustVertex(polygonVertex, itemCoordinate)
- }
- }
-
- onClicked: _mapPolygon.removePolygonVertex(polygonVertex)
- }
- }
-
- Component {
- id: dragHandleComponent
-
- MapQuickItem {
- id: mapQuickItem
- anchorPoint.x: dragHandle.width / 2
- anchorPoint.y: dragHandle.height / 2
- z: QGroundControl.zOrderMapItems + 2
- visible: interactive
-
- sourceItem: Rectangle {
- id: dragHandle
- width: ScreenTools.defaultFontPixelHeight * 1.5
- height: width
- radius: width / 2
- color: "white"
- opacity: .90
- }
- }
- }
-
- // Add all polygon vertex drag handles to the map
- Component {
- id: dragHandlesComponent
-
- Repeater {
- model: _mapPolygon.pathModel
-
- delegate: Item {
- property var _visuals: [ ]
-
- Component.onCompleted: {
- var dragHandle = dragHandleComponent.createObject(map)
- dragHandle.coordinate = Qt.binding(function() { return object.coordinate })
- map.addMapItem(dragHandle)
- var dragArea = dragAreaComponent.createObject(map, { "itemIndicator": dragHandle, "itemCoordinate": object.coordinate })
- dragArea.polygonVertex = Qt.binding(function() { return index })
- _visuals.push(dragHandle)
- _visuals.push(dragArea)
- }
-
- Component.onDestruction: {
- for (var i=0; i<_visuals.length; i++) {
- _visuals[i].destroy()
- }
- _visuals = [ ]
- }
- }
+ radius: _circleRadius
+ visible: _circleSupported && _circleRadius > 0 && (planView || _circleEnabled)
}
}
diff --git a/src/PlanView/PlanView.qml b/src/PlanView/PlanView.qml
index c7a950531fe0a78cf10cbcbfb7471dbf45d8eb3c..b6b9d4e5e723ff8b748faa4dd6d9127f0f73fead 100644
--- a/src/PlanView/PlanView.qml
+++ b/src/PlanView/PlanView.qml
@@ -239,6 +239,10 @@ QGCView {
function fitViewportToItems() {
mapFitFunctions.fitMapViewportToFenceItems()
}
+
+ function upload() {
+ sendToVehicle()
+ }
}
RallyPointController {
@@ -274,6 +278,10 @@ QGCView {
function fitViewportToItems() {
mapFitFunctions.fitMapViewportToRallyItems()
}
+
+ function upload() {
+ sendToVehicle()
+ }
}
QGCPalette { id: qgcPal; colorGroupEnabled: enabled }
@@ -505,6 +513,7 @@ QGCView {
z: QGroundControl.zOrderMapItems - 1
}
}
+
GeoFenceMapVisuals {
map: editorMap
myGeoFenceController: geoFenceController
@@ -513,35 +522,11 @@ QGCView {
planView: true
}
- // Rally points on map
-
- MapItemView {
- model: rallyPointController.points
-
- delegate: MapQuickItem {
- id: itemIndicator
- anchorPoint.x: sourceItem.anchorPointX
- anchorPoint.y: sourceItem.anchorPointY
- coordinate: object.coordinate
- z: QGroundControl.zOrderMapItems
-
- sourceItem: MissionItemIndexLabel {
- id: itemIndexLabel
- label: qsTr("R", "rally point map item label")
- checked: _editingLayer == _layerRallyPoints ? object == rallyPointController.currentRallyPoint : false
-
- onClicked: rallyPointController.currentRallyPoint = object
-
- onCheckedChanged: {
- if (checked) {
- // Setup our drag item
- itemDragger.visible = true
- itemDragger.coordinateItem = Qt.binding(function() { return object })
- itemDragger.mapCoordinateIndicator = Qt.binding(function() { return itemIndicator })
- }
- }
- }
- }
+ RallyPointMapVisuals {
+ map: editorMap
+ myRallyPointController: rallyPointController
+ interactive: _editingLayer == _layerRallyPoints
+ planView: true
}
ToolStrip {
@@ -632,11 +617,12 @@ QGCView {
// Plan Element selector (Mission/Fence/Rally)
Row {
id: planElementSelectorRow
+ anchors.topMargin: Math.round(ScreenTools.defaultFontPixelHeight / 3)
anchors.top: parent.top
anchors.left: parent.left
anchors.right: parent.right
spacing: _horizontalMargin
- visible: false // WIP: Temporarily remove - QGroundControl.corePlugin.options.enablePlanViewSelector
+ visible: QGroundControl.corePlugin.options.enablePlanViewSelector
readonly property real _buttonRadius: ScreenTools.defaultFontPixelHeight * 0.75
@@ -657,7 +643,6 @@ QGCView {
_syncDropDownController = rallyPointController
break
}
- _syncDropDownController.fitViewportToItems()
}
}
@@ -742,22 +727,23 @@ QGCView {
} // Item - Mission Item editor
// GeoFence Editor
- Loader {
- anchors.top: planElementSelectorRow.visible ? planElementSelectorRow.bottom : planElementSelectorRow.top
- anchors.left: parent.left
- anchors.right: parent.right
- sourceComponent: _editingLayer == _layerGeoFence ? geoFenceEditorComponent : undefined
-
- property real availableWidth: _rightPanelWidth
- property real availableHeight: ScreenTools.availableHeight
- property var myGeoFenceController: geoFenceController
+ GeoFenceEditor {
+ anchors.topMargin: ScreenTools.defaultFontPixelHeight / 2
+ anchors.top: planElementSelectorRow.bottom
+ anchors.left: parent.left
+ anchors.right: parent.right
+ availableHeight: ScreenTools.availableHeight
+ myGeoFenceController: geoFenceController
+ flightMap: editorMap
+ visible: _editingLayer == _layerGeoFence
}
// Rally Point Editor
RallyPointEditorHeader {
id: rallyPointHeader
- anchors.top: planElementSelectorRow.visible ? planElementSelectorRow.bottom : planElementSelectorRow.top
+ anchors.topMargin: ScreenTools.defaultFontPixelHeight / 2
+ anchors.top: planElementSelectorRow.bottom
anchors.left: parent.left
anchors.right: parent.right
visible: _editingLayer == _layerRallyPoints
@@ -766,7 +752,8 @@ QGCView {
RallyPointItemEditor {
id: rallyPointEditor
- anchors.top: planElementSelectorRow.visible ? planElementSelectorRow.bottom : planElementSelectorRow.top
+ anchors.topMargin: ScreenTools.defaultFontPixelHeight / 2
+ anchors.top: rallyPointHeader.bottom
anchors.left: parent.left
anchors.right: parent.right
visible: _editingLayer == _layerRallyPoints && rallyPointController.points.count
@@ -831,19 +818,6 @@ QGCView {
}
}
-
-
- Component {
- id: geoFenceEditorComponent
-
- GeoFenceEditor {
- availableWidth: _rightPanelWidth
- availableHeight: ScreenTools.availableHeight
- myGeoFenceController: geoFenceController
- flightMap: editorMap
- }
- }
-
//- ToolStrip DropPanel Components
Component {
diff --git a/src/PlanView/QGCMapPolygonControls.qml b/src/PlanView/QGCMapPolygonControls.qml
deleted file mode 100644
index 114f05bb343ca1d4785ffe195e396bf4e23d5d2d..0000000000000000000000000000000000000000
--- a/src/PlanView/QGCMapPolygonControls.qml
+++ /dev/null
@@ -1,79 +0,0 @@
-import QtQuick 2.3
-import QtQuick.Controls 1.2
-
-import QGroundControl.ScreenTools 1.0
-import QGroundControl.Controls 1.0
-import QGroundControl.Palette 1.0
-
-/// Controls for drawing/editing map polygon
-Column {
- id: root
- spacing: _margin
-
- property var sectionLabel: qsTr("Polygon:") ///< Section label
- property var flightMap ///< Must be set to FlightMap control
- property var polygon ///< Must be set to MapPolygon
-
- signal polygonEditCompleted ///< Signalled when either a capture or adjust has completed
-
- property real _margin: ScreenTools.defaultFontPixelWidth / 2
-
- function polygonCaptureStarted() {
- polygon.clear()
- }
-
- function polygonCaptureFinished(coordinates) {
- polygon.path = coordinates
- polygonEditCompleted()
- }
-
- function polygonAdjustVertex(vertexIndex, vertexCoordinate) {
- polygon.adjustCoordinate(vertexIndex, vertexCoordinate)
- }
-
- function polygonAdjustStarted() { }
-
- function polygonAdjustFinished() {
- polygonEditCompleted()
- }
-
- QGCLabel { text: sectionLabel }
-
- Rectangle {
- anchors.left: parent.left
- anchors.right: parent.right
- height: 1
- color: qgcPal.text
- }
-
- Row {
- spacing: ScreenTools.defaultFontPixelWidth
-
- QGCButton {
- text: flightMap.polygonDraw.drawingPolygon ? qsTr("Finish Draw") : qsTr("Draw")
- visible: !flightMap.polygonDraw.adjustingPolygon
- enabled: ((flightMap.polygonDraw.drawingPolygon && flightMap.polygonDraw.polygonReady) || !flightMap.polygonDraw.drawingPolygon)
-
- onClicked: {
- if (flightMap.polygonDraw.drawingPolygon) {
- flightMap.polygonDraw.finishCapturePolygon()
- } else {
- flightMap.polygonDraw.startCapturePolygon(root)
- }
- }
- }
-
- QGCButton {
- text: flightMap.polygonDraw.adjustingPolygon ? qsTr("Finish Adjust") : qsTr("Adjust")
- visible: polygon.path.length > 0 && !flightMap.polygonDraw.drawingPolygon
-
- onClicked: {
- if (flightMap.polygonDraw.adjustingPolygon) {
- flightMap.polygonDraw.finishAdjustPolygon()
- } else {
- flightMap.polygonDraw.startAdjustPolygon(root, polygon.path)
- }
- }
- }
- }
-}
diff --git a/src/PlanView/RallyPointEditorHeader.qml b/src/PlanView/RallyPointEditorHeader.qml
index 4e271b51af7fc11dc1a765542ae1be9accecddef..7f99828d3bc715de84a939cc1dc91133c6503f45 100644
--- a/src/PlanView/RallyPointEditorHeader.qml
+++ b/src/PlanView/RallyPointEditorHeader.qml
@@ -27,7 +27,7 @@ QGCFlickable {
anchors.margins: _margin
anchors.left: parent.left
anchors.top: parent.top
- text: qsTr("Rally Points (WIP careful!)")
+ text: qsTr("Rally Points")
color: "black"
}
@@ -37,7 +37,7 @@ QGCFlickable {
anchors.left: parent.left
anchors.right: parent.right
anchors.top: editorLabel.bottom
- height: infoLabel.height + helpLabel.height + (_margin * 2)
+ height: helpLabel.height + helpLabel.height + (_margin * 2)
color: qgcPal.windowShadeDark
radius: _radius
diff --git a/src/PlanView/RallyPointMapVisuals.qml b/src/PlanView/RallyPointMapVisuals.qml
new file mode 100644
index 0000000000000000000000000000000000000000..1f05dfc30fb50834a56bb71c0df467147eb4567d
--- /dev/null
+++ b/src/PlanView/RallyPointMapVisuals.qml
@@ -0,0 +1,98 @@
+/****************************************************************************
+ *
+ * (c) 2009-2016 QGROUNDCONTROL PROJECT
+ *
+ * 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
+
+/// Rally Point map visuals
+Item {
+ z: QGroundControl.zOrderMapItems
+
+ property var map
+ property var myRallyPointController
+ property bool interactive: false ///< true: user can interact with items
+ property bool planView: false ///< true: visuals showing in plan view
+
+ property bool _interactive: interactive
+ property var _rallyPointsComponent
+ property bool _rallyPointsSupported: myRallyPointController.rallyPointsSupported
+ property var _rallyPoints: myRallyPointController.points
+
+ Component.onCompleted: {
+ _rallyPointsComponent = rallyPointsComponent.createObject(map)
+ }
+
+ Component.onDestruction: {
+ _rallyPointsComponent.destroy()
+ }
+
+ Component {
+ id: rallyPointComponent
+
+ MapQuickItem {
+ id: itemIndicator
+ anchorPoint.x: sourceItem.anchorPointX
+ anchorPoint.y: sourceItem.anchorPointY
+ z: QGroundControl.zOrderMapItems
+
+ property var rallyPointObject
+
+ sourceItem: MissionItemIndexLabel {
+ id: itemIndexLabel
+ label: qsTr("R", "rally point map item label")
+ checked: _editingLayer == _layerRallyPoints ? rallyPointObject == myRallyPointController.currentRallyPoint : false
+
+ onClicked: myRallyPointController.currentRallyPoint = rallyPointObject
+ }
+ }
+ }
+
+ // Add all rally points to the map
+ Component {
+ id: rallyPointsComponent
+
+ Repeater {
+ model: _rallyPoints
+
+ delegate: Item {
+ property var _visuals: [ ]
+
+ Component.onCompleted: {
+ var rallyPoint = rallyPointComponent.createObject(map)
+ rallyPoint.coordinate = Qt.binding(function() { return object.coordinate })
+ rallyPoint.rallyPointObject = Qt.binding(function() { return object })
+ map.addMapItem(rallyPoint)
+ _visuals.push(rallyPoint)
+/*
+ var dragArea = dragAreaComponent.createObject(map, { "itemIndicator": dragHandle, "itemCoordinate": object.coordinate })
+ dragArea.polygonVertex = Qt.binding(function() { return index })
+ _visuals.push(dragHandle)
+ _visuals.push(dragArea)
+*/
+ }
+
+ Component.onDestruction: {
+ for (var i=0; i<_visuals.length; i++) {
+ _visuals[i].destroy()
+ }
+ _visuals = [ ]
+ }
+ }
+ }
+ }
+
+}
diff --git a/src/PlanView/SurveyMapVisual.qml b/src/PlanView/SurveyMapVisual.qml
index e46205f7a6f27090bb00d90cdf8d6730a46be0e4..4110ddcbe9e0c675ab50c70c9ac8175c7582400f 100644
--- a/src/PlanView/SurveyMapVisual.qml
+++ b/src/PlanView/SurveyMapVisual.qml
@@ -88,28 +88,14 @@ Item {
}
QGCMapPolygonVisuals {
- id: mapPolygonVisuals
- mapControl: map
- mapPolygon: _mapPolygon
-
- Component.onCompleted: {
- mapPolygonVisuals.addVisuals()
- if (_missionItem.isCurrentItem) {
- mapPolygonVisuals.addHandles()
- }
- }
-
- Connections {
- target: _missionItem
-
- onIsCurrentItemChanged: {
- if (_missionItem.isCurrentItem) {
- mapPolygonVisuals.addHandles()
- } else {
- mapPolygonVisuals.removeHandles()
- }
- }
- }
+ id: mapPolygonVisuals
+ mapControl: map
+ mapPolygon: _mapPolygon
+ interactive: _missionItem.isCurrentItem
+ borderWidth: 1
+ borderColor: "black"
+ interiorColor: "green"
+ interiorOpacity: 0.5
}
// Survey grid lines
diff --git a/src/QmlControls/QGroundControl.Controls.qmldir b/src/QmlControls/QGroundControl.Controls.qmldir
index 11503bb22a357c0e11c247ed9e62c72c6db792f2..813cd7436176c1e7da8b6a2033a5ee2c91d9c61b 100644
--- a/src/QmlControls/QGroundControl.Controls.qmldir
+++ b/src/QmlControls/QGroundControl.Controls.qmldir
@@ -28,6 +28,7 @@ ParameterEditorDialog 1.0 ParameterEditorDialog.qml
PlanToolBar 1.0 PlanToolBar.qml
RallyPointEditorHeader 1.0 RallyPointEditorHeader.qml
RallyPointItemEditor 1.0 RallyPointItemEditor.qml
+RallyPointMapVisuals 1.0 RallyPointMapVisuals.qml
RCChannelMonitor 1.0 RCChannelMonitor.qml
QGCButton 1.0 QGCButton.qml
QGCCheckBox 1.0 QGCCheckBox.qml