Commit 557c1e1f authored by DonLakeFlyer's avatar DonLakeFlyer

GeoFence, Rally Point support reworked and back on

parent d2ef6d01
...@@ -101,6 +101,7 @@ ...@@ -101,6 +101,7 @@
<file alias="QGroundControl/Controls/qmldir">src/QmlControls/QGroundControl.Controls.qmldir</file> <file alias="QGroundControl/Controls/qmldir">src/QmlControls/QGroundControl.Controls.qmldir</file>
<file alias="QGroundControl/Controls/RallyPointEditorHeader.qml">src/PlanView/RallyPointEditorHeader.qml</file> <file alias="QGroundControl/Controls/RallyPointEditorHeader.qml">src/PlanView/RallyPointEditorHeader.qml</file>
<file alias="QGroundControl/Controls/RallyPointItemEditor.qml">src/PlanView/RallyPointItemEditor.qml</file> <file alias="QGroundControl/Controls/RallyPointItemEditor.qml">src/PlanView/RallyPointItemEditor.qml</file>
<file alias="QGroundControl/Controls/RallyPointMapVisuals.qml">src/PlanView/RallyPointMapVisuals.qml</file>
<file alias="QGroundControl/Controls/RCChannelMonitor.qml">src/QmlControls/RCChannelMonitor.qml</file> <file alias="QGroundControl/Controls/RCChannelMonitor.qml">src/QmlControls/RCChannelMonitor.qml</file>
<file alias="QGroundControl/Controls/RoundButton.qml">src/QmlControls/RoundButton.qml</file> <file alias="QGroundControl/Controls/RoundButton.qml">src/QmlControls/RoundButton.qml</file>
<file alias="QGroundControl/Controls/SectionHeader.qml">src/PlanView/SectionHeader.qml</file> <file alias="QGroundControl/Controls/SectionHeader.qml">src/PlanView/SectionHeader.qml</file>
...@@ -152,7 +153,6 @@ ...@@ -152,7 +153,6 @@
<file alias="QGroundControl/FlightMap/QGCCompassWidget.qml">src/FlightMap/Widgets/QGCCompassWidget.qml</file> <file alias="QGroundControl/FlightMap/QGCCompassWidget.qml">src/FlightMap/Widgets/QGCCompassWidget.qml</file>
<file alias="QGCInstrumentWidget.qml">src/FlightMap/Widgets/QGCInstrumentWidget.qml</file> <file alias="QGCInstrumentWidget.qml">src/FlightMap/Widgets/QGCInstrumentWidget.qml</file>
<file alias="QGCInstrumentWidgetAlternate.qml">src/FlightMap/Widgets/QGCInstrumentWidgetAlternate.qml</file> <file alias="QGCInstrumentWidgetAlternate.qml">src/FlightMap/Widgets/QGCInstrumentWidgetAlternate.qml</file>
<file alias="QGroundControl/FlightMap/QGCMapPolygonControls.qml">src/PlanView/QGCMapPolygonControls.qml</file>
<file alias="QGroundControl/FlightMap/QGCPitchIndicator.qml">src/FlightMap/Widgets/QGCPitchIndicator.qml</file> <file alias="QGroundControl/FlightMap/QGCPitchIndicator.qml">src/FlightMap/Widgets/QGCPitchIndicator.qml</file>
<file alias="QGroundControl/FlightMap/QGCVideoBackground.qml">src/FlightMap/QGCVideoBackground.qml</file> <file alias="QGroundControl/FlightMap/QGCVideoBackground.qml">src/FlightMap/QGCVideoBackground.qml</file>
<file alias="QGroundControl/FlightMap/qmldir">src/FlightMap/qmldir</file> <file alias="QGroundControl/FlightMap/qmldir">src/FlightMap/qmldir</file>
...@@ -215,7 +215,4 @@ ...@@ -215,7 +215,4 @@
<file alias="APMArduSubMockLink.params">src/comm/APMArduSubMockLink.params</file> <file alias="APMArduSubMockLink.params">src/comm/APMArduSubMockLink.params</file>
<file alias="PX4MockLink.params">src/comm/PX4MockLink.params</file> <file alias="PX4MockLink.params">src/comm/PX4MockLink.params</file>
</qresource> </qresource>
<qresource prefix="/FirmwarePlugin">
<file alias="NoGeoFenceEditor.qml">src/FirmwarePlugin/NoGeoFenceEditor.qml</file>
</qresource>
</RCC> </RCC>
...@@ -23,9 +23,10 @@ const char* APMGeoFenceManager::_fenceEnableParam = "FENCE_ENABLE"; ...@@ -23,9 +23,10 @@ const char* APMGeoFenceManager::_fenceEnableParam = "FENCE_ENABLE";
APMGeoFenceManager::APMGeoFenceManager(Vehicle* vehicle) APMGeoFenceManager::APMGeoFenceManager(Vehicle* vehicle)
: GeoFenceManager(vehicle) : GeoFenceManager(vehicle)
, _fenceSupported(false) , _fenceSupported(false)
, _breachReturnEnabled(vehicle->fixedWing())
, _circleEnabled(false) , _circleEnabled(false)
, _polygonSupported(false)
, _polygonEnabled(false) , _polygonEnabled(false)
, _breachReturnSupported(vehicle->fixedWing())
, _firstParamLoadComplete(false) , _firstParamLoadComplete(false)
, _readTransactionInProgress(false) , _readTransactionInProgress(false)
, _writeTransactionInProgress(false) , _writeTransactionInProgress(false)
...@@ -223,27 +224,43 @@ bool APMGeoFenceManager::inProgress(void) const ...@@ -223,27 +224,43 @@ bool APMGeoFenceManager::inProgress(void) const
return _readTransactionInProgress || _writeTransactionInProgress; return _readTransactionInProgress || _writeTransactionInProgress;
} }
void APMGeoFenceManager::_setCircleEnabled(bool circleEnabled)
{
if (circleEnabled != _circleEnabled) {
_circleEnabled = circleEnabled;
emit circleEnabledChanged(circleEnabled);
}
}
void APMGeoFenceManager::_setPolygonEnabled(bool polygonEnabled)
{
if (polygonEnabled != _polygonEnabled) {
_polygonEnabled = polygonEnabled;
emit polygonEnabledChanged(polygonEnabled);
}
}
void APMGeoFenceManager::_updateEnabledFlags(void) void APMGeoFenceManager::_updateEnabledFlags(void)
{ {
bool fenceEnabled; bool fenceEnabled = false;
if (_fenceSupported) {
if (_fenceEnableFact) { if (_fenceEnableFact) {
fenceEnabled = _fenceEnableFact->rawValue().toBool(); fenceEnabled = _fenceEnableFact->rawValue().toBool();
} else { } else {
fenceEnabled = true; fenceEnabled = true;
} }
bool newCircleEnabled = _fenceSupported && fenceEnabled && _fenceTypeFact && (_fenceTypeFact->rawValue().toInt() & 2); bool newCircleEnabled = fenceEnabled && _fenceTypeFact && (_fenceTypeFact->rawValue().toInt() & 2);
if (newCircleEnabled != _circleEnabled) { _setCircleEnabled(newCircleEnabled);
_circleEnabled = newCircleEnabled;
emit circleEnabledChanged(newCircleEnabled);
}
bool newPolygonEnabled = _fenceSupported && fenceEnabled && bool newPolygonEnabled = _fenceSupported && fenceEnabled &&
((_vehicle->multiRotor() && _fenceTypeFact && (_fenceTypeFact->rawValue().toInt() & 4)) || ((_vehicle->multiRotor() && _fenceTypeFact && (_fenceTypeFact->rawValue().toInt() & 4)) ||
_vehicle->fixedWing()); _vehicle->fixedWing());
if (newPolygonEnabled != _polygonEnabled) { _setPolygonEnabled(newPolygonEnabled);
_polygonEnabled = newPolygonEnabled; } else {
emit polygonEnabledChanged(newPolygonEnabled); _setCircleEnabled(false);
_setPolygonEnabled(false);
} }
} }
...@@ -260,24 +277,26 @@ void APMGeoFenceManager::_parametersReady(void) ...@@ -260,24 +277,26 @@ void APMGeoFenceManager::_parametersReady(void)
QStringList paramNames; QStringList paramNames;
QStringList paramLabels; QStringList paramLabels;
_polygonSupported = true;
if (_vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, _fenceEnableParam)) { if (_vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, _fenceEnableParam)) {
_fenceEnableFact = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, _fenceEnableParam); _fenceEnableFact = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, _fenceEnableParam);
connect(_fenceEnableFact, &Fact::rawValueChanged, this, &APMGeoFenceManager::_updateEnabledFlags); connect(_fenceEnableFact, &Fact::rawValueChanged, this, &APMGeoFenceManager::_updateEnabledFlags);
} }
if (_vehicle->multiRotor()) { if (_vehicle->multiRotor()) {
_breachReturnSupported = false;
_fenceTypeFact = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, QStringLiteral("FENCE_TYPE")); _fenceTypeFact = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, QStringLiteral("FENCE_TYPE"));
connect(_fenceTypeFact, &Fact::rawValueChanged, this, &APMGeoFenceManager::_updateEnabledFlags); connect(_fenceTypeFact, &Fact::rawValueChanged, this, &APMGeoFenceManager::_updateEnabledFlags);
_circleRadiusFact = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, QStringLiteral("FENCE_RADIUS")); _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") paramNames << QStringLiteral("FENCE_ENABLE") << QStringLiteral("FENCE_TYPE") << QStringLiteral("FENCE_ACTION") << QStringLiteral("FENCE_ALT_MAX")
<< QStringLiteral("FENCE_RADIUS") << QStringLiteral("FENCE_MARGIN"); << QStringLiteral("FENCE_RADIUS") << QStringLiteral("FENCE_MARGIN");
paramLabels << QStringLiteral("Enabled:") << QStringLiteral("Type:") << QStringLiteral("Breach Action:") << QStringLiteral("Max Altitude:") paramLabels << QStringLiteral("Enabled:") << QStringLiteral("Type:") << QStringLiteral("Breach Action:") << QStringLiteral("Max Altitude:")
<< QStringLiteral("Radius:") << QStringLiteral("Margin:"); << QStringLiteral("Radius:") << QStringLiteral("Margin:");
} if (_vehicle->fixedWing()) { } if (_vehicle->fixedWing()) {
_breachReturnSupported = true;
paramNames << QStringLiteral("FENCE_ACTION") << QStringLiteral("FENCE_MINALT") << QStringLiteral("FENCE_MAXALT") << QStringLiteral("FENCE_RETALT") paramNames << QStringLiteral("FENCE_ACTION") << QStringLiteral("FENCE_MINALT") << QStringLiteral("FENCE_MAXALT") << QStringLiteral("FENCE_RETALT")
<< QStringLiteral("FENCE_AUTOENABLE") << QStringLiteral("FENCE_RET_RALLY"); << QStringLiteral("FENCE_AUTOENABLE") << QStringLiteral("FENCE_RET_RALLY");
paramLabels << QStringLiteral("Breach Action:") << QStringLiteral("Min Altitude:") << QStringLiteral("Max Altitude:") << QStringLiteral("Return Altitude:") paramLabels << QStringLiteral("Breach Action:") << QStringLiteral("Min Altitude:") << QStringLiteral("Max Altitude:") << QStringLiteral("Return Altitude:")
...@@ -297,36 +316,11 @@ void APMGeoFenceManager::_parametersReady(void) ...@@ -297,36 +316,11 @@ void APMGeoFenceManager::_parametersReady(void)
emit paramsChanged(_params); emit paramsChanged(_params);
emit paramLabelsChanged(_paramLabels); emit paramLabelsChanged(_paramLabels);
_updateEnabledFlags(); emit breachReturnSupportedChanged(_breachReturnSupported);
emit polygonSupportedChanged(_polygonSupported);
} }
qCDebug(GeoFenceManagerLog) << "fenceSupported:circleEnabled:polygonEnabled:breachReturnEnabled" << _updateEnabledFlags();
_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");
} }
} }
......
...@@ -28,30 +28,32 @@ public: ...@@ -28,30 +28,32 @@ public:
bool inProgress (void) const final; bool inProgress (void) const final;
void loadFromVehicle (void) final; void loadFromVehicle (void) final;
void sendToVehicle (const QGeoCoordinate& breachReturn, QmlObjectListModel& polygon) final; void sendToVehicle (const QGeoCoordinate& breachReturn, QmlObjectListModel& polygon) final;
bool circleEnabled (void) const final { return _circleEnabled; } bool polygonSupported (void) const final { return _polygonSupported; }
bool polygonEnabled (void) const final { return _polygonEnabled; } bool polygonEnabled (void) const final { return _polygonEnabled; }
bool breachReturnEnabled (void) const final { return _breachReturnEnabled; } bool breachReturnSupported (void) const final { return _breachReturnSupported; }
float circleRadius (void) const final; bool circleEnabled (void) const { return _circleEnabled; }
Fact* circleRadiusFact (void) const { return _circleRadiusFact; }
QVariantList params (void) const final { return _params; } QVariantList params (void) const final { return _params; }
QStringList paramLabels (void) const final { return _paramLabels; } QStringList paramLabels (void) const final { return _paramLabels; }
QString editorQml (void) const final;
void removeAll (void) final; void removeAll (void) final;
private slots: private slots:
void _mavlinkMessageReceived(const mavlink_message_t& message); void _mavlinkMessageReceived (const mavlink_message_t& message);
void _updateEnabledFlags(void); void _parametersReady (void);
void _circleRadiusRawValueChanged(QVariant value);
void _parametersReady(void);
private: private:
void _requestFencePoint(uint8_t pointIndex); void _requestFencePoint (uint8_t pointIndex);
void _sendFencePoint(uint8_t pointIndex); void _sendFencePoint (uint8_t pointIndex);
void _updateEnabledFlags(void);
void _setCircleEnabled (bool circleEnabled);
void _setPolygonEnabled (bool polygonEnabled);
private: private:
bool _fenceSupported; bool _fenceSupported;
bool _breachReturnEnabled;
bool _circleEnabled; bool _circleEnabled;
bool _polygonSupported;
bool _polygonEnabled; bool _polygonEnabled;
bool _breachReturnSupported;
bool _firstParamLoadComplete; bool _firstParamLoadComplete;
QVariantList _params; QVariantList _params;
......
...@@ -51,8 +51,6 @@ ...@@ -51,8 +51,6 @@
<file alias="APMParameterFactMetaData.Rover.3.2.xml">APMParameterFactMetaData.Rover.3.2.xml</file> <file alias="APMParameterFactMetaData.Rover.3.2.xml">APMParameterFactMetaData.Rover.3.2.xml</file>
<file alias="APMParameterFactMetaData.Sub.3.4.xml">APMParameterFactMetaData.Sub.3.4.xml</file> <file alias="APMParameterFactMetaData.Sub.3.4.xml">APMParameterFactMetaData.Sub.3.4.xml</file>
<file alias="APMParameterFactMetaData.Sub.3.5.xml">APMParameterFactMetaData.Sub.3.5.xml</file> <file alias="APMParameterFactMetaData.Sub.3.5.xml">APMParameterFactMetaData.Sub.3.5.xml</file>
<file alias="CopterGeoFenceEditor.qml">CopterGeoFenceEditor.qml</file>
<file alias="PlaneGeoFenceEditor.qml">PlaneGeoFenceEditor.qml</file>
<file alias="Copter.OfflineEditing.params">Copter3.4.OfflineEditing.params</file> <file alias="Copter.OfflineEditing.params">Copter3.4.OfflineEditing.params</file>
<file alias="Plane.OfflineEditing.params">Plane3.7.OfflineEditing.params</file> <file alias="Plane.OfflineEditing.params">Plane3.7.OfflineEditing.params</file>
</qresource> </qresource>
......
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()
}
}
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<actionModel.count; i++) {
if (actionModel.get(i).actionValue == fenceAction.rawValue) {
actionCombo.currentIndex = i
return
}
}
actionCombo.currentIndex = 0
}
}
ExclusiveGroup { id: returnLocationRadioGroup }
property bool _returnPointUsed: fenceAction.rawValue == 1 || fenceAction.rawValue == 3
QGCRadioButton {
anchors.leftMargin: ScreenTools.defaultFontPixelWidth
anchors.left: parent.left
text: qsTr("Fly to breach return point")
checked: fenceRetRally.rawValue != 1
enabled: _returnPointUsed
exclusiveGroup: returnLocationRadioGroup
onClicked: fenceRetRally.rawValue = 0
}
QGCRadioButton {
anchors.leftMargin: ScreenTools.defaultFontPixelWidth
anchors.left: parent.left
text: qsTr("Fly to nearest rally point")
checked: fenceRetRally.rawValue == 1
enabled: _returnPointUsed
exclusiveGroup: returnLocationRadioGroup
onClicked: fenceRetRally.rawValue = 1
}
Item { width: 1; height: 1 }
GridLayout {
anchors.left: parent.left
anchors.right: parent.right
columnSpacing: ScreenTools.defaultFontPixelWidth
columns: 2
QGCCheckBox {
id: minAltFenceCheckBox
text: qsTr("Min altitude:")
checked: fenceMinAlt.value > 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()
}
}
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
}
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
}
}
}
...@@ -15,7 +15,6 @@ ...@@ -15,7 +15,6 @@
PX4GeoFenceManager::PX4GeoFenceManager(Vehicle* vehicle) PX4GeoFenceManager::PX4GeoFenceManager(Vehicle* vehicle)
: GeoFenceManager(vehicle) : GeoFenceManager(vehicle)
, _firstParamLoadComplete(false) , _firstParamLoadComplete(false)
, _circleEnabled(false)
, _circleRadiusFact(NULL) , _circleRadiusFact(NULL)
{ {
connect(_vehicle->parameterManager(), &ParameterManager::parametersReadyChanged, this, &PX4GeoFenceManager::_parametersReady); connect(_vehicle->parameterManager(), &ParameterManager::parametersReadyChanged, this, &PX4GeoFenceManager::_parametersReady);
...@@ -36,14 +35,13 @@ void PX4GeoFenceManager::_parametersReady(void) ...@@ -36,14 +35,13 @@ void PX4GeoFenceManager::_parametersReady(void)
_firstParamLoadComplete = true; _firstParamLoadComplete = true;
_circleRadiusFact = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, QStringLiteral("GF_MAX_HOR_DIST")); _circleRadiusFact = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, QStringLiteral("GF_MAX_HOR_DIST"));
connect(_circleRadiusFact, &Fact::rawValueChanged, this, &PX4GeoFenceManager::_circleRadiusRawValueChanged); emit circleRadiusFactChanged(_circleRadiusFact);
emit circleRadiusChanged(circleRadius());
QStringList paramNames; QStringList paramNames;
QStringList paramLabels; QStringList paramLabels;
paramNames << QStringLiteral("GF_ACTION") << QStringLiteral("GF_MAX_HOR_DIST") << QStringLiteral("GF_MAX_VER_DIST"); 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(); _params.clear();
_paramLabels.clear(); _paramLabels.clear();
...@@ -55,32 +53,8 @@ void PX4GeoFenceManager::_parametersReady(void) ...@@ -55,32 +53,8 @@ void PX4GeoFenceManager::_parametersReady(void)
_paramLabels << paramLabels[i]; _paramLabels << paramLabels[i];
} }
} }
emit paramsChanged(_params); emit paramsChanged(_params);
emit paramLabelsChanged(_paramLabels); 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
}
...@@ -23,25 +23,19 @@ public: ...@@ -23,25 +23,19 @@ public:
~PX4GeoFenceManager(); ~PX4GeoFenceManager();
// Overrides from GeoFenceManager // Overrides from GeoFenceManager
bool circleEnabled (void) const final { return _circleEnabled; } bool circleEnabled (void) const { return true; }
float circleRadius (void) const final; Fact* circleRadiusFact (void) const { return _circleRadiusFact; }
QVariantList params (void) const final { return _params; } QVariantList params (void) const final { return _params; }
QStringList paramLabels (void) const final { return _paramLabels; } QStringList paramLabels (void) const final { return _paramLabels; }
QString editorQml (void) const final { return QStringLiteral("qrc:/FirmwarePlugin/PX4/PX4GeoFenceEditor.qml"); }
void removeAll (void) final;
private slots: private slots:
void _circleRadiusRawValueChanged(QVariant value);
void _parametersReady(void); void _parametersReady(void);
private: private:
bool _firstParamLoadComplete; bool _firstParamLoadComplete;
Fact* _circleRadiusFact;
QVariantList _params; QVariantList _params;
QStringList _paramLabels; QStringList _paramLabels;
bool _circleEnabled;
Fact* _circleRadiusFact;
}; };
#endif #endif
...@@ -21,7 +21,6 @@ ...@@ -21,7 +21,6 @@
</qresource> </qresource>
<qresource prefix="/FirmwarePlugin/PX4"> <qresource prefix="/FirmwarePlugin/PX4">
<file alias="PX4ParameterFactMetaData.xml">PX4ParameterFactMetaData.xml</file> <file alias="PX4ParameterFactMetaData.xml">PX4ParameterFactMetaData.xml</file>
<file alias="PX4GeoFenceEditor.qml">PX4GeoFenceEditor.qml</file>
<file alias="PX4.OfflineEditing.params">V1.4.OfflineEditing.params</file> <file alias="PX4.OfflineEditing.params">V1.4.OfflineEditing.params</file>
</qresource> </qresource>
</RCC> </RCC>
...@@ -40,6 +40,8 @@ FlightMap { ...@@ -40,6 +40,8 @@ FlightMap {
property var rightPanelWidth property var rightPanelWidth
property var qgcView ///< QGCView control which contains this map 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 _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
property var _activeVehicleCoordinate: _activeVehicle ? _activeVehicle.coordinate : QtPositioning.coordinate() property var _activeVehicleCoordinate: _activeVehicle ? _activeVehicle.coordinate : QtPositioning.coordinate()
property var _gotoHereCoordinate: QtPositioning.coordinate() property var _gotoHereCoordinate: QtPositioning.coordinate()
...@@ -201,6 +203,7 @@ FlightMap { ...@@ -201,6 +203,7 @@ FlightMap {
map: flightMap map: flightMap
myGeoFenceController: geoFenceController myGeoFenceController: geoFenceController
interactive: false interactive: false
planView: false
homePosition: _activeVehicle && _activeVehicle.homePosition.isValid ? _activeVehicle.homePosition : undefined homePosition: _activeVehicle && _activeVehicle.homePosition.isValid ? _activeVehicle.homePosition : undefined
} }
......
...@@ -80,14 +80,12 @@ void GeoFenceController::setBreachReturnPoint(const QGeoCoordinate& breachReturn ...@@ -80,14 +80,12 @@ void GeoFenceController::setBreachReturnPoint(const QGeoCoordinate& breachReturn
void GeoFenceController::_signalAll(void) void GeoFenceController::_signalAll(void)
{ {
emit breachReturnSupportedChanged(breachReturnSupported());
emit breachReturnPointChanged(breachReturnPoint());
emit circleEnabledChanged(circleEnabled()); emit circleEnabledChanged(circleEnabled());
emit circleRadiusFactChanged(circleRadiusFact());
emit polygonEnabledChanged(polygonEnabled()); emit polygonEnabledChanged(polygonEnabled());
emit breachReturnEnabledChanged(breachReturnEnabled()); emit polygonSupportedChanged(polygonSupported());
emit breachReturnPointChanged(breachReturnPoint());
emit circleRadiusChanged(circleRadius());
emit paramsChanged(params());
emit paramLabelsChanged(paramLabels());
emit editorQmlChanged(editorQml());
emit dirtyChanged(dirty()); emit dirtyChanged(dirty());
} }
...@@ -99,13 +97,11 @@ void GeoFenceController::_activeVehicleBeingRemoved(void) ...@@ -99,13 +97,11 @@ void GeoFenceController::_activeVehicleBeingRemoved(void)
void GeoFenceController::_activeVehicleSet(void) void GeoFenceController::_activeVehicleSet(void)
{ {
GeoFenceManager* geoFenceManager = _activeVehicle->geoFenceManager(); GeoFenceManager* geoFenceManager = _activeVehicle->geoFenceManager();
connect(geoFenceManager, &GeoFenceManager::polygonEnabledChanged, this, &GeoFenceController::_setDirty); connect(geoFenceManager, &GeoFenceManager::breachReturnSupportedChanged, this, &GeoFenceController::breachReturnSupportedChanged);
connect(geoFenceManager, &GeoFenceManager::circleEnabledChanged, this, &GeoFenceController::circleEnabledChanged); connect(geoFenceManager, &GeoFenceManager::circleEnabledChanged, this, &GeoFenceController::circleEnabledChanged);
connect(geoFenceManager, &GeoFenceManager::circleRadiusFactChanged, this, &GeoFenceController::circleRadiusFactChanged);
connect(geoFenceManager, &GeoFenceManager::polygonEnabledChanged, this, &GeoFenceController::polygonEnabledChanged); connect(geoFenceManager, &GeoFenceManager::polygonEnabledChanged, this, &GeoFenceController::polygonEnabledChanged);
connect(geoFenceManager, &GeoFenceManager::breachReturnEnabledChanged, this, &GeoFenceController::breachReturnEnabledChanged); connect(geoFenceManager, &GeoFenceManager::polygonSupportedChanged, this, &GeoFenceController::polygonSupportedChanged);
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::loadComplete, this, &GeoFenceController::_loadComplete);
connect(geoFenceManager, &GeoFenceManager::inProgressChanged, this, &GeoFenceController::syncInProgressChanged); connect(geoFenceManager, &GeoFenceManager::inProgressChanged, this, &GeoFenceController::syncInProgressChanged);
...@@ -134,78 +130,19 @@ bool GeoFenceController::_loadJsonFile(QJsonDocument& jsonDoc, QString& errorStr ...@@ -134,78 +130,19 @@ bool GeoFenceController::_loadJsonFile(QJsonDocument& jsonDoc, QString& errorStr
return false; return false;
} }
if (breachReturnEnabled()) {
if (json.contains(_jsonBreachReturnKey) if (json.contains(_jsonBreachReturnKey)
&& !JsonHelper::loadGeoCoordinate(json[_jsonBreachReturnKey], false /* altitudeRequired */, _breachReturnPoint, errorString)) { && !JsonHelper::loadGeoCoordinate(json[_jsonBreachReturnKey], false /* altitudeRequired */, _breachReturnPoint, errorString)) {
return false; return false;
} }
} else {
_breachReturnPoint = QGeoCoordinate();
}
if (polygonEnabled()) {
if (!_mapPolygon.loadFromJson(json, true, errorString)) { if (!_mapPolygon.loadFromJson(json, true, errorString)) {
return false; return false;
} }
}
_mapPolygon.setDirty(false); _mapPolygon.setDirty(false);
return true; 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()));
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; i<visualItems->count(); i++) {
SimpleMissionItem* item = qobject_cast<SimpleMissionItem*>(visualItems->get(i));
if (item && item->command() == MavlinkQmlSingleton::MAV_CMD_DO_JUMP) {
item->missionItem().setParam1((int)item->missionItem().param1() + 1);
}
}
}
return true;
}
#endif
void GeoFenceController::loadFromFile(const QString& filename) void GeoFenceController::loadFromFile(const QString& filename)
{ {
QString errorString; QString errorString;
...@@ -222,13 +159,7 @@ void GeoFenceController::loadFromFile(const QString& filename) ...@@ -222,13 +159,7 @@ void GeoFenceController::loadFromFile(const QString& filename)
QJsonDocument jsonDoc; QJsonDocument jsonDoc;
QByteArray bytes = file.readAll(); QByteArray bytes = file.readAll();
if (JsonHelper::isJsonFile(bytes, jsonDoc)) {
_loadJsonFile(jsonDoc, errorString); _loadJsonFile(jsonDoc, errorString);
} else {
// FIXME: No MP file format support
qgcApp()->showMessage("GeoFence file is in incorrect format.");
return;
}
} }
if (!errorString.isEmpty()) { if (!errorString.isEmpty()) {
...@@ -261,27 +192,11 @@ void GeoFenceController::saveToFile(const QString& filename) ...@@ -261,27 +192,11 @@ void GeoFenceController::saveToFile(const QString& filename)
fenceFileObject[JsonHelper::jsonVersionKey] = 1; fenceFileObject[JsonHelper::jsonVersionKey] = 1;
fenceFileObject[JsonHelper::jsonGroundStationKey] = JsonHelper::jsonGroundStationValue; fenceFileObject[JsonHelper::jsonGroundStationKey] = JsonHelper::jsonGroundStationValue;
QStringList paramNames;
ParameterManager* paramMgr = _activeVehicle->parameterManager();
GeoFenceManager* fenceMgr = _activeVehicle->geoFenceManager();
QVariantList params = fenceMgr->params();
for (int i=0; i< params.count(); i++) {
paramNames.append(params[i].value<Fact*>()->name());
}
if (paramNames.count() > 0) {
paramMgr->saveToJson(_activeVehicle->defaultComponentId(), paramNames, fenceFileObject);
}
if (breachReturnEnabled()) {
QJsonValue jsonBreachReturn; QJsonValue jsonBreachReturn;
JsonHelper::saveGeoCoordinate(_breachReturnPoint, false /* writeAltitude */, jsonBreachReturn); JsonHelper::saveGeoCoordinate(_breachReturnPoint, false /* writeAltitude */, jsonBreachReturn);
fenceFileObject[_jsonBreachReturnKey] = jsonBreachReturn; fenceFileObject[_jsonBreachReturnKey] = jsonBreachReturn;
}
if (polygonEnabled()) {
_mapPolygon.saveToJson(fenceFileObject); _mapPolygon.saveToJson(fenceFileObject);
}
QJsonDocument saveDoc(fenceFileObject); QJsonDocument saveDoc(fenceFileObject);
file.write(saveDoc.toJson()); file.write(saveDoc.toJson());
...@@ -345,19 +260,39 @@ void GeoFenceController::_polygonDirtyChanged(bool dirty) ...@@ -345,19 +260,39 @@ void GeoFenceController::_polygonDirtyChanged(bool dirty)
} }
} }
bool GeoFenceController::breachReturnSupported(void) const
{
return _activeVehicle->geoFenceManager()->breachReturnSupported();
}
bool GeoFenceController::circleEnabled(void) const bool GeoFenceController::circleEnabled(void) const
{ {
return _activeVehicle->geoFenceManager()->circleEnabled(); 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 bool GeoFenceController::polygonEnabled(void) const
{ {
return _activeVehicle->geoFenceManager()->polygonEnabled(); return _activeVehicle->geoFenceManager()->polygonEnabled();
} }
bool GeoFenceController::breachReturnEnabled(void) const QVariantList GeoFenceController::params(void) const
{
return _activeVehicle->geoFenceManager()->params();
}
QStringList GeoFenceController::paramLabels(void) const
{ {
return _activeVehicle->geoFenceManager()->breachReturnEnabled(); return _activeVehicle->geoFenceManager()->paramLabels();
} }
void GeoFenceController::_setDirty(void) void GeoFenceController::_setDirty(void)
...@@ -380,26 +315,6 @@ void GeoFenceController::_setReturnPointFromManager(QGeoCoordinate breachReturnP ...@@ -380,26 +315,6 @@ void GeoFenceController::_setReturnPointFromManager(QGeoCoordinate breachReturnP
emit breachReturnPointChanged(_breachReturnPoint); 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<QGeoCoordinate>& polygon) void GeoFenceController::_loadComplete(const QGeoCoordinate& breachReturn, const QList<QGeoCoordinate>& polygon)
{ {
_setReturnPointFromManager(breachReturn); _setReturnPointFromManager(breachReturn);
...@@ -427,15 +342,3 @@ void GeoFenceController::removeAllFromVehicle(void) ...@@ -427,15 +342,3 @@ void GeoFenceController::removeAllFromVehicle(void)
{ {
_activeVehicle->geoFenceManager()->removeAll(); _activeVehicle->geoFenceManager()->removeAll();
} }
void GeoFenceController::addFence(void)
{
// GeoFenceMapVisuals control is resposible for this
emit addFencePolygon();
}
void GeoFenceController::removeFence(void)
{
_mapPolygon.clear();
}
...@@ -29,21 +29,20 @@ public: ...@@ -29,21 +29,20 @@ public:
GeoFenceController(QObject* parent = NULL); GeoFenceController(QObject* parent = NULL);
~GeoFenceController(); ~GeoFenceController();
Q_PROPERTY(bool circleEnabled READ circleEnabled NOTIFY circleEnabledChanged)
Q_PROPERTY(float circleRadius READ circleRadius NOTIFY circleRadiusChanged)
Q_PROPERTY(bool polygonEnabled READ polygonEnabled NOTIFY polygonEnabledChanged)
Q_PROPERTY(QGCMapPolygon* mapPolygon READ mapPolygon CONSTANT) Q_PROPERTY(QGCMapPolygon* mapPolygon READ mapPolygon CONSTANT)
Q_PROPERTY(bool breachReturnEnabled READ breachReturnEnabled NOTIFY breachReturnEnabledChanged)
Q_PROPERTY(QGeoCoordinate breachReturnPoint READ breachReturnPoint WRITE setBreachReturnPoint NOTIFY breachReturnPointChanged) Q_PROPERTY(QGeoCoordinate breachReturnPoint READ breachReturnPoint WRITE setBreachReturnPoint NOTIFY breachReturnPointChanged)
// 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(QVariantList params READ params NOTIFY paramsChanged)
Q_PROPERTY(QStringList paramLabels READ paramLabels NOTIFY paramLabelsChanged) Q_PROPERTY(QStringList paramLabels READ paramLabels NOTIFY paramLabelsChanged)
Q_PROPERTY(QString editorQml READ editorQml NOTIFY editorQmlChanged)
Q_INVOKABLE void addFence(void); Q_INVOKABLE void addPolygon (void) { emit addInitialFencePolygon(); }
Q_INVOKABLE void removeFence(void); Q_INVOKABLE void removePolygon (void) { _mapPolygon.clear(); }
void start (bool editMode) final; void start (bool editMode) final;
void startStaticActiveVehicle (Vehicle* vehicle) final; void startStaticActiveVehicle (Vehicle* vehicle) final;
...@@ -61,28 +60,29 @@ public: ...@@ -61,28 +60,29 @@ public:
QString fileExtension(void) const final; QString fileExtension(void) const final;
bool circleEnabled (void) const; bool circleEnabled (void) const;
Fact* circleRadiusFact (void) const;
bool polygonSupported (void) const;
bool polygonEnabled (void) const; bool polygonEnabled (void) const;
bool breachReturnEnabled (void) const; bool breachReturnSupported (void) const;
float circleRadius (void) const;
QGCMapPolygon* mapPolygon (void) { return &_mapPolygon; }
QGeoCoordinate breachReturnPoint (void) const { return _breachReturnPoint; }
QVariantList params (void) const; QVariantList params (void) const;
QStringList paramLabels (void) const; QStringList paramLabels (void) const;
QString editorQml (void) const; QGCMapPolygon* mapPolygon (void) { return &_mapPolygon; }
QGeoCoordinate breachReturnPoint (void) const { return _breachReturnPoint; }
void setBreachReturnPoint(const QGeoCoordinate& breachReturnPoint); void setBreachReturnPoint(const QGeoCoordinate& breachReturnPoint);
signals: signals:
void addFencePolygon (void); void breachReturnPointChanged (QGeoCoordinate breachReturnPoint);
void editorQmlChanged (QString editorQml);
void loadComplete (void);
void addInitialFencePolygon (void);
void circleEnabledChanged (bool circleEnabled); void circleEnabledChanged (bool circleEnabled);
void circleRadiusFactChanged (Fact* circleRadiusFact);
void polygonSupportedChanged (bool polygonSupported);
void polygonEnabledChanged (bool polygonEnabled); void polygonEnabledChanged (bool polygonEnabled);
void breachReturnEnabledChanged (bool breachReturnEnabled); void breachReturnSupportedChanged (bool breachReturnSupported);
void circleRadiusChanged (float circleRadius);
void breachReturnPointChanged (QGeoCoordinate breachReturnPoint);
void paramsChanged (QVariantList params); void paramsChanged (QVariantList params);
void paramLabelsChanged (QStringList paramLabels); void paramLabelsChanged (QStringList paramLabels);
void editorQmlChanged (QString editorQml);
void loadComplete (void);
private slots: private slots:
void _polygonDirtyChanged(bool dirty); void _polygonDirtyChanged(bool dirty);
...@@ -103,7 +103,6 @@ private: ...@@ -103,7 +103,6 @@ private:
bool _dirty; bool _dirty;
QGCMapPolygon _mapPolygon; QGCMapPolygon _mapPolygon;
QGeoCoordinate _breachReturnPoint; QGeoCoordinate _breachReturnPoint;
QVariantList _params;
static const char* _jsonFileTypeValue; static const char* _jsonFileTypeValue;
static const char* _jsonBreachReturnKey; static const char* _jsonBreachReturnKey;
......
...@@ -14,6 +14,7 @@ ...@@ -14,6 +14,7 @@
#include <QGeoCoordinate> #include <QGeoCoordinate>
#include "QGCLoggingCategory.h" #include "QGCLoggingCategory.h"
#include "FactSystem.h"
class Vehicle; class Vehicle;
class QmlObjectListModel; class QmlObjectListModel;
...@@ -39,20 +40,39 @@ public: ...@@ -39,20 +40,39 @@ public:
/// Send the current settings to the vehicle /// Send the current settings to the vehicle
virtual void sendToVehicle(const QGeoCoordinate& breachReturn, QmlObjectListModel& polygon); 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; } /// Returns true if this vehicle support polygon fence
virtual bool polygonEnabled (void) const { return false; } /// Signal: polygonSupportedChanged
virtual bool breachReturnEnabled (void) const { return false; } virtual bool polygonSupported(void) const { return false; }
virtual float circleRadius (void) const { return 0.0; } /// Returns true if polygon fence is currently enabled on this vehicle
QList<QGeoCoordinate> polygon (void) const { return _polygon; } /// Signal: polygonEnabledChanged
QGeoCoordinate breachReturnPoint (void) const { return _breachReturnPoint; } 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(); }
/// Returns true if circular fence is currently enabled on vehicle
/// Signal: circleEnabledChanged
virtual bool circleEnabled(void) const { return false; }
virtual QVariantList params (void) const { return QVariantList(); } /// Returns the fact which controls the fence circle radius. NULL if not supported
virtual QStringList paramLabels (void) const { return QStringList(); } /// Signal: circleRadiusFactChanged
virtual Fact* circleRadiusFact(void) const { return NULL; }
virtual QString editorQml(void) const { return QStringLiteral("qrc:/FirmwarePlugin/NoGeoFenceEditor.qml"); } QList<QGeoCoordinate> polygon (void) const { return _polygon; }
QGeoCoordinate breachReturnPoint (void) const { return _breachReturnPoint; }
/// Error codes returned in error signal /// Error codes returned in error signal
typedef enum { typedef enum {
...@@ -64,14 +84,15 @@ public: ...@@ -64,14 +84,15 @@ public:
signals: signals:
void loadComplete (const QGeoCoordinate& breachReturn, const QList<QGeoCoordinate>& polygon); void loadComplete (const QGeoCoordinate& breachReturn, const QList<QGeoCoordinate>& polygon);
void circleEnabledChanged (bool circleEnabled);
void polygonEnabledChanged (bool polygonEnabled);
void breachReturnEnabledChanged (bool fenceEnabled);
void circleRadiusChanged (float circleRadius);
void inProgressChanged (bool inProgress); void inProgressChanged (bool inProgress);
void error (int errorCode, const QString& errorMsg); void error (int errorCode, const QString& errorMsg);
void paramsChanged (QVariantList params); void paramsChanged (QVariantList params);
void paramLabelsChanged (QStringList paramLabels); 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: protected:
void _sendError(ErrorCode_t errorCode, const QString& errorMsg); void _sendError(ErrorCode_t errorCode, const QString& errorMsg);
......
...@@ -24,6 +24,11 @@ Item { ...@@ -24,6 +24,11 @@ Item {
property var mapControl ///< Map control to place item in property var mapControl ///< Map control to place item in
property var mapPolygon ///< QGCMapPolygon object 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 _polygonComponent
property var _dragHandlesComponent property var _dragHandlesComponent
...@@ -40,10 +45,12 @@ Item { ...@@ -40,10 +45,12 @@ Item {
} }
function addHandles() { function addHandles() {
if (!_dragHandlesComponent) {
_dragHandlesComponent = dragHandlesComponent.createObject(mapControl) _dragHandlesComponent = dragHandlesComponent.createObject(mapControl)
_splitHandlesComponent = splitHandlesComponent.createObject(mapControl) _splitHandlesComponent = splitHandlesComponent.createObject(mapControl)
_centerDragHandleComponent = centerDragHandleComponent.createObject(mapControl) _centerDragHandleComponent = centerDragHandleComponent.createObject(mapControl)
} }
}
function removeHandles() { function removeHandles() {
if (_dragHandlesComponent) { if (_dragHandlesComponent) {
...@@ -60,6 +67,52 @@ Item { ...@@ -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: { Component.onDestruction: {
removeVisuals() removeVisuals()
removeHandles() removeHandles()
...@@ -69,8 +122,10 @@ Item { ...@@ -69,8 +122,10 @@ Item {
id: polygonComponent id: polygonComponent
MapPolygon { MapPolygon {
color: "green" color: interiorColor
opacity: 0.5 opacity: interiorOpacity
border.color: borderColor
border.width: borderWidth
path: mapPolygon.path path: mapPolygon.path
} }
} }
...@@ -250,4 +305,3 @@ Item { ...@@ -250,4 +305,3 @@ Item {
} }
} }
...@@ -4,6 +4,8 @@ import QtQuick.Controls 1.2 ...@@ -4,6 +4,8 @@ import QtQuick.Controls 1.2
import QGroundControl 1.0 import QGroundControl 1.0
import QGroundControl.ScreenTools 1.0 import QGroundControl.ScreenTools 1.0
import QGroundControl.Controls 1.0 import QGroundControl.Controls 1.0
import QGroundControl.FactSystem 1.0
import QGroundControl.FactControls 1.0
QGCFlickable { QGCFlickable {
id: root id: root
...@@ -45,14 +47,19 @@ QGCFlickable { ...@@ -45,14 +47,19 @@ QGCFlickable {
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
anchors.top: geoFenceLabel.bottom anchors.top: geoFenceLabel.bottom
height: editorLoader.y + editorLoader.height + (_margin * 2) height: fenceColumn.y + fenceColumn.height + (_margin * 2)
color: qgcPal.windowShadeDark color: qgcPal.windowShadeDark
radius: _radius radius: _radius
Column {
id: fenceColumn
anchors.margins: _margin
anchors.left: parent.left
anchors.right: parent.right
spacing: ScreenTools.defaultFontPixelHeight / 2
QGCLabel { QGCLabel {
id: geoLabel id: geoLabel
anchors.margins: _margin
anchors.top: parent.top
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
wrapMode: Text.WordWrap wrapMode: Text.WordWrap
...@@ -60,16 +67,54 @@ QGCFlickable { ...@@ -60,16 +67,54 @@ QGCFlickable {
text: qsTr("GeoFencing allows you to set a virtual ‘fence’ around the area you want to fly in.") text: qsTr("GeoFencing allows you to set a virtual ‘fence’ around the area you want to fly in.")
} }
Loader { Repeater {
id: editorLoader model: myGeoFenceController.params
anchors.margins: _margin
anchors.top: geoLabel.bottom Item {
anchors.left: parent.left width: fenceColumn.width
source: myGeoFenceController.editorQml height: textField.height
property bool showCombo: modelData.enumStrings.length > 0
QGCLabel {
id: textFieldLabel
anchors.baseline: textField.baseline
text: myGeoFenceController.paramLabels[index]
}
property real availableWidth: parent.width - (_margin * 2) FactTextField {
property var geoFenceController: myGeoFenceController id: textField
property var myFlightMap: flightMap 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()
}
QGCButton {
text: qsTr("Remove fence polygon")
visible: myGeoFenceController.polygonSupported && myGeoFenceController.mapPolygon.count > 0
onClicked: myGeoFenceController.removePolygon()
}
} }
} }
} }
......
This diff is collapsed.
...@@ -239,6 +239,10 @@ QGCView { ...@@ -239,6 +239,10 @@ QGCView {
function fitViewportToItems() { function fitViewportToItems() {
mapFitFunctions.fitMapViewportToFenceItems() mapFitFunctions.fitMapViewportToFenceItems()
} }
function upload() {
sendToVehicle()
}
} }
RallyPointController { RallyPointController {
...@@ -274,6 +278,10 @@ QGCView { ...@@ -274,6 +278,10 @@ QGCView {
function fitViewportToItems() { function fitViewportToItems() {
mapFitFunctions.fitMapViewportToRallyItems() mapFitFunctions.fitMapViewportToRallyItems()
} }
function upload() {
sendToVehicle()
}
} }
QGCPalette { id: qgcPal; colorGroupEnabled: enabled } QGCPalette { id: qgcPal; colorGroupEnabled: enabled }
...@@ -505,6 +513,7 @@ QGCView { ...@@ -505,6 +513,7 @@ QGCView {
z: QGroundControl.zOrderMapItems - 1 z: QGroundControl.zOrderMapItems - 1
} }
} }
GeoFenceMapVisuals { GeoFenceMapVisuals {
map: editorMap map: editorMap
myGeoFenceController: geoFenceController myGeoFenceController: geoFenceController
...@@ -513,35 +522,11 @@ QGCView { ...@@ -513,35 +522,11 @@ QGCView {
planView: true planView: true
} }
// Rally points on map RallyPointMapVisuals {
map: editorMap
MapItemView { myRallyPointController: rallyPointController
model: rallyPointController.points interactive: _editingLayer == _layerRallyPoints
planView: true
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 })
}
}
}
}
} }
ToolStrip { ToolStrip {
...@@ -632,11 +617,12 @@ QGCView { ...@@ -632,11 +617,12 @@ QGCView {
// Plan Element selector (Mission/Fence/Rally) // Plan Element selector (Mission/Fence/Rally)
Row { Row {
id: planElementSelectorRow id: planElementSelectorRow
anchors.topMargin: Math.round(ScreenTools.defaultFontPixelHeight / 3)
anchors.top: parent.top anchors.top: parent.top
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
spacing: _horizontalMargin spacing: _horizontalMargin
visible: false // WIP: Temporarily remove - QGroundControl.corePlugin.options.enablePlanViewSelector visible: QGroundControl.corePlugin.options.enablePlanViewSelector
readonly property real _buttonRadius: ScreenTools.defaultFontPixelHeight * 0.75 readonly property real _buttonRadius: ScreenTools.defaultFontPixelHeight * 0.75
...@@ -657,7 +643,6 @@ QGCView { ...@@ -657,7 +643,6 @@ QGCView {
_syncDropDownController = rallyPointController _syncDropDownController = rallyPointController
break break
} }
_syncDropDownController.fitViewportToItems()
} }
} }
...@@ -742,22 +727,23 @@ QGCView { ...@@ -742,22 +727,23 @@ QGCView {
} // Item - Mission Item editor } // Item - Mission Item editor
// GeoFence Editor // GeoFence Editor
Loader { GeoFenceEditor {
anchors.top: planElementSelectorRow.visible ? planElementSelectorRow.bottom : planElementSelectorRow.top anchors.topMargin: ScreenTools.defaultFontPixelHeight / 2
anchors.top: planElementSelectorRow.bottom
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
sourceComponent: _editingLayer == _layerGeoFence ? geoFenceEditorComponent : undefined availableHeight: ScreenTools.availableHeight
myGeoFenceController: geoFenceController
property real availableWidth: _rightPanelWidth flightMap: editorMap
property real availableHeight: ScreenTools.availableHeight visible: _editingLayer == _layerGeoFence
property var myGeoFenceController: geoFenceController
} }
// Rally Point Editor // Rally Point Editor
RallyPointEditorHeader { RallyPointEditorHeader {
id: rallyPointHeader id: rallyPointHeader
anchors.top: planElementSelectorRow.visible ? planElementSelectorRow.bottom : planElementSelectorRow.top anchors.topMargin: ScreenTools.defaultFontPixelHeight / 2
anchors.top: planElementSelectorRow.bottom
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
visible: _editingLayer == _layerRallyPoints visible: _editingLayer == _layerRallyPoints
...@@ -766,7 +752,8 @@ QGCView { ...@@ -766,7 +752,8 @@ QGCView {
RallyPointItemEditor { RallyPointItemEditor {
id: rallyPointEditor id: rallyPointEditor
anchors.top: planElementSelectorRow.visible ? planElementSelectorRow.bottom : planElementSelectorRow.top anchors.topMargin: ScreenTools.defaultFontPixelHeight / 2
anchors.top: rallyPointHeader.bottom
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
visible: _editingLayer == _layerRallyPoints && rallyPointController.points.count visible: _editingLayer == _layerRallyPoints && rallyPointController.points.count
...@@ -831,19 +818,6 @@ QGCView { ...@@ -831,19 +818,6 @@ QGCView {
} }
} }
Component {
id: geoFenceEditorComponent
GeoFenceEditor {
availableWidth: _rightPanelWidth
availableHeight: ScreenTools.availableHeight
myGeoFenceController: geoFenceController
flightMap: editorMap
}
}
//- ToolStrip DropPanel Components //- ToolStrip DropPanel Components
Component { Component {
......
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)
}
}
}
}
}
...@@ -27,7 +27,7 @@ QGCFlickable { ...@@ -27,7 +27,7 @@ QGCFlickable {
anchors.margins: _margin anchors.margins: _margin
anchors.left: parent.left anchors.left: parent.left
anchors.top: parent.top anchors.top: parent.top
text: qsTr("Rally Points (WIP careful!)") text: qsTr("Rally Points")
color: "black" color: "black"
} }
...@@ -37,7 +37,7 @@ QGCFlickable { ...@@ -37,7 +37,7 @@ QGCFlickable {
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
anchors.top: editorLabel.bottom anchors.top: editorLabel.bottom
height: infoLabel.height + helpLabel.height + (_margin * 2) height: helpLabel.height + helpLabel.height + (_margin * 2)
color: qgcPal.windowShadeDark color: qgcPal.windowShadeDark
radius: _radius radius: _radius
......
/****************************************************************************
*
* (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
/// 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 = [ ]
}
}
}
}
}
...@@ -91,25 +91,11 @@ Item { ...@@ -91,25 +91,11 @@ Item {
id: mapPolygonVisuals id: mapPolygonVisuals
mapControl: map mapControl: map
mapPolygon: _mapPolygon mapPolygon: _mapPolygon
interactive: _missionItem.isCurrentItem
Component.onCompleted: { borderWidth: 1
mapPolygonVisuals.addVisuals() borderColor: "black"
if (_missionItem.isCurrentItem) { interiorColor: "green"
mapPolygonVisuals.addHandles() interiorOpacity: 0.5
}
}
Connections {
target: _missionItem
onIsCurrentItemChanged: {
if (_missionItem.isCurrentItem) {
mapPolygonVisuals.addHandles()
} else {
mapPolygonVisuals.removeHandles()
}
}
}
} }
// Survey grid lines // Survey grid lines
......
...@@ -28,6 +28,7 @@ ParameterEditorDialog 1.0 ParameterEditorDialog.qml ...@@ -28,6 +28,7 @@ ParameterEditorDialog 1.0 ParameterEditorDialog.qml
PlanToolBar 1.0 PlanToolBar.qml PlanToolBar 1.0 PlanToolBar.qml
RallyPointEditorHeader 1.0 RallyPointEditorHeader.qml RallyPointEditorHeader 1.0 RallyPointEditorHeader.qml
RallyPointItemEditor 1.0 RallyPointItemEditor.qml RallyPointItemEditor 1.0 RallyPointItemEditor.qml
RallyPointMapVisuals 1.0 RallyPointMapVisuals.qml
RCChannelMonitor 1.0 RCChannelMonitor.qml RCChannelMonitor 1.0 RCChannelMonitor.qml
QGCButton 1.0 QGCButton.qml QGCButton 1.0 QGCButton.qml
QGCCheckBox 1.0 QGCCheckBox.qml QGCCheckBox 1.0 QGCCheckBox.qml
......
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