16 changed files with 757 additions and 9 deletions
@ -0,0 +1,30 @@
@@ -0,0 +1,30 @@
|
||||
[ |
||||
{ |
||||
"name": "angle", |
||||
"shortDescription": "Angle from ground station to vehicle", |
||||
"type": "double", |
||||
"min": 0, |
||||
"max": 360, |
||||
"decimalPlaces": 1, |
||||
"units": "deg", |
||||
"defaultValue": 45 |
||||
}, |
||||
{ |
||||
"name": "distance", |
||||
"shortDescription": "Horizontal distance from ground station to vehicle", |
||||
"type": "double", |
||||
"min": 0, |
||||
"decimalPlaces": 1, |
||||
"units": "m", |
||||
"defaultValue": 5 |
||||
}, |
||||
{ |
||||
"name": "height", |
||||
"shortDescription": "Vertical distance from ground station to vehicle", |
||||
"type": "double", |
||||
"min": 0, |
||||
"decimalPlaces": 1, |
||||
"units": "m", |
||||
"defaultValue": 5 |
||||
} |
||||
] |
@ -0,0 +1,44 @@
@@ -0,0 +1,44 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* (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. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
#include "APMFollowComponent.h" |
||||
#include "APMAutoPilotPlugin.h" |
||||
#include "APMAirframeComponent.h" |
||||
#include "ParameterManager.h" |
||||
|
||||
APMFollowComponent::APMFollowComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent) |
||||
: VehicleComponent(vehicle, autopilot, parent), |
||||
_name(tr("Follow Me")) |
||||
{ |
||||
} |
||||
|
||||
QString APMFollowComponent::name(void) const |
||||
{ |
||||
return _name; |
||||
} |
||||
|
||||
QString APMFollowComponent::description(void) const |
||||
{ |
||||
return tr("Follow Me Setup is used to configure support for the vehicle following the ground station location."); |
||||
} |
||||
|
||||
QString APMFollowComponent::iconResource(void) const |
||||
{ |
||||
return QStringLiteral("/qmlimages/FollowComponentIcon.png"); |
||||
} |
||||
|
||||
QUrl APMFollowComponent::setupSource(void) const |
||||
{ |
||||
return QUrl::fromUserInput(QStringLiteral("qrc:/qml/APMFollowComponent.qml")); |
||||
} |
||||
|
||||
QUrl APMFollowComponent::summaryQmlSource(void) const |
||||
{ |
||||
return QUrl::fromUserInput(QStringLiteral("qrc:/qml/APMFollowComponentSummary.qml")); |
||||
} |
@ -0,0 +1,38 @@
@@ -0,0 +1,38 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* (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. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
#pragma once |
||||
|
||||
#include "VehicleComponent.h" |
||||
|
||||
class APMFollowComponent : public VehicleComponent |
||||
{ |
||||
Q_OBJECT |
||||
|
||||
public: |
||||
APMFollowComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = nullptr); |
||||
|
||||
// Overrides from VehicleComponent
|
||||
QStringList setupCompleteChangedTriggerList(void) const override { return QStringList(); } |
||||
|
||||
// Virtuals from VehicleComponent
|
||||
QString name (void) const override; |
||||
QString description (void) const override; |
||||
QString iconResource (void) const override; |
||||
bool requiresSetup (void) const override { return false; } |
||||
bool setupComplete (void) const override { return true; } |
||||
QUrl setupSource (void) const override; |
||||
QUrl summaryQmlSource (void) const override; |
||||
bool allowSetupWhileArmed (void) const override { return true; } |
||||
bool allowSetupWhileFlying (void) const override { return true; } |
||||
|
||||
private: |
||||
const QString _name; |
||||
QVariantList _summaryItems; |
||||
}; |
@ -0,0 +1,453 @@
@@ -0,0 +1,453 @@
|
||||
/**************************************************************************** |
||||
* |
||||
* (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 QtQuick.Dialogs 1.2 |
||||
import QtQuick.Layouts 1.2 |
||||
|
||||
import QGroundControl 1.0 |
||||
import QGroundControl.FactSystem 1.0 |
||||
import QGroundControl.FactControls 1.0 |
||||
import QGroundControl.Palette 1.0 |
||||
import QGroundControl.Controls 1.0 |
||||
import QGroundControl.ScreenTools 1.0 |
||||
import QGroundControl.Controllers 1.0 |
||||
|
||||
SetupPage { |
||||
id: followPage |
||||
pageComponent: followPageComponent |
||||
|
||||
FactPanelController { |
||||
id: controller |
||||
} |
||||
|
||||
Component { |
||||
id: followPageComponent |
||||
|
||||
ColumnLayout { |
||||
id: flowLayout |
||||
spacing: _margins |
||||
|
||||
property Fact _followEnabled: controller.getParameterFact(-1, "FOLL_ENABLE") |
||||
property bool _followParamsAvailable: controller.parameterExists(-1, "FOLL_SYSID") |
||||
property Fact _followDistanceMax: controller.getParameterFact(-1, "FOLL_DIST_MAX", false /* reportMissing */) |
||||
property Fact _followSysId: controller.getParameterFact(-1, "FOLL_SYSID", false /* reportMissing */) |
||||
property Fact _followOffsetX: controller.getParameterFact(-1, "FOLL_OFS_X", false /* reportMissing */) |
||||
property Fact _followOffsetY: controller.getParameterFact(-1, "FOLL_OFS_Y", false /* reportMissing */) |
||||
property Fact _followOffsetZ: controller.getParameterFact(-1, "FOLL_OFS_Z", false /* reportMissing */) |
||||
property Fact _followOffsetType: controller.getParameterFact(-1, "FOLL_OFS_TYPE", false /* reportMissing */) |
||||
property Fact _followAltitudeType: controller.getParameterFact(-1, "FOLL_ALT_TYPE", false /* reportMissing */) |
||||
property Fact _followYawBehavior: controller.getParameterFact(-1, "FOLL_YAW_BEHAVE", false /* reportMissing */) |
||||
property int _followComboMaintainIndex: 0 |
||||
property int _followComboSpecifyIndex: 1 |
||||
property bool _followMaintain: followPositionCombo.currentIndex === _followComboMaintainIndex |
||||
property bool _isFollowMeSetup: _followEnabled.rawValue == 1 && _followParamsAvailable && _followOffsetType.rawValue == 1 && _followAltitudeType.rawValue == 1 && _followSysId.rawValue == 0 |
||||
|
||||
readonly property int _followYawBehaviorNone: 0 |
||||
readonly property int _followYawBehaviorFace: 1 |
||||
readonly property int _followYawBehaviorSame: 2 |
||||
readonly property int _followYawBehaviorFlight: 3 |
||||
|
||||
Component.onCompleted: _setUIFromParams() |
||||
|
||||
function _setUIFromParams() { |
||||
if (!_followParamsAvailable) { |
||||
return |
||||
} |
||||
|
||||
if (_followOffsetX.rawValue == 0 && _followOffsetY.rawValue == 0 && _followOffsetZ.rawValue == 0) { |
||||
followPositionCombo.currentIndex =_followComboMaintainIndex |
||||
controller.distance.rawValue = 0 |
||||
controller.angle.rawValue = 0 |
||||
controller.height.rawValue = 0 |
||||
} else { |
||||
followPositionCombo.currentIndex =_followComboSpecifyIndex |
||||
var angleRadians = Math.atan2(_followOffsetX.rawValue, _followOffsetY.rawValue) |
||||
if (angleRadians == 0) { |
||||
controller.distance.rawValue = _followOffsetY.rawValue |
||||
} else { |
||||
controller.distance.rawValue = _followOffsetX.rawValue / Math.sin(angleRadians) |
||||
} |
||||
controller.angle.rawValue = _radiansToHeading(angleRadians) |
||||
} |
||||
controller.height.rawValue = -_followOffsetZ.rawValue |
||||
pointVehicleCombo.currentIndex = _followYawBehavior.rawValue |
||||
} |
||||
|
||||
function _setFollowMeParamDefaults() { |
||||
_followOffsetType.rawValue = 1 // Relative to vehicle |
||||
_followAltitudeType.rawValue = 1 // Altitude is relative |
||||
_followSysId.rawValue = 0 // Follow first message sent |
||||
|
||||
controller.distance.value = controller.distance.defaultValue |
||||
controller.angle.value = controller.angle.defaultValue |
||||
controller.height.value = controller.height.defaultValue |
||||
|
||||
_setXYOffsetByAngleAndDistance(controller.angle.rawValue, controller.distance.rawValue) |
||||
_followOffsetZ.rawValue = -controller.height.rawValue |
||||
_setUIFromParams() |
||||
} |
||||
|
||||
function _setXYOffsetByAngleAndDistance(headingAngleDegrees, distance) { |
||||
if (distance == 0) { |
||||
_followOffsetX.rawValue = _followOffsetY.rawValue = 0 |
||||
} else { |
||||
var angleRadians = _headingToRadians(headingAngleDegrees) |
||||
if (angleRadians == 0) { |
||||
_followOffsetX.rawValue = 0 |
||||
_followOffsetY.rawValue = distance |
||||
} else { |
||||
_followOffsetX.rawValue = Math.sin(angleRadians) * distance |
||||
_followOffsetY.rawValue = Math.cos(angleRadians) * distance |
||||
if (_followOffsetX.rawValue < 0.0001) { |
||||
_followOffsetX.rawValue = 0 |
||||
} |
||||
if (_followOffsetY.rawValue < 0.0001) { |
||||
_followOffsetY.rawValue = 0 |
||||
} |
||||
} |
||||
} |
||||
} |
||||
|
||||
function _radiansToHeading(radians) { |
||||
var geometricAngle = QGroundControl.radiansToDegrees(radians) |
||||
var headingAngle = 90 - geometricAngle |
||||
if (headingAngle < 0) { |
||||
headingAngle += 360 |
||||
} else if (headingAngle > 360) { |
||||
headingAngle -= 360 |
||||
} |
||||
return headingAngle |
||||
} |
||||
|
||||
function _headingToRadians(heading) { |
||||
var geometricAngle = -(heading - 90) |
||||
return QGroundControl.degreesToRadians(geometricAngle) |
||||
} |
||||
|
||||
APMFollowComponentController { |
||||
id: controller |
||||
|
||||
onMissingParametersAvailable: { |
||||
_followDistanceMax = controller.getParameterFact(-1, "FOLL_DIST_MAX") |
||||
_followSysId = controller.getParameterFact(-1, "FOLL_SYSID") |
||||
_followOffsetX = controller.getParameterFact(-1, "FOLL_OFS_X") |
||||
_followOffsetY = controller.getParameterFact(-1, "FOLL_OFS_Y") |
||||
_followOffsetZ = controller.getParameterFact(-1, "FOLL_OFS_Z") |
||||
_followOffsetType = controller.getParameterFact(-1, "FOLL_OFS_TYPE") |
||||
_followAltitudeType = controller.getParameterFact(-1, "FOLL_ALT_TYPE") |
||||
_followYawBehavior = controller.getParameterFact(-1, "FOLL_YAW_BEHAVE") |
||||
_followParamsAvailable = true |
||||
vehicleParamRefreshLabel.visible = false |
||||
_followYawBehavior.rawValue = 1 // Point at GCS |
||||
_setFollowMeParamDefaults() |
||||
} |
||||
} |
||||
|
||||
QGCPalette { id: ggcPal; colorGroupEnabled: true } |
||||
|
||||
QGCCheckBox { |
||||
text: qsTr("Enable Follow Me") |
||||
checked: _isFollowMeSetup |
||||
onClicked: { |
||||
if (checked) { |
||||
_followEnabled.rawValue = 1 |
||||
controller.getMissingParameters([ "FOLL_DIST_MAX", "FOLL_SYSID", "FOLL_OFS_X", "FOLL_OFS_Y", "FOLL_OFS_Z", "FOLL_OFS_TYPE", "FOLL_ALT_TYPE", "FOLL_YAW_BEHAVE" ]) |
||||
vehicleParamRefreshLabel.visible = true |
||||
} else { |
||||
_followEnabled.rawValue = 0 |
||||
} |
||||
} |
||||
} |
||||
|
||||
QGCLabel { |
||||
id: vehicleParamRefreshLabel |
||||
text: qsTr("Waiting for Vehicle to update") |
||||
visible: false |
||||
} |
||||
|
||||
ColumnLayout { |
||||
Layout.fillWidth: true |
||||
spacing: ScreenTools.defaultFontPixelWidth |
||||
visible: _isFollowMeSetup |
||||
|
||||
ColumnLayout { |
||||
Layout.fillWidth: true |
||||
spacing: ScreenTools.defaultFontPixelWidth |
||||
visible: _followParamsAvailable && _isFollowMeSetup |
||||
|
||||
GridLayout { |
||||
Layout.fillWidth: true |
||||
columns: 2 |
||||
|
||||
QGCLabel { text: qsTr("Vehicle Position") } |
||||
QGCComboBox { |
||||
id: followPositionCombo |
||||
Layout.fillWidth: true |
||||
model: [ qsTr("Maintain Current Offsets"), qsTr("Specify Offsets")] |
||||
|
||||
onActivated: { |
||||
if (index == 0) { |
||||
_followOffsetX.rawValue = _followOffsetY.rawValue = _followOffsetZ.rawValue = 0 |
||||
_setUIFromParams() |
||||
} else { |
||||
_setFollowMeParamDefaults() |
||||
} |
||||
} |
||||
} |
||||
|
||||
QGCLabel { text: qsTr("Point Vehicle") } |
||||
QGCComboBox { |
||||
id: pointVehicleCombo |
||||
Layout.fillWidth: true |
||||
// NOTE: The indices for the model below must match the values for FOLL_YAW_BEHAVE |
||||
model: [ qsTr("Maintain current vehicle orientation"), qsTr("Point at ground station location"), qsTr("Same orientation as ground station"), qsTr("Same direction as ground station movement") ] |
||||
onActivated: _followYawBehavior.rawValue = index |
||||
} |
||||
} |
||||
|
||||
GridLayout { |
||||
Layout.fillWidth: true |
||||
columns: 4 |
||||
visible: !_followMaintain |
||||
|
||||
QGCLabel { |
||||
Layout.columnSpan: 2 |
||||
Layout.alignment: Qt.AlignHCenter |
||||
text: qsTr("Vehicle Offsets") |
||||
} |
||||
|
||||
QGCLabel { text: qsTr("Angle") } |
||||
FactTextField { |
||||
fact: controller.angle |
||||
onUpdated: { console.log("updated"); _setXYOffsetByAngleAndDistance(controller.angle.rawValue, controller.distance.rawValue) } |
||||
} |
||||
|
||||
QGCLabel { text: qsTr("Distance") } |
||||
FactTextField { |
||||
fact: controller.distance |
||||
onUpdated: _setXYOffsetByAngleAndDistance(controller.angle.rawValue, controller.distance.rawValue) |
||||
} |
||||
|
||||
QGCLabel { text: qsTr("Height") } |
||||
FactTextField { |
||||
fact: controller.height |
||||
visible: !_followMaintain |
||||
onUpdated: _followOffsetZ.rawValue = -controller.height.rawValue |
||||
} |
||||
} |
||||
} |
||||
} |
||||
|
||||
RowLayout { |
||||
spacing: ScreenTools.defaultFontPixelWidth * 2 |
||||
visible: _isFollowMeSetup && !_followMaintain |
||||
|
||||
Item { |
||||
height: ScreenTools.defaultFontPixelWidth * 50 |
||||
width: height |
||||
|
||||
Rectangle { |
||||
anchors.top: parent.top |
||||
anchors.bottom: parent.bottom |
||||
anchors.horizontalCenter: parent.horizontalCenter |
||||
width: 3 |
||||
color: qgcPal.windowShade |
||||
} |
||||
|
||||
Rectangle { |
||||
anchors.left: parent.left |
||||
anchors.right: parent.right |
||||
anchors.verticalCenter: parent.verticalCenter |
||||
height: 3 |
||||
color: qgcPal.windowShade |
||||
} |
||||
|
||||
QGCLabel { |
||||
anchors.horizontalCenter: parent.horizontalCenter |
||||
anchors.topMargin: parent.height / 4 |
||||
anchors.top: parent.top |
||||
text: qsTr("Click in the graphic to change angle") |
||||
opacity: 0.5 |
||||
} |
||||
|
||||
Image { |
||||
id: gcsIcon |
||||
anchors.centerIn: parent |
||||
source: "/res/QGCLogoArrow" |
||||
mipmap: true |
||||
antialiasing: true |
||||
fillMode: Image.PreserveAspectFit |
||||
height: ScreenTools.defaultFontPixelHeight * 2.5 |
||||
sourceSize.height: height |
||||
} |
||||
|
||||
Item { |
||||
id: vehicleHolder |
||||
anchors.fill: parent |
||||
|
||||
transform: Rotation { |
||||
origin.x: vehicleHolder.width / 2 |
||||
origin.y: vehicleHolder.height / 2 |
||||
angle: controller.angle.rawValue |
||||
} |
||||
|
||||
Image { |
||||
id: vehicleIcon |
||||
anchors.top: parent.top |
||||
anchors.horizontalCenter: parent.horizontalCenter |
||||
source: controller.vehicle.vehicleImageOpaque |
||||
mipmap: true |
||||
height: ScreenTools.defaultFontPixelHeight * 2.5 |
||||
sourceSize.height: height |
||||
fillMode: Image.PreserveAspectFit |
||||
|
||||
transform: Rotation { |
||||
origin.x: vehicleIcon.width / 2 |
||||
origin.y: vehicleIcon.height / 2 |
||||
angle: _followYawBehavior.rawValue == _followYawBehaviorNone ? |
||||
0 : |
||||
(_followYawBehavior.rawValue == _followYawBehaviorFace ? |
||||
180 : |
||||
-controller.angle.rawValue) |
||||
} |
||||
} |
||||
|
||||
Rectangle { |
||||
id: distanceLine |
||||
x: parent.width / 2 |
||||
y: vehicleIcon.height |
||||
height: (parent.height / 2) - (vehicleIcon.height + (gcsIcon.height / 2)) |
||||
width: 2 |
||||
color: qgcPal.text |
||||
opacity: 0.4 |
||||
|
||||
Rectangle { |
||||
anchors.top: parent.top |
||||
anchors.horizontalCenter: parent.horizontalCenter |
||||
width: ScreenTools.defaultFontPixelWidth * 2 |
||||
height: 2 |
||||
color: qgcPal.text |
||||
} |
||||
|
||||
Rectangle { |
||||
anchors.bottom: parent.bottom |
||||
anchors.horizontalCenter: parent.horizontalCenter |
||||
width: ScreenTools.defaultFontPixelWidth * 2 |
||||
height: 2 |
||||
color: qgcPal.text |
||||
} |
||||
} |
||||
|
||||
QGCLabel { |
||||
id: distanceLabel |
||||
anchors.centerIn: distanceLine |
||||
text: controller.distance.valueString + " " + QGroundControl.appSettingsDistanceUnitsString |
||||
|
||||
transform: Rotation { |
||||
origin.x: distanceLabel.width / 2 |
||||
origin.y: distanceLabel.height / 2 |
||||
angle: -controller.angle.rawValue |
||||
} |
||||
} |
||||
} |
||||
|
||||
MouseArea { |
||||
anchors.fill: parent |
||||
|
||||
onClicked: { |
||||
// Translate x,y to centered |
||||
var x = mouse.x - (width / 2) |
||||
var y = (height - mouse.y) - (height / 2) |
||||
controller.angle.rawValue = _radiansToHeading(Math.atan2(y, x)) |
||||
} |
||||
} |
||||
} |
||||
|
||||
ColumnLayout { |
||||
Layout.fillHeight: true |
||||
spacing: 0 |
||||
|
||||
Image { |
||||
id: vehicleIconHeight |
||||
source: controller.vehicle.vehicleImageOpaque |
||||
mipmap: true |
||||
height: ScreenTools.defaultFontPixelHeight * 2.5 |
||||
sourceSize.height: height |
||||
fillMode: Image.PreserveAspectFit |
||||
|
||||
transform: Rotation { |
||||
origin.x: vehicleIconHeight.width / 2 |
||||
origin.y: vehicleIconHeight.height / 2 |
||||
angle: 65 |
||||
axis { x: 1; y: 0; z: 0 } |
||||
} |
||||
} |
||||
|
||||
Item { |
||||
Layout.alignment: Qt.AlignHCenter |
||||
Layout.fillHeight: true |
||||
width: Math.max(ScreenTools.defaultFontPixelWidth * 2, heightLabel.width) |
||||
|
||||
Rectangle { |
||||
id: heightLine |
||||
anchors.top: parent.top |
||||
anchors.bottom: parent.bottom |
||||
anchors.horizontalCenter: parent.horizontalCenter |
||||
width: 2 |
||||
color: qgcPal.text |
||||
opacity: 0.4 |
||||
|
||||
Rectangle { |
||||
anchors.top: parent.top |
||||
anchors.horizontalCenter: parent.horizontalCenter |
||||
width: ScreenTools.defaultFontPixelWidth * 2 |
||||
height: 2 |
||||
color: qgcPal.text |
||||
} |
||||
|
||||
Rectangle { |
||||
anchors.bottom: parent.bottom |
||||
anchors.horizontalCenter: parent.horizontalCenter |
||||
width: ScreenTools.defaultFontPixelWidth * 2 |
||||
height: 2 |
||||
color: qgcPal.text |
||||
} |
||||
} |
||||
|
||||
QGCLabel { |
||||
id: heightLabel |
||||
anchors.centerIn: parent |
||||
text: controller.height.valueString + " " + QGroundControl.appSettingsDistanceUnitsString |
||||
} |
||||
} |
||||
|
||||
Image { |
||||
id: gcsIconHeight |
||||
source: "/res/QGCLogoArrow" |
||||
mipmap: true |
||||
antialiasing: true |
||||
fillMode: Image.PreserveAspectFit |
||||
height: ScreenTools.defaultFontPixelHeight * 2.5 |
||||
sourceSize.height: height |
||||
|
||||
transform: Rotation { |
||||
origin.x: gcsIconHeight.width / 2 |
||||
origin.y: gcsIconHeight.height / 2 |
||||
angle: 65 |
||||
axis { x: 1; y: 0; z: 0 } |
||||
} |
||||
} |
||||
} |
||||
} |
||||
} |
||||
} |
||||
} |
@ -0,0 +1,24 @@
@@ -0,0 +1,24 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* (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. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
#include "APMFollowComponentController.h" |
||||
|
||||
const char* APMFollowComponentController::settingsGroup = "APMFollow"; |
||||
const char* APMFollowComponentController::angleName = "angle"; |
||||
const char* APMFollowComponentController::distanceName = "distance"; |
||||
const char* APMFollowComponentController::heightName = "height"; |
||||
|
||||
APMFollowComponentController::APMFollowComponentController(void) |
||||
: _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/APMFollowComponent.FactMetaData.json"), this)) |
||||
, _angleFact (settingsGroup, _metaDataMap[angleName]) |
||||
, _distanceFact (settingsGroup, _metaDataMap[distanceName]) |
||||
, _heightFact (settingsGroup, _metaDataMap[heightName]) |
||||
{ |
||||
|
||||
} |
@ -0,0 +1,40 @@
@@ -0,0 +1,40 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* (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. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
#pragma once |
||||
|
||||
#include "FactPanelController.h" |
||||
|
||||
class APMFollowComponentController : public FactPanelController |
||||
{ |
||||
Q_OBJECT |
||||
|
||||
public: |
||||
APMFollowComponentController(void); |
||||
|
||||
Q_PROPERTY(Fact* angle READ angleFact CONSTANT) |
||||
Q_PROPERTY(Fact* distance READ distanceFact CONSTANT) |
||||
Q_PROPERTY(Fact* height READ heightFact CONSTANT) |
||||
|
||||
Fact* angleFact (void) { return &_angleFact; } |
||||
Fact* distanceFact (void) { return &_distanceFact; } |
||||
Fact* heightFact (void) { return &_heightFact; } |
||||
|
||||
static const char* settingsGroup; |
||||
static const char* angleName; |
||||
static const char* distanceName; |
||||
static const char* heightName; |
||||
|
||||
private: |
||||
QMap<QString, FactMetaData*> _metaDataMap; |
||||
|
||||
SettingsFact _angleFact; |
||||
SettingsFact _distanceFact; |
||||
SettingsFact _heightFact; |
||||
}; |
@ -0,0 +1,58 @@
@@ -0,0 +1,58 @@
|
||||
/**************************************************************************** |
||||
* |
||||
* (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 QGroundControl.FactSystem 1.0 |
||||
import QGroundControl.FactControls 1.0 |
||||
import QGroundControl.Controls 1.0 |
||||
import QGroundControl.Palette 1.0 |
||||
|
||||
Item { |
||||
anchors.fill: parent |
||||
|
||||
FactPanelController { id: controller; } |
||||
|
||||
property Fact _batt1Monitor: controller.getParameterFact(-1, "BATT_MONITOR") |
||||
property Fact _batt2Monitor: controller.getParameterFact(-1, "BATT2_MONITOR", false /* reportMissing */) |
||||
property bool _batt2MonitorAvailable: controller.parameterExists(-1, "BATT2_MONITOR") |
||||
property bool _batt1MonitorEnabled: _batt1Monitor.rawValue !== 0 |
||||
property bool _batt2MonitorEnabled: _batt2MonitorAvailable && _batt2Monitor.rawValue !== 0 |
||||
property Fact _battCapacity: controller.getParameterFact(-1, "BATT_CAPACITY", false /* reportMissing */) |
||||
property Fact _batt2Capacity: controller.getParameterFact(-1, "BATT2_CAPACITY", false /* reportMissing */) |
||||
property bool _battCapacityAvailable: controller.parameterExists(-1, "BATT_CAPACITY") |
||||
|
||||
Column { |
||||
anchors.fill: parent |
||||
|
||||
VehicleSummaryRow { |
||||
labelText: qsTr("Batt1 monitor") |
||||
valueText: _batt1Monitor.enumStringValue |
||||
} |
||||
|
||||
VehicleSummaryRow { |
||||
labelText: qsTr("Batt1 capacity") |
||||
valueText: _batt1MonitorEnabled ? _battCapacity.valueString + " " + _battCapacity.units : "" |
||||
visible: _batt1MonitorEnabled |
||||
} |
||||
|
||||
VehicleSummaryRow { |
||||
labelText: qsTr("Batt2 monitor") |
||||
valueText: _batt2MonitorAvailable ? _batt2Monitor.enumStringValue : "" |
||||
visible: _batt2MonitorAvailable |
||||
} |
||||
|
||||
VehicleSummaryRow { |
||||
labelText: qsTr("Batt2 capacity") |
||||
valueText: _batt2MonitorEnabled ? _batt2Capacity.valueString + " " + _batt2Capacity.units : "" |
||||
visible: _batt2MonitorEnabled |
||||
} |
||||
} |
||||
} |
Loading…
Reference in new issue