diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro
index bd4371c13794aedfa1a5c387ab19925166d85fe3..6ca491818d5b0f697a76a5f13f97ac9d094e5918 100644
--- a/qgroundcontrol.pro
+++ b/qgroundcontrol.pro
@@ -440,6 +440,7 @@ HEADERS += \
src/MissionManager/MissionController.h \
src/MissionManager/MissionItem.h \
src/MissionManager/MissionManager.h \
+ src/MissionManager/MissionSettingsComplexItem.h \
src/MissionManager/PlanElementController.h \
src/MissionManager/QGCMapPolygon.h \
src/MissionManager/RallyPoint.h \
@@ -610,6 +611,7 @@ SOURCES += \
src/MissionManager/MissionController.cc \
src/MissionManager/MissionItem.cc \
src/MissionManager/MissionManager.cc \
+ src/MissionManager/MissionSettingsComplexItem.cc \
src/MissionManager/PlanElementController.cc \
src/MissionManager/QGCMapPolygon.cc \
src/MissionManager/RallyPoint.cc \
diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc
index 9bf28ede744f4ccfc1b09f5e893fe7dec1b536b0..2b8bff4655ee0f44e7d7bf323a6961fa191b0366 100644
--- a/qgroundcontrol.qrc
+++ b/qgroundcontrol.qrc
@@ -38,7 +38,6 @@
src/ui/MainWindowNative.qml
src/ui/preferences/MavlinkSettings.qml
src/MissionEditor/MissionEditor.qml
- src/MissionEditor/MissionSettingsEditor.qml
src/AutoPilotPlugins/Common/MixersComponent.qml
src/ui/preferences/MockLink.qml
src/ui/preferences/MockLinkSettings.qml
@@ -67,6 +66,7 @@
src/QmlControls/MissionItemIndexLabel.qml
src/MissionEditor/MissionItemMapVisual.qml
src/MissionEditor/MissionItemStatus.qml
+ src/MissionEditor/MissionSettingsMapVisual.qml
src/QmlControls/ModeSwitchDisplay.qml
src/QmlControls/MultiRotorMotorDisplay.qml
src/QmlControls/OfflineMapButton.qml
@@ -170,6 +170,7 @@
src/MissionEditor/SimpleItemEditor.qml
src/MissionEditor/SurveyItemEditor.qml
src/MissionEditor/FWLandingPatternEditor.qml
+ src/MissionEditor/MissionSettingsEditor.qml
src/ui/preferences/TcpSettings.qml
src/test.qml
src/ui/preferences/UdpSettings.qml
@@ -183,11 +184,6 @@
src/MissionManager/MavCmdInfoRover.json
src/MissionManager/MavCmdInfoSub.json
src/MissionManager/MavCmdInfoVTOL.json
- src/Vehicle/VehicleFact.json
- src/Vehicle/BatteryFact.json
- src/Vehicle/GPSFact.json
- src/Vehicle/WindFact.json
- src/Vehicle/VibrationFact.json
src/Settings/App.SettingsGroup.json
src/Settings/AutoConnect.SettingsGroup.json
src/MissionManager/Survey.SettingsGroup.json
@@ -196,6 +192,12 @@
src/MissionManager/RallyPoint.FactMetaData.json
src/MissionManager/FWLandingPattern.FactMetaData.json
src/comm/USBBoardInfo.json
+ src/MissionManager/MissionSettings.FactMetaData.json
+ src/Vehicle/VehicleFact.json
+ src/Vehicle/BatteryFact.json
+ src/Vehicle/GPSFact.json
+ src/Vehicle/WindFact.json
+ src/Vehicle/VibrationFact.json
src/Vehicle/TemperatureFact.json
diff --git a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
index b6f13089f22a1a82810b06a0996df3d641837054..c399aab7231a7a09cfa87d8a4bb2f1b19ff063b5 100644
--- a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
+++ b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
@@ -266,7 +266,8 @@ QList PX4FirmwarePlugin::supportedMissionCommands(void)
<< MAV_CMD_DO_CHANGE_SPEED
<< MAV_CMD_DO_LAND_START
<< MAV_CMD_DO_MOUNT_CONFIGURE
- << MAV_CMD_DO_MOUNT_CONTROL;
+ << MAV_CMD_DO_MOUNT_CONTROL
+ << MAV_CMD_IMAGE_START_CAPTURE << MAV_CMD_IMAGE_STOP_CAPTURE << MAV_CMD_VIDEO_START_CAPTURE << MAV_CMD_VIDEO_STOP_CAPTURE;
return list;
}
diff --git a/src/FlightDisplay/FlightDisplayViewMap.qml b/src/FlightDisplay/FlightDisplayViewMap.qml
index 8fb459b75ec3bcceb44167772bbf491b5d86e035..ef5fa6e60dc9cc49205b03ac169d685c7b3f2d94 100644
--- a/src/FlightDisplay/FlightDisplayViewMap.qml
+++ b/src/FlightDisplay/FlightDisplayViewMap.qml
@@ -210,9 +210,13 @@ FlightMap {
}
}
- // Add the mission items to the map
- MissionItemView {
+ // Add the mission item visuals to the map
+ Repeater {
model: _mainIsMap ? missionController.visualItems : 0
+
+ delegate: MissionItemMapVisual {
+ map: flightMap
+ }
}
// Add lines between waypoints
diff --git a/src/FlightMap/MapItems/MissionItemView.qml b/src/FlightMap/MapItems/MissionItemView.qml
index 3ee6a129ca9ea847c6d13de5c2e6e329b7a91ab8..d3ea2173ff8c0ec45786ef6e1fb657d7aa78bff7 100644
--- a/src/FlightMap/MapItems/MissionItemView.qml
+++ b/src/FlightMap/MapItems/MissionItemView.qml
@@ -25,7 +25,7 @@ MapItemView {
delegate: MissionItemIndicator {
id: itemIndicator
coordinate: object.coordinate
- visible: object.specifiesCoordinate && (index != 0 || object.showHomePosition)
+ visible: object.specifiesCoordinate
z: QGroundControl.zOrderMapItems
missionItem: object
sequenceNumber: object.sequenceNumber
diff --git a/src/MissionEditor/FWLandingPatternEditor.qml b/src/MissionEditor/FWLandingPatternEditor.qml
index b76e84408fa1a2dc0d6222a6a24fea4d7256f442..d2b23d8a4516a3d9fa825b39bfe0a2e90931d2be 100644
--- a/src/MissionEditor/FWLandingPatternEditor.qml
+++ b/src/MissionEditor/FWLandingPatternEditor.qml
@@ -49,9 +49,9 @@ Rectangle {
text: qsTr("WIP (NOT FOR REAL FLIGHT!)")
}
- Item { width: 1; height: _margin }
-
- SectionHeader { text: qsTr("Loiter point") }
+ SectionHeader {
+ text: qsTr("Loiter point")
+ }
Item { width: 1; height: _spacer }
@@ -80,8 +80,6 @@ Rectangle {
onClicked: missionItem.loiterClockwise = checked
}
- Item { width: 1; height: ScreenTools.defaultFontPixelHeight / 2 }
-
SectionHeader { text: qsTr("Landing point") }
Item { width: 1; height: _spacer }
diff --git a/src/MissionEditor/MissionEditor.qml b/src/MissionEditor/MissionEditor.qml
index 9dddb5cefe5ef2820decedf8fcc774ad9342b69c..c1bd59d1ddcb2a8a86332dd688e4392abf6c4ede 100644
--- a/src/MissionEditor/MissionEditor.qml
+++ b/src/MissionEditor/MissionEditor.qml
@@ -585,6 +585,7 @@ QGCView {
highlightMoveDuration: 250
delegate: MissionItemEditor {
+ map: editorMap
missionItem: object
width: parent.width
readOnly: false
@@ -601,8 +602,7 @@ QGCView {
setCurrentItem(removeIndex)
}
- onInsert: insertSimpleMissionItem(editorMap.center, index)
- onMoveHomeToMapCenter: _visualItems.get(0).coordinate = editorMap.center
+ onInsert: insertSimpleMissionItem(editorMap.center, index)
}
} // QGCListView
} // Item - Mission Item editor
diff --git a/src/MissionEditor/MissionItemEditor.qml b/src/MissionEditor/MissionItemEditor.qml
index 64b4770da9daec3d8fd7d8e17d36d5a0c24c978b..f586e7abd5aa6d5c731425cf24b9a393b472fc0d 100644
--- a/src/MissionEditor/MissionItemEditor.qml
+++ b/src/MissionEditor/MissionItemEditor.qml
@@ -18,13 +18,13 @@ Rectangle {
color: _currentItem ? qgcPal.buttonHighlight : qgcPal.windowShade
radius: _radius
+ property var map ///< Map control
property var missionItem ///< MissionItem associated with this editor
property bool readOnly ///< true: read only view, false: full editing view
signal clicked
signal remove
signal insert
- signal moveHomeToMapCenter
property bool _currentItem: missionItem.isCurrentItem
property color _outerTextColor: _currentItem ? "black" : qgcPal.text
@@ -125,7 +125,7 @@ Rectangle {
anchors.rightMargin: ScreenTools.defaultFontPixelWidth
anchors.left: label.right
anchors.top: parent.top
- visible: missionItem.sequenceNumber != 0 && missionItem.isCurrentItem && !missionItem.rawEdit && missionItem.isSimpleItem
+ visible: missionItem.isCurrentItem && !missionItem.rawEdit && missionItem.isSimpleItem
text: missionItem.commandName
Component {
@@ -141,9 +141,9 @@ Rectangle {
QGCLabel {
anchors.fill: commandPicker
- visible: missionItem.sequenceNumber == 0 || !missionItem.isCurrentItem || !missionItem.isSimpleItem
+ visible: !missionItem.isCurrentItem || !missionItem.isSimpleItem
verticalAlignment: Text.AlignVCenter
- text: missionItem.sequenceNumber == 0 ? qsTr("Mission Settings") : missionItem.commandName
+ text: missionItem.commandName
color: _outerTextColor
}
@@ -154,7 +154,7 @@ Rectangle {
anchors.left: parent.left
anchors.top: commandPicker.bottom
height: item ? item.height : 0
- source: missionItem.sequenceNumber == 0 ? "qrc:/qml/MissionSettingsEditor.qml" : missionItem.editorQml
+ source: missionItem.editorQml
onLoaded: {
item.visible = Qt.binding(function() { return _currentItem; })
diff --git a/src/MissionEditor/MissionSettingsEditor.qml b/src/MissionEditor/MissionSettingsEditor.qml
index e353578a33c51664d1edd4a430b895b5c68a591a..a2af6bbeb71b733449ff55a2b6f281321f85326f 100644
--- a/src/MissionEditor/MissionSettingsEditor.qml
+++ b/src/MissionEditor/MissionSettingsEditor.qml
@@ -19,6 +19,12 @@ Rectangle {
visible: missionItem.isCurrentItem
radius: _radius
+ ExclusiveGroup {
+ id: sectionHeaderExclusiverGroup
+ }
+
+ property ExclusiveGroup sectionHeaderGroup: ScreenTools.isShortScreen ? sectionHeaderExclusiverGroup : null
+
Loader {
id: deferedload
active: valuesRect.visible
@@ -37,7 +43,7 @@ Rectangle {
property bool _offlineEditing: _missionVehicle.isOfflineEditingVehicle
property bool _showOfflineEditingCombos: _offlineEditing && _noMissionItemsAdded
property bool _showCruiseSpeed: !_missionVehicle.multiRotor
- property bool _showHoverSpeed: _missionVehicle.multiRotor || missionController.vehicle.vtol
+ property bool _showHoverSpeed: _missionVehicle.multiRotor || _missionVehicle.vtol
property bool _multipleFirmware: QGroundControl.supportedFirmwareCount > 2
property real _fieldWidth: ScreenTools.defaultFontPixelWidth * 16
property bool _mobile: ScreenTools.isMobile
@@ -54,54 +60,72 @@ Rectangle {
anchors.top: parent.top
spacing: _margin
- SectionHeader { text: qsTr("Planned Home Position") }
+ SectionHeader {
+ id: plannedHomePositionSection
+ text: qsTr("Planned Home Position")
+ showSpacer: false
+ exclusiveGroup: sectionHeaderGroup
+ }
- Repeater {
- model: missionItem.textFieldFacts
- RowLayout {
+ Column {
+ anchors.left: parent.left
+ anchors.right: parent.right
+ spacing: _margin
+ visible: plannedHomePositionSection.checked
+
+ GridLayout {
anchors.left: parent.left
anchors.right: parent.right
- spacing: _margin
- visible: _mobile ? index == 2 : true // Cheating here since we known we only have Lat/Lon/Alt
+ columnSpacing: ScreenTools.defaultFontPixelWidth
+ rowSpacing: columnSpacing
+ columns: 2
- QGCLabel { text: object.name; Layout.fillWidth: true }
+ QGCLabel {
+ text: qsTr("Latitude")
+ }
FactTextField {
- Layout.preferredWidth: _fieldWidth
- showUnits: true
- fact: object
- visible: !_root.readOnly
+ fact: missionItem.plannedHomePositionLatitude
+ Layout.fillWidth: true
}
- FactLabel {
- Layout.preferredWidth: _fieldWidth
- fact: object
- visible: _root.readOnly
+
+ QGCLabel {
+ text: qsTr("Longitude")
+ }
+ FactTextField {
+ fact: missionItem.plannedHomePositionLongitude
+ Layout.fillWidth: true
}
- }
- }
- QGCLabel {
- width: parent.width
- wrapMode: Text.WordWrap
- font.pointSize: ScreenTools.smallFontPointSize
- text: qsTr("Actual position set by vehicle at flight time.")
- horizontalAlignment: Text.AlignHCenter
- }
+ QGCLabel {
+ text: qsTr("Altitude")
+ }
+ FactTextField {
+ fact: missionItem.plannedHomePositionAltitude
+ Layout.fillWidth: true
+ }
+ }
- QGCButton {
- text: qsTr("Set Home To Map Center")
- onClicked: editorRoot.moveHomeToMapCenter()
- anchors.horizontalCenter: parent.horizontalCenter
- }
+ QGCLabel {
+ width: parent.width
+ wrapMode: Text.WordWrap
+ font.pointSize: ScreenTools.smallFontPointSize
+ text: qsTr("Actual position set by vehicle at flight time.")
+ horizontalAlignment: Text.AlignHCenter
+ }
- Item {
- height: _sectionSpacer
- width: 1
- visible: !ScreenTools.isTinyScreen
+ QGCButton {
+ text: qsTr("Set Home To Map Center")
+ onClicked: missionItem.coordinate = map.center
+ anchors.horizontalCenter: parent.horizontalCenter
+ }
}
SectionHeader {
+ id: vehicleInfoSectionHeader
text: qsTr("Vehicle Info")
- visible: _multipleFirmware
+ visible: _multipleFirmware && _showOfflineEditingCombos
+ checked: false
+ exclusiveGroup: sectionHeaderGroup
}
GridLayout {
@@ -110,74 +134,197 @@ Rectangle {
columnSpacing: ScreenTools.defaultFontPixelWidth
rowSpacing: columnSpacing
columns: 2
- visible: _multipleFirmware
+ visible: vehicleInfoSectionHeader.visible && vehicleInfoSectionHeader.checked
QGCLabel {
- text: _firmwareLabel
- visible: _showOfflineEditingCombos
- Layout.fillWidth: true
+ text: _firmwareLabel
+ Layout.fillWidth: true
}
FactComboBox {
- fact: QGroundControl.settingsManager.appSettings.offlineEditingFirmwareType
- indexModel: false
- visible: _showOfflineEditingCombos
+ fact: QGroundControl.settingsManager.appSettings.offlineEditingFirmwareType
+ indexModel: false
Layout.preferredWidth: _fieldWidth
}
QGCLabel {
- text: _vehicleLabel
- visible: _showOfflineEditingCombos
- Layout.fillWidth: true
+ text: _vehicleLabel
+ Layout.fillWidth: true
}
FactComboBox {
- id: offlineVehicleCombo
- fact: QGroundControl.settingsManager.appSettings.offlineEditingVehicleType
- indexModel: false
- visible: _showOfflineEditingCombos
+ fact: QGroundControl.settingsManager.appSettings.offlineEditingVehicleType
+ indexModel: false
Layout.preferredWidth: _fieldWidth
}
QGCLabel {
- text: qsTr("Cruise speed")
- visible: _showCruiseSpeed
- Layout.fillWidth: true
+ text: qsTr("Cruise speed")
+ visible: _showCruiseSpeed
+ Layout.fillWidth: true
}
FactTextField {
- fact: QGroundControl.settingsManager.appSettings.offlineEditingCruiseSpeed
- visible: _showCruiseSpeed
+ fact: QGroundControl.settingsManager.appSettings.offlineEditingCruiseSpeed
+ visible: _showCruiseSpeed
Layout.preferredWidth: _fieldWidth
}
QGCLabel {
- text: qsTr("Hover speed")
- visible: _showHoverSpeed
- Layout.fillWidth: true
+ text: qsTr("Hover speed")
+ visible: _showHoverSpeed
+ Layout.fillWidth: true
}
FactTextField {
- fact: QGroundControl.settingsManager.appSettings.offlineEditingHoverSpeed
- visible: _showHoverSpeed
+ fact: QGroundControl.settingsManager.appSettings.offlineEditingHoverSpeed
+ visible: _showHoverSpeed
Layout.preferredWidth: _fieldWidth
}
} // GridLayout
- RowLayout {
+ SectionHeader {
+ id: missionDefaultsSectionHeader
+ text: qsTr("Mission Defaults")
+ checked: false
+ exclusiveGroup: sectionHeaderGroup
+ }
+
+ Column {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
- visible: !_multipleFirmware
- QGCLabel { text: qsTr("Hover speed"); Layout.fillWidth: true }
- FactTextField {
- Layout.preferredWidth: _fieldWidth
- fact: QGroundControl.settingsManager.appSettings.offlineEditingHoverSpeed
+ visible: missionDefaultsSectionHeader.checked
+
+ GridLayout {
+ anchors.left: parent.left
+ anchors.right: parent.right
+ columnSpacing: ScreenTools.defaultFontPixelWidth
+ rowSpacing: columnSpacing
+ columns: 2
+
+ QGCLabel {
+ text: qsTr("Altitude")
+ }
+ FactTextField {
+ fact: QGroundControl.settingsManager.appSettings.defaultMissionItemAltitude
+ Layout.fillWidth: true
+ }
+
+ QGCCheckBox {
+ id: flightSpeedCheckBox
+ text: qsTr("Flight speed")
+ visible: !_missionVehicle.vtol
+ checked: missionItem.specifyMissionFlightSpeed
+ onClicked: missionItem.specifyMissionFlightSpeed = checked
+ }
+ FactTextField {
+ Layout.fillWidth: true
+ fact: missionItem.missionFlightSpeed
+ visible: flightSpeedCheckBox.visible
+ enabled: flightSpeedCheckBox.checked
+ }
+ } // GridLayout
+
+ /*
+ FIXME: NYI
+ FactComboBox {
+ anchors.left: parent.left
+ anchors.right: parent.right
+ fact: missionItem.missionEndAction
+ indexModel: false
+ }
+ */
+ }
+
+ SectionHeader {
+ id: cameraSectionHeader
+ text: qsTr("Camera")
+ checked: false
+ exclusiveGroup: sectionHeaderGroup
+ }
+
+ Column {
+ anchors.left: parent.left
+ anchors.right: parent.right
+ spacing: _margin
+ visible: cameraSectionHeader.checked
+
+ FactComboBox {
+ id: cameraActionCombo
+ anchors.left: parent.left
+ anchors.right: parent.right
+ fact: missionItem.cameraAction
+ indexModel: false
+ }
+
+ RowLayout {
+ anchors.left: parent.left
+ anchors.right: parent.right
+ spacing: ScreenTools.defaultFontPixelWidth
+ visible: cameraActionCombo.currentIndex == 1
+
+ QGCLabel {
+ text: qsTr("Time")
+ Layout.fillWidth: true
+ }
+ FactTextField {
+ fact: missionItem.cameraPhotoIntervalTime
+ Layout.preferredWidth: _fieldWidth
+ }
+ }
+
+ RowLayout {
+ anchors.left: parent.left
+ anchors.right: parent.right
+ spacing: ScreenTools.defaultFontPixelWidth
+ visible: cameraActionCombo.currentIndex == 2
+
+ QGCLabel {
+ text: qsTr("Distance")
+ Layout.fillWidth: true
+ }
+ FactTextField {
+ fact: missionItem.cameraPhotoIntervalDistance
+ Layout.preferredWidth: _fieldWidth
+ }
+ }
+
+ GridLayout {
+ anchors.left: parent.left
+ anchors.right: parent.right
+ columnSpacing: 0
+ rowSpacing: 0
+ columns: 3
+
+ Item { width: 1; height: 1 }
+ QGCLabel { text: qsTr("Pitch") }
+ QGCLabel { text: qsTr("Yaw") }
+
+ QGCCheckBox {
+ id: gimbalCheckBox
+ text: qsTr("Gimbal")
+ checked: missionItem.specifyGimbal
+ onClicked: missionItem.specifyGimbal = checked
+ Layout.fillWidth: true
+ }
+ FactTextField {
+ fact: missionItem.gimbalPitch
+ implicitWidth: ScreenTools.defaultFontPixelWidth * 9
+ enabled: gimbalCheckBox.checked
+ }
+
+ FactTextField {
+ fact: missionItem.gimbalYaw
+ implicitWidth: ScreenTools.defaultFontPixelWidth * 9
+ enabled: gimbalCheckBox.checked
+ }
}
}
QGCLabel {
- width: parent.width
- wrapMode: Text.WordWrap
- font.pointSize: ScreenTools.smallFontPointSize
- text: qsTr("Speeds are only used for time calculations. Actual vehicle speed will not be affected.")
- horizontalAlignment: Text.AlignHCenter
+ width: parent.width
+ wrapMode: Text.WordWrap
+ font.pointSize: ScreenTools.smallFontPointSize
+ text: qsTr("Speeds are only used for time calculations. Actual vehicle speed will not be affected.")
+ horizontalAlignment: Text.AlignHCenter
+ visible: _offlineEditing && _missionVehicle.vtol
}
} // Column
} // Item
diff --git a/src/MissionEditor/MissionSettingsMapVisual.qml b/src/MissionEditor/MissionSettingsMapVisual.qml
new file mode 100644
index 0000000000000000000000000000000000000000..21fea1d8f973271227433c622faa3c3b71d2d6b3
--- /dev/null
+++ b/src/MissionEditor/MissionSettingsMapVisual.qml
@@ -0,0 +1,128 @@
+/****************************************************************************
+ *
+ * (c) 2009-2016 QGROUNDCONTROL PROJECT
+ *
+ * QGroundControl is licensed according to the terms in the file
+ * COPYING.md in the root of the source code directory.
+ *
+ ****************************************************************************/
+
+import QtQuick 2.3
+import QtQuick.Controls 1.2
+import QtLocation 5.3
+import QtPositioning 5.3
+
+import QGroundControl 1.0
+import QGroundControl.ScreenTools 1.0
+import QGroundControl.Palette 1.0
+import QGroundControl.Controls 1.0
+import QGroundControl.FlightMap 1.0
+
+/// Mission Settings map visuals
+Item {
+ property var map ///< Map control to place item in
+
+ property var _missionItem: object
+ property var _itemVisual
+ property var _dragArea
+ property bool _itemVisualShowing: false
+ property bool _dragAreaShowing: false
+
+ function hideItemVisuals() {
+ if (_itemVisualShowing) {
+ _itemVisual.destroy()
+ _itemVisualShowing = false
+ }
+ }
+
+ function showItemVisuals() {
+ if (!_itemVisualShowing) {
+ _itemVisual = indicatorComponent.createObject(map)
+ map.addMapItem(_itemVisual)
+ _itemVisualShowing = true
+ }
+ }
+
+ function hideDragArea() {
+ if (_dragAreaShowing) {
+ _dragArea.destroy()
+ _dragAreaShowing = false
+ }
+ }
+
+ function showDragArea() {
+ if (!_dragAreaShowing && _missionItem.specifiesCoordinate) {
+ _dragArea = dragAreaComponent.createObject(map)
+ _dragAreaShowing = true
+ }
+ }
+
+ Component.onCompleted: {
+ showItemVisuals()
+ if (_missionItem.isCurrentItem) {
+ showDragArea()
+ }
+ }
+
+ Component.onDestruction: {
+ hideDragArea()
+ hideItemVisuals()
+ }
+
+
+ Connections {
+ target: _missionItem
+
+ onIsCurrentItemChanged: {
+ if (_missionItem.isCurrentItem) {
+ showDragArea()
+ } else {
+ hideDragArea()
+ }
+ }
+ }
+
+ // Control which is used to drag items
+ Component {
+ id: dragAreaComponent
+
+ MissionItemIndicatorDrag {
+ itemIndicator: _itemVisual
+ itemCoordinate: _missionItem.coordinate
+
+ onItemCoordinateChanged: _missionItem.coordinate = itemCoordinate
+ }
+ }
+
+ Component {
+ id: indicatorComponent
+
+ MissionItemIndicator {
+ coordinate: _missionItem.coordinate
+ visible: _missionItem.showHomePosition
+ z: QGroundControl.zOrderMapItems
+ missionItem: _missionItem
+
+ onClicked: setCurrentItem(_missionItem.sequenceNumber)
+
+ // These are the non-coordinate child mission items attached to this item
+ Row {
+ anchors.top: parent.top
+ anchors.left: parent.right
+
+ Repeater {
+ model: _missionItem.childItems
+
+ delegate: MissionItemIndexLabel {
+ label: object.abbreviation
+ checked: object.isCurrentItem
+ z: 2
+ specifiesCoordinate: false
+
+ onClicked: setCurrentItem(object.sequenceNumber)
+ }
+ }
+ }
+ }
+ }
+}
diff --git a/src/MissionEditor/SectionHeader.qml b/src/MissionEditor/SectionHeader.qml
index 842b56c81ca8b071bffa01f91e596e1b573d7a54..36beba4459251cd780dabb2ab45cdbe3c9e1cad0 100644
--- a/src/MissionEditor/SectionHeader.qml
+++ b/src/MissionEditor/SectionHeader.qml
@@ -5,20 +5,55 @@ import QtQuick.Layouts 1.2
import QGroundControl.ScreenTools 1.0
import QGroundControl.Palette 1.0
-Column {
+QGCMouseArea {
+ id: _root
anchors.left: parent.left
anchors.right: parent.right
+ height: column.height
+ onClicked: checked = !checked
- property alias text: label.text
+ property alias text: label.text
+ property bool checked: true
+ property bool showSpacer: true
+ property ExclusiveGroup exclusiveGroup: null
- QGCPalette { id: qgcPal; colorGroupEnabled: true }
+ property real _sectionSpacer: ScreenTools.defaultFontPixelWidth / 2 // spacing between section headings
+
+ onExclusiveGroupChanged: {
+ if (exclusiveGroup)
+ exclusiveGroup.bindCheckable(_root)
+ }
- QGCLabel { id: label }
+ QGCPalette { id: qgcPal; colorGroupEnabled: true }
- Rectangle {
+ ColumnLayout {
+ id: column
anchors.left: parent.left
anchors.right: parent.right
- height: 1
- color: qgcPal.text
+
+ Item {
+ height: _sectionSpacer
+ width: 1
+ visible: showSpacer
+ }
+
+ QGCLabel {
+ id: label
+ Layout.fillWidth: true
+
+ Image {
+ anchors.right: parent.right
+ anchors.verticalCenter: parent.verticalCenter
+ source: "/qmlimages/arrow-down.png"
+ visible: !_root.checked
+ }
+ }
+
+ Rectangle {
+ anchors.left: parent.left
+ anchors.right: parent.right
+ height: 1
+ color: qgcPal.text
+ }
}
}
diff --git a/src/MissionEditor/SurveyItemEditor.qml b/src/MissionEditor/SurveyItemEditor.qml
index a7654cd86f623426c95ec9ee84b124c43f546af5..7853a6e9165c2e58a8fcf64539cc7d6e0c9468cb 100644
--- a/src/MissionEditor/SurveyItemEditor.qml
+++ b/src/MissionEditor/SurveyItemEditor.qml
@@ -166,7 +166,10 @@ Rectangle {
anchors.right: parent.right
spacing: _margin
- SectionHeader { text: qsTr("Camera") }
+ SectionHeader {
+ text: qsTr("Camera")
+ showSpacer: false
+ }
QGCComboBox {
id: gridTypeCombo
@@ -327,8 +330,6 @@ Rectangle {
}
}
- Item { height: _sectionSpacer; width: 1; visible: !ScreenTools.isTinyScreen }
-
SectionHeader { text: qsTr("Grid") }
GridLayout {
@@ -395,8 +396,6 @@ Rectangle {
spacing: _margin
visible: gridTypeCombo.currentIndex == _gridTypeManual
- Item { height: _sectionSpacer; width: 1; visible: !ScreenTools.isTinyScreen }
-
SectionHeader { text: qsTr("Grid") }
FactTextFieldGrid {
@@ -447,8 +446,6 @@ Rectangle {
}
}
- Item { height: _sectionSpacer; width: 1; visible: !ScreenTools.isTinyScreen }
-
SectionHeader { text: qsTr("Statistics") }
Grid {
diff --git a/src/MissionManager/FixedWingLandingComplexItem.cc b/src/MissionManager/FixedWingLandingComplexItem.cc
index 29631be18c8dd2f6d87e6bcdfb965afad55c5e6e..8c8bb18de6c8764dd6a1f104659f073ab3474d4a 100644
--- a/src/MissionManager/FixedWingLandingComplexItem.cc
+++ b/src/MissionManager/FixedWingLandingComplexItem.cc
@@ -105,8 +105,10 @@ void FixedWingLandingComplexItem::setDirty(bool dirty)
}
}
-void FixedWingLandingComplexItem::save(QJsonObject& saveObject) const
+void FixedWingLandingComplexItem::save(QJsonArray& missionItems) const
{
+ QJsonObject saveObject;
+
saveObject[JsonHelper::jsonVersionKey] = 1;
saveObject[VisualMissionItem::jsonTypeKey] = VisualMissionItem::jsonTypeComplexItemValue;
saveObject[ComplexMissionItem::jsonComplexItemTypeKey] = jsonComplexItemTypeValue;
@@ -128,6 +130,8 @@ void FixedWingLandingComplexItem::save(QJsonObject& saveObject) const
saveObject[_jsonLoiterClockwiseKey] = _loiterClockwise;
saveObject[_jsonLoiterAltitudeRelativeKey] = _loiterAltitudeRelative;
saveObject[_jsonLandingAltitudeRelativeKey] = _landingAltitudeRelative;
+
+ missionItems.append(saveObject);
}
void FixedWingLandingComplexItem::setSequenceNumber(int sequenceNumber)
@@ -236,7 +240,7 @@ QmlObjectListModel* FixedWingLandingComplexItem::getMissionItems(void) const
0.0, 0.0, 0.0, 0.0, // param 1-4
_landingCoordinate.latitude(),
_landingCoordinate.longitude(),
- 0.0, // altitude
+ _landingAltitudeFact.rawValue().toDouble(),
true, // autoContinue
false, // isCurrentItem
pMissionItems); // parent - allow delete on pMissionItems to delete everthing
diff --git a/src/MissionManager/FixedWingLandingComplexItem.h b/src/MissionManager/FixedWingLandingComplexItem.h
index 0afc1e96e053765b0591957a13f4151854607941..208202bb0936ca72c18f4ca58fc00ace0edfcdef 100644
--- a/src/MissionManager/FixedWingLandingComplexItem.h
+++ b/src/MissionManager/FixedWingLandingComplexItem.h
@@ -80,7 +80,7 @@ public:
void setDirty (bool dirty) final;
void setCoordinate (const QGeoCoordinate& coordinate) final { setLoiterCoordinate(coordinate); }
void setSequenceNumber (int sequenceNumber) final;
- void save (QJsonObject& saveObject) const final;
+ void save (QJsonArray& missionItems) const final;
static const char* jsonComplexItemTypeValue;
diff --git a/src/MissionManager/MavCmdInfoCommon.json b/src/MissionManager/MavCmdInfoCommon.json
index 6da634ecb5941a70d6ba4c2796d7534139250f9a..ab845fbf4ae77cb2c5a3eb4435c69abe8cf6d758 100644
--- a/src/MissionManager/MavCmdInfoCommon.json
+++ b/src/MissionManager/MavCmdInfoCommon.json
@@ -965,11 +965,58 @@
{ "id": 510, "rawName": "MAV_CMD_GET_MESSAGE_INTERVAL", "friendlyName": "Get message interval" },
{ "id": 511, "rawName": "MAV_CMD_SET_MESSAGE_INTERVAL", "friendlyName": "Set message interval" },
{ "id": 520, "rawName": "MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES", "friendlyName": "Get capabilities" },
- { "id": 2000, "rawName": "MAV_CMD_IMAGE_START_CAPTURE", "friendlyName": "Start image capture" },
+ {
+ "id": 2000,
+ "rawName": "MAV_CMD_IMAGE_START_CAPTURE",
+ "friendlyName": "Start image capture" ,
+ "description": "Start taking one or more photos.",
+ "category": "Camera",
+ "param1": {
+ "label": "Interval",
+ "default": 0,
+ "units": "secs",
+ "decimalPlaces": 0
+ },
+ "param2": {
+ "label": "Photo count",
+ "default": 1,
+ "decimalPlaces": 0
+ },
+ "param3": {
+ "label": "Resolution",
+ "default": -1,
+ "decimalPlaces": 0
+ },
+ "param6": {
+ "label": "Camera id",
+ "default": 0,
+ "decimalPlaces": 0
+ }
+ },
{ "id": 2001, "rawName": "MAV_CMD_IMAGE_STOP_CAPTURE", "friendlyName": "Stop image capture" },
{ "id": 2003, "rawName": "MAV_CMD_DO_TRIGGER_CONTROL", "friendlyName": "Trigger control" },
- { "id": 2500, "rawName": "MAV_CMD_VIDEO_START_CAPTURE", "friendlyName": "Start video capture" },
- { "id": 2501, "rawName": "MAV_CMD_VIDEO_STOP_CAPTURE", "friendlyName": "Stop video cpture" },
+ {
+ "id": 2500,
+ "rawName": "MAV_CMD_VIDEO_START_CAPTURE",
+ "friendlyName": "Start video capture",
+ "description": "Start taking video.",
+ "category": "Camera",
+ "param1": {
+ "label": "Camera id",
+ "default": 0,
+ "decimalPlaces": 0
+ },
+ "param2": {
+ "label": "FPS",
+ "default": -1,
+ "decimalPlaces": 0
+ },
+ "param3": {
+ "label": "Resolution",
+ "default": -1,
+ "decimalPlaces": 0
+ }
+ },
{ "id": 2800, "rawName": "MAV_CMD_PANORAMA_CREATE", "friendlyName": "Create panorama" },
{
"id": 3000,
diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc
index 3bb9f10c5406d314c39cf67fb3947fb86bd6c9ad..f738b93db0c7a9fc462ba617bc34dcd7b67bb1b5 100644
--- a/src/MissionManager/MissionController.cc
+++ b/src/MissionManager/MissionController.cc
@@ -21,6 +21,7 @@
#include "ParameterManager.h"
#include "QGroundControlQmlGlobal.h"
#include "SettingsManager.h"
+#include "MissionSettingsComplexItem.h"
#ifndef __mobile__
#include "MainWindow.h"
@@ -29,7 +30,6 @@
QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog")
-
const char* MissionController::_settingsGroup = "MissionController";
const char* MissionController::_jsonFileTypeValue = "Mission";
const char* MissionController::_jsonItemsKey = "items";
@@ -49,7 +49,6 @@ const int MissionController::_missionFileVersion = 2;
MissionController::MissionController(QObject *parent)
: PlanElementController(parent)
, _visualItems(NULL)
- , _complexItems(NULL)
, _firstItemsFromVehicle(false)
, _missionItemsRequested(false)
, _queuedSend(false)
@@ -91,7 +90,7 @@ void MissionController::_init(void)
{
// We start with an empty mission
_visualItems = new QmlObjectListModel(this);
- _addPlannedHomePosition(_activeVehicle, _visualItems, false /* addToCenter */);
+ _addMissionSettings(_activeVehicle, _visualItems, false /* addToCenter */);
_initAllVisualItems();
}
@@ -121,11 +120,13 @@ void MissionController::_newMissionItemsAvailableFromVehicle(void)
_visualItems = newControllerMissionItems;
if (!_activeVehicle->firmwarePlugin()->sendHomePositionToVehicle() || _visualItems->count() == 0) {
- _addPlannedHomePosition(_activeVehicle, _visualItems,true /* addToCenter */);
+ _addMissionSettings(_activeVehicle, _visualItems, true /* addToCenter */);
}
_missionItemsRequested = false;
+ MissionSettingsComplexItem::scanForMissionSettings(_visualItems, _activeVehicle);
+
_initAllVisualItems();
emit newItemsFromVehicle();
}
@@ -237,7 +238,6 @@ int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate
_initVisualItem(newItem);
_visualItems->insert(i, newItem);
- _complexItems->append(newItem);
_recalcAll();
@@ -249,12 +249,6 @@ void MissionController::removeMissionItem(int index)
VisualMissionItem* item = qobject_cast(_visualItems->removeAt(index));
_deinitVisualItem(item);
- if (!item->isSimpleItem()) {
- ComplexMissionItem* complexItem = qobject_cast(_complexItems->removeOne(item));
- if (!complexItem) {
- qWarning() << "Complex item missing";
- }
- }
item->deleteLater();
_recalcAll();
@@ -267,13 +261,13 @@ void MissionController::removeAll(void)
_deinitAllVisualItems();
_visualItems->deleteLater();
_visualItems = new QmlObjectListModel(this);
- _addPlannedHomePosition(_activeVehicle, _visualItems, false /* addToCenter */);
+ _addMissionSettings(_activeVehicle, _visualItems, false /* addToCenter */);
_initAllVisualItems();
_visualItems->setDirty(true);
}
}
-bool MissionController::_loadJsonMissionFile(Vehicle* vehicle, const QByteArray& bytes, QmlObjectListModel* visualItems, QmlObjectListModel* complexItems, QString& errorString)
+bool MissionController::_loadJsonMissionFile(Vehicle* vehicle, const QByteArray& bytes, QmlObjectListModel* visualItems, QString& errorString)
{
QJsonParseError jsonParseError;
QJsonDocument jsonDoc(QJsonDocument::fromJson(bytes, &jsonParseError));
@@ -300,13 +294,13 @@ bool MissionController::_loadJsonMissionFile(Vehicle* vehicle, const QByteArray&
}
if (fileVersion == 1) {
- return _loadJsonMissionFileV1(vehicle, json, visualItems, complexItems, errorString);
+ return _loadJsonMissionFileV1(vehicle, json, visualItems, errorString);
} else {
- return _loadJsonMissionFileV2(vehicle, json, visualItems, complexItems, errorString);
+ return _loadJsonMissionFileV2(vehicle, json, visualItems, errorString);
}
}
-bool MissionController::_loadJsonMissionFileV1(Vehicle* vehicle, const QJsonObject& json, QmlObjectListModel* visualItems, QmlObjectListModel* complexItems, QString& errorString)
+bool MissionController::_loadJsonMissionFileV1(Vehicle* vehicle, const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
{
// Validate root object keys
QList rootKeyInfoList = {
@@ -320,6 +314,7 @@ bool MissionController::_loadJsonMissionFileV1(Vehicle* vehicle, const QJsonObje
}
// Read complex items
+ QList surveyItems;
QJsonArray complexArray(json[_jsonComplexItemsKey].toArray());
qCDebug(MissionControllerLog) << "Json load: complex item count" << complexArray.count();
for (int i=0; iload(itemObject, itemObject["id"].toInt(), errorString)) {
- complexItems->append(item);
+ surveyItems.append(item);
} else {
return false;
}
@@ -346,13 +341,13 @@ bool MissionController::_loadJsonMissionFileV1(Vehicle* vehicle, const QJsonObje
int nextSequenceNumber = 1; // Start with 1 since home is in 0
QJsonArray itemArray(json[_jsonItemsKey].toArray());
- qCDebug(MissionControllerLog) << "Json load: simple item loop start simpleItemCount:ComplexItemCount" << itemArray.count() << complexItems->count();
+ qCDebug(MissionControllerLog) << "Json load: simple item loop start simpleItemCount:ComplexItemCount" << itemArray.count() << surveyItems.count();
do {
qCDebug(MissionControllerLog) << "Json load: simple item loop nextSimpleItemIndex:nextComplexItemIndex:nextSequenceNumber" << nextSimpleItemIndex << nextComplexItemIndex << nextSequenceNumber;
// If there is a complex item that should be next in sequence add it in
- if (nextComplexItemIndex < complexItems->count()) {
- SurveyMissionItem* complexItem = qobject_cast(complexItems->get(nextComplexItemIndex));
+ if (nextComplexItemIndex < surveyItems.count()) {
+ SurveyMissionItem* complexItem = surveyItems[nextComplexItemIndex];
if (complexItem->sequenceNumber() == nextSequenceNumber) {
qCDebug(MissionControllerLog) << "Json load: injecting complex item expectedSequence:actualSequence:" << nextSequenceNumber << complexItem->sequenceNumber();
@@ -383,24 +378,27 @@ bool MissionController::_loadJsonMissionFileV1(Vehicle* vehicle, const QJsonObje
nextSequenceNumber++;
}
- } while (nextSimpleItemIndex < itemArray.count() || nextComplexItemIndex < complexItems->count());
+ } while (nextSimpleItemIndex < itemArray.count() || nextComplexItemIndex < surveyItems.count());
if (json.contains(_jsonPlannedHomePositionKey)) {
SimpleMissionItem* item = new SimpleMissionItem(vehicle, visualItems);
if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0, errorString)) {
- visualItems->insert(0, item);
+ MissionSettingsComplexItem* settingsItem = new MissionSettingsComplexItem(vehicle, visualItems);
+ settingsItem->setCoordinate(item->coordinate());
+ visualItems->insert(0, settingsItem);
+ item->deleteLater();
} else {
return false;
}
} else {
- _addPlannedHomePosition(vehicle, visualItems, true /* addToCenter */);
+ _addMissionSettings(vehicle, visualItems, true /* addToCenter */);
}
return true;
}
-bool MissionController::_loadJsonMissionFileV2(Vehicle* vehicle, const QJsonObject& json, QmlObjectListModel* visualItems, QmlObjectListModel* complexItems, QString& errorString)
+bool MissionController::_loadJsonMissionFileV2(Vehicle* vehicle, const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
{
// Validate root object keys
QList rootKeyInfoList = {
@@ -433,9 +431,9 @@ bool MissionController::_loadJsonMissionFileV2(Vehicle* vehicle, const QJsonObje
settingsManager->appSettings()->offlineEditingHoverSpeed()->setRawValue(json[_jsonHoverSpeedKey].toDouble());
}
- SimpleMissionItem* homeItem = new SimpleMissionItem(vehicle, visualItems);
- homeItem->setCoordinate(homeCoordinate);
- visualItems->insert(0, homeItem);
+ MissionSettingsComplexItem* settingsItem = new MissionSettingsComplexItem(vehicle, visualItems);
+ settingsItem->setCoordinate(homeCoordinate);
+ visualItems->insert(0, settingsItem);
qCDebug(MissionControllerLog) << "plannedHomePosition" << homeCoordinate;
// Read mission items
@@ -487,7 +485,6 @@ bool MissionController::_loadJsonMissionFileV2(Vehicle* vehicle, const QJsonObje
nextSequenceNumber = surveyItem->lastSequenceNumber() + 1;
qCDebug(MissionControllerLog) << "Survey load complete: nextSequenceNumber" << nextSequenceNumber;
visualItems->append(surveyItem);
- complexItems->append(surveyItem);
} else if (complexItemType == FixedWingLandingComplexItem::jsonComplexItemTypeValue) {
qCDebug(MissionControllerLog) << "Loading Fixed Wing Landing Pattern: nextSequenceNumber" << nextSequenceNumber;
FixedWingLandingComplexItem* landingItem = new FixedWingLandingComplexItem(vehicle, visualItems);
@@ -497,7 +494,15 @@ bool MissionController::_loadJsonMissionFileV2(Vehicle* vehicle, const QJsonObje
nextSequenceNumber = landingItem->lastSequenceNumber() + 1;
qCDebug(MissionControllerLog) << "FW Landing Pattern load complete: nextSequenceNumber" << nextSequenceNumber;
visualItems->append(landingItem);
- complexItems->append(landingItem);
+ } else if (complexItemType == MissionSettingsComplexItem::jsonComplexItemTypeValue) {
+ qCDebug(MissionControllerLog) << "Loading Mission Settings: nextSequenceNumber" << nextSequenceNumber;
+ MissionSettingsComplexItem* settingsItem = new MissionSettingsComplexItem(vehicle, visualItems);
+ if (!settingsItem->load(itemObject, nextSequenceNumber++, errorString)) {
+ return false;
+ }
+ nextSequenceNumber = settingsItem->lastSequenceNumber() + 1;
+ qCDebug(MissionControllerLog) << "Mission Settings load complete: nextSequenceNumber" << nextSequenceNumber;
+ visualItems->append(settingsItem);
} else {
errorString = tr("Unsupported complex item type: %1").arg(complexItemType);
}
@@ -571,7 +576,7 @@ bool MissionController::_loadTextMissionFile(Vehicle* vehicle, QTextStream& stre
}
if (addPlannedHomePosition || visualItems->count() == 0) {
- _addPlannedHomePosition(vehicle, visualItems, true /* addToCenter */);
+ _addMissionSettings(vehicle, visualItems, true /* addToCenter */);
// Update sequence numbers in DO_JUMP commands to take into account added home position in index 0
for (int i=1; icount(); i++) {
@@ -588,9 +593,8 @@ bool MissionController::_loadTextMissionFile(Vehicle* vehicle, QTextStream& stre
void MissionController::loadFromFile(const QString& filename)
{
QmlObjectListModel* newVisualItems = NULL;
- QmlObjectListModel* newComplexItems = NULL;
- if (!loadItemsFromFile(_activeVehicle, filename, &newVisualItems, &newComplexItems)) {
+ if (!loadItemsFromFile(_activeVehicle, filename, &newVisualItems)) {
return;
}
@@ -598,24 +602,21 @@ void MissionController::loadFromFile(const QString& filename)
_deinitAllVisualItems();
_visualItems->deleteLater();
}
- if (_complexItems) {
- _complexItems->deleteLater();
- }
_visualItems = newVisualItems;
- _complexItems = newComplexItems;
if (_visualItems->count() == 0) {
- _addPlannedHomePosition(_activeVehicle, _visualItems, true /* addToCenter */);
+ _addMissionSettings(_activeVehicle, _visualItems, true /* addToCenter */);
}
+ MissionSettingsComplexItem::scanForMissionSettings(_visualItems, _activeVehicle);
+
_initAllVisualItems();
}
-bool MissionController::loadItemsFromFile(Vehicle* vehicle, const QString& filename, QmlObjectListModel** visualItems, QmlObjectListModel** complexItems)
+bool MissionController::loadItemsFromFile(Vehicle* vehicle, const QString& filename, QmlObjectListModel** visualItems)
{
*visualItems = NULL;
- *complexItems = NULL;
QString errorString;
@@ -624,7 +625,6 @@ bool MissionController::loadItemsFromFile(Vehicle* vehicle, const QString& filen
}
*visualItems = new QmlObjectListModel();
- *complexItems = new QmlObjectListModel();
QFile file(filename);
@@ -639,13 +639,12 @@ bool MissionController::loadItemsFromFile(Vehicle* vehicle, const QString& filen
stream.seek(0);
_loadTextMissionFile(vehicle, stream, *visualItems, errorString);
} else {
- _loadJsonMissionFile(vehicle, bytes, *visualItems, *complexItems, errorString);
+ _loadJsonMissionFile(vehicle, bytes, *visualItems, errorString);
}
}
if (!errorString.isEmpty()) {
(*visualItems)->deleteLater();
- (*complexItems)->deleteLater();
qgcApp()->showMessage(errorString);
return false;
@@ -691,13 +690,13 @@ void MissionController::saveToFile(const QString& filename)
// Mission settings
- SimpleMissionItem* homeItem = qobject_cast(_visualItems->get(0));
- if (!homeItem) {
- qgcApp()->showMessage(QStringLiteral("Internal error: VisualMissionItem at index 0 not SimpleMissionItem"));
+ MissionSettingsComplexItem* settingsItem = _visualItems->value(0);
+ if (!settingsItem) {
+ qWarning() << "First item is not MissionSettingsComplexItem";
return;
}
QJsonValue coordinateValue;
- JsonHelper::saveGeoCoordinate(homeItem->coordinate(), true /* writeAltitude */, coordinateValue);
+ JsonHelper::saveGeoCoordinate(settingsItem->coordinate(), true /* writeAltitude */, coordinateValue);
missionFileObject[_jsonPlannedHomePositionKey] = coordinateValue;
missionFileObject[_jsonFirmwareTypeKey] = _activeVehicle->firmwareType();
missionFileObject[_jsonVehicleTypeKey] = _activeVehicle->vehicleType();
@@ -706,12 +705,9 @@ void MissionController::saveToFile(const QString& filename)
// Save the visual items
QJsonArray rgMissionItems;
- for (int i=1; i<_visualItems->count(); i++) {
- QJsonObject itemObject;
-
+ for (int i=0; i<_visualItems->count(); i++) {
VisualMissionItem* visualItem = qobject_cast(_visualItems->get(i));
- visualItem->save(itemObject);
- rgMissionItems.append(itemObject);
+ visualItem->save(rgMissionItems);
}
missionFileObject[_jsonItemsKey] = rgMissionItems;
@@ -785,13 +781,13 @@ void MissionController::_recalcWaypointLines(void)
bool firstCoordinateItem = true;
VisualMissionItem* lastCoordinateItem = qobject_cast(_visualItems->get(0));
- SimpleMissionItem* homeItem = qobject_cast(lastCoordinateItem);
+ MissionSettingsComplexItem* settingsItem = qobject_cast(lastCoordinateItem);
- if (!homeItem) {
- qWarning() << "Home item is not SimpleMissionItem";
+ if (!settingsItem) {
+ qWarning() << "First item is not MissionSettingsComplexItem";
}
- bool showHomePosition = homeItem->showHomePosition();
+ bool showHomePosition = false; // FIXME: settingsItem->showHomePosition();
qCDebug(MissionControllerLog) << "_recalcWaypointLines";
@@ -816,7 +812,7 @@ void MissionController::_recalcWaypointLines(void)
if (!item->isStandaloneCoordinate()) {
firstCoordinateItem = false;
VisualItemPair pair(lastCoordinateItem, item);
- if (lastCoordinateItem != homeItem || (showHomePosition && linkBackToHome)) {
+ if (lastCoordinateItem != settingsItem || (showHomePosition && linkBackToHome)) {
if (old_table.contains(pair)) {
// Do nothing, this segment already exists and is wired up
_linesTable[pair] = old_table.take(pair);
@@ -840,7 +836,6 @@ void MissionController::_recalcWaypointLines(void)
}
}
-
{
// Create a temporary QObjectList and replace the model data
QObjectList objs;
@@ -853,7 +848,6 @@ void MissionController::_recalcWaypointLines(void)
_waypointLines.swapObjectList(objs);
}
-
// Anything left in the old table is an obsolete line object that can go
qDeleteAll(old_table);
@@ -864,18 +858,19 @@ void MissionController::_recalcWaypointLines(void)
void MissionController::_recalcAltitudeRangeBearing()
{
- if (!_visualItems->count())
+ if (!_visualItems->count()) {
return;
+ }
bool firstCoordinateItem = true;
VisualMissionItem* lastCoordinateItem = qobject_cast(_visualItems->get(0));
- SimpleMissionItem* homeItem = qobject_cast(lastCoordinateItem);
+ MissionSettingsComplexItem* settingsItem = qobject_cast(lastCoordinateItem);
- if (!homeItem) {
- qWarning() << "Home item is not SimpleMissionItem";
+ if (!settingsItem) {
+ qWarning() << "First item is not MissionSettingsComplexItem";
}
- bool showHomePosition = homeItem->showHomePosition();
+ bool showHomePosition = settingsItem->showHomePosition();
qCDebug(MissionControllerLog) << "_recalcAltitudeRangeBearing";
@@ -890,8 +885,8 @@ void MissionController::_recalcAltitudeRangeBearing()
double minAltSeen = 0.0;
double maxAltSeen = 0.0;
- const double homePositionAltitude = homeItem->coordinate().altitude();
- minAltSeen = maxAltSeen = homeItem->coordinate().altitude();
+ const double homePositionAltitude = settingsItem->coordinate().altitude();
+ minAltSeen = maxAltSeen = settingsItem->coordinate().altitude();
double missionDistance = 0.0;
double missionMaxTelemetry = 0.0;
@@ -981,7 +976,7 @@ void MissionController::_recalcAltitudeRangeBearing()
if (!item->isStandaloneCoordinate()) {
firstCoordinateItem = false;
- if (lastCoordinateItem != homeItem || linkBackToHome) {
+ if (lastCoordinateItem != settingsItem || linkBackToHome) {
// This is a subsequent waypoint or we are forcing the first waypoint back to home
double azimuth, distance, altDifference;
@@ -991,7 +986,7 @@ void MissionController::_recalcAltitudeRangeBearing()
item->setDistance(distance);
missionDistance += distance;
- missionMaxTelemetry = qMax(missionMaxTelemetry, _calcDistanceToHome(item, homeItem));
+ missionMaxTelemetry = qMax(missionMaxTelemetry, _calcDistanceToHome(item, settingsItem));
// Calculate mission time
if (vtolVehicle) {
@@ -1017,7 +1012,7 @@ void MissionController::_recalcAltitudeRangeBearing()
double cruiseSpeed = _activeVehicle->multiRotor() ? currentHoverSpeed : currentCruiseSpeed;
missionDistance += complexDistance;
missionTime += complexDistance / cruiseSpeed;
- missionMaxTelemetry = qMax(missionMaxTelemetry, complexItem->greatestDistanceTo(homeItem->exitCoordinate()));
+ missionMaxTelemetry = qMax(missionMaxTelemetry, complexItem->greatestDistanceTo(settingsItem->exitCoordinate()));
// Let the complex item know the current cruise speed
complexItem->setCruiseSpeed(cruiseSpeed);
@@ -1107,57 +1102,36 @@ void MissionController::_recalcAll(void)
/// Initializes a new set of mission items
void MissionController::_initAllVisualItems(void)
{
- SimpleMissionItem* homeItem = NULL;
+ MissionSettingsComplexItem* settingsItem = NULL;
// Setup home position at index 0
- homeItem = qobject_cast(_visualItems->get(0));
- if (!homeItem) {
- qWarning() << "homeItem not SimpleMissionItem";
+ settingsItem = qobject_cast(_visualItems->get(0));
+ if (!settingsItem) {
+ qWarning() << "First item not MissionSettingsComplexItem";
return;
}
- homeItem->setHomePositionSpecialCase(true);
- homeItem->setShowHomePosition(_editMode);
- homeItem->missionItem().setCommand(MAV_CMD_NAV_WAYPOINT);
- homeItem->missionItem().setFrame(MAV_FRAME_GLOBAL);
- homeItem->setIsCurrentItem(true);
+ settingsItem->setShowHomePosition(_editMode);
+ settingsItem->setIsCurrentItem(true);
if (!_editMode && _activeVehicle && _activeVehicle->homePositionAvailable()) {
- homeItem->setCoordinate(_activeVehicle->homePosition());
- homeItem->setShowHomePosition(true);
+ settingsItem->setCoordinate(_activeVehicle->homePosition());
+ settingsItem->setShowHomePosition(true);
}
emit plannedHomePositionChanged(plannedHomePosition());
- connect(homeItem, &VisualMissionItem::coordinateChanged, this, &MissionController::_homeCoordinateChanged);
+ connect(settingsItem, &VisualMissionItem::coordinateChanged, this, &MissionController::_homeCoordinateChanged);
- QmlObjectListModel* newComplexItems = new QmlObjectListModel(this);
for (int i=0; i<_visualItems->count(); i++) {
VisualMissionItem* item = qobject_cast(_visualItems->get(i));
_initVisualItem(item);
-
- // Set up complex item list
- if (!item->isSimpleItem()) {
- ComplexMissionItem* complexItem = qobject_cast(item);
-
- if (complexItem) {
- newComplexItems->append(item);
- } else {
- qWarning() << "isSimpleItem == false, but not ComplexMissionItem";
- }
- }
- }
-
- if (_complexItems) {
- _complexItems->deleteLater();
}
- _complexItems = newComplexItems;
_recalcAll();
emit visualItemsChanged();
- emit complexVisualItemsChanged();
connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
@@ -1256,14 +1230,14 @@ void MissionController::_activeVehicleSet(void)
void MissionController::_activeVehicleHomePositionAvailableChanged(bool homePositionAvailable)
{
if (!_editMode && _visualItems) {
- SimpleMissionItem* homeItem = qobject_cast(_visualItems->get(0));
+ MissionSettingsComplexItem* settingsItem = qobject_cast(_visualItems->get(0));
- if (homeItem) {
- homeItem->setShowHomePosition(homePositionAvailable);
+ if (settingsItem) {
+ settingsItem->setShowHomePosition(homePositionAvailable);
emit plannedHomePositionChanged(plannedHomePosition());
_recalcWaypointLines();
} else {
- qWarning() << "Unabled to cast home item to SimpleMissionItem";
+ qWarning() << "First item is not MissionSettingsComplexItem";
}
}
}
@@ -1271,16 +1245,17 @@ void MissionController::_activeVehicleHomePositionAvailableChanged(bool homePosi
void MissionController::_activeVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
{
if (!_editMode && _visualItems) {
- VisualMissionItem* item = qobject_cast(_visualItems->get(0));
- if (item) {
- if (item->coordinate() != homePosition) {
- item->setCoordinate(homePosition);
+ MissionSettingsComplexItem* settingsItem = qobject_cast(_visualItems->get(0));
+ if (settingsItem) {
+ if (settingsItem->coordinate() != homePosition) {
+ settingsItem->setCoordinate(homePosition);
+ settingsItem->setShowHomePosition(true);
qCDebug(MissionControllerLog) << "Home position update" << homePosition;
emit plannedHomePositionChanged(plannedHomePosition());
_recalcWaypointLines();
}
} else {
- qWarning() << "Unabled to cast home item to VisualMissionItem";
+ qWarning() << "First item is not MissionSettingsComplexItem";
}
}
}
@@ -1393,13 +1368,13 @@ double MissionController::_normalizeLon(double lon)
return lon + 180.0;
}
-/// Add the home position item to the front of the list
-void MissionController::_addPlannedHomePosition(Vehicle* vehicle, QmlObjectListModel* visualItems, bool addToCenter)
+/// Add the Mission Settings complex item to the front of the items
+void MissionController::_addMissionSettings(Vehicle* vehicle, QmlObjectListModel* visualItems, bool addToCenter)
{
bool homePositionSet = false;
- SimpleMissionItem* homeItem = new SimpleMissionItem(vehicle, visualItems);
- visualItems->insert(0, homeItem);
+ MissionSettingsComplexItem* settingsItem = new MissionSettingsComplexItem(vehicle, visualItems);
+ visualItems->insert(0, settingsItem);
if (visualItems->count() > 1 && addToCenter) {
double north = 0.0;
@@ -1430,12 +1405,12 @@ void MissionController::_addPlannedHomePosition(Vehicle* vehicle, QmlObjectListM
if (firstCoordSet) {
homePositionSet = true;
- homeItem->setCoordinate(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0));
+ settingsItem->setCoordinate(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0));
}
}
if (!homePositionSet) {
- homeItem->setCoordinate(qgcApp()->lastKnownHomePosition());
+ settingsItem->setCoordinate(qgcApp()->lastKnownHomePosition());
}
}
@@ -1474,9 +1449,9 @@ void MissionController::setDirty(bool dirty)
QGeoCoordinate MissionController::plannedHomePosition(void)
{
if (_visualItems && _visualItems->count() > 0) {
- SimpleMissionItem* item = qobject_cast(_visualItems->get(0));
- if (item && item->showHomePosition()) {
- return item->coordinate();
+ MissionSettingsComplexItem* settingsItem = qobject_cast(_visualItems->get(0));
+ if (settingsItem && settingsItem->showHomePosition()) {
+ return settingsItem->coordinate();
}
}
diff --git a/src/MissionManager/MissionController.h b/src/MissionManager/MissionController.h
index 13032292873e579c3122203c6ee0914dd5cf7599..9e4447a8441661e0edd3fec92069170afa80f26a 100644
--- a/src/MissionManager/MissionController.h
+++ b/src/MissionManager/MissionController.h
@@ -34,11 +34,10 @@ public:
MissionController(QObject* parent = NULL);
~MissionController();
- Q_PROPERTY(QGeoCoordinate plannedHomePosition READ plannedHomePosition NOTIFY plannedHomePositionChanged)
- Q_PROPERTY(QmlObjectListModel* visualItems READ visualItems NOTIFY visualItemsChanged)
- Q_PROPERTY(QmlObjectListModel* complexVisualItems READ complexVisualItems NOTIFY complexVisualItemsChanged)
- Q_PROPERTY(QmlObjectListModel* waypointLines READ waypointLines NOTIFY waypointLinesChanged)
-
+ // Mission settings
+ Q_PROPERTY(QGeoCoordinate plannedHomePosition READ plannedHomePosition NOTIFY plannedHomePositionChanged)
+ Q_PROPERTY(QmlObjectListModel* visualItems READ visualItems NOTIFY visualItemsChanged)
+ Q_PROPERTY(QmlObjectListModel* waypointLines READ waypointLines NOTIFY waypointLinesChanged)
Q_PROPERTY(QStringList complexMissionItemNames MEMBER _complexMissionItemNames CONSTANT)
Q_PROPERTY(double missionDistance READ missionDistance NOTIFY missionDistanceChanged)
@@ -67,9 +66,8 @@ public:
/// @param[in] vehicle Vehicle we are loading items for
/// @param[in] filename File to load from
/// @param[out] visualItems Visual items loaded, returns NULL if error
- /// @param[out] complexItems Complex items loaded, returns NULL if error
/// @return success/fail
- static bool loadItemsFromFile(Vehicle* vehicle, const QString& filename, QmlObjectListModel** visualItems, QmlObjectListModel** complexItems);
+ static bool loadItemsFromFile(Vehicle* vehicle, const QString& filename, QmlObjectListModel** visualItems);
/// Sends the mission items to the specified vehicle
static void sendItemsToVehicle(Vehicle* vehicle, QmlObjectListModel* visualMissionItems);
@@ -94,7 +92,6 @@ public:
QGeoCoordinate plannedHomePosition (void);
QmlObjectListModel* visualItems (void) { return _visualItems; }
- QmlObjectListModel* complexVisualItems (void) { return _complexItems; }
QmlObjectListModel* waypointLines (void) { return &_waypointLines; }
double missionDistance (void) const { return _missionDistance; }
@@ -110,7 +107,6 @@ public:
signals:
void plannedHomePositionChanged(QGeoCoordinate plannedHomePosition);
void visualItemsChanged(void);
- void complexVisualItemsChanged(void);
void waypointLinesChanged(void);
void newItemsFromVehicle(void);
void missionDistanceChanged(double missionDistance);
@@ -151,10 +147,10 @@ private:
bool _findPreviousAltitude(int newIndex, double* prevAltitude, MAV_FRAME* prevFrame);
static double _normalizeLat(double lat);
static double _normalizeLon(double lon);
- static void _addPlannedHomePosition(Vehicle* vehicle, QmlObjectListModel* visualItems, bool addToCenter);
- static bool _loadJsonMissionFile(Vehicle* vehicle, const QByteArray& bytes, QmlObjectListModel* visualItems, QmlObjectListModel* complexItems, QString& errorString);
- static bool _loadJsonMissionFileV1(Vehicle* vehicle, const QJsonObject& json, QmlObjectListModel* visualItems, QmlObjectListModel* complexItems, QString& errorString);
- static bool _loadJsonMissionFileV2(Vehicle* vehicle, const QJsonObject& json, QmlObjectListModel* visualItems, QmlObjectListModel* complexItems, QString& errorString);
+ static void _addMissionSettings(Vehicle* vehicle, QmlObjectListModel* visualItems, bool addToCenter);
+ static bool _loadJsonMissionFile(Vehicle* vehicle, const QByteArray& bytes, QmlObjectListModel* visualItems, QString& errorString);
+ static bool _loadJsonMissionFileV1(Vehicle* vehicle, const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString);
+ static bool _loadJsonMissionFileV2(Vehicle* vehicle, const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString);
static bool _loadTextMissionFile(Vehicle* vehicle, QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString);
int _nextSequenceNumber(void);
void _setMissionDistance(double missionDistance);
@@ -171,7 +167,6 @@ private:
private:
QmlObjectListModel* _visualItems;
- QmlObjectListModel* _complexItems;
QmlObjectListModel _waypointLines;
CoordVectHashTable _linesTable;
bool _firstItemsFromVehicle;
@@ -189,6 +184,8 @@ private:
QStringList _complexMissionItemNames;
static const char* _settingsGroup;
+
+ // Json file keys for persistence
static const char* _jsonFileTypeValue;
static const char* _jsonFirmwareTypeKey;
static const char* _jsonVehicleTypeKey;
diff --git a/src/MissionManager/MissionManager.cc b/src/MissionManager/MissionManager.cc
index 2aa7ad8cc1ec13d32130b4d92c9e408724e5200b..acac452c2b724f20c90b34ecf486b315f3d62eb6 100644
--- a/src/MissionManager/MissionManager.cc
+++ b/src/MissionManager/MissionManager.cc
@@ -91,7 +91,7 @@ void MissionManager::writeMissionItems(const QList& missionItems)
/// This begins the write sequence with the vehicle. This may be called during a retry.
void MissionManager::_writeMissionCount(void)
{
- qCDebug(MissionManagerLog) << "_writeMissionCount retry count" << _retryCount;
+ qCDebug(MissionManagerLog) << "_writeMissionCount count:_retryCount" << _missionItems.count() << _retryCount;
mavlink_message_t message;
mavlink_mission_count_t missionCount;
@@ -427,7 +427,7 @@ void MissionManager::_handleMissionItem(const mavlink_message_t& message, bool m
seq = missionItem.seq;
}
- qCDebug(MissionManagerLog) << "_handleMissionItem sequenceNumber:" << seq;
+ qCDebug(MissionManagerLog) << "_handleMissionItem sequenceNumber:" << seq << command;
if (_itemIndicesToRead.contains(seq)) {
_itemIndicesToRead.removeOne(seq);
@@ -483,8 +483,6 @@ void MissionManager::_handleMissionRequest(const mavlink_message_t& message, boo
mavlink_msg_mission_request_decode(&message, &missionRequest);
- qCDebug(MissionManagerLog) << "_handleMissionRequest sequenceNumber:" << missionRequest.seq;
-
if (!_itemIndicesToWrite.contains(missionRequest.seq)) {
if (missionRequest.seq > _missionItems.count()) {
_sendError(RequestRangeError, QString("Vehicle requested item outside range, count:request %1:%2. Send to Vehicle failed.").arg(_missionItems.count()).arg(missionRequest.seq));
@@ -497,11 +495,13 @@ void MissionManager::_handleMissionRequest(const mavlink_message_t& message, boo
_itemIndicesToWrite.removeOne(missionRequest.seq);
}
- mavlink_message_t messageOut;
+ MissionItem* item = _missionItems[missionRequest.seq];
+ qCDebug(MissionManagerLog) << "_handleMissionRequest sequenceNumber:" << missionRequest.seq << item->command();
+
+ mavlink_message_t messageOut;
if (missionItemInt) {
mavlink_mission_item_int_t missionItem;
- MissionItem* item = _missionItems[missionRequest.seq];
missionItem.target_system = _vehicle->id();
missionItem.target_component = MAV_COMP_ID_MISSIONPLANNER;
@@ -526,8 +526,6 @@ void MissionManager::_handleMissionRequest(const mavlink_message_t& message, boo
} else {
mavlink_mission_item_t missionItem;
- MissionItem* item = _missionItems[missionRequest.seq];
-
missionItem.target_system = _vehicle->id();
missionItem.target_component = MAV_COMP_ID_MISSIONPLANNER;
missionItem.seq = missionRequest.seq;
diff --git a/src/MissionManager/MissionSettings.FactMetaData.json b/src/MissionManager/MissionSettings.FactMetaData.json
new file mode 100644
index 0000000000000000000000000000000000000000..78905484bcd0a30366f4f9d997f53543e3e71c79
--- /dev/null
+++ b/src/MissionManager/MissionSettings.FactMetaData.json
@@ -0,0 +1,86 @@
+[
+{
+ "name": "PlannedHomePositionLatitude",
+ "shortDescription": "Planned home position latitude",
+ "type": "double",
+ "decimalPlaces": 7,
+ "defaultValue": 37.803784
+},
+{
+ "name": "PlannedHomePositionLongitude",
+ "shortDescription": "Planned home position longitude",
+ "type": "double",
+ "decimalPlaces": 7,
+ "defaultValue": -122.462276
+},
+{
+ "name": "PlannedHomePositionAltitude",
+ "shortDescription": "Planned home position altitude",
+ "type": "double",
+ "units": "m",
+ "decimalPlaces": 1,
+ "defaultValue": 0
+},
+{
+ "name": "FlightSpeed",
+ "shortDescription": "Flight speed for mission.",
+ "type": "double",
+ "units": "m/s",
+ "min": 0,
+ "decimalPlaces": 1
+},
+{
+ "name": "CameraAction",
+ "shortDescription": "Specify whether the camera should take photos or video",
+ "type": "uint32",
+ "enumStrings": "No camera action,Take photos (time),Take photos (distance),Take video",
+ "enumValues": "0,1,2,3",
+ "defaultValue": 0
+},
+{
+ "name": "CameraPhotoIntervalDistance",
+ "shortDescription": "Specify the distance between each photo",
+ "type": "double",
+ "units": "m",
+ "min": 0,
+ "decimalPlaces": 1,
+ "defaultValue": 1
+},
+{
+ "name": "CameraPhotoIntervalTime",
+ "shortDescription": "Specify the time between each photo",
+ "type": "uint32",
+ "units": "secs",
+ "min": 1,
+ "decimalPlaces": 0,
+ "defaultValue": 10
+},
+{
+ "name": "GimbalPitch",
+ "shortDescription": "Gimbal pitch rotation.",
+ "type": "double",
+ "units": "deg",
+ "min": 0.0,
+ "max": 360.0,
+ "decimalPlaces": 0,
+ "defaultValue": 0
+},
+{
+ "name": "GimbalYaw",
+ "shortDescription": "Gimbal yaw rotation.",
+ "type": "double",
+ "units": "deg",
+ "min": 0.0,
+ "max": 360.0,
+ "decimalPlaces": 0,
+ "defaultValue": 0
+},
+{
+ "name": "MissionEndAction",
+ "shortDescription": "The action to take when the mission completed.",
+ "type": "uint32",
+ "enumStrings": "No action on mission completion,Loiter after mission completes,RTL after mission completes,Land after mission completes",
+ "enumValues": "0,1,2,3",
+ "defaultValue": 0
+}
+]
diff --git a/src/MissionManager/MissionSettingsComplexItem.cc b/src/MissionManager/MissionSettingsComplexItem.cc
new file mode 100644
index 0000000000000000000000000000000000000000..f53f6ccad36675450197dcedfbb54d89c527d47a
--- /dev/null
+++ b/src/MissionManager/MissionSettingsComplexItem.cc
@@ -0,0 +1,476 @@
+/****************************************************************************
+ *
+ * (c) 2009-2016 QGROUNDCONTROL PROJECT
+ *
+ * QGroundControl is licensed according to the terms in the file
+ * COPYING.md in the root of the source code directory.
+ *
+ ****************************************************************************/
+
+#include "MissionSettingsComplexItem.h"
+#include "JsonHelper.h"
+#include "MissionController.h"
+#include "QGCGeo.h"
+#include "QGroundControlQmlGlobal.h"
+#include "SimpleMissionItem.h"
+#include "SettingsManager.h"
+#include "AppSettings.h"
+
+#include
+
+QGC_LOGGING_CATEGORY(MissionSettingsComplexItemLog, "MissionSettingsComplexItemLog")
+
+const char* MissionSettingsComplexItem::jsonComplexItemTypeValue = "MissionSettings";
+
+const char* MissionSettingsComplexItem::_plannedHomePositionLatitudeName = "PlannedHomePositionLatitude";
+const char* MissionSettingsComplexItem::_plannedHomePositionLongitudeName = "PlannedHomePositionLongitude";
+const char* MissionSettingsComplexItem::_plannedHomePositionAltitudeName = "PlannedHomePositionAltitude";
+const char* MissionSettingsComplexItem::_missionFlightSpeedName = "FlightSpeed";
+const char* MissionSettingsComplexItem::_gimbalPitchName = "GimbalPitch";
+const char* MissionSettingsComplexItem::_gimbalYawName = "GimbalYaw";
+const char* MissionSettingsComplexItem::_cameraActionName = "CameraAction";
+const char* MissionSettingsComplexItem::_cameraPhotoIntervalDistanceName = "CameraPhotoIntervalDistance";
+const char* MissionSettingsComplexItem::_cameraPhotoIntervalTimeName = "CameraPhotoIntervalTime";
+const char* MissionSettingsComplexItem::_missionEndActionName = "MissionEndAction";
+
+QMap MissionSettingsComplexItem::_metaDataMap;
+
+MissionSettingsComplexItem::MissionSettingsComplexItem(Vehicle* vehicle, QObject* parent)
+ : ComplexMissionItem(vehicle, parent)
+ , _specifyMissionFlightSpeed(false)
+ , _specifyGimbal(false)
+ , _plannedHomePositionLatitudeFact (0, _plannedHomePositionLatitudeName, FactMetaData::valueTypeDouble)
+ , _plannedHomePositionLongitudeFact (0, _plannedHomePositionLongitudeName, FactMetaData::valueTypeDouble)
+ , _plannedHomePositionAltitudeFact (0, _plannedHomePositionAltitudeName, FactMetaData::valueTypeDouble)
+ , _missionFlightSpeedFact (0, _missionFlightSpeedName, FactMetaData::valueTypeDouble)
+ , _gimbalYawFact (0, _gimbalYawName, FactMetaData::valueTypeDouble)
+ , _gimbalPitchFact (0, _gimbalPitchName, FactMetaData::valueTypeDouble)
+ , _cameraActionFact (0, _cameraActionName, FactMetaData::valueTypeDouble)
+ , _cameraPhotoIntervalDistanceFact (0, _cameraPhotoIntervalDistanceName, FactMetaData::valueTypeDouble)
+ , _cameraPhotoIntervalTimeFact (0, _cameraPhotoIntervalTimeName, FactMetaData::valueTypeUint32)
+ , _missionEndActionFact (0, _missionEndActionName, FactMetaData::valueTypeUint32)
+ , _sequenceNumber(0)
+ , _dirty(false)
+{
+ _editorQml = "qrc:/qml/MissionSettingsEditor.qml";
+
+ if (_metaDataMap.isEmpty()) {
+ _metaDataMap = FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/MissionSettings.FactMetaData.json"), NULL /* metaDataParent */);
+ }
+
+ _plannedHomePositionLatitudeFact.setMetaData (_metaDataMap[_plannedHomePositionLatitudeName]);
+ _plannedHomePositionLongitudeFact.setMetaData (_metaDataMap[_plannedHomePositionLongitudeName]);
+ _plannedHomePositionAltitudeFact.setMetaData (_metaDataMap[_plannedHomePositionAltitudeName]);
+ _missionFlightSpeedFact.setMetaData (_metaDataMap[_missionFlightSpeedName]);
+ _gimbalPitchFact.setMetaData (_metaDataMap[_gimbalPitchName]);
+ _gimbalYawFact.setMetaData (_metaDataMap[_gimbalYawName]);
+ _cameraActionFact.setMetaData (_metaDataMap[_cameraActionName]);
+ _cameraPhotoIntervalDistanceFact.setMetaData (_metaDataMap[_cameraPhotoIntervalDistanceName]);
+ _cameraPhotoIntervalTimeFact.setMetaData (_metaDataMap[_cameraPhotoIntervalTimeName]);
+ _missionEndActionFact.setMetaData (_metaDataMap[_missionEndActionName]);
+
+ _plannedHomePositionLatitudeFact.setRawValue (_plannedHomePositionLatitudeFact.rawDefaultValue());
+ _plannedHomePositionLongitudeFact.setRawValue (_plannedHomePositionLongitudeFact.rawDefaultValue());
+ _plannedHomePositionAltitudeFact.setRawValue (_plannedHomePositionAltitudeFact.rawDefaultValue());
+ _gimbalPitchFact.setRawValue (_gimbalPitchFact.rawDefaultValue());
+ _gimbalYawFact.setRawValue (_gimbalYawFact.rawDefaultValue());
+ _cameraActionFact.setRawValue (_cameraActionFact.rawDefaultValue());
+ _cameraPhotoIntervalDistanceFact.setRawValue (_cameraPhotoIntervalDistanceFact.rawDefaultValue());
+ _cameraPhotoIntervalTimeFact.setRawValue (_cameraPhotoIntervalTimeFact.rawDefaultValue());
+ _missionEndActionFact.setRawValue (_missionEndActionFact.rawDefaultValue());
+
+ // FIXME: Flight speed default value correctly based firmware parameter if online
+ AppSettings* appSettings = qgcApp()->toolbox()->settingsManager()->appSettings();
+ Fact* speedFact = vehicle->multiRotor() ? appSettings->offlineEditingHoverSpeed() : appSettings->offlineEditingCruiseSpeed();
+ _missionFlightSpeedFact.setRawValue(speedFact->rawValue().toDouble());
+
+ setHomePositionSpecialCase(true);
+
+ connect(this, &MissionSettingsComplexItem::specifyMissionFlightSpeedChanged, this, &MissionSettingsComplexItem::_setDirtyAndUpdateLastSequenceNumber);
+ connect(this, &MissionSettingsComplexItem::specifyGimbalChanged, this, &MissionSettingsComplexItem::_setDirtyAndUpdateLastSequenceNumber);
+
+ connect(&_plannedHomePositionLatitudeFact, &Fact::valueChanged, this, &MissionSettingsComplexItem::_setDirtyAndUpdateCoordinate);
+ connect(&_plannedHomePositionLongitudeFact, &Fact::valueChanged, this, &MissionSettingsComplexItem::_setDirtyAndUpdateCoordinate);
+ connect(&_plannedHomePositionAltitudeFact, &Fact::valueChanged, this, &MissionSettingsComplexItem::_setDirtyAndUpdateCoordinate);
+ connect(&_missionFlightSpeedFact, &Fact::valueChanged, this, &MissionSettingsComplexItem::_setDirty);
+ connect(&_gimbalPitchFact, &Fact::valueChanged, this, &MissionSettingsComplexItem::_setDirty);
+ connect(&_gimbalYawFact, &Fact::valueChanged, this, &MissionSettingsComplexItem::_setDirty);
+ connect(&_cameraActionFact, &Fact::valueChanged, this, &MissionSettingsComplexItem::_setDirtyAndUpdateLastSequenceNumber);
+ connect(&_cameraPhotoIntervalDistanceFact, &Fact::valueChanged, this, &MissionSettingsComplexItem::_setDirty);
+ connect(&_cameraPhotoIntervalTimeFact, &Fact::valueChanged, this, &MissionSettingsComplexItem::_setDirty);
+ connect(&_missionEndActionFact, &Fact::valueChanged, this, &MissionSettingsComplexItem::_setDirty);
+}
+
+
+void MissionSettingsComplexItem::setSpecifyMissionFlightSpeed(bool specifyMissionFlightSpeed)
+{
+ if (specifyMissionFlightSpeed != _specifyMissionFlightSpeed) {
+ _specifyMissionFlightSpeed = specifyMissionFlightSpeed;
+ emit specifyMissionFlightSpeedChanged(specifyMissionFlightSpeed);
+ }
+}
+
+void MissionSettingsComplexItem::setSpecifyGimbal(bool specifyGimbal)
+{
+ if (specifyGimbal != _specifyGimbal) {
+ _specifyGimbal = specifyGimbal;
+ emit specifyGimbalChanged(specifyGimbal);
+ }
+}
+
+int MissionSettingsComplexItem::lastSequenceNumber(void) const
+{
+ int lastSequenceNumber = _sequenceNumber + 1; // +1 for planned home position
+
+ if (_specifyMissionFlightSpeed) {
+ lastSequenceNumber++;
+ }
+ if (_specifyGimbal) {
+ lastSequenceNumber++;
+ }
+ if (_cameraActionFact.rawValue().toInt() != CameraActionNone) {
+ lastSequenceNumber++;
+ }
+
+ return lastSequenceNumber;
+}
+
+void MissionSettingsComplexItem::setDirty(bool dirty)
+{
+ if (_dirty != dirty) {
+ _dirty = dirty;
+ emit dirtyChanged(_dirty);
+ }
+}
+
+void MissionSettingsComplexItem::save(QJsonArray& missionItems) const
+{
+ QmlObjectListModel* items = getMissionItems();
+
+ // First item show be planned home position, we are not reponsible for save/load
+ // Remained we just output as is
+ for (int i=1; icount(); i++) {
+ MissionItem* item = items->value(i);
+ QJsonObject saveObject;
+ item->save(saveObject);
+ missionItems.append(saveObject);
+ }
+
+ items->deleteLater();
+}
+
+void MissionSettingsComplexItem::setSequenceNumber(int sequenceNumber)
+{
+ if (_sequenceNumber != sequenceNumber) {
+ _sequenceNumber = sequenceNumber;
+ emit sequenceNumberChanged(sequenceNumber);
+ emit lastSequenceNumberChanged(lastSequenceNumber());
+ }
+}
+
+bool MissionSettingsComplexItem::load(const QJsonObject& complexObject, int sequenceNumber, QString& errorString)
+{
+ Q_UNUSED(complexObject);
+ Q_UNUSED(sequenceNumber);
+ Q_UNUSED(errorString);
+#if 0
+ QList keyInfoList = {
+ { JsonHelper::jsonVersionKey, QJsonValue::Double, true },
+ { VisualMissionItem::jsonTypeKey, QJsonValue::String, true },
+ { ComplexMissionItem::jsonComplexItemTypeKey, QJsonValue::String, true },
+ { _jsonLoiterCoordinateKey, QJsonValue::Array, true },
+ { _jsonLoiterRadiusKey, QJsonValue::Double, true },
+ { _jsonLoiterClockwiseKey, QJsonValue::Bool, true },
+ { _jsonLoiterAltitudeRelativeKey, QJsonValue::Bool, true },
+ { _jsonLandingCoordinateKey, QJsonValue::Array, true },
+ { _jsonLandingAltitudeRelativeKey, QJsonValue::Bool, true },
+ };
+ if (!JsonHelper::validateKeys(complexObject, keyInfoList, errorString)) {
+ return false;
+ }
+
+ QString itemType = complexObject[VisualMissionItem::jsonTypeKey].toString();
+ QString complexType = complexObject[ComplexMissionItem::jsonComplexItemTypeKey].toString();
+ if (itemType != VisualMissionItem::jsonTypeComplexItemValue || complexType != jsonComplexItemTypeValue) {
+ errorString = tr("QGroundControl does not support loading this complex mission item type: %1:2").arg(itemType).arg(complexType);
+ return false;
+ }
+
+ setSequenceNumber(sequenceNumber);
+
+ QGeoCoordinate coordinate;
+ if (!JsonHelper::loadGeoCoordinate(complexObject[_jsonLoiterCoordinateKey], true /* altitudeRequired */, coordinate, errorString)) {
+ return false;
+ }
+ _loiterCoordinate = coordinate;
+ _loiterAltitudeFact.setRawValue(coordinate.altitude());
+
+ if (!JsonHelper::loadGeoCoordinate(complexObject[_jsonLandingCoordinateKey], true /* altitudeRequired */, coordinate, errorString)) {
+ return false;
+ }
+ _landingCoordinate = coordinate;
+ _landingAltitudeFact.setRawValue(coordinate.altitude());
+
+ _loiterRadiusFact.setRawValue(complexObject[_jsonLoiterRadiusKey].toDouble());
+ _loiterClockwise = complexObject[_jsonLoiterClockwiseKey].toBool();
+ _loiterAltitudeRelative = complexObject[_jsonLoiterAltitudeRelativeKey].toBool();
+ _landingAltitudeRelative = complexObject[_jsonLandingAltitudeRelativeKey].toBool();
+
+ _landingCoordSet = true;
+ _recalcFromHeadingAndDistanceChange();
+#endif
+ return true;
+}
+
+double MissionSettingsComplexItem::greatestDistanceTo(const QGeoCoordinate &other) const
+{
+ Q_UNUSED(other);
+ return 0;
+}
+
+bool MissionSettingsComplexItem::specifiesCoordinate(void) const
+{
+ return false;
+}
+
+QmlObjectListModel* MissionSettingsComplexItem::getMissionItems(void) const
+{
+ QmlObjectListModel* pMissionItems = new QmlObjectListModel;
+
+ int seqNum = _sequenceNumber;
+
+ // IMPORTANT NOTE: If anything changed here you just also change MissionSettingsComplexItem::scanForMissionSettings
+
+ // Planned home position
+ MissionItem* item = new MissionItem(seqNum++,
+ MAV_CMD_NAV_WAYPOINT,
+ MAV_FRAME_GLOBAL,
+ 0, // Hold time
+ 0, // Acceptance radius
+ 0, // Not sure?
+ 0, // Yaw
+ _plannedHomePositionLatitudeFact.rawValue().toDouble(),
+ _plannedHomePositionLongitudeFact.rawValue().toDouble(),
+ _plannedHomePositionAltitudeFact.rawValue().toDouble(),
+ true, // autoContinue
+ false, // isCurrentItem
+ pMissionItems); // parent - allow delete on pMissionItems to delete everthing
+ pMissionItems->append(item);
+
+ if (_specifyGimbal) {
+ MissionItem* item = new MissionItem(seqNum++,
+ MAV_CMD_DO_MOUNT_CONTROL,
+ MAV_FRAME_MISSION,
+ _gimbalPitchFact.rawValue().toDouble(),
+ 0, // Gimbal roll
+ _gimbalYawFact.rawValue().toDouble(),
+ 0, 0, 0, // param 4-6 not used
+ MAV_MOUNT_MODE_MAVLINK_TARGETING,
+ true, // autoContinue
+ false, // isCurrentItem
+ pMissionItems); // parent - allow delete on pMissionItems to delete everthing
+ pMissionItems->append(item);
+ }
+
+ if (_specifyMissionFlightSpeed) {
+ qDebug() << _missionFlightSpeedFact.rawValue().toDouble();
+ MissionItem* item = new MissionItem(seqNum++,
+ MAV_CMD_DO_CHANGE_SPEED,
+ MAV_FRAME_MISSION,
+ _vehicle->multiRotor() ? 1 /* groundspeed */ : 0 /* airspeed */, // Change airspeed or groundspeed
+ _missionFlightSpeedFact.rawValue().toDouble(),
+ -1, // No throttle change
+ 0, // Absolute speed change
+ 0, 0, 0, // param 5-7 not used
+ true, // autoContinue
+ false, // isCurrentItem
+ pMissionItems); // parent - allow delete on pMissionItems to delete everthing
+ pMissionItems->append(item);
+ }
+
+ if (_cameraActionFact.rawValue().toInt() != CameraActionNone) {
+ MissionItem* item = NULL;
+
+ switch (_cameraActionFact.rawValue().toInt()) {
+ case TakePhotosIntervalTime:
+ item = new MissionItem(seqNum++,
+ MAV_CMD_IMAGE_START_CAPTURE,
+ MAV_FRAME_MISSION,
+ _cameraPhotoIntervalTimeFact.rawValue().toInt(), // Interval
+ 0, // Unlimited photo count
+ -1, // Max resolution
+ 0, 0, // param 4-5 not used
+ 0, // Camera ID
+ 0, // param 7 not used
+ true, // autoContinue
+ false, // isCurrentItem
+ pMissionItems); // parent - allow delete on pMissionItems to delete everthing
+ break;
+ case TakePhotoIntervalDistance:
+ item = new MissionItem(seqNum++,
+ MAV_CMD_DO_SET_CAM_TRIGG_DIST,
+ MAV_FRAME_MISSION,
+ _cameraPhotoIntervalDistanceFact.rawValue().toDouble(), // Trigger distance
+ 0, 0, 0, 0, 0, 0, // param 2-7 not used
+ true, // autoContinue
+ false, // isCurrentItem
+ pMissionItems); // parent - allow delete on pMissionItems to delete everthing
+ break;
+ case TakeVideo:
+ item = new MissionItem(seqNum++,
+ MAV_CMD_VIDEO_START_CAPTURE,
+ MAV_FRAME_MISSION,
+ 0, // Camera ID
+ -1, // Max fps
+ -1, // Max resolution
+ 0, 0, 0, 0, // param 5-7 not used
+ true, // autoContinue
+ false, // isCurrentItem
+ pMissionItems); // parent - allow delete on pMissionItems to delete everthing
+ break;
+ }
+ if (item) {
+ pMissionItems->append(item);
+ }
+ }
+
+ return pMissionItems;
+}
+
+void MissionSettingsComplexItem::scanForMissionSettings(QmlObjectListModel* visualItems, Vehicle* vehicle)
+{
+ bool foundGimbal = false;
+ bool foundSpeed = false;
+ bool foundCameraAction = false;
+
+ MissionSettingsComplexItem* settingsItem = visualItems->value(0);
+ if (!settingsItem) {
+ qWarning() << "First item is not MissionSettingsComplexItem";
+ return;
+ }
+
+ // Scan through the initial mission items for possible mission settings
+
+ while (visualItems->count()> 1) {
+ SimpleMissionItem* item = visualItems->value(1);
+ if (!item) {
+ // We hit a complex item there can be no more possible mission settings
+ return;
+ }
+ MissionItem& missionItem = item->missionItem();
+
+ // See MissionSettingsComplexItem::getMissionItems for specs on what compomises a known mission settings
+
+ switch ((MAV_CMD)item->command()) {
+ case MAV_CMD_DO_MOUNT_CONTROL:
+ if (!foundGimbal && missionItem.param2() == 0 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == MAV_MOUNT_MODE_MAVLINK_TARGETING) {
+ foundGimbal = true;
+ settingsItem->setSpecifyGimbal(true);
+ settingsItem->gimbalPitch()->setRawValue(missionItem.param1());
+ settingsItem->gimbalYaw()->setRawValue(missionItem.param3());
+ visualItems->removeAt(1)->deleteLater();
+ } else {
+ return;
+ }
+ break;
+
+ case MAV_CMD_DO_CHANGE_SPEED:
+ if (!foundSpeed && missionItem.param3() == -1 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) {
+ if (vehicle->multiRotor()) {
+ if (missionItem.param1() != 1) {
+ return;
+ }
+ } else {
+ if (missionItem.param1() != 0) {
+ return;
+ }
+ }
+ foundSpeed = true;
+ settingsItem->setSpecifyMissionFlightSpeed(true);
+ settingsItem->missionFlightSpeed()->setRawValue(missionItem.param2());
+ visualItems->removeAt(1)->deleteLater();
+ } else {
+ return;
+ }
+ break;
+
+ case MAV_CMD_IMAGE_START_CAPTURE:
+ if (!foundCameraAction && missionItem.param1() != 0 && missionItem.param2() == 0 && missionItem.param3() == -1 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) {
+ foundCameraAction = true;
+ settingsItem->cameraAction()->setRawValue(TakePhotosIntervalTime);
+ settingsItem->cameraPhotoIntervalTime()->setRawValue(missionItem.param1());
+ visualItems->removeAt(1)->deleteLater();
+ } else {
+ return;
+ }
+ break;
+
+ case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
+ if (!foundCameraAction && missionItem.param1() != 0 && missionItem.param2() == 0 && missionItem.param3() == 0 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) {
+ foundCameraAction = true;
+ settingsItem->cameraAction()->setRawValue(TakePhotoIntervalDistance);
+ settingsItem->cameraPhotoIntervalDistance()->setRawValue(missionItem.param1());
+ visualItems->removeAt(1)->deleteLater();
+ } else {
+ return;
+ }
+ break;
+
+ case MAV_CMD_VIDEO_START_CAPTURE:
+ if (!foundCameraAction && missionItem.param1() == 0 && missionItem.param2() == -1 && missionItem.param3() == -1 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) {
+ foundCameraAction = true;
+ settingsItem->cameraAction()->setRawValue(TakeVideo);
+ visualItems->removeAt(1)->deleteLater();
+ } else {
+ return;
+ }
+ break;
+
+ default:
+ return;
+ }
+ }
+}
+
+double MissionSettingsComplexItem::complexDistance(void) const
+{
+ return 0;
+}
+
+void MissionSettingsComplexItem::setCruiseSpeed(double cruiseSpeed)
+{
+ // We don't care about cruise speed
+ Q_UNUSED(cruiseSpeed);
+}
+
+void MissionSettingsComplexItem::_setDirty(void)
+{
+ setDirty(true);
+}
+
+void MissionSettingsComplexItem::setCoordinate(const QGeoCoordinate& coordinate)
+{
+ if (this->coordinate() != coordinate) {
+ _plannedHomePositionLatitudeFact.setRawValue(coordinate.latitude());
+ _plannedHomePositionLongitudeFact.setRawValue(coordinate.longitude());
+ _plannedHomePositionAltitudeFact.setRawValue(coordinate.altitude());
+ }
+}
+
+void MissionSettingsComplexItem::_setDirtyAndUpdateLastSequenceNumber(void)
+{
+ emit lastSequenceNumberChanged(lastSequenceNumber());
+ setDirty(true);
+}
+
+void MissionSettingsComplexItem::_setDirtyAndUpdateCoordinate(void)
+{
+ emit coordinateChanged(coordinate());
+ emit exitCoordinateChanged(coordinate());
+ setDirty(true);
+}
+
+QGeoCoordinate MissionSettingsComplexItem::coordinate(void) const
+{
+ return QGeoCoordinate(_plannedHomePositionLatitudeFact.rawValue().toDouble(), _plannedHomePositionLongitudeFact.rawValue().toDouble(), _plannedHomePositionAltitudeFact.rawValue().toDouble());
+}
diff --git a/src/MissionManager/MissionSettingsComplexItem.h b/src/MissionManager/MissionSettingsComplexItem.h
new file mode 100644
index 0000000000000000000000000000000000000000..5386b18a68ccdd92602aee928a4771a81fd9d295
--- /dev/null
+++ b/src/MissionManager/MissionSettingsComplexItem.h
@@ -0,0 +1,150 @@
+/****************************************************************************
+ *
+ * (c) 2009-2016 QGROUNDCONTROL PROJECT
+ *
+ * QGroundControl is licensed according to the terms in the file
+ * COPYING.md in the root of the source code directory.
+ *
+ ****************************************************************************/
+
+#ifndef MissionSettingsComplexItem_H
+#define MissionSettingsComplexItem_H
+
+#include "ComplexMissionItem.h"
+#include "MissionItem.h"
+#include "Fact.h"
+#include "QGCLoggingCategory.h"
+
+Q_DECLARE_LOGGING_CATEGORY(MissionSettingsComplexItemLog)
+
+class MissionSettingsComplexItem : public ComplexMissionItem
+{
+ Q_OBJECT
+
+public:
+ MissionSettingsComplexItem(Vehicle* vehicle, QObject* parent = NULL);
+
+ enum MissionEndAction {
+ MissionEndNoAction,
+ MissionEndLoiter,
+ MissionEndRTL,
+ MissionEndLand
+ };
+ Q_ENUMS(MissionEndAction)
+
+ enum CameraAction {
+ CameraActionNone,
+ TakePhotosIntervalTime,
+ TakePhotoIntervalDistance,
+ TakeVideo
+ };
+ Q_ENUMS(CameraAction)
+
+ Q_PROPERTY(bool specifyMissionFlightSpeed READ specifyMissionFlightSpeed WRITE setSpecifyMissionFlightSpeed NOTIFY specifyMissionFlightSpeedChanged)
+ Q_PROPERTY(Fact* missionFlightSpeed READ missionFlightSpeed CONSTANT)
+ Q_PROPERTY(bool specifyGimbal READ specifyGimbal WRITE setSpecifyGimbal NOTIFY specifyGimbalChanged)
+ Q_PROPERTY(Fact* gimbalPitch READ gimbalPitch CONSTANT)
+ Q_PROPERTY(Fact* gimbalYaw READ gimbalYaw CONSTANT)
+ Q_PROPERTY(Fact* cameraAction READ cameraAction CONSTANT)
+ Q_PROPERTY(Fact* cameraPhotoIntervalTime READ cameraPhotoIntervalTime CONSTANT)
+ Q_PROPERTY(Fact* cameraPhotoIntervalDistance READ cameraPhotoIntervalDistance CONSTANT)
+ Q_PROPERTY(Fact* missionEndAction READ missionEndAction CONSTANT)
+ Q_PROPERTY(Fact* plannedHomePositionLatitude READ plannedHomePositionLatitude CONSTANT)
+ Q_PROPERTY(Fact* plannedHomePositionLongitude READ plannedHomePositionLongitude CONSTANT)
+ Q_PROPERTY(Fact* plannedHomePositionAltitude READ plannedHomePositionAltitude CONSTANT)
+
+ bool specifyMissionFlightSpeed (void) const { return _specifyMissionFlightSpeed; }
+ bool specifyGimbal (void) const { return _specifyGimbal; }
+ Fact* plannedHomePositionLatitude (void) { return &_plannedHomePositionLatitudeFact; }
+ Fact* plannedHomePositionLongitude(void) { return &_plannedHomePositionLongitudeFact; }
+ Fact* plannedHomePositionAltitude (void) { return &_plannedHomePositionAltitudeFact; }
+ Fact* missionFlightSpeed (void) { return &_missionFlightSpeedFact; }
+ Fact* gimbalYaw (void) { return &_gimbalYawFact; }
+ Fact* gimbalPitch (void) { return &_gimbalPitchFact; }
+ Fact* cameraAction (void) { return &_cameraActionFact; }
+ Fact* cameraPhotoIntervalTime (void) { return &_cameraPhotoIntervalTimeFact; }
+ Fact* cameraPhotoIntervalDistance (void) { return &_cameraPhotoIntervalDistanceFact; }
+ Fact* missionEndAction (void) { return &_missionEndActionFact; }
+
+ void setSpecifyMissionFlightSpeed (bool specifyMissionFlightSpeed);
+ void setSpecifyGimbal (bool specifyGimbal);
+
+ /// Scans the loaded items for the settings items
+ static void scanForMissionSettings(QmlObjectListModel* visualItems, Vehicle* vehicle);
+
+ // Overrides from ComplexMissionItem
+
+ double complexDistance (void) const final;
+ int lastSequenceNumber (void) const final;
+ QmlObjectListModel* getMissionItems (void) const final;
+ bool load (const QJsonObject& complexObject, int sequenceNumber, QString& errorString) final;
+ double greatestDistanceTo (const QGeoCoordinate &other) const final;
+ void setCruiseSpeed (double cruiseSpeed) final;
+ QString mapVisualQML (void) const final { return QStringLiteral("MissionSettingsMapVisual.qml"); }
+
+ // Overrides from VisualMissionItem
+
+ bool dirty (void) const final { return _dirty; }
+ bool isSimpleItem (void) const final { return false; }
+ bool isStandaloneCoordinate (void) const final { return false; }
+ bool specifiesCoordinate (void) const final;
+ QString commandDescription (void) const final { return "Mission Settings"; }
+ QString commandName (void) const final { return "Mission Settings"; }
+ QString abbreviation (void) const final { return "H"; }
+ QGeoCoordinate coordinate (void) const final;
+ QGeoCoordinate exitCoordinate (void) const final { return coordinate(); }
+ int sequenceNumber (void) const final { return _sequenceNumber; }
+ double flightSpeed (void) final { return std::numeric_limits::quiet_NaN(); }
+
+ bool coordinateHasRelativeAltitude (void) const final { return true; }
+ bool exitCoordinateHasRelativeAltitude (void) const final { return true; }
+ bool exitCoordinateSameAsEntry (void) const final { return true; }
+
+ void setDirty (bool dirty) final;
+ void setCoordinate (const QGeoCoordinate& coordinate) final;
+ void setSequenceNumber (int sequenceNumber) final;
+ void save (QJsonArray& missionItems) const final;
+
+ static const char* jsonComplexItemTypeValue;
+
+signals:
+ bool specifyMissionFlightSpeedChanged (bool specifyMissionFlightSpeed);
+ bool specifyGimbalChanged (bool specifyGimbal);
+
+private slots:
+ void _setDirtyAndUpdateLastSequenceNumber(void);
+ void _setDirtyAndUpdateCoordinate(void);
+ void _setDirty(void);
+
+private:
+ bool _specifyMissionFlightSpeed;
+ bool _specifyGimbal;
+ Fact _plannedHomePositionLatitudeFact;
+ Fact _plannedHomePositionLongitudeFact;
+ Fact _plannedHomePositionAltitudeFact;
+ Fact _missionFlightSpeedFact;
+ Fact _gimbalYawFact;
+ Fact _gimbalPitchFact;
+ Fact _cameraActionFact;
+ Fact _cameraPhotoIntervalDistanceFact;
+ Fact _cameraPhotoIntervalTimeFact;
+ Fact _missionEndActionFact;
+
+ int _sequenceNumber;
+ bool _dirty;
+
+ static QMap _metaDataMap;
+
+ static const char* _plannedHomePositionLatitudeName;
+ static const char* _plannedHomePositionLongitudeName;
+ static const char* _plannedHomePositionAltitudeName;
+ static const char* _missionFlightSpeedName;
+ static const char* _gimbalPitchName;
+ static const char* _gimbalYawName;
+ static const char* _cameraActionName;
+ static const char* _cameraPhotoIntervalDistanceName;
+ static const char* _cameraPhotoIntervalTimeName;
+ static const char* _missionEndActionName;
+};
+
+#endif
diff --git a/src/MissionManager/SimpleMissionItem.cc b/src/MissionManager/SimpleMissionItem.cc
index 775bf83a49a042d3becad0fe9798f5c81a674d32..1ead1b36e0dd9b2805b8a611388c77042f534c1a 100644
--- a/src/MissionManager/SimpleMissionItem.cc
+++ b/src/MissionManager/SimpleMissionItem.cc
@@ -50,8 +50,6 @@ static const struct EnumInfo_s _rgMavFrameInfo[] = {
SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, QObject* parent)
: VisualMissionItem(vehicle, parent)
, _rawEdit(false)
- , _homePositionSpecialCase(false)
- , _showHomePosition(false)
, _commandTree(qgcApp()->toolbox()->missionCommandTree())
, _altitudeRelativeToHomeFact (0, "Altitude is relative to home", FactMetaData::valueTypeUint32)
, _supportedCommandFact (0, "Command:", FactMetaData::valueTypeUint32)
@@ -82,8 +80,6 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, const MissionItem& missio
, _missionItem(missionItem)
, _rawEdit(false)
, _dirty(false)
- , _homePositionSpecialCase(false)
- , _showHomePosition(false)
, _commandTree(qgcApp()->toolbox()->missionCommandTree())
, _altitudeRelativeToHomeFact (0, "Altitude is relative to home", FactMetaData::valueTypeUint32)
, _supportedCommandFact (0, "Command:", FactMetaData::valueTypeUint32)
@@ -112,8 +108,6 @@ SimpleMissionItem::SimpleMissionItem(const SimpleMissionItem& other, QObject* pa
, _missionItem(other._vehicle)
, _rawEdit(false)
, _dirty(false)
- , _homePositionSpecialCase(false)
- , _showHomePosition(false)
, _commandTree(qgcApp()->toolbox()->missionCommandTree())
, _altitudeRelativeToHomeFact (0, "Altitude is relative to home", FactMetaData::valueTypeUint32)
, _supportedCommandFact (0, "Command:", FactMetaData::valueTypeUint32)
@@ -246,9 +240,11 @@ SimpleMissionItem::~SimpleMissionItem()
{
}
-void SimpleMissionItem::save(QJsonObject& saveObject) const
+void SimpleMissionItem::save(QJsonArray& missionItems) const
{
- _missionItem.save(saveObject);
+ QJsonObject itemObject;
+ _missionItem.save(itemObject);
+ missionItems.append(itemObject);
}
bool SimpleMissionItem::load(QTextStream &loadStream)
@@ -584,14 +580,6 @@ QString SimpleMissionItem::category(void) const
return _commandTree->getUIInfo(_vehicle, (MAV_CMD)command())->category();
}
-void SimpleMissionItem::setShowHomePosition(bool showHomePosition)
-{
- if (showHomePosition != _showHomePosition) {
- _showHomePosition = showHomePosition;
- emit showHomePositionChanged(_showHomePosition);
- }
-}
-
void SimpleMissionItem::setCommand(MavlinkQmlSingleton::Qml_MAV_CMD command)
{
if ((MAV_CMD)command != _missionItem.command()) {
diff --git a/src/MissionManager/SimpleMissionItem.h b/src/MissionManager/SimpleMissionItem.h
index da281a2ebbc1cabb89ea800ecfbd7110b0c938ad..df09b63c16d0fb52f82079577de20b56713a24f0 100644
--- a/src/MissionManager/SimpleMissionItem.h
+++ b/src/MissionManager/SimpleMissionItem.h
@@ -32,10 +32,8 @@ public:
Q_PROPERTY(QString category READ category NOTIFY commandChanged)
Q_PROPERTY(MavlinkQmlSingleton::Qml_MAV_CMD command READ command WRITE setCommand NOTIFY commandChanged)
Q_PROPERTY(bool friendlyEditAllowed READ friendlyEditAllowed NOTIFY friendlyEditAllowedChanged)
- Q_PROPERTY(bool homePosition READ homePosition CONSTANT) ///< true: This item is being used as a home position indicator
Q_PROPERTY(bool rawEdit READ rawEdit WRITE setRawEdit NOTIFY rawEditChanged) ///< true: raw item editing with all params
Q_PROPERTY(bool relativeAltitude READ relativeAltitude NOTIFY frameChanged)
- Q_PROPERTY(bool showHomePosition READ showHomePosition WRITE setShowHomePosition NOTIFY showHomePositionChanged)
// These properties are used to display the editing ui
Q_PROPERTY(QmlObjectListModel* checkboxFacts READ checkboxFacts NOTIFY uiModelChanged)
@@ -47,9 +45,7 @@ public:
QString category (void) const;
MavlinkQmlSingleton::Qml_MAV_CMD command(void) const { return (MavlinkQmlSingleton::Qml_MAV_CMD)_missionItem._commandFact.cookedValue().toInt(); }
bool friendlyEditAllowed (void) const;
- bool homePosition (void) const { return _homePositionSpecialCase; }
bool rawEdit (void) const;
- bool showHomePosition (void) const { return _showHomePosition; }
QmlObjectListModel* textFieldFacts (void);
@@ -62,9 +58,6 @@ public:
void setCommand(MavlinkQmlSingleton::Qml_MAV_CMD command);
- void setHomePositionSpecialCase(bool homePositionSpecialCase) { _homePositionSpecialCase = homePositionSpecialCase; }
- void setShowHomePosition(bool showHomePosition);
-
void setAltDifference (double altDifference);
void setAltPercent (double altPercent);
void setAzimuth (double azimuth);
@@ -99,7 +92,7 @@ public:
void setDirty (bool dirty) final;
void setCoordinate (const QGeoCoordinate& coordinate) final;
void setSequenceNumber (int sequenceNumber) final;
- void save (QJsonObject& saveObject) const final;
+ void save (QJsonArray& missionItems) const final;
public slots:
void setDefaultsForCommand(void);
@@ -111,7 +104,6 @@ signals:
void headingDegreesChanged (double heading);
void rawEditChanged (bool rawEdit);
void uiModelChanged (void);
- void showHomePositionChanged (bool showHomePosition);
private slots:
void _setDirtyFromSignal(void);
@@ -132,8 +124,6 @@ private:
MissionItem _missionItem;
bool _rawEdit;
bool _dirty;
- bool _homePositionSpecialCase; ///< true: This item is being used as a ui home position indicator
- bool _showHomePosition;
MissionCommandTree* _commandTree;
diff --git a/src/MissionManager/SurveyMissionItem.cc b/src/MissionManager/SurveyMissionItem.cc
index d8ac44ae66e77f7bbbc923df99b10e1af398e8df..9206b6168de641db424eb299c620bacac038c8f8 100644
--- a/src/MissionManager/SurveyMissionItem.cc
+++ b/src/MissionManager/SurveyMissionItem.cc
@@ -293,8 +293,10 @@ void SurveyMissionItem::setDirty(bool dirty)
}
}
-void SurveyMissionItem::save(QJsonObject& saveObject) const
+void SurveyMissionItem::save(QJsonArray& missionItems) const
{
+ QJsonObject saveObject;
+
saveObject[JsonHelper::jsonVersionKey] = 3;
saveObject[VisualMissionItem::jsonTypeKey] = VisualMissionItem::jsonTypeComplexItemValue;
saveObject[ComplexMissionItem::jsonComplexItemTypeKey] = jsonComplexItemTypeValue;
@@ -344,6 +346,8 @@ void SurveyMissionItem::save(QJsonObject& saveObject) const
}
saveObject[_jsonPolygonObjectKey] = polygonArray;
+
+ missionItems.append(saveObject);
}
void SurveyMissionItem::setSequenceNumber(int sequenceNumber)
diff --git a/src/MissionManager/SurveyMissionItem.h b/src/MissionManager/SurveyMissionItem.h
index 37b0e8d46619e03c1efc77ac7a98d72695df4532..4fddb63d0267b2cec7b2b5de168793783bec22d6 100644
--- a/src/MissionManager/SurveyMissionItem.h
+++ b/src/MissionManager/SurveyMissionItem.h
@@ -127,7 +127,7 @@ public:
void setCoordinate (const QGeoCoordinate& coordinate) final;
void setSequenceNumber (int sequenceNumber) final;
void setTurnaroundDist (double dist) { _turnaroundDistFact.setRawValue(dist); }
- void save (QJsonObject& saveObject) const final;
+ void save (QJsonArray& missionItems) const final;
static const char* jsonComplexItemTypeValue;
diff --git a/src/MissionManager/VisualMissionItem.cc b/src/MissionManager/VisualMissionItem.cc
index db8b1ba780894057b781a421be6f8a3008f8065d..8fbaa7964fe74f7c46a0b591f5d7d82445e5c9b9 100644
--- a/src/MissionManager/VisualMissionItem.cc
+++ b/src/MissionManager/VisualMissionItem.cc
@@ -25,6 +25,8 @@ VisualMissionItem::VisualMissionItem(Vehicle* vehicle, QObject* parent)
, _vehicle(vehicle)
, _isCurrentItem(false)
, _dirty(false)
+ , _homePositionSpecialCase(false)
+ , _showHomePosition(false)
, _altDifference(0.0)
, _altPercent(0.0)
, _azimuth(0.0)
@@ -38,6 +40,8 @@ VisualMissionItem::VisualMissionItem(const VisualMissionItem& other, QObject* pa
, _vehicle(NULL)
, _isCurrentItem(false)
, _dirty(false)
+ , _homePositionSpecialCase(false)
+ , _showHomePosition(false)
, _altDifference(0.0)
, _altPercent(0.0)
, _azimuth(0.0)
@@ -52,6 +56,8 @@ const VisualMissionItem& VisualMissionItem::operator=(const VisualMissionItem& o
setIsCurrentItem(other._isCurrentItem);
setDirty(other._dirty);
+ _homePositionSpecialCase = other._homePositionSpecialCase;
+ setShowHomePosition(other.showHomePosition());
setAltDifference(other._altDifference);
setAltPercent(other._altPercent);
setAzimuth(other._azimuth);
@@ -103,3 +109,11 @@ void VisualMissionItem::setAzimuth(double azimuth)
emit azimuthChanged(_azimuth);
}
}
+
+void VisualMissionItem::setShowHomePosition(bool showHomePosition)
+{
+ if (showHomePosition != _showHomePosition) {
+ _showHomePosition = showHomePosition;
+ emit showHomePositionChanged(_showHomePosition);
+ }
+}
diff --git a/src/MissionManager/VisualMissionItem.h b/src/MissionManager/VisualMissionItem.h
index 65f38a861b265cdeac4a6c4a06e720f5fa5e7a42..0b381102e22ea8d349677c82b1bbdb60c3601c47 100644
--- a/src/MissionManager/VisualMissionItem.h
+++ b/src/MissionManager/VisualMissionItem.h
@@ -40,6 +40,9 @@ public:
const VisualMissionItem& operator=(const VisualMissionItem& other);
+ Q_PROPERTY(bool homePosition READ homePosition CONSTANT) ///< true: This item is being used as a home position indicator
+ Q_PROPERTY(bool showHomePosition READ showHomePosition WRITE setShowHomePosition NOTIFY showHomePositionChanged)
+
// The following properties are calculated/set by the MissionController recalc methods
Q_PROPERTY(double altDifference READ altDifference WRITE setAltDifference NOTIFY altDifferenceChanged) ///< Change in altitude from previous waypoint
@@ -87,6 +90,11 @@ public:
// Property accesors
+ bool homePosition (void) const { return _homePositionSpecialCase; }
+ bool showHomePosition (void) const { return _showHomePosition; }
+ void setHomePositionSpecialCase (bool homePositionSpecialCase) { _homePositionSpecialCase = homePositionSpecialCase; }
+ void setShowHomePosition (bool showHomePosition);
+
double altDifference (void) const { return _altDifference; }
double altPercent (void) const { return _altPercent; }
double azimuth (void) const { return _azimuth; }
@@ -126,8 +134,8 @@ public:
virtual void setSequenceNumber (int sequenceNumber) = 0;
/// Save the item(s) in Json format
- /// @param saveObject Save the item to this json object
- virtual void save(QJsonObject& saveObject) const = 0;
+ /// @param missionItems Current set of mission items, new items should be appended to the end
+ virtual void save(QJsonArray& missionItems) const = 0;
/// @return The QML resource file which contains the control which visualizes the item on the map.
virtual QString mapVisualQML(void) const = 0;
@@ -137,6 +145,7 @@ public:
static const char* jsonTypeComplexItemValue; ///< Item type is Complex Item
signals:
+ void showHomePositionChanged (bool showHomePosition);
void altDifferenceChanged (double altDifference);
void altPercentChanged (double altPercent);
void azimuthChanged (double azimuth);
@@ -162,6 +171,8 @@ protected:
Vehicle* _vehicle;
bool _isCurrentItem;
bool _dirty;
+ bool _homePositionSpecialCase; ///< true: This item is being used as a ui home position indicator
+ bool _showHomePosition;
double _altDifference; ///< Difference in altitude from previous waypoint
double _altPercent; ///< Percent of total altitude change in mission
double _azimuth; ///< Azimuth to previous waypoint
diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc
index 4bd35c45abdfc200d9ed51ad58ae7de39621cfe6..a068eb571829c0af113e46751308933e94f08619 100644
--- a/src/Vehicle/Vehicle.cc
+++ b/src/Vehicle/Vehicle.cc
@@ -1661,10 +1661,9 @@ void Vehicle::_startMissionRequest(void)
_missionManager->requestMissionItems();
} else {
QmlObjectListModel* visualItems = NULL;
- QmlObjectListModel* complexItems = NULL;
QDir missionAutoLoadDir(missionAutoLoadDirPath);
QString autoloadFilename = missionAutoLoadDir.absoluteFilePath(tr("AutoLoad%1.mission").arg(_id));
- if (MissionController::loadItemsFromFile(this, autoloadFilename, &visualItems, &complexItems)) {
+ if (MissionController::loadItemsFromFile(this, autoloadFilename, &visualItems)) {
MissionController::sendItemsToVehicle(this, visualItems);
}
}