Commit e3566933 authored by Don Gagne's avatar Don Gagne

Mission Settings replaces Planned Home Position

- Shot Interval in Survey
- Much change to time/distance calc
parent 63aecd5d
...@@ -32,6 +32,7 @@ ...@@ -32,6 +32,7 @@
<file alias="MainWindowNative.qml">src/ui/MainWindowNative.qml</file> <file alias="MainWindowNative.qml">src/ui/MainWindowNative.qml</file>
<file alias="MavlinkSettings.qml">src/ui/preferences/MavlinkSettings.qml</file> <file alias="MavlinkSettings.qml">src/ui/preferences/MavlinkSettings.qml</file>
<file alias="MissionEditor.qml">src/MissionEditor/MissionEditor.qml</file> <file alias="MissionEditor.qml">src/MissionEditor/MissionEditor.qml</file>
<file alias="MissionSettingsEditor.qml">src/MissionEditor/MissionSettingsEditor.qml</file>
<file alias="MockLink.qml">src/ui/preferences/MockLink.qml</file> <file alias="MockLink.qml">src/ui/preferences/MockLink.qml</file>
<file alias="MockLinkSettings.qml">src/ui/preferences/MockLinkSettings.qml</file> <file alias="MockLinkSettings.qml">src/ui/preferences/MockLinkSettings.qml</file>
<file alias="MultiVehicleView.qml">src/MultiVehicle/MultiVehicleView.qml</file> <file alias="MultiVehicleView.qml">src/MultiVehicle/MultiVehicleView.qml</file>
......
...@@ -944,9 +944,8 @@ QGCView { ...@@ -944,9 +944,8 @@ QGCView {
missionItems: missionController.visualItems missionItems: missionController.visualItems
expandedWidth: missionItemEditor.x - (ScreenTools.defaultFontPixelWidth * 2) expandedWidth: missionItemEditor.x - (ScreenTools.defaultFontPixelWidth * 2)
missionDistance: missionController.missionDistance missionDistance: missionController.missionDistance
missionTime: missionController.missionTime
missionMaxTelemetry: missionController.missionMaxTelemetry missionMaxTelemetry: missionController.missionMaxTelemetry
cruiseDistance: missionController.cruiseDistance
hoverDistance: missionController.hoverDistance
visible: _editingLayer == _layerMission && !ScreenTools.isShortScreen visible: _editingLayer == _layerMission && !ScreenTools.isShortScreen
} }
} // FlightMap } // FlightMap
......
...@@ -26,8 +26,9 @@ Rectangle { ...@@ -26,8 +26,9 @@ Rectangle {
signal insert signal insert
signal moveHomeToMapCenter signal moveHomeToMapCenter
property bool _currentItem: missionItem.isCurrentItem property bool _currentItem: missionItem.isCurrentItem
property color _outerTextColor: _currentItem ? "black" : qgcPal.text property color _outerTextColor: _currentItem ? "black" : qgcPal.text
property bool _noMissionItemsAdded: ListView.view.model.count == 1
readonly property real _editFieldWidth: Math.min(width - _margin * 2, ScreenTools.defaultFontPixelWidth * 12) readonly property real _editFieldWidth: Math.min(width - _margin * 2, ScreenTools.defaultFontPixelWidth * 12)
readonly property real _margin: ScreenTools.defaultFontPixelWidth / 2 readonly property real _margin: ScreenTools.defaultFontPixelWidth / 2
...@@ -38,7 +39,6 @@ Rectangle { ...@@ -38,7 +39,6 @@ Rectangle {
colorGroupEnabled: enabled colorGroupEnabled: enabled
} }
MouseArea { MouseArea {
anchors.fill: parent anchors.fill: parent
visible: !missionItem.isCurrentItem visible: !missionItem.isCurrentItem
...@@ -121,7 +121,6 @@ Rectangle { ...@@ -121,7 +121,6 @@ Rectangle {
anchors.rightMargin: ScreenTools.defaultFontPixelWidth anchors.rightMargin: ScreenTools.defaultFontPixelWidth
anchors.left: label.right anchors.left: label.right
anchors.top: parent.top anchors.top: parent.top
//anchors.right: hamburger.left
visible: missionItem.sequenceNumber != 0 && missionItem.isCurrentItem && !missionItem.rawEdit && missionItem.isSimpleItem visible: missionItem.sequenceNumber != 0 && missionItem.isCurrentItem && !missionItem.rawEdit && missionItem.isSimpleItem
text: missionItem.commandName text: missionItem.commandName
...@@ -133,7 +132,7 @@ Rectangle { ...@@ -133,7 +132,7 @@ Rectangle {
} }
} }
onClicked: qgcView.showDialog(commandDialog, qsTr("Select Mission Command"), qgcView.showDialogDefaultWidth, StandardButton.Cancel) onClicked: qgcView.showDialog(commandDialog, qsTr("Select Mission Command"), qgcView.showDialogDefaultWidth, StandardButton.Cancel)
} }
QGCLabel { QGCLabel {
...@@ -141,7 +140,7 @@ Rectangle { ...@@ -141,7 +140,7 @@ Rectangle {
visible: missionItem.sequenceNumber == 0 || !missionItem.isCurrentItem || !missionItem.isSimpleItem visible: missionItem.sequenceNumber == 0 || !missionItem.isCurrentItem || !missionItem.isSimpleItem
verticalAlignment: Text.AlignVCenter verticalAlignment: Text.AlignVCenter
text: missionItem.sequenceNumber == 0 ? text: missionItem.sequenceNumber == 0 ?
qsTr("Planned Home Position") : qsTr("Mission Settings") :
(missionItem.isSimpleItem ? missionItem.commandName : qsTr("Survey")) (missionItem.isSimpleItem ? missionItem.commandName : qsTr("Survey"))
color: _outerTextColor color: _outerTextColor
} }
...@@ -153,8 +152,12 @@ Rectangle { ...@@ -153,8 +152,12 @@ Rectangle {
anchors.left: parent.left anchors.left: parent.left
anchors.top: commandPicker.bottom anchors.top: commandPicker.bottom
height: item ? item.height : 0 height: item ? item.height : 0
source: missionItem.isSimpleItem ? "qrc:/qml/SimpleItemEditor.qml" : "qrc:/qml/SurveyItemEditor.qml" source: missionItem.sequenceNumber == 0 ? "qrc:/qml/MissionSettingsEditor.qml" : (missionItem.isSimpleItem ? "qrc:/qml/SimpleItemEditor.qml" : "qrc:/qml/SurveyItemEditor.qml")
onLoaded: { item.visible = Qt.binding(function() { return _currentItem; }) }
onLoaded: {
item.visible = Qt.binding(function() { return _currentItem; })
}
property real availableWidth: _root.width - (_margin * 2) ///< How wide the editor should be property real availableWidth: _root.width - (_margin * 2) ///< How wide the editor should be
property var editorRoot: _root property var editorRoot: _root
} }
......
...@@ -20,20 +20,6 @@ import QGroundControl.FactSystem 1.0 ...@@ -20,20 +20,6 @@ import QGroundControl.FactSystem 1.0
import QGroundControl.FactControls 1.0 import QGroundControl.FactControls 1.0
Rectangle { Rectangle {
readonly property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
property Fact _offlineEditingVehicleType: QGroundControl.offlineEditingVehicleType
property Fact _offlineEditingCruiseSpeed: QGroundControl.offlineEditingCruiseSpeed
property Fact _offlineEditingHoverSpeed: QGroundControl.offlineEditingHoverSpeed
property var currentMissionItem ///< Mission item to display status for
property var missionItems ///< List of all available mission items
property real expandedWidth ///< Width of control when expanded
property real missionDistance
property real missionMaxTelemetry
property real cruiseDistance
property real hoverDistance
width: _expanded ? expandedWidth : _collapsedWidth width: _expanded ? expandedWidth : _collapsedWidth
height: Math.max(valueGrid.height, valueMissionGrid.height) + (_margins * 2) height: Math.max(valueGrid.height, valueMissionGrid.height) + (_margins * 2)
radius: ScreenTools.defaultFontPixelWidth * 0.5 radius: ScreenTools.defaultFontPixelWidth * 0.5
...@@ -41,42 +27,35 @@ Rectangle { ...@@ -41,42 +27,35 @@ Rectangle {
opacity: 0.80 opacity: 0.80
clip: true clip: true
readonly property real margins: ScreenTools.defaultFontPixelWidth property var currentMissionItem ///< Mission item to display status for
property var missionItems ///< List of all available mission items
property real _collapsedWidth: valueGrid.width + (margins * 2) property real expandedWidth ///< Width of control when expanded
property bool _expanded: true property real missionDistance ///< Total mission distance
property real missionTime ///< Total mission time
property real _distance: _statusValid ? _currentMissionItem.distance : 0 property real missionMaxTelemetry
property real _altDifference: _statusValid ? _currentMissionItem.altDifference : 0
property real _gradient: _statusValid && _currentMissionItem.distance > 0 ? Math.atan(_currentMissionItem.altDifference / _currentMissionItem.distance) : 0 property real _collapsedWidth: valueGrid.width + (_margins * 2)
property real _gradientPercent: isNaN(_gradient) ? 0 : _gradient * 100 property bool _expanded: true
property real _azimuth: _statusValid ? _currentMissionItem.azimuth : -1
property real _missionDistance: _missionValid ? missionDistance : 0 property bool _statusValid: currentMissionItem != undefined
property real _missionMaxTelemetry: _missionValid ? missionMaxTelemetry : 0 property bool _missionValid: missionItems != undefined
property real _missionTime: _missionValid && _missionSpeed > 0 ? (_isVTOL ? _hoverTime + _cruiseTime : _missionDistance / _missionSpeed) : 0
property real _hoverDistance: _missionValid ? hoverDistance : 0 property real _distance: _statusValid ? _currentMissionItem.distance : NaN
property real _cruiseDistance: _missionValid ? cruiseDistance : 0 property real _altDifference: _statusValid ? _currentMissionItem.altDifference : NaN
property real _hoverTime: _missionValid && _offlineEditingHoverSpeed.value > 0 ? _hoverDistance / _offlineEditingHoverSpeed.value : 0 property real _gradient: _statusValid && _currentMissionItem.distance > 0 ? Math.atan(_currentMissionItem.altDifference / _currentMissionItem.distance) : NaN
property real _cruiseTime: _missionValid && _offlineEditingCruiseSpeed.value > 0 ? _cruiseDistance / _offlineEditingCruiseSpeed.value : 0 property real _gradientPercent: isNaN(_gradient) ? NaN : _gradient * 100
property real _azimuth: _statusValid ? _currentMissionItem.azimuth : NaN
property bool _statusValid: currentMissionItem != undefined property real _missionDistance: _missionValid ? missionDistance : NaN
property bool _vehicleValid: _activeVehicle != undefined property real _missionMaxTelemetry: _missionValid ? missionMaxTelemetry : NaN
property bool _missionValid: missionItems != undefined property real _missionTime: _missionValid ? missionTime : NaN
property bool _currentSurvey: _statusValid ? _currentMissionItem.commandName == "Survey" : false
property bool _isVTOL: _vehicleValid ? _activeVehicle.vtol : _offlineEditingVehicleType.enumStringValue == "VTOL" //hardcoded property string _distanceText: isNaN(_distance) ? "-.-" : QGroundControl.metersToAppSettingsDistanceUnits(_distance).toFixed(2) + " " + QGroundControl.appSettingsDistanceUnitsString
property real _missionSpeed: _offlineEditingVehicleType.enumStringValue == "Fixedwing" ? _offlineEditingCruiseSpeed.value : _offlineEditingHoverSpeed.value property string _altDifferenceText: isNaN(_altDifference) ? "-.-" : QGroundControl.metersToAppSettingsDistanceUnits(_altDifference).toFixed(2) + " " + QGroundControl.appSettingsDistanceUnitsString
property string _gradientText: isNaN(_gradient) ? "-.-" : _gradientPercent.toFixed(0) + "%"
property string _distanceText: _statusValid ? QGroundControl.metersToAppSettingsDistanceUnits(_distance).toFixed(2) + " " + QGroundControl.appSettingsDistanceUnitsString : " " property string _azimuthText: isNaN(_azimuth) ? "-.-" : Math.round(_azimuth)
property string _altText: _statusValid ? QGroundControl.metersToAppSettingsDistanceUnits(_altDifference).toFixed(2) + " " + QGroundControl.appSettingsDistanceUnitsString : " " property string _missionDistanceText: isNaN(_missionDistance) ? "-.-" : QGroundControl.metersToAppSettingsDistanceUnits(_missionDistance).toFixed(2) + " " + QGroundControl.appSettingsDistanceUnitsString
property string _gradientText: _statusValid ? _gradientPercent.toFixed(0) + "%" : " " property string _missionTimeText: isNaN(_missionTime) ? "-.-" : Number(_missionTime / 60).toFixed(1) + " min"
property string _azimuthText: _statusValid ? Math.round(_azimuth) : " " property string _missionMaxTelemetryText: isNaN(_missionMaxTelemetry) ? "-.-" : QGroundControl.metersToAppSettingsDistanceUnits(_missionMaxTelemetry).toFixed(2) + " " + QGroundControl.appSettingsDistanceUnitsString
property string _missionDistanceText: _missionValid ? QGroundControl.metersToAppSettingsDistanceUnits(_missionDistance).toFixed(2) + " " + QGroundControl.appSettingsDistanceUnitsString : " "
property string _missionTimeText: _missionValid ? Number(_missionTime / 60).toFixed(1) + " min" : " "
property string _missionMaxTelemetryText: _missionValid ? QGroundControl.metersToAppSettingsDistanceUnits(_missionMaxTelemetry).toFixed(2) + " " + QGroundControl.appSettingsDistanceUnitsString : " "
property string _hoverDistanceText: _missionValid ? QGroundControl.metersToAppSettingsDistanceUnits(_hoverDistance).toFixed(2) + " " + QGroundControl.appSettingsDistanceUnitsString : " "
property string _cruiseDistanceText: _missionValid ? QGroundControl.metersToAppSettingsDistanceUnits(_cruiseDistance).toFixed(2) + " " + QGroundControl.appSettingsDistanceUnitsString : " "
property string _hoverTimeText: _missionValid ? _hoverTime.toFixed(0) + "s" : " "
property string _cruiseTimeText: _missionValid ? _cruiseTime.toFixed(0) + "s" : " "
readonly property real _margins: ScreenTools.defaultFontPixelWidth readonly property real _margins: ScreenTools.defaultFontPixelWidth
...@@ -103,7 +82,7 @@ Rectangle { ...@@ -103,7 +82,7 @@ Rectangle {
QGCLabel { text: _distanceText } QGCLabel { text: _distanceText }
QGCLabel { text: qsTr("Alt diff:") } QGCLabel { text: qsTr("Alt diff:") }
QGCLabel { text: _altText } QGCLabel { text: _altDifferenceText }
QGCLabel { text: qsTr("Gradient:") } QGCLabel { text: qsTr("Gradient:") }
QGCLabel { text: _gradientText } QGCLabel { text: _gradientText }
...@@ -166,42 +145,6 @@ Rectangle { ...@@ -166,42 +145,6 @@ Rectangle {
QGCLabel { text: qsTr("Max telem dist:") } QGCLabel { text: qsTr("Max telem dist:") }
QGCLabel { text: _missionMaxTelemetryText } QGCLabel { text: _missionMaxTelemetryText }
QGCLabel {
text: qsTr("Hover distance:")
visible: _isVTOL
}
QGCLabel {
text: _hoverDistanceText
visible: _isVTOL
}
QGCLabel {
text: qsTr("Cruise distance:")
visible: _isVTOL
}
QGCLabel {
text: _cruiseDistanceText
visible: _isVTOL
}
QGCLabel {
text: qsTr("Hover time:")
visible: _isVTOL
}
QGCLabel {
text: _hoverTimeText
visible: _isVTOL
}
QGCLabel {
text: qsTr("Cruise time:")
visible: _isVTOL
}
QGCLabel {
text: _cruiseTimeText
visible: _isVTOL
}
} }
} }
} }
import QtQuick 2.5
import QtQuick.Controls 1.2
import QtQuick.Layouts 1.2
import QGroundControl 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Vehicle 1.0
import QGroundControl.Controls 1.0
import QGroundControl.FactControls 1.0
import QGroundControl.Palette 1.0
// Editor for Mission Settings
Rectangle {
id: valuesRect
width: availableWidth
height: deferedload.status == Loader.Ready ? (visible ? deferedload.item.height : 0) : 0
color: qgcPal.windowShadeDark
visible: missionItem.isCurrentItem
radius: _radius
Loader {
id: deferedload
active: valuesRect.visible
asynchronous: true
anchors.margins: _margin
anchors.left: valuesRect.left
anchors.right: valuesRect.right
anchors.top: valuesRect.top
sourceComponent: Component {
Item {
id: valuesItem
height: valuesColumn.height + (_margin * 2)
property var _missionVehicle: missionController.vehicle
property bool _offlineEditing: _missionVehicle.isOfflineEditingVehicle
property bool _showOfflineEditingCombos: _offlineEditing && _noMissionItemsAdded
property bool _showCruiseSpeed: !_missionVehicle.multiRotor
property bool _showHoverSpeed: _missionVehicle.multiRotor || missionController.vehicle.vtol
readonly property string _firmwareLabel: qsTr("Firmware:")
readonly property string _vehicleLabel: qsTr("Vehicle:")
QGCPalette { id: qgcPal }
Column {
id: valuesColumn
anchors.left: parent.left
anchors.right: parent.right
anchors.top: parent.top
spacing: _margin
QGCLabel { text: qsTr("Planned Home Position:") }
Rectangle {
anchors.left: parent.left
anchors.right: parent.right
height: 1
color: qgcPal.text
}
Repeater {
model: missionItem.textFieldFacts
Item {
width: valuesColumn.width
height: textField.height
QGCLabel {
id: textFieldLabel
anchors.baseline: textField.baseline
text: object.name
}
FactTextField {
id: textField
anchors.right: parent.right
width: _editFieldWidth
showUnits: true
fact: object
visible: !_root.readOnly
}
FactLabel {
anchors.baseline: textFieldLabel.baseline
anchors.right: parent.right
fact: object
visible: _root.readOnly
}
}
}
QGCButton {
text: qsTr("Move Home to map center")
visible: missionItem.homePosition
onClicked: editorRoot.moveHomeToMapCenter()
anchors.horizontalCenter: parent.horizontalCenter
}
QGCLabel {
width: parent.width
wrapMode: Text.WordWrap
font.pointSize: ScreenTools.smallFontPointSize
text: qsTr("Note: Planned home position for mission display only. Actual home position set by vehicle at flight time.")
}
QGCLabel { text: qsTr("Vehicle Info:") }
Rectangle {
anchors.left: parent.left
anchors.right: parent.right
height: 1
color: qgcPal.text
}
GridLayout {
anchors.left: parent.left
anchors.right: parent.right
columnSpacing: ScreenTools.defaultFontPixelWidth
rowSpacing: columnSpacing
columns: 2
QGCLabel {
text: _firmwareLabel
visible: _showOfflineEditingCombos
}
FactComboBox {
Layout.fillWidth: true
fact: QGroundControl.offlineEditingFirmwareType
indexModel: false
visible: _showOfflineEditingCombos
}
QGCLabel {
text: _firmwareLabel
visible: !_showOfflineEditingCombos
}
QGCLabel {
text: _missionVehicle.firmwareTypeString
visible: !_showOfflineEditingCombos
}
QGCLabel {
text: _vehicleLabel
visible: _showOfflineEditingCombos
}
FactComboBox {
id: offlineVehicleCombo
Layout.fillWidth: true
fact: QGroundControl.offlineEditingVehicleType
indexModel: false
visible: _showOfflineEditingCombos
}
QGCLabel {
text: _vehicleLabel
visible: !_showOfflineEditingCombos
}
QGCLabel {
text: _missionVehicle.vehicleTypeString
visible: !_showOfflineEditingCombos
}
QGCLabel {
Layout.row: 2
text: qsTr("Cruise speed:")
visible: _showCruiseSpeed
}
FactTextField {
Layout.fillWidth: true
fact: QGroundControl.offlineEditingCruiseSpeed
visible: _showCruiseSpeed
}
QGCLabel {
Layout.row: 3
text: qsTr("Hover speed:")
visible: _showHoverSpeed
}
FactTextField {
Layout.fillWidth: true
fact: QGroundControl.offlineEditingHoverSpeed
visible: _showHoverSpeed
}
} // GridLayout
QGCLabel {
width: parent.width
wrapMode: Text.WordWrap
font.pointSize: ScreenTools.smallFontPointSize
text: qsTr("Note: Speeds are planned speeds only for time calculations. Actual vehicle will not be affected.")
}
} // Column
} // Item
} // Component
} // Loader
} // Rectangle
...@@ -579,14 +579,17 @@ Rectangle { ...@@ -579,14 +579,17 @@ Rectangle {
} }
Grid { Grid {
columns: 2 columns: 2
spacing: ScreenTools.defaultFontPixelWidth columnSpacing: ScreenTools.defaultFontPixelWidth
QGCLabel { text: qsTr("Survey area:") } QGCLabel { text: qsTr("Survey area:") }
QGCLabel { text: QGroundControl.squareMetersToAppSettingsAreaUnits(missionItem.coveredArea).toFixed(2) + " " + QGroundControl.appSettingsAreaUnitsString } QGCLabel { text: QGroundControl.squareMetersToAppSettingsAreaUnits(missionItem.coveredArea).toFixed(2) + " " + QGroundControl.appSettingsAreaUnitsString }
QGCLabel { text: qsTr("# shots:") } QGCLabel { text: qsTr("# shots:") }
QGCLabel { text: missionItem.cameraShots } QGCLabel { text: missionItem.cameraShots }
QGCLabel { text: qsTr("Shot interval:") }
QGCLabel { text: missionItem.timeBetweenShots.toFixed(1) + " " + qsTr("secs")}
} }
} }
} }
...@@ -46,6 +46,9 @@ public: ...@@ -46,6 +46,9 @@ public:
/// @return the greatest distance from any point of the complex item to some coordinate /// @return the greatest distance from any point of the complex item to some coordinate
virtual double greatestDistanceTo(const QGeoCoordinate &other) const = 0; virtual double greatestDistanceTo(const QGeoCoordinate &other) const = 0;
/// Informs the complex item of the cruise speed it will fly at
virtual void setCruiseSpeed(double cruiseSpeed) = 0;
/// This mission item attribute specifies the type of the complex item. /// This mission item attribute specifies the type of the complex item.
static const char* jsonComplexItemTypeKey; static const char* jsonComplexItemTypeKey;
......
...@@ -5,7 +5,7 @@ ...@@ -5,7 +5,7 @@
"mavCmdInfo": [ "mavCmdInfo": [
{ {
"comment": "MAV_CMD_NAV_LAST: Used for fake home position waypoint", "comment": "MAV_CMD_NAV_LAST: Used for mission settings / planned home position waypoint",
"id": 95, "id": 95,
"rawName": "HomeRaw", "rawName": "HomeRaw",
"friendlyName": "Home Position", "friendlyName": "Home Position",
......
...@@ -33,6 +33,9 @@ const char* MissionController::_jsonFileTypeValue = "Mission"; ...@@ -33,6 +33,9 @@ const char* MissionController::_jsonFileTypeValue = "Mission";
const char* MissionController::_jsonItemsKey = "items"; const char* MissionController::_jsonItemsKey = "items";
const char* MissionController::_jsonPlannedHomePositionKey = "plannedHomePosition"; const char* MissionController::_jsonPlannedHomePositionKey = "plannedHomePosition";
const char* MissionController::_jsonFirmwareTypeKey = "firmwareType"; const char* MissionController::_jsonFirmwareTypeKey = "firmwareType";
const char* MissionController::_jsonVehicleTypeKey = "vehicleType";
const char* MissionController::_jsonCruiseSpeedKey = "cruiseSpeed";
const char* MissionController::_jsonHoverSpeedKey = "hoverSpeed";
const char* MissionController::_jsonParamsKey = "params"; const char* MissionController::_jsonParamsKey = "params";
// Deprecated V1 format keys // Deprecated V1 format keys
...@@ -49,9 +52,12 @@ MissionController::MissionController(QObject *parent) ...@@ -49,9 +52,12 @@ MissionController::MissionController(QObject *parent)
, _missionItemsRequested(false) , _missionItemsRequested(false)
, _queuedSend(false) , _queuedSend(false)
, _missionDistance(0.0) , _missionDistance(0.0)
, _missionTime(0.0)
, _missionHoverDistance(0.0)
, _missionHoverTime(0.0)
, _missionCruiseDistance(0.0)
, _missionCruiseTime(0.0)
, _missionMaxTelemetry(0.0) , _missionMaxTelemetry(0.0)
, _cruiseDistance(0.0)
, _hoverDistance(0.0)
{ {
} }
...@@ -396,6 +402,9 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec ...@@ -396,6 +402,9 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec
{ _jsonPlannedHomePositionKey, QJsonValue::Array, true }, { _jsonPlannedHomePositionKey, QJsonValue::Array, true },
{ _jsonItemsKey, QJsonValue::Array, true }, { _jsonItemsKey, QJsonValue::Array, true },
{ _jsonFirmwareTypeKey, QJsonValue::Double, true }, { _jsonFirmwareTypeKey, QJsonValue::Double, true },
{ _jsonVehicleTypeKey, QJsonValue::Double, false },
{ _jsonCruiseSpeedKey, QJsonValue::Double, false },
{ _jsonHoverSpeedKey, QJsonValue::Double, false },
}; };
if (!JsonHelper::validateKeys(json, rootKeyInfoList, errorString)) { if (!JsonHelper::validateKeys(json, rootKeyInfoList, errorString)) {
return false; return false;
...@@ -403,11 +412,21 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec ...@@ -403,11 +412,21 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec
qCDebug(MissionControllerLog) << "MissionController::_loadJsonMissionFileV2 itemCount:" << json[_jsonItemsKey].toArray().count(); qCDebug(MissionControllerLog) << "MissionController::_loadJsonMissionFileV2 itemCount:" << json[_jsonItemsKey].toArray().count();
// Planned home position // Mission Settings
QGeoCoordinate homeCoordinate; QGeoCoordinate homeCoordinate;
if (!JsonHelper::loadGeoCoordinate(json[_jsonPlannedHomePositionKey], true /* altitudeRequired */, homeCoordinate, errorString)) { if (!JsonHelper::loadGeoCoordinate(json[_jsonPlannedHomePositionKey], true /* altitudeRequired */, homeCoordinate, errorString)) {
return false; return false;
} }
if (json.contains(_jsonVehicleTypeKey) && _activeVehicle->isOfflineEditingVehicle()) {
QGroundControlQmlGlobal::offlineEditingVehicleType()->setRawValue(json[_jsonVehicleTypeKey].toDouble());
}
if (json.contains(_jsonCruiseSpeedKey)) {
QGroundControlQmlGlobal::offlineEditingCruiseSpeed()->setRawValue(json[_jsonCruiseSpeedKey].toDouble());
}
if (json.contains(_jsonHoverSpeedKey)) {
QGroundControlQmlGlobal::offlineEditingHoverSpeed()->setRawValue(json[_jsonHoverSpeedKey].toDouble());
}
SimpleMissionItem* homeItem = new SimpleMissionItem(_activeVehicle, this); SimpleMissionItem* homeItem = new SimpleMissionItem(_activeVehicle, this);
homeItem->setCoordinate(homeCoordinate); homeItem->setCoordinate(homeCoordinate);
visualItems->insert(0, homeItem); visualItems->insert(0, homeItem);
...@@ -645,19 +664,8 @@ void MissionController::saveToFile(const QString& filename) ...@@ -645,19 +664,8 @@ void MissionController::saveToFile(const QString& filename)
missionFileObject[JsonHelper::jsonVersionKey] = _missionFileVersion; missionFileObject[JsonHelper::jsonVersionKey] = _missionFileVersion;
missionFileObject[JsonHelper::jsonGroundStationKey] = JsonHelper::jsonGroundStationValue; missionFileObject[JsonHelper::jsonGroundStationKey] = JsonHelper::jsonGroundStationValue;
MAV_AUTOPILOT firmwareType = MAV_AUTOPILOT_GENERIC; // Mission settings
if (_activeVehicle) {
firmwareType = _activeVehicle->firmwareType();
} else {
// FIXME: Hack duplicated code from QGroundControlQmlGlobal. Had to do this for now since
// QGroundControlQmlGlobal is not available from C++ side.
QSettings settings;
firmwareType = (MAV_AUTOPILOT)settings.value("OfflineEditingFirmwareType", MAV_AUTOPILOT_ARDUPILOTMEGA).toInt();
}
missionFileObject[_jsonFirmwareTypeKey] = firmwareType;
// Save planned home position
SimpleMissionItem* homeItem = qobject_cast<SimpleMissionItem*>(_visualItems->get(0)); SimpleMissionItem* homeItem = qobject_cast<SimpleMissionItem*>(_visualItems->get(0));
if (!homeItem) { if (!homeItem) {
qgcApp()->showMessage(QStringLiteral("Internal error: VisualMissionItem at index 0 not SimpleMissionItem")); qgcApp()->showMessage(QStringLiteral("Internal error: VisualMissionItem at index 0 not SimpleMissionItem"));
...@@ -666,6 +674,10 @@ void MissionController::saveToFile(const QString& filename) ...@@ -666,6 +674,10 @@ void MissionController::saveToFile(const QString& filename)
QJsonValue coordinateValue; QJsonValue coordinateValue;
JsonHelper::saveGeoCoordinate(homeItem->coordinate(), true /* writeAltitude */, coordinateValue); JsonHelper::saveGeoCoordinate(homeItem->coordinate(), true /* writeAltitude */, coordinateValue);
missionFileObject[_jsonPlannedHomePositionKey] = coordinateValue; missionFileObject[_jsonPlannedHomePositionKey] = coordinateValue;
missionFileObject[_jsonFirmwareTypeKey] = _activeVehicle->firmwareType();
missionFileObject[_jsonVehicleTypeKey] = _activeVehicle->vehicleType();
missionFileObject[_jsonCruiseSpeedKey] = _activeVehicle->cruiseSpeed();
missionFileObject[_jsonHoverSpeedKey] = _activeVehicle->hoverSpeed();
// Save the visual items // Save the visual items
QJsonArray rgMissionItems; QJsonArray rgMissionItems;
...@@ -730,7 +742,7 @@ void MissionController::_calcPrevWaypointValues(double homeAlt, VisualMissionIte ...@@ -730,7 +742,7 @@ void MissionController::_calcPrevWaypointValues(double homeAlt, VisualMissionIte
} }
} }
void MissionController::_calcHomeDist(VisualMissionItem* currentItem, VisualMissionItem* homeItem, double* distance) double MissionController::_calcDistanceToHome(VisualMissionItem* currentItem, VisualMissionItem* homeItem)
{ {
QGeoCoordinate currentCoord = currentItem->coordinate(); QGeoCoordinate currentCoord = currentItem->coordinate();
QGeoCoordinate homeCoord = homeItem->exitCoordinate(); QGeoCoordinate homeCoord = homeItem->exitCoordinate();
...@@ -740,11 +752,7 @@ void MissionController::_calcHomeDist(VisualMissionItem* currentItem, VisualMiss ...@@ -740,11 +752,7 @@ void MissionController::_calcHomeDist(VisualMissionItem* currentItem, VisualMiss
qCDebug(MissionControllerLog) << "distanceOk" << distanceOk; qCDebug(MissionControllerLog) << "distanceOk" << distanceOk;
if (distanceOk) { return distanceOk ? homeCoord.distanceTo(currentCoord) : 0.0;
*distance = homeCoord.distanceTo(currentCoord);
} else {
*distance = 0.0;
}
} }
void MissionController::_recalcWaypointLines(void) void MissionController::_recalcWaypointLines(void)
...@@ -771,7 +779,7 @@ void MissionController::_recalcWaypointLines(void) ...@@ -771,7 +779,7 @@ void MissionController::_recalcWaypointLines(void)
VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i)); VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
// If we still haven't found the first coordinate item and we hit a a takeoff command link back to home // If we still haven't found the first coordinate item and we hit a takeoff command, link back to home
if (firstCoordinateItem && if (firstCoordinateItem &&
item->isSimpleItem() && item->isSimpleItem() &&
(qobject_cast<SimpleMissionItem*>(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF || (qobject_cast<SimpleMissionItem*>(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF ||
...@@ -842,7 +850,7 @@ void MissionController::_recalcAltitudeRangeBearing() ...@@ -842,7 +850,7 @@ void MissionController::_recalcAltitudeRangeBearing()
qWarning() << "Home item is not SimpleMissionItem"; qWarning() << "Home item is not SimpleMissionItem";
} }
bool showHomePosition = homeItem->showHomePosition(); bool showHomePosition = homeItem->showHomePosition();
qCDebug(MissionControllerLog) << "_recalcAltitudeRangeBearing"; qCDebug(MissionControllerLog) << "_recalcAltitudeRangeBearing";
...@@ -862,47 +870,68 @@ void MissionController::_recalcAltitudeRangeBearing() ...@@ -862,47 +870,68 @@ void MissionController::_recalcAltitudeRangeBearing()
double missionDistance = 0.0; double missionDistance = 0.0;
double missionMaxTelemetry = 0.0; double missionMaxTelemetry = 0.0;
double missionTime = 0.0;
double vtolHoverTime = 0.0;
double vtolCruiseTime = 0.0;
double vtolHoverDistance = 0.0;
double vtolCruiseDistance = 0.0;
double currentCruiseSpeed = _activeVehicle->cruiseSpeed();
double currentHoverSpeed = _activeVehicle->hoverSpeed();
bool vtolCalc = (QGroundControlQmlGlobal::offlineEditingVehicleType()->enumStringValue() == "VTOL" || (_activeVehicle && _activeVehicle->vtol())) ? true : false ; bool vtolVehicle = _activeVehicle->vtol();
double cruiseDistance = 0.0; bool vtolInHover = true;
double hoverDistance = 0.0;
bool hoverDistanceCalc = false;
bool hoverTransition = false;
bool cruiseTransition = false;
bool hoverDistanceReset = false;
bool linkBackToHome = false; bool linkBackToHome = false;
for (int i=1; i<_visualItems->count(); i++) { for (int i=1; i<_visualItems->count(); i++) {
VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i)); VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item);
ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);
// Assume the worst // Assume the worst
item->setAzimuth(0.0); item->setAzimuth(0.0);
item->setDistance(0.0); item->setDistance(0.0);
// If we still haven't found the first coordinate item and we hit a takeoff command link back to home if (simpleItem && simpleItem->command() == MavlinkQmlSingleton::MAV_CMD_DO_CHANGE_SPEED) {
if (firstCoordinateItem && // Adjust cruise speed for time calculations
item->isSimpleItem() && double newSpeed = simpleItem->missionItem().param2();
qobject_cast<SimpleMissionItem*>(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF) { if (newSpeed > 0) {
linkBackToHome = true; if (_activeVehicle->multiRotor()) {
hoverDistanceCalc = true; currentHoverSpeed = newSpeed;
} else {
currentCruiseSpeed = newSpeed;
}
}
} }
if (item->isSimpleItem() && vtolCalc) { // Link back to home if first item is takeoff and we have home position
SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item); if (firstCoordinateItem && simpleItem && simpleItem->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF) {
if (simpleItem->command() == MavlinkQmlSingleton::MAV_CMD_DO_VTOL_TRANSITION){ //transition waypoint value if (showHomePosition) {
if (simpleItem->missionItem().param1() == 3){ //hover mode value linkBackToHome = true;
hoverDistanceCalc = true; }
hoverTransition = true; }
}
else if (simpleItem->missionItem().param1() == 4){ // Update VTOL state
hoverDistanceCalc = false; if (simpleItem && vtolVehicle) {
cruiseTransition = true; switch (simpleItem->command()) {
case MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF:
vtolInHover = false;
break;
case MavlinkQmlSingleton::MAV_CMD_NAV_LAND:
vtolInHover = false;
break;
case MavlinkQmlSingleton::MAV_CMD_DO_VTOL_TRANSITION:
{
int transitionState = simpleItem->missionItem().param1();
if (transitionState == MAV_VTOL_STATE_TRANSITION_TO_MC) {
vtolInHover = true;
} else if (transitionState == MAV_VTOL_STATE_TRANSITION_TO_FW) {
vtolInHover = false;
} }
} }
if(!hoverTransition && cruiseTransition && !hoverDistanceReset && !linkBackToHome){ break;
hoverDistance = missionDistance; default:
hoverDistanceReset = true; break;
} }
} }
...@@ -927,62 +956,60 @@ void MissionController::_recalcAltitudeRangeBearing() ...@@ -927,62 +956,60 @@ void MissionController::_recalcAltitudeRangeBearing()
if (!item->isStandaloneCoordinate()) { if (!item->isStandaloneCoordinate()) {
firstCoordinateItem = false; firstCoordinateItem = false;
if (lastCoordinateItem != homeItem || (showHomePosition && linkBackToHome)) { if (lastCoordinateItem != homeItem || linkBackToHome) {
double azimuth, distance, altDifference, telemetryDistance; // This is a subsequent waypoint or we are forcing the first waypoint back to home
double azimuth, distance, altDifference;
// Subsequent coordinate items link to last coordinate item. If the last coordinate item
// is an invalid home position we skip the line
_calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItem, &azimuth, &distance, &altDifference); _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
item->setAltDifference(altDifference); item->setAltDifference(altDifference);
item->setAzimuth(azimuth); item->setAzimuth(azimuth);
item->setDistance(distance); item->setDistance(distance);
missionDistance += distance; missionDistance += distance;
missionMaxTelemetry = qMax(missionMaxTelemetry, _calcDistanceToHome(item, homeItem));
if (item->isSimpleItem()) {
_calcHomeDist(item, homeItem, &telemetryDistance); // Calculate mission time
if (vtolVehicle) {
if (vtolCalc) { if (vtolInHover) {
SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item); double hoverTime = distance / _activeVehicle->hoverSpeed();
if (simpleItem->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF || hoverDistanceCalc){ missionTime += hoverTime;
hoverDistance += distance; vtolHoverTime += hoverTime;
} vtolHoverDistance += distance;
cruiseDistance = missionDistance - hoverDistance; } else {
if(simpleItem->command() == MavlinkQmlSingleton::MAV_CMD_NAV_LAND && !linkBackToHome && !cruiseTransition && !hoverTransition){ double cruiseTime = distance / currentCruiseSpeed;
hoverDistance = cruiseDistance; missionTime += cruiseTime;
cruiseDistance = missionDistance - hoverDistance; vtolCruiseTime += cruiseTime;
} vtolCruiseDistance += distance;
} }
} else { } else {
missionDistance += qobject_cast<ComplexMissionItem*>(item)->complexDistance(); missionTime += distance / (_activeVehicle->multiRotor() ? currentHoverSpeed : currentCruiseSpeed);
telemetryDistance = qobject_cast<ComplexMissionItem*>(item)->greatestDistanceTo(homeItem->exitCoordinate());
if (vtolCalc){
cruiseDistance += qobject_cast<ComplexMissionItem*>(item)->complexDistance(); //assume all survey missions undertaken in cruise
}
}
if (telemetryDistance > missionMaxTelemetry) {
missionMaxTelemetry = telemetryDistance;
} }
} }
else if (lastCoordinateItem == homeItem && !item->isSimpleItem()){ if (complexItem) {
missionDistance += qobject_cast<ComplexMissionItem*>(item)->complexDistance(); // Add in distance/time inside survey as well
missionMaxTelemetry = qobject_cast<ComplexMissionItem*>(item)->greatestDistanceTo(homeItem->exitCoordinate()); // This code assumes all surveys are done cruise not hover
double complexDistance = complexItem->complexDistance();
if (vtolCalc){ double cruiseSpeed = _activeVehicle->multiRotor() ? currentHoverSpeed : currentCruiseSpeed;
cruiseDistance += qobject_cast<ComplexMissionItem*>(item)->complexDistance(); //assume all survey missions undertaken in cruise missionDistance += complexDistance;
} missionTime += complexDistance / cruiseSpeed;
missionMaxTelemetry = qMax(missionMaxTelemetry, complexItem->greatestDistanceTo(homeItem->exitCoordinate()));
// Let the complex item know the current cruise speed
complexItem->setCruiseSpeed(cruiseSpeed);
} }
lastCoordinateItem = item;
} }
lastCoordinateItem = item;
} }
} }
setMissionDistance(missionDistance); _setMissionMaxTelemetry(missionMaxTelemetry);
setMissionMaxTelemetry(missionMaxTelemetry); _setMissionDistance(missionDistance);
setCruiseDistance(cruiseDistance); _setMissionTime(missionTime);
setHoverDistance(hoverDistance); _setMissionHoverDistance(vtolHoverDistance);
_setMissionHoverTime(vtolHoverTime);
_setMissionCruiseDistance(vtolCruiseDistance);
_setMissionCruiseTime(vtolCruiseTime);
// Walk the list again calculating altitude percentages // Walk the list again calculating altitude percentages
double altRange = maxAltSeen - minAltSeen; double altRange = maxAltSeen - minAltSeen;
...@@ -1187,6 +1214,8 @@ void MissionController::_activeVehicleSet(void) ...@@ -1187,6 +1214,8 @@ void MissionController::_activeVehicleSet(void)
connect(missionManager, &MissionManager::currentItemChanged, this, &MissionController::_currentMissionItemChanged); connect(missionManager, &MissionManager::currentItemChanged, this, &MissionController::_currentMissionItemChanged);
connect(_activeVehicle, &Vehicle::homePositionAvailableChanged, this, &MissionController::_activeVehicleHomePositionAvailableChanged); connect(_activeVehicle, &Vehicle::homePositionAvailableChanged, this, &MissionController::_activeVehicleHomePositionAvailableChanged);
connect(_activeVehicle, &Vehicle::homePositionChanged, this, &MissionController::_activeVehicleHomePositionChanged); connect(_activeVehicle, &Vehicle::homePositionChanged, this, &MissionController::_activeVehicleHomePositionChanged);
connect(_activeVehicle, &Vehicle::cruiseSpeedChanged, this, &MissionController::_recalcAltitudeRangeBearing);
connect(_activeVehicle, &Vehicle::hoverSpeedChanged, this, &MissionController::_recalcAltitudeRangeBearing);
if (_activeVehicle->parameterManager()->parametersReady() && !syncInProgress()) { if (_activeVehicle->parameterManager()->parametersReady() && !syncInProgress()) {
// We are switching between two previously existing vehicles. We have to manually ask for the items from the Vehicle. // We are switching between two previously existing vehicles. We have to manually ask for the items from the Vehicle.
...@@ -1230,7 +1259,15 @@ void MissionController::_activeVehicleHomePositionChanged(const QGeoCoordinate& ...@@ -1230,7 +1259,15 @@ void MissionController::_activeVehicleHomePositionChanged(const QGeoCoordinate&
} }
} }
void MissionController::setMissionDistance(double missionDistance) void MissionController::_setMissionMaxTelemetry(double missionMaxTelemetry)
{
if (!qFuzzyCompare(_missionMaxTelemetry, missionMaxTelemetry)) {
_missionMaxTelemetry = missionMaxTelemetry;
emit missionMaxTelemetryChanged(_missionMaxTelemetry);
}
}
void MissionController::_setMissionDistance(double missionDistance)
{ {
if (!qFuzzyCompare(_missionDistance, missionDistance)) { if (!qFuzzyCompare(_missionDistance, missionDistance)) {
_missionDistance = missionDistance; _missionDistance = missionDistance;
...@@ -1238,27 +1275,43 @@ void MissionController::setMissionDistance(double missionDistance) ...@@ -1238,27 +1275,43 @@ void MissionController::setMissionDistance(double missionDistance)
} }
} }
void MissionController::setMissionMaxTelemetry(double missionMaxTelemetry) void MissionController::_setMissionTime(double missionTime)
{ {
if (!qFuzzyCompare(_missionMaxTelemetry, missionMaxTelemetry)) { if (!qFuzzyCompare(_missionTime, missionTime)) {
_missionMaxTelemetry = missionMaxTelemetry; _missionTime = missionTime;
emit missionMaxTelemetryChanged(_missionMaxTelemetry); emit missionTimeChanged();
}
}
void MissionController::_setMissionHoverTime(double missionHoverTime)
{
if (!qFuzzyCompare(_missionHoverTime, missionHoverTime)) {
_missionHoverTime = missionHoverTime;
emit missionHoverTimeChanged();
} }
} }
void MissionController::setCruiseDistance(double cruiseDistance) void MissionController::_setMissionHoverDistance(double missionHoverDistance)
{ {
if (!qFuzzyCompare(_cruiseDistance, cruiseDistance)) { if (!qFuzzyCompare(_missionHoverDistance, missionHoverDistance)) {
_cruiseDistance = cruiseDistance; _missionHoverDistance = missionHoverDistance;
emit cruiseDistanceChanged(_cruiseDistance); emit missionHoverDistanceChanged(_missionHoverDistance);
} }
} }
void MissionController::setHoverDistance(double hoverDistance) void MissionController::_setMissionCruiseTime(double missionCruiseTime)
{ {
if (!qFuzzyCompare(_hoverDistance, hoverDistance)) { if (!qFuzzyCompare(_missionCruiseTime, missionCruiseTime)) {
_hoverDistance = hoverDistance; _missionCruiseTime = missionCruiseTime;
emit hoverDistanceChanged(_hoverDistance); emit missionCruiseTimeChanged();
}
}
void MissionController::_setMissionCruiseDistance(double missionCruiseDistance)
{
if (!qFuzzyCompare(_missionCruiseDistance, missionCruiseDistance)) {
_missionCruiseDistance = missionCruiseDistance;
emit missionCruiseDistanceChanged(_missionCruiseDistance);
} }
} }
...@@ -1437,3 +1490,21 @@ QString MissionController::fileExtension(void) const ...@@ -1437,3 +1490,21 @@ QString MissionController::fileExtension(void) const
{ {
return QGCApplication::missionFileExtension; return QGCApplication::missionFileExtension;
} }
double MissionController::cruiseSpeed(void) const
{
if (_activeVehicle) {
return _activeVehicle->cruiseSpeed();
} else {
return 0.0f;
}
}
double MissionController::hoverSpeed(void) const
{
if (_activeVehicle) {
return _activeVehicle->hoverSpeed();
} else {
return 0.0f;
}
}
...@@ -34,15 +34,18 @@ public: ...@@ -34,15 +34,18 @@ public:
MissionController(QObject* parent = NULL); MissionController(QObject* parent = NULL);
~MissionController(); ~MissionController();
Q_PROPERTY(QGeoCoordinate plannedHomePosition READ plannedHomePosition NOTIFY plannedHomePositionChanged) Q_PROPERTY(QGeoCoordinate plannedHomePosition READ plannedHomePosition NOTIFY plannedHomePositionChanged)
Q_PROPERTY(QmlObjectListModel* visualItems READ visualItems NOTIFY visualItemsChanged) Q_PROPERTY(QmlObjectListModel* visualItems READ visualItems NOTIFY visualItemsChanged)
Q_PROPERTY(QmlObjectListModel* complexVisualItems READ complexVisualItems NOTIFY complexVisualItemsChanged) Q_PROPERTY(QmlObjectListModel* complexVisualItems READ complexVisualItems NOTIFY complexVisualItemsChanged)
Q_PROPERTY(QmlObjectListModel* waypointLines READ waypointLines NOTIFY waypointLinesChanged) Q_PROPERTY(QmlObjectListModel* waypointLines READ waypointLines NOTIFY waypointLinesChanged)
Q_PROPERTY(double missionDistance READ missionDistance NOTIFY missionDistanceChanged) Q_PROPERTY(double missionDistance READ missionDistance NOTIFY missionDistanceChanged)
Q_PROPERTY(double missionMaxTelemetry READ missionMaxTelemetry NOTIFY missionMaxTelemetryChanged) Q_PROPERTY(double missionTime READ missionTime NOTIFY missionTimeChanged)
Q_PROPERTY(double cruiseDistance READ cruiseDistance NOTIFY cruiseDistanceChanged) Q_PROPERTY(double missionHoverDistance READ missionHoverDistance NOTIFY missionHoverDistanceChanged)
Q_PROPERTY(double hoverDistance READ hoverDistance NOTIFY hoverDistanceChanged) Q_PROPERTY(double missionCruiseDistance READ missionCruiseDistance NOTIFY missionCruiseDistanceChanged)
Q_PROPERTY(double missionHoverTime READ missionHoverTime NOTIFY missionHoverTimeChanged)
Q_PROPERTY(double missionCruiseTime READ missionCruiseTime NOTIFY missionCruiseTimeChanged)
Q_PROPERTY(double missionMaxTelemetry READ missionMaxTelemetry NOTIFY missionMaxTelemetryChanged)
Q_INVOKABLE void removeMissionItem(int index); Q_INVOKABLE void removeMissionItem(int index);
...@@ -80,15 +83,14 @@ public: ...@@ -80,15 +83,14 @@ public:
QmlObjectListModel* waypointLines (void) { return &_waypointLines; } QmlObjectListModel* waypointLines (void) { return &_waypointLines; }
double missionDistance (void) const { return _missionDistance; } double missionDistance (void) const { return _missionDistance; }
double missionTime (void) const { return _missionTime; }
double missionHoverDistance (void) const { return _missionHoverDistance; }
double missionHoverTime (void) const { return _missionHoverTime; }
double missionCruiseDistance (void) const { return _missionCruiseDistance; }
double missionCruiseTime (void) const { return _missionCruiseTime; }
double missionMaxTelemetry (void) const { return _missionMaxTelemetry; } double missionMaxTelemetry (void) const { return _missionMaxTelemetry; }
double cruiseDistance (void) const { return _cruiseDistance; } double cruiseSpeed (void) const;
double hoverDistance (void) const { return _hoverDistance; } double hoverSpeed (void) const;
void setMissionDistance (double missionDistance );
void setMissionMaxTelemetry (double missionMaxTelemetry);
void setCruiseDistance (double cruiseDistance );
void setHoverDistance (double hoverDistance );
signals: signals:
void plannedHomePositionChanged(QGeoCoordinate plannedHomePosition); void plannedHomePositionChanged(QGeoCoordinate plannedHomePosition);
...@@ -97,9 +99,16 @@ signals: ...@@ -97,9 +99,16 @@ signals:
void waypointLinesChanged(void); void waypointLinesChanged(void);
void newItemsFromVehicle(void); void newItemsFromVehicle(void);
void missionDistanceChanged(double missionDistance); void missionDistanceChanged(double missionDistance);
void missionTimeChanged(void);
void missionHoverDistanceChanged(double missionHoverDistance);
void missionHoverTimeChanged(void);
void missionCruiseDistanceChanged(double missionCruiseDistance);
void missionCruiseTimeChanged(void);
void missionMaxTelemetryChanged(double missionMaxTelemetry); void missionMaxTelemetryChanged(double missionMaxTelemetry);
void cruiseDistanceChanged(double cruiseDistance); void cruiseDistanceChanged(double cruiseDistance);
void hoverDistanceChanged(double hoverDistance); void hoverDistanceChanged(double hoverDistance);
void cruiseSpeedChanged(double cruiseSpeed);
void hoverSpeedChanged(double hoverSpeed);
private slots: private slots:
void _newMissionItemsAvailableFromVehicle(); void _newMissionItemsAvailableFromVehicle();
...@@ -123,7 +132,7 @@ private: ...@@ -123,7 +132,7 @@ private:
void _deinitVisualItem(VisualMissionItem* item); void _deinitVisualItem(VisualMissionItem* item);
void _setupActiveVehicle(Vehicle* activeVehicle, bool forceLoadFromVehicle); void _setupActiveVehicle(Vehicle* activeVehicle, bool forceLoadFromVehicle);
static void _calcPrevWaypointValues(double homeAlt, VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference); static void _calcPrevWaypointValues(double homeAlt, VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference);
static void _calcHomeDist(VisualMissionItem* currentItem, VisualMissionItem* homeItem, double* distance); static double _calcDistanceToHome(VisualMissionItem* currentItem, VisualMissionItem* homeItem);
bool _findLastAltitude(double* lastAltitude, MAV_FRAME* frame); bool _findLastAltitude(double* lastAltitude, MAV_FRAME* frame);
bool _findLastAcceptanceRadius(double* lastAcceptanceRadius); bool _findLastAcceptanceRadius(double* lastAcceptanceRadius);
void _addPlannedHomePosition(QmlObjectListModel* visualItems, bool addToCenter); void _addPlannedHomePosition(QmlObjectListModel* visualItems, bool addToCenter);
...@@ -134,6 +143,13 @@ private: ...@@ -134,6 +143,13 @@ private:
bool _loadJsonMissionFileV2(const QJsonObject& json, QmlObjectListModel* visualItems, QmlObjectListModel* complexItems, QString& errorString); bool _loadJsonMissionFileV2(const QJsonObject& json, QmlObjectListModel* visualItems, QmlObjectListModel* complexItems, QString& errorString);
bool _loadTextMissionFile(QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString); bool _loadTextMissionFile(QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString);
int _nextSequenceNumber(void); int _nextSequenceNumber(void);
void _setMissionDistance(double missionDistance);
void _setMissionTime(double missionTime);
void _setMissionHoverDistance(double missionHoverDistance);
void _setMissionHoverTime(double missionHoverTime);
void _setMissionCruiseDistance(double missionCruiseDistance);
void _setMissionCruiseTime(double missionCruiseTime);
void _setMissionMaxTelemetry(double missionMaxTelemetry);
// Overrides from PlanElementController // Overrides from PlanElementController
void _activeVehicleBeingRemoved(void) final; void _activeVehicleBeingRemoved(void) final;
...@@ -148,13 +164,19 @@ private: ...@@ -148,13 +164,19 @@ private:
bool _missionItemsRequested; bool _missionItemsRequested;
bool _queuedSend; bool _queuedSend;
double _missionDistance; double _missionDistance;
double _missionTime;
double _missionHoverDistance;
double _missionHoverTime;
double _missionCruiseDistance;
double _missionCruiseTime;
double _missionMaxTelemetry; double _missionMaxTelemetry;
double _cruiseDistance;
double _hoverDistance;
static const char* _settingsGroup; static const char* _settingsGroup;
static const char* _jsonFileTypeValue; static const char* _jsonFileTypeValue;
static const char* _jsonFirmwareTypeKey; static const char* _jsonFirmwareTypeKey;
static const char* _jsonVehicleTypeKey;
static const char* _jsonCruiseSpeedKey;
static const char* _jsonHoverSpeedKey;
static const char* _jsonItemsKey; static const char* _jsonItemsKey;
static const char* _jsonPlannedHomePositionKey; static const char* _jsonPlannedHomePositionKey;
static const char* _jsonParamsKey; static const char* _jsonParamsKey;
......
...@@ -54,4 +54,6 @@ void PlanElementController::_activeVehicleChanged(Vehicle* activeVehicle) ...@@ -54,4 +54,6 @@ void PlanElementController::_activeVehicleChanged(Vehicle* activeVehicle)
// Whenever vehicle changes we need to update syncInProgress // Whenever vehicle changes we need to update syncInProgress
emit syncInProgressChanged(syncInProgress()); emit syncInProgressChanged(syncInProgress());
emit vehicleChanged(_activeVehicle);
} }
...@@ -35,6 +35,8 @@ public: ...@@ -35,6 +35,8 @@ public:
Q_PROPERTY(QString fileExtension READ fileExtension CONSTANT) Q_PROPERTY(QString fileExtension READ fileExtension CONSTANT)
virtual QString fileExtension(void) const = 0; virtual QString fileExtension(void) const = 0;
Q_PROPERTY(Vehicle* vehicle READ vehicle NOTIFY vehicleChanged)
/// Should be called immediately upon Component.onCompleted. /// Should be called immediately upon Component.onCompleted.
/// @param editMode true: controller being used in Plan view, false: controller being used in Fly view /// @param editMode true: controller being used in Plan view, false: controller being used in Fly view
Q_INVOKABLE virtual void start(bool editMode); Q_INVOKABLE virtual void start(bool editMode);
...@@ -55,9 +57,12 @@ public: ...@@ -55,9 +57,12 @@ public:
virtual bool dirty (void) const = 0; virtual bool dirty (void) const = 0;
virtual void setDirty (bool dirty) = 0; virtual void setDirty (bool dirty) = 0;
Vehicle* vehicle(void) { return _activeVehicle; }
signals: signals:
void syncInProgressChanged (bool syncInProgress); void syncInProgressChanged (bool syncInProgress);
void dirtyChanged (bool dirty); void dirtyChanged (bool dirty);
void vehicleChanged (Vehicle* vehicle);
protected: protected:
MultiVehicleManager* _multiVehicleMgr; MultiVehicleManager* _multiVehicleMgr;
......
...@@ -12,6 +12,7 @@ ...@@ -12,6 +12,7 @@
#include "JsonHelper.h" #include "JsonHelper.h"
#include "MissionController.h" #include "MissionController.h"
#include "QGCGeo.h" #include "QGCGeo.h"
#include "QGroundControlQmlGlobal.h"
#include <QPolygonF> #include <QPolygonF>
...@@ -70,6 +71,7 @@ SurveyMissionItem::SurveyMissionItem(Vehicle* vehicle, QObject* parent) ...@@ -70,6 +71,7 @@ SurveyMissionItem::SurveyMissionItem(Vehicle* vehicle, QObject* parent)
, _surveyDistance(0.0) , _surveyDistance(0.0)
, _cameraShots(0) , _cameraShots(0)
, _coveredArea(0.0) , _coveredArea(0.0)
, _timeBetweenShots(0.0)
, _gridAltitudeFact (0, _gridAltitudeFactName, FactMetaData::valueTypeDouble) , _gridAltitudeFact (0, _gridAltitudeFactName, FactMetaData::valueTypeDouble)
, _gridAngleFact (0, _gridAngleFactName, FactMetaData::valueTypeDouble) , _gridAngleFact (0, _gridAngleFactName, FactMetaData::valueTypeDouble)
, _gridSpacingFact (0, _gridSpacingFactName, FactMetaData::valueTypeDouble) , _gridSpacingFact (0, _gridSpacingFactName, FactMetaData::valueTypeDouble)
...@@ -132,7 +134,11 @@ SurveyMissionItem::SurveyMissionItem(Vehicle* vehicle, QObject* parent) ...@@ -132,7 +134,11 @@ SurveyMissionItem::SurveyMissionItem(Vehicle* vehicle, QObject* parent)
connect(&_cameraResolutionHeightFact, &Fact::valueChanged, this, &SurveyMissionItem::_cameraValueChanged); connect(&_cameraResolutionHeightFact, &Fact::valueChanged, this, &SurveyMissionItem::_cameraValueChanged);
connect(&_cameraFocalLengthFact, &Fact::valueChanged, this, &SurveyMissionItem::_cameraValueChanged); connect(&_cameraFocalLengthFact, &Fact::valueChanged, this, &SurveyMissionItem::_cameraValueChanged);
connect(this, &SurveyMissionItem::cameraTriggerChanged, this, &SurveyMissionItem::_cameraTriggerChanged); connect(this, &SurveyMissionItem::cameraTriggerChanged, this, &SurveyMissionItem::_cameraTriggerChanged);
connect(&_cameraTriggerDistanceFact, &Fact::valueChanged, this, &SurveyMissionItem::timeBetweenShotsChanged);
connect(_vehicle, &Vehicle::cruiseSpeedChanged, this, &SurveyMissionItem::timeBetweenShotsChanged);
connect(_vehicle, &Vehicle::hoverSpeedChanged, this, &SurveyMissionItem::timeBetweenShotsChanged);
} }
void SurveyMissionItem::_setSurveyDistance(double surveyDistance) void SurveyMissionItem::_setSurveyDistance(double surveyDistance)
...@@ -780,6 +786,7 @@ QmlObjectListModel* SurveyMissionItem::getMissionItems(void) const ...@@ -780,6 +786,7 @@ QmlObjectListModel* SurveyMissionItem::getMissionItems(void) const
pMissionItems->append(item); pMissionItems->append(item);
if (_cameraTrigger && i == 0) { if (_cameraTrigger && i == 0) {
// Turn on camera
MissionItem* item = new MissionItem(seqNum++, // sequence number MissionItem* item = new MissionItem(seqNum++, // sequence number
MAV_CMD_DO_SET_CAM_TRIGG_DIST, // MAV_CMD MAV_CMD_DO_SET_CAM_TRIGG_DIST, // MAV_CMD
MAV_FRAME_MISSION, // MAV_FRAME MAV_FRAME_MISSION, // MAV_FRAME
...@@ -793,6 +800,7 @@ QmlObjectListModel* SurveyMissionItem::getMissionItems(void) const ...@@ -793,6 +800,7 @@ QmlObjectListModel* SurveyMissionItem::getMissionItems(void) const
} }
if (_cameraTrigger) { if (_cameraTrigger) {
// Turn off camera
MissionItem* item = new MissionItem(seqNum++, // sequence number MissionItem* item = new MissionItem(seqNum++, // sequence number
MAV_CMD_DO_SET_CAM_TRIGG_DIST, // MAV_CMD MAV_CMD_DO_SET_CAM_TRIGG_DIST, // MAV_CMD
MAV_FRAME_MISSION, // MAV_FRAME MAV_FRAME_MISSION, // MAV_FRAME
...@@ -810,10 +818,9 @@ QmlObjectListModel* SurveyMissionItem::getMissionItems(void) const ...@@ -810,10 +818,9 @@ QmlObjectListModel* SurveyMissionItem::getMissionItems(void) const
void SurveyMissionItem::_cameraTriggerChanged(void) void SurveyMissionItem::_cameraTriggerChanged(void)
{ {
setDirty(true); setDirty(true);
if (_gridPoints.count()) { // Camera trigger adds items
// If we have grid turn on/off camera trigger will add/remove two camera trigger mission items emit lastSequenceNumberChanged(lastSequenceNumber());
emit lastSequenceNumberChanged(lastSequenceNumber()); // We now have camera shot count
}
emit cameraShotsChanged(cameraShots()); emit cameraShotsChanged(cameraShots());
} }
...@@ -826,3 +833,16 @@ void SurveyMissionItem::_cameraValueChanged(void) ...@@ -826,3 +833,16 @@ void SurveyMissionItem::_cameraValueChanged(void)
{ {
emit cameraValueChanged(); emit cameraValueChanged();
} }
double SurveyMissionItem::timeBetweenShots(void) const
{
return _cruiseSpeed == 0 ? 0 : _cameraTriggerDistanceFact.rawValue().toDouble() / _cruiseSpeed;
}
void SurveyMissionItem::setCruiseSpeed(double cruiseSpeed)
{
if (!qFuzzyCompare(_cruiseSpeed, cruiseSpeed)) {
_cruiseSpeed = cruiseSpeed;
emit timeBetweenShotsChanged();
}
}
...@@ -48,6 +48,7 @@ public: ...@@ -48,6 +48,7 @@ public:
Q_PROPERTY(bool cameraOrientationLandscape MEMBER _cameraOrientationLandscape NOTIFY cameraOrientationLandscapeChanged) Q_PROPERTY(bool cameraOrientationLandscape MEMBER _cameraOrientationLandscape NOTIFY cameraOrientationLandscapeChanged)
Q_PROPERTY(bool manualGrid MEMBER _manualGrid NOTIFY manualGridChanged) Q_PROPERTY(bool manualGrid MEMBER _manualGrid NOTIFY manualGridChanged)
Q_PROPERTY(QString camera MEMBER _camera NOTIFY cameraChanged) Q_PROPERTY(QString camera MEMBER _camera NOTIFY cameraChanged)
Q_PROPERTY(double timeBetweenShots READ timeBetweenShots NOTIFY timeBetweenShotsChanged)
Q_INVOKABLE void clearPolygon(void); Q_INVOKABLE void clearPolygon(void);
Q_INVOKABLE void addPolygonCoordinate(const QGeoCoordinate coordinate); Q_INVOKABLE void addPolygonCoordinate(const QGeoCoordinate coordinate);
...@@ -72,6 +73,7 @@ public: ...@@ -72,6 +73,7 @@ public:
int cameraShots(void) const; int cameraShots(void) const;
double coveredArea(void) const { return _coveredArea; } double coveredArea(void) const { return _coveredArea; }
double timeBetweenShots(void) const;
// Overrides from ComplexMissionItem // Overrides from ComplexMissionItem
...@@ -80,6 +82,8 @@ public: ...@@ -80,6 +82,8 @@ public:
QmlObjectListModel* getMissionItems (void) const final; QmlObjectListModel* getMissionItems (void) const final;
bool load (const QJsonObject& complexObject, int sequenceNumber, QString& errorString) final; bool load (const QJsonObject& complexObject, int sequenceNumber, QString& errorString) final;
double greatestDistanceTo (const QGeoCoordinate &other) const final; double greatestDistanceTo (const QGeoCoordinate &other) const final;
void setCruiseSpeed (double cruiseSpeed) final;
// Overrides from VisualMissionItem // Overrides from VisualMissionItem
...@@ -121,6 +125,7 @@ signals: ...@@ -121,6 +125,7 @@ signals:
void cameraOrientationLandscapeChanged (bool cameraOrientationLandscape); void cameraOrientationLandscapeChanged (bool cameraOrientationLandscape);
void cameraChanged (QString camera); void cameraChanged (QString camera);
void manualGridChanged (bool manualGrid); void manualGridChanged (bool manualGrid);
void timeBetweenShotsChanged (void);
private slots: private slots:
void _cameraTriggerChanged(void); void _cameraTriggerChanged(void);
...@@ -158,6 +163,8 @@ private: ...@@ -158,6 +163,8 @@ private:
double _surveyDistance; double _surveyDistance;
int _cameraShots; int _cameraShots;
double _coveredArea; double _coveredArea;
double _timeBetweenShots;
double _cruiseSpeed;
Fact _gridAltitudeFact; Fact _gridAltitudeFact;
Fact _gridAngleFact; Fact _gridAngleFact;
...@@ -198,7 +205,6 @@ private: ...@@ -198,7 +205,6 @@ private:
static const char* _jsonCameraOrientationLandscapeKey; static const char* _jsonCameraOrientationLandscapeKey;
static const char* _jsonFixedValueIsAltitudeKey; static const char* _jsonFixedValueIsAltitudeKey;
static const char* _gridAltitudeFactName; static const char* _gridAltitudeFactName;
static const char* _gridAngleFactName; static const char* _gridAngleFactName;
static const char* _gridSpacingFactName; static const char* _gridSpacingFactName;
......
...@@ -3,7 +3,7 @@ ...@@ -3,7 +3,7 @@
"name": "OfflineEditingFirmwareType", "name": "OfflineEditingFirmwareType",
"shortDescription": "Offline editing firmware type", "shortDescription": "Offline editing firmware type",
"type": "uint32", "type": "uint32",
"enumStrings": "ArduPilot Firmware,PX4 Pro Firmware,Mavlink Generic Firmware", "enumStrings": "ArduPilot,PX4 Pro,Mavlink Generic",
"enumValues": "3,12,0", "enumValues": "3,12,0",
"defaultValue": 3 "defaultValue": 3
}, },
...@@ -11,7 +11,7 @@ ...@@ -11,7 +11,7 @@
"name": "OfflineEditingVehicleType", "name": "OfflineEditingVehicleType",
"shortDescription": "Offline editing vehicle type", "shortDescription": "Offline editing vehicle type",
"type": "uint32", "type": "uint32",
"enumStrings": "Fixedwing,Multicopter,VTOL,Rover,Sub", "enumStrings": "Fixed Wing,Multi-Rotor,VTOL,Rover,Sub",
"enumValues": "1,2,19,10,12", "enumValues": "1,2,19,10,12",
"defaultValue": 1 "defaultValue": 1
}, },
......
...@@ -96,6 +96,8 @@ Vehicle::Vehicle(LinkInterface* link, ...@@ -96,6 +96,8 @@ Vehicle::Vehicle(LinkInterface* link,
, _onboardControlSensorsUnhealthy(0) , _onboardControlSensorsUnhealthy(0)
, _gpsRawIntMessageAvailable(false) , _gpsRawIntMessageAvailable(false)
, _globalPositionIntMessageAvailable(false) , _globalPositionIntMessageAvailable(false)
, _cruiseSpeed(QGroundControlQmlGlobal::offlineEditingCruiseSpeed()->rawValue().toDouble())
, _hoverSpeed(QGroundControlQmlGlobal::offlineEditingHoverSpeed()->rawValue().toDouble())
, _connectionLost(false) , _connectionLost(false)
, _connectionLostEnabled(true) , _connectionLostEnabled(true)
, _missionManager(NULL) , _missionManager(NULL)
...@@ -150,7 +152,7 @@ Vehicle::Vehicle(LinkInterface* link, ...@@ -150,7 +152,7 @@ Vehicle::Vehicle(LinkInterface* link,
connect(_uas, &UAS::imageReady, this, &Vehicle::_imageReady); connect(_uas, &UAS::imageReady, this, &Vehicle::_imageReady);
connect(this, &Vehicle::remoteControlRSSIChanged, this, &Vehicle::_remoteControlRSSIChanged); connect(this, &Vehicle::remoteControlRSSIChanged, this, &Vehicle::_remoteControlRSSIChanged);
_firmwarePlugin = _firmwarePluginManager->firmwarePluginForAutopilot(_firmwareType, _vehicleType); _commonInit();
_autopilotPlugin = _firmwarePlugin->autopilotPlugin(this); _autopilotPlugin = _firmwarePlugin->autopilotPlugin(this);
// connect this vehicle to the follow me handle manager // connect this vehicle to the follow me handle manager
...@@ -183,21 +185,6 @@ Vehicle::Vehicle(LinkInterface* link, ...@@ -183,21 +185,6 @@ Vehicle::Vehicle(LinkInterface* link,
_loadSettings(); _loadSettings();
_missionManager = new MissionManager(this);
connect(_missionManager, &MissionManager::error, this, &Vehicle::_missionManagerError);
connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &Vehicle::_newMissionItemsAvailable);
_parameterManager = new ParameterManager(this);
connect(_parameterManager, &ParameterManager::parametersReadyChanged, this, &Vehicle::_parametersReady);
// GeoFenceManager needs to access ParameterManager so make sure to create after
_geoFenceManager = _firmwarePlugin->newGeoFenceManager(this);
connect(_geoFenceManager, &GeoFenceManager::error, this, &Vehicle::_geoFenceManagerError);
connect(_geoFenceManager, &GeoFenceManager::loadComplete, this, &Vehicle::_newGeoFenceAvailable);
_rallyPointManager = _firmwarePlugin->newRallyPointManager(this);
connect(_rallyPointManager, &RallyPointManager::error, this, &Vehicle::_rallyPointManagerError);
// Ask the vehicle for firmware version info. // Ask the vehicle for firmware version info.
sendMavCommand(MAV_COMP_ID_ALL, // Don't know default component id yet. sendMavCommand(MAV_COMP_ID_ALL, // Don't know default component id yet.
MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES, MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES,
...@@ -214,27 +201,6 @@ Vehicle::Vehicle(LinkInterface* link, ...@@ -214,27 +201,6 @@ Vehicle::Vehicle(LinkInterface* link,
// Invalidate the timer to signal first announce // Invalidate the timer to signal first announce
_lowBatteryAnnounceTimer.invalidate(); _lowBatteryAnnounceTimer.invalidate();
// Build FactGroup object model
_addFact(&_rollFact, _rollFactName);
_addFact(&_pitchFact, _pitchFactName);
_addFact(&_headingFact, _headingFactName);
_addFact(&_groundSpeedFact, _groundSpeedFactName);
_addFact(&_airSpeedFact, _airSpeedFactName);
_addFact(&_climbRateFact, _climbRateFactName);
_addFact(&_altitudeRelativeFact, _altitudeRelativeFactName);
_addFact(&_altitudeAMSLFact, _altitudeAMSLFactName);
_addFactGroup(&_gpsFactGroup, _gpsFactGroupName);
_addFactGroup(&_batteryFactGroup, _batteryFactGroupName);
_addFactGroup(&_windFactGroup, _windFactGroupName);
_addFactGroup(&_vibrationFactGroup, _vibrationFactGroupName);
_gpsFactGroup.setVehicle(this);
_batteryFactGroup.setVehicle(this);
_windFactGroup.setVehicle(this);
_vibrationFactGroup.setVehicle(this);
} }
// Disconnected Vehicle for offline editing // Disconnected Vehicle for offline editing
...@@ -275,6 +241,8 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType, ...@@ -275,6 +241,8 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
, _onboardControlSensorsUnhealthy(0) , _onboardControlSensorsUnhealthy(0)
, _gpsRawIntMessageAvailable(false) , _gpsRawIntMessageAvailable(false)
, _globalPositionIntMessageAvailable(false) , _globalPositionIntMessageAvailable(false)
, _cruiseSpeed(QGroundControlQmlGlobal::offlineEditingCruiseSpeed()->rawValue().toDouble())
, _hoverSpeed(QGroundControlQmlGlobal::offlineEditingHoverSpeed()->rawValue().toDouble())
, _connectionLost(false) , _connectionLost(false)
, _connectionLostEnabled(true) , _connectionLostEnabled(true)
, _missionManager(NULL) , _missionManager(NULL)
...@@ -314,8 +282,13 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType, ...@@ -314,8 +282,13 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
, _windFactGroup(this) , _windFactGroup(this)
, _vibrationFactGroup(this) , _vibrationFactGroup(this)
{ {
_firmwarePlugin = _firmwarePluginManager->firmwarePluginForAutopilot(_firmwareType, _vehicleType); _commonInit();
_firmwarePlugin->initializeVehicle(this); _firmwarePlugin->initializeVehicle(this);
}
void Vehicle::_commonInit(void)
{
_firmwarePlugin = _firmwarePluginManager->firmwarePluginForAutopilot(_firmwareType, _vehicleType);
_missionManager = new MissionManager(this); _missionManager = new MissionManager(this);
connect(_missionManager, &MissionManager::error, this, &Vehicle::_missionManagerError); connect(_missionManager, &MissionManager::error, this, &Vehicle::_missionManagerError);
...@@ -329,6 +302,12 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType, ...@@ -329,6 +302,12 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
_rallyPointManager = _firmwarePlugin->newRallyPointManager(this); _rallyPointManager = _firmwarePlugin->newRallyPointManager(this);
connect(_rallyPointManager, &RallyPointManager::error, this, &Vehicle::_rallyPointManagerError); connect(_rallyPointManager, &RallyPointManager::error, this, &Vehicle::_rallyPointManagerError);
// Offline editing vehicle tracks settings changes for offline editing settings
connect(QGroundControlQmlGlobal::offlineEditingFirmwareType(), &Fact::rawValueChanged, this, &Vehicle::_offlineFirmwareTypeSettingChanged);
connect(QGroundControlQmlGlobal::offlineEditingVehicleType(), &Fact::rawValueChanged, this, &Vehicle::_offlineVehicleTypeSettingChanged);
connect(QGroundControlQmlGlobal::offlineEditingCruiseSpeed(), &Fact::rawValueChanged, this, &Vehicle::_offlineCruiseSpeedSettingChanged);
connect(QGroundControlQmlGlobal::offlineEditingHoverSpeed(), &Fact::rawValueChanged, this, &Vehicle::_offlineHoverSpeedSettingChanged);
// Build FactGroup object model // Build FactGroup object model
_addFact(&_rollFact, _rollFactName); _addFact(&_rollFact, _rollFactName);
...@@ -344,11 +323,6 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType, ...@@ -344,11 +323,6 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
_addFactGroup(&_batteryFactGroup, _batteryFactGroupName); _addFactGroup(&_batteryFactGroup, _batteryFactGroupName);
_addFactGroup(&_windFactGroup, _windFactGroupName); _addFactGroup(&_windFactGroup, _windFactGroupName);
_addFactGroup(&_vibrationFactGroup, _vibrationFactGroupName); _addFactGroup(&_vibrationFactGroup, _vibrationFactGroupName);
_gpsFactGroup.setVehicle(NULL);
_batteryFactGroup.setVehicle(NULL);
_windFactGroup.setVehicle(NULL);
_vibrationFactGroup.setVehicle(NULL);
} }
Vehicle::~Vehicle() Vehicle::~Vehicle()
...@@ -366,8 +340,59 @@ Vehicle::~Vehicle() ...@@ -366,8 +340,59 @@ Vehicle::~Vehicle()
} }
void void Vehicle::_offlineFirmwareTypeSettingChanged(QVariant value)
Vehicle::resetCounters() {
_firmwareType = static_cast<MAV_AUTOPILOT>(value.toInt());
emit firmwareTypeChanged();
}
void Vehicle::_offlineVehicleTypeSettingChanged(QVariant value)
{
_vehicleType = static_cast<MAV_TYPE>(value.toInt());
emit vehicleTypeChanged();
}
void Vehicle::_offlineCruiseSpeedSettingChanged(QVariant value)
{
_cruiseSpeed = value.toDouble();
emit cruiseSpeedChanged(_cruiseSpeed);
}
void Vehicle::_offlineHoverSpeedSettingChanged(QVariant value)
{
_hoverSpeed = value.toDouble();
emit hoverSpeedChanged(_hoverSpeed);
}
QString Vehicle::firmwareTypeString(void) const
{
if (px4Firmware()) {
return QStringLiteral("PX4 Pro");
} else if (apmFirmware()) {
return QStringLiteral("ArduPilot");
} else {
return tr("MAVLink Generic");
}
}
QString Vehicle::vehicleTypeString(void) const
{
if (fixedWing()) {
return tr("Fixed Wing");
} else if (multiRotor()) {
return tr("Multi-Rotor");
} else if (vtol()) {
return tr("VTOL");
} else if (rover()) {
return tr("Rover");
} else if (sub()) {
return tr("Sub");
} else {
return tr("Unknown");
}
}
void Vehicle::resetCounters()
{ {
_messagesReceived = 0; _messagesReceived = 0;
_messagesSent = 0; _messagesSent = 0;
...@@ -2084,7 +2109,6 @@ const char* VehicleGPSFactGroup::_lockFactName = "lock"; ...@@ -2084,7 +2109,6 @@ const char* VehicleGPSFactGroup::_lockFactName = "lock";
VehicleGPSFactGroup::VehicleGPSFactGroup(QObject* parent) VehicleGPSFactGroup::VehicleGPSFactGroup(QObject* parent)
: FactGroup(1000, ":/json/Vehicle/GPSFact.json", parent) : FactGroup(1000, ":/json/Vehicle/GPSFact.json", parent)
, _vehicle(NULL)
, _hdopFact (0, _hdopFactName, FactMetaData::valueTypeDouble) , _hdopFact (0, _hdopFactName, FactMetaData::valueTypeDouble)
, _vdopFact (0, _vdopFactName, FactMetaData::valueTypeDouble) , _vdopFact (0, _vdopFactName, FactMetaData::valueTypeDouble)
, _courseOverGroundFact (0, _courseOverGroundFactName, FactMetaData::valueTypeDouble) , _courseOverGroundFact (0, _courseOverGroundFactName, FactMetaData::valueTypeDouble)
...@@ -2169,11 +2193,6 @@ QString Vehicle::takeControlFlightMode(void) const ...@@ -2169,11 +2193,6 @@ QString Vehicle::takeControlFlightMode(void) const
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void VehicleGPSFactGroup::setVehicle(Vehicle* vehicle)
{
_vehicle = vehicle;
}
const char* VehicleBatteryFactGroup::_voltageFactName = "voltage"; const char* VehicleBatteryFactGroup::_voltageFactName = "voltage";
const char* VehicleBatteryFactGroup::_percentRemainingFactName = "percentRemaining"; const char* VehicleBatteryFactGroup::_percentRemainingFactName = "percentRemaining";
const char* VehicleBatteryFactGroup::_mahConsumedFactName = "mahConsumed"; const char* VehicleBatteryFactGroup::_mahConsumedFactName = "mahConsumed";
...@@ -2192,7 +2211,6 @@ const int VehicleBatteryFactGroup::_cellCountUnavailable = -1.0; ...@@ -2192,7 +2211,6 @@ const int VehicleBatteryFactGroup::_cellCountUnavailable = -1.0;
VehicleBatteryFactGroup::VehicleBatteryFactGroup(QObject* parent) VehicleBatteryFactGroup::VehicleBatteryFactGroup(QObject* parent)
: FactGroup(1000, ":/json/Vehicle/BatteryFact.json", parent) : FactGroup(1000, ":/json/Vehicle/BatteryFact.json", parent)
, _vehicle(NULL)
, _voltageFact (0, _voltageFactName, FactMetaData::valueTypeDouble) , _voltageFact (0, _voltageFactName, FactMetaData::valueTypeDouble)
, _percentRemainingFact (0, _percentRemainingFactName, FactMetaData::valueTypeInt32) , _percentRemainingFact (0, _percentRemainingFactName, FactMetaData::valueTypeInt32)
, _mahConsumedFact (0, _mahConsumedFactName, FactMetaData::valueTypeInt32) , _mahConsumedFact (0, _mahConsumedFactName, FactMetaData::valueTypeInt32)
...@@ -2216,18 +2234,12 @@ VehicleBatteryFactGroup::VehicleBatteryFactGroup(QObject* parent) ...@@ -2216,18 +2234,12 @@ VehicleBatteryFactGroup::VehicleBatteryFactGroup(QObject* parent)
_cellCountFact.setRawValue (_cellCountUnavailable); _cellCountFact.setRawValue (_cellCountUnavailable);
} }
void VehicleBatteryFactGroup::setVehicle(Vehicle* vehicle)
{
_vehicle = vehicle;
}
const char* VehicleWindFactGroup::_directionFactName = "direction"; const char* VehicleWindFactGroup::_directionFactName = "direction";
const char* VehicleWindFactGroup::_speedFactName = "speed"; const char* VehicleWindFactGroup::_speedFactName = "speed";
const char* VehicleWindFactGroup::_verticalSpeedFactName = "verticalSpeed"; const char* VehicleWindFactGroup::_verticalSpeedFactName = "verticalSpeed";
VehicleWindFactGroup::VehicleWindFactGroup(QObject* parent) VehicleWindFactGroup::VehicleWindFactGroup(QObject* parent)
: FactGroup(1000, ":/json/Vehicle/WindFact.json", parent) : FactGroup(1000, ":/json/Vehicle/WindFact.json", parent)
, _vehicle(NULL)
, _directionFact (0, _directionFactName, FactMetaData::valueTypeDouble) , _directionFact (0, _directionFactName, FactMetaData::valueTypeDouble)
, _speedFact (0, _speedFactName, FactMetaData::valueTypeDouble) , _speedFact (0, _speedFactName, FactMetaData::valueTypeDouble)
, _verticalSpeedFact(0, _verticalSpeedFactName, FactMetaData::valueTypeDouble) , _verticalSpeedFact(0, _verticalSpeedFactName, FactMetaData::valueTypeDouble)
...@@ -2242,11 +2254,6 @@ VehicleWindFactGroup::VehicleWindFactGroup(QObject* parent) ...@@ -2242,11 +2254,6 @@ VehicleWindFactGroup::VehicleWindFactGroup(QObject* parent)
_verticalSpeedFact.setRawValue (std::numeric_limits<float>::quiet_NaN()); _verticalSpeedFact.setRawValue (std::numeric_limits<float>::quiet_NaN());
} }
void VehicleWindFactGroup::setVehicle(Vehicle* vehicle)
{
_vehicle = vehicle;
}
const char* VehicleVibrationFactGroup::_xAxisFactName = "xAxis"; const char* VehicleVibrationFactGroup::_xAxisFactName = "xAxis";
const char* VehicleVibrationFactGroup::_yAxisFactName = "yAxis"; const char* VehicleVibrationFactGroup::_yAxisFactName = "yAxis";
const char* VehicleVibrationFactGroup::_zAxisFactName = "zAxis"; const char* VehicleVibrationFactGroup::_zAxisFactName = "zAxis";
...@@ -2256,7 +2263,6 @@ const char* VehicleVibrationFactGroup::_clipCount3FactName = "clipCount3"; ...@@ -2256,7 +2263,6 @@ const char* VehicleVibrationFactGroup::_clipCount3FactName = "clipCount3";
VehicleVibrationFactGroup::VehicleVibrationFactGroup(QObject* parent) VehicleVibrationFactGroup::VehicleVibrationFactGroup(QObject* parent)
: FactGroup(1000, ":/json/Vehicle/VibrationFact.json", parent) : FactGroup(1000, ":/json/Vehicle/VibrationFact.json", parent)
, _vehicle(NULL)
, _xAxisFact (0, _xAxisFactName, FactMetaData::valueTypeDouble) , _xAxisFact (0, _xAxisFactName, FactMetaData::valueTypeDouble)
, _yAxisFact (0, _yAxisFactName, FactMetaData::valueTypeDouble) , _yAxisFact (0, _yAxisFactName, FactMetaData::valueTypeDouble)
, _zAxisFact (0, _zAxisFactName, FactMetaData::valueTypeDouble) , _zAxisFact (0, _zAxisFactName, FactMetaData::valueTypeDouble)
...@@ -2276,8 +2282,3 @@ VehicleVibrationFactGroup::VehicleVibrationFactGroup(QObject* parent) ...@@ -2276,8 +2282,3 @@ VehicleVibrationFactGroup::VehicleVibrationFactGroup(QObject* parent)
_yAxisFact.setRawValue(std::numeric_limits<float>::quiet_NaN()); _yAxisFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
_zAxisFact.setRawValue(std::numeric_limits<float>::quiet_NaN()); _zAxisFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
} }
void VehicleVibrationFactGroup::setVehicle(Vehicle* vehicle)
{
_vehicle = vehicle;
}
...@@ -63,8 +63,6 @@ public: ...@@ -63,8 +63,6 @@ public:
Fact* clipCount2 (void) { return &_clipCount2Fact; } Fact* clipCount2 (void) { return &_clipCount2Fact; }
Fact* clipCount3 (void) { return &_clipCount3Fact; } Fact* clipCount3 (void) { return &_clipCount3Fact; }
void setVehicle(Vehicle* vehicle);
static const char* _xAxisFactName; static const char* _xAxisFactName;
static const char* _yAxisFactName; static const char* _yAxisFactName;
static const char* _zAxisFactName; static const char* _zAxisFactName;
...@@ -73,7 +71,6 @@ public: ...@@ -73,7 +71,6 @@ public:
static const char* _clipCount3FactName; static const char* _clipCount3FactName;
private: private:
Vehicle* _vehicle;
Fact _xAxisFact; Fact _xAxisFact;
Fact _yAxisFact; Fact _yAxisFact;
Fact _zAxisFact; Fact _zAxisFact;
...@@ -97,14 +94,11 @@ public: ...@@ -97,14 +94,11 @@ public:
Fact* speed (void) { return &_speedFact; } Fact* speed (void) { return &_speedFact; }
Fact* verticalSpeed (void) { return &_verticalSpeedFact; } Fact* verticalSpeed (void) { return &_verticalSpeedFact; }
void setVehicle(Vehicle* vehicle);
static const char* _directionFactName; static const char* _directionFactName;
static const char* _speedFactName; static const char* _speedFactName;
static const char* _verticalSpeedFactName; static const char* _verticalSpeedFactName;
private: private:
Vehicle* _vehicle;
Fact _directionFact; Fact _directionFact;
Fact _speedFact; Fact _speedFact;
Fact _verticalSpeedFact; Fact _verticalSpeedFact;
...@@ -129,8 +123,6 @@ public: ...@@ -129,8 +123,6 @@ public:
Fact* count (void) { return &_countFact; } Fact* count (void) { return &_countFact; }
Fact* lock (void) { return &_lockFact; } Fact* lock (void) { return &_lockFact; }
void setVehicle(Vehicle* vehicle);
static const char* _hdopFactName; static const char* _hdopFactName;
static const char* _vdopFactName; static const char* _vdopFactName;
static const char* _courseOverGroundFactName; static const char* _courseOverGroundFactName;
...@@ -138,7 +130,6 @@ public: ...@@ -138,7 +130,6 @@ public:
static const char* _lockFactName; static const char* _lockFactName;
private: private:
Vehicle* _vehicle;
Fact _hdopFact; Fact _hdopFact;
Fact _vdopFact; Fact _vdopFact;
Fact _courseOverGroundFact; Fact _courseOverGroundFact;
...@@ -168,8 +159,6 @@ public: ...@@ -168,8 +159,6 @@ public:
Fact* cellCount (void) { return &_cellCountFact; } Fact* cellCount (void) { return &_cellCountFact; }
void setVehicle(Vehicle* vehicle);
static const char* _voltageFactName; static const char* _voltageFactName;
static const char* _percentRemainingFactName; static const char* _percentRemainingFactName;
static const char* _mahConsumedFactName; static const char* _mahConsumedFactName;
...@@ -187,7 +176,6 @@ public: ...@@ -187,7 +176,6 @@ public:
static const int _cellCountUnavailable; static const int _cellCountUnavailable;
private: private:
Vehicle* _vehicle;
Fact _voltageFact; Fact _voltageFact;
Fact _percentRemainingFact; Fact _percentRemainingFact;
Fact _mahConsumedFact; Fact _mahConsumedFact;
...@@ -245,8 +233,8 @@ public: ...@@ -245,8 +233,8 @@ public:
Q_PROPERTY(bool active READ active WRITE setActive NOTIFY activeChanged) Q_PROPERTY(bool active READ active WRITE setActive NOTIFY activeChanged)
Q_PROPERTY(int flowImageIndex READ flowImageIndex NOTIFY flowImageIndexChanged) Q_PROPERTY(int flowImageIndex READ flowImageIndex NOTIFY flowImageIndexChanged)
Q_PROPERTY(int rcRSSI READ rcRSSI NOTIFY rcRSSIChanged) Q_PROPERTY(int rcRSSI READ rcRSSI NOTIFY rcRSSIChanged)
Q_PROPERTY(bool px4Firmware READ px4Firmware CONSTANT) Q_PROPERTY(bool px4Firmware READ px4Firmware NOTIFY firmwareTypeChanged)
Q_PROPERTY(bool apmFirmware READ apmFirmware CONSTANT) Q_PROPERTY(bool apmFirmware READ apmFirmware NOTIFY firmwareTypeChanged)
Q_PROPERTY(bool soloFirmware READ soloFirmware WRITE setSoloFirmware NOTIFY soloFirmwareChanged) Q_PROPERTY(bool soloFirmware READ soloFirmware WRITE setSoloFirmware NOTIFY soloFirmwareChanged)
Q_PROPERTY(bool genericFirmware READ genericFirmware CONSTANT) Q_PROPERTY(bool genericFirmware READ genericFirmware CONSTANT)
Q_PROPERTY(bool connectionLost READ connectionLost NOTIFY connectionLostChanged) Q_PROPERTY(bool connectionLost READ connectionLost NOTIFY connectionLostChanged)
...@@ -254,26 +242,28 @@ public: ...@@ -254,26 +242,28 @@ public:
Q_PROPERTY(uint messagesReceived READ messagesReceived NOTIFY messagesReceivedChanged) Q_PROPERTY(uint messagesReceived READ messagesReceived NOTIFY messagesReceivedChanged)
Q_PROPERTY(uint messagesSent READ messagesSent NOTIFY messagesSentChanged) Q_PROPERTY(uint messagesSent READ messagesSent NOTIFY messagesSentChanged)
Q_PROPERTY(uint messagesLost READ messagesLost NOTIFY messagesLostChanged) Q_PROPERTY(uint messagesLost READ messagesLost NOTIFY messagesLostChanged)
Q_PROPERTY(bool fixedWing READ fixedWing CONSTANT) Q_PROPERTY(bool fixedWing READ fixedWing NOTIFY vehicleTypeChanged)
Q_PROPERTY(bool multiRotor READ multiRotor CONSTANT) Q_PROPERTY(bool multiRotor READ multiRotor NOTIFY vehicleTypeChanged)
Q_PROPERTY(bool vtol READ vtol CONSTANT) Q_PROPERTY(bool vtol READ vtol NOTIFY vehicleTypeChanged)
Q_PROPERTY(bool rover READ rover CONSTANT) Q_PROPERTY(bool rover READ rover NOTIFY vehicleTypeChanged)
Q_PROPERTY(bool sub READ sub NOTIFY vehicleTypeChanged)
Q_PROPERTY(bool supportsManualControl READ supportsManualControl CONSTANT) Q_PROPERTY(bool supportsManualControl READ supportsManualControl CONSTANT)
Q_PROPERTY(bool supportsThrottleModeCenterZero READ supportsThrottleModeCenterZero CONSTANT) Q_PROPERTY(bool supportsThrottleModeCenterZero READ supportsThrottleModeCenterZero CONSTANT)
Q_PROPERTY(bool supportsJSButton READ supportsJSButton CONSTANT) Q_PROPERTY(bool supportsJSButton READ supportsJSButton CONSTANT)
Q_PROPERTY(bool supportsRadio READ supportsRadio CONSTANT) Q_PROPERTY(bool supportsRadio READ supportsRadio CONSTANT)
Q_PROPERTY(bool sub READ sub CONSTANT)
Q_PROPERTY(bool autoDisconnect MEMBER _autoDisconnect NOTIFY autoDisconnectChanged) Q_PROPERTY(bool autoDisconnect MEMBER _autoDisconnect NOTIFY autoDisconnectChanged)
Q_PROPERTY(QString prearmError READ prearmError WRITE setPrearmError NOTIFY prearmErrorChanged) Q_PROPERTY(QString prearmError READ prearmError WRITE setPrearmError NOTIFY prearmErrorChanged)
Q_PROPERTY(int motorCount READ motorCount CONSTANT) Q_PROPERTY(int motorCount READ motorCount CONSTANT)
Q_PROPERTY(bool coaxialMotors READ coaxialMotors CONSTANT) Q_PROPERTY(bool coaxialMotors READ coaxialMotors CONSTANT)
Q_PROPERTY(bool xConfigMotors READ xConfigMotors CONSTANT) Q_PROPERTY(bool xConfigMotors READ xConfigMotors CONSTANT)
Q_PROPERTY(bool isOfflineEditingVehicle READ isOfflineEditingVehicle CONSTANT) Q_PROPERTY(bool isOfflineEditingVehicle READ isOfflineEditingVehicle CONSTANT)
Q_PROPERTY(QString brandImage READ brandImage CONSTANT) Q_PROPERTY(QString brandImage READ brandImage NOTIFY firmwareTypeChanged)
Q_PROPERTY(QStringList unhealthySensors READ unhealthySensors NOTIFY unhealthySensorsChanged) Q_PROPERTY(QStringList unhealthySensors READ unhealthySensors NOTIFY unhealthySensorsChanged)
Q_PROPERTY(QString missionFlightMode READ missionFlightMode CONSTANT) Q_PROPERTY(QString missionFlightMode READ missionFlightMode CONSTANT)
Q_PROPERTY(QString rtlFlightMode READ rtlFlightMode CONSTANT) Q_PROPERTY(QString rtlFlightMode READ rtlFlightMode CONSTANT)
Q_PROPERTY(QString takeControlFlightMode READ takeControlFlightMode CONSTANT) Q_PROPERTY(QString takeControlFlightMode READ takeControlFlightMode CONSTANT)
Q_PROPERTY(QString firmwareTypeString READ firmwareTypeString NOTIFY firmwareTypeChanged)
Q_PROPERTY(QString vehicleTypeString READ vehicleTypeString NOTIFY vehicleTypeChanged)
/// true: Vehicle is flying, false: Vehicle is on ground /// true: Vehicle is flying, false: Vehicle is on ground
Q_PROPERTY(bool flying READ flying WRITE setFlying NOTIFY flyingChanged) Q_PROPERTY(bool flying READ flying WRITE setFlying NOTIFY flyingChanged)
...@@ -528,6 +518,10 @@ public: ...@@ -528,6 +518,10 @@ public:
QString missionFlightMode () const; QString missionFlightMode () const;
QString rtlFlightMode () const; QString rtlFlightMode () const;
QString takeControlFlightMode () const; QString takeControlFlightMode () const;
double cruiseSpeed () const { return _cruiseSpeed; }
double hoverSpeed () const { return _hoverSpeed; }
QString firmwareTypeString () const;
QString vehicleTypeString () const;
Fact* roll (void) { return &_rollFact; } Fact* roll (void) { return &_rollFact; }
Fact* heading (void) { return &_headingFact; } Fact* heading (void) { return &_headingFact; }
...@@ -615,6 +609,10 @@ signals: ...@@ -615,6 +609,10 @@ signals:
void prearmErrorChanged(const QString& prearmError); void prearmErrorChanged(const QString& prearmError);
void soloFirmwareChanged(bool soloFirmware); void soloFirmwareChanged(bool soloFirmware);
void unhealthySensorsChanged(void); void unhealthySensorsChanged(void);
void cruiseSpeedChanged(double cruiseSpeed);
void hoverSpeedChanged(double hoverSpeed);
void firmwareTypeChanged(void);
void vehicleTypeChanged(void);
void messagesReceivedChanged (); void messagesReceivedChanged ();
void messagesSentChanged (); void messagesSentChanged ();
...@@ -673,6 +671,10 @@ private slots: ...@@ -673,6 +671,10 @@ private slots:
void _remoteControlRSSIChanged(uint8_t rssi); void _remoteControlRSSIChanged(uint8_t rssi);
void _handleFlightModeChanged(const QString& flightMode); void _handleFlightModeChanged(const QString& flightMode);
void _announceArmedChanged(bool armed); void _announceArmedChanged(bool armed);
void _offlineFirmwareTypeSettingChanged(QVariant value);
void _offlineVehicleTypeSettingChanged(QVariant value);
void _offlineCruiseSpeedSettingChanged(QVariant value);
void _offlineHoverSpeedSettingChanged(QVariant value);
void _handleTextMessage (int newCount); void _handleTextMessage (int newCount);
void _handletextMessageReceived (UASMessage* message); void _handletextMessageReceived (UASMessage* message);
...@@ -724,8 +726,8 @@ private: ...@@ -724,8 +726,8 @@ private:
void _ackMavlinkLogData(uint16_t sequence); void _ackMavlinkLogData(uint16_t sequence);
void _sendNextQueuedMavCommand(void); void _sendNextQueuedMavCommand(void);
void _updatePriorityLink(void); void _updatePriorityLink(void);
void _commonInit(void);
private:
int _id; ///< Mavlink system id int _id; ///< Mavlink system id
bool _active; bool _active;
bool _offlineEditingVehicle; ///< This Vehicle is a "disconnected" vehicle for ui use while offline editing bool _offlineEditingVehicle; ///< This Vehicle is a "disconnected" vehicle for ui use while offline editing
...@@ -771,6 +773,8 @@ private: ...@@ -771,6 +773,8 @@ private:
uint32_t _onboardControlSensorsUnhealthy; uint32_t _onboardControlSensorsUnhealthy;
bool _gpsRawIntMessageAvailable; bool _gpsRawIntMessageAvailable;
bool _globalPositionIntMessageAvailable; bool _globalPositionIntMessageAvailable;
double _cruiseSpeed;
double _hoverSpeed;
typedef struct { typedef struct {
int component; int component;
......
...@@ -13,6 +13,7 @@ import QtQuick.Controls 1.2 ...@@ -13,6 +13,7 @@ import QtQuick.Controls 1.2
import QtQuick.Controls.Styles 1.2 import QtQuick.Controls.Styles 1.2
import QtQuick.Dialogs 1.1 import QtQuick.Dialogs 1.1
import QtMultimedia 5.5 import QtMultimedia 5.5
import QtQuick.Layouts 1.2
import QGroundControl 1.0 import QGroundControl 1.0
import QGroundControl.FactSystem 1.0 import QGroundControl.FactSystem 1.0
...@@ -33,6 +34,10 @@ QGCView { ...@@ -33,6 +34,10 @@ QGCView {
property Fact _percentRemainingAnnounce: QGroundControl.batteryPercentRemainingAnnounce property Fact _percentRemainingAnnounce: QGroundControl.batteryPercentRemainingAnnounce
property real _labelWidth: ScreenTools.defaultFontPixelWidth * 15 property real _labelWidth: ScreenTools.defaultFontPixelWidth * 15
property real _editFieldWidth: ScreenTools.defaultFontPixelWidth * 30 property real _editFieldWidth: ScreenTools.defaultFontPixelWidth * 30
property bool _showCruiseSpeed: offlineVehicleCombo.currentText != "Multicopter"
property bool _showHoverSpeed: offlineVehicleCombo.currentText != "FixedWing"
readonly property string _requiresRestart: qsTr("(Requires Restart)")
QGCPalette { id: qgcPal } QGCPalette { id: qgcPal }
...@@ -117,90 +122,6 @@ QGCView { ...@@ -117,90 +122,6 @@ QGCView {
} }
} }
//----------------------------------------------------------------- //-----------------------------------------------------------------
//-- Offline mission editing
Item {
width: qgcView.width * 0.8
height: offlineLabel.height
anchors.margins: ScreenTools.defaultFontPixelWidth
anchors.horizontalCenter: parent.horizontalCenter
QGCLabel {
id: offlineLabel
text: qsTr("Offline Mission Editing (Requires Restart)")
font.family: ScreenTools.demiboldFontFamily
}
}
Rectangle {
height: offlineCol.height + (ScreenTools.defaultFontPixelHeight * 2)
width: qgcView.width * 0.8
color: qgcPal.windowShade
anchors.margins: ScreenTools.defaultFontPixelWidth
anchors.horizontalCenter: parent.horizontalCenter
Column {
id: offlineCol
spacing: ScreenTools.defaultFontPixelWidth
anchors.centerIn: parent
Row {
spacing: ScreenTools.defaultFontPixelWidth
QGCLabel {
text: qsTr("Firmware:")
width: _labelWidth
anchors.baseline: offlineTypeCombo.baseline
}
FactComboBox {
id: offlineTypeCombo
width: _editFieldWidth
fact: QGroundControl.offlineEditingFirmwareType
indexModel: false
}
}
Row {
spacing: ScreenTools.defaultFontPixelWidth
QGCLabel {
text: qsTr("Vehicle:")
width: _labelWidth
anchors.baseline: offlineVehicleCombo.baseline
}
FactComboBox {
id: offlineVehicleCombo
width: _editFieldWidth
fact: QGroundControl.offlineEditingVehicleType
indexModel: false
}
}
Row {
spacing: ScreenTools.defaultFontPixelWidth
visible: offlineVehicleCombo.currentText != "Multicopter"
QGCLabel {
text: qsTr("Cruise speed:")
width: _labelWidth
anchors.baseline: cruiseSpeedField.baseline
}
FactTextField {
id: cruiseSpeedField
width: _editFieldWidth
fact: QGroundControl.offlineEditingCruiseSpeed
enabled: true
}
}
Row {
spacing: ScreenTools.defaultFontPixelWidth
visible: offlineVehicleCombo.currentText != "Fixedwing"
QGCLabel {
id: hoverSpeedLabel
text: qsTr("Hover speed:")
width: _labelWidth
anchors.baseline: hoverSpeedField.baseline
}
FactTextField {
id: hoverSpeedField
width: _editFieldWidth
fact: QGroundControl.offlineEditingHoverSpeed
enabled: true
}
}
}
}
//-----------------------------------------------------------------
//-- Miscelanous //-- Miscelanous
Item { Item {
width: qgcView.width * 0.8 width: qgcView.width * 0.8
...@@ -274,7 +195,7 @@ QGCView { ...@@ -274,7 +195,7 @@ QGCView {
} }
QGCLabel { QGCLabel {
anchors.verticalCenter: parent.verticalCenter anchors.verticalCenter: parent.verticalCenter
text: qsTr("(Requires Restart)") text: _requiresRestart
} }
} }
//----------------------------------------------------------------- //-----------------------------------------------------------------
......
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