Commit 557c1e1f authored by DonLakeFlyer's avatar DonLakeFlyer

GeoFence, Rally Point support reworked and back on

parent d2ef6d01
......@@ -101,6 +101,7 @@
<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/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/RoundButton.qml">src/QmlControls/RoundButton.qml</file>
<file alias="QGroundControl/Controls/SectionHeader.qml">src/PlanView/SectionHeader.qml</file>
......@@ -152,7 +153,6 @@
<file alias="QGroundControl/FlightMap/QGCCompassWidget.qml">src/FlightMap/Widgets/QGCCompassWidget.qml</file>
<file alias="QGCInstrumentWidget.qml">src/FlightMap/Widgets/QGCInstrumentWidget.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/QGCVideoBackground.qml">src/FlightMap/QGCVideoBackground.qml</file>
<file alias="QGroundControl/FlightMap/qmldir">src/FlightMap/qmldir</file>
......@@ -215,7 +215,4 @@
<file alias="APMArduSubMockLink.params">src/comm/APMArduSubMockLink.params</file>
<file alias="PX4MockLink.params">src/comm/PX4MockLink.params</file>
</qresource>
<qresource prefix="/FirmwarePlugin">
<file alias="NoGeoFenceEditor.qml">src/FirmwarePlugin/NoGeoFenceEditor.qml</file>
</qresource>
</RCC>
......@@ -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();
}
}
......
......@@ -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;
......
......@@ -51,8 +51,6 @@
<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.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="Plane.OfflineEditing.params">Plane3.7.OfflineEditing.params</file>
</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 @@
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