From 90ec26a55c5d85f11c136f9196c69a098928328a Mon Sep 17 00:00:00 2001
From: Don Gagne <dongagne@outlook.com>
Date: Fri, 27 Sep 2019 13:07:47 -0700
Subject: [PATCH] Rework presets

---
 qgroundcontrol.qrc                             |   5 +-
 src/MissionManager/CameraCalc.cc               |  43 +---
 src/MissionManager/CameraCalc.h                |   2 +-
 src/MissionManager/ComplexMissionItem.cc       |  76 +------
 src/MissionManager/ComplexMissionItem.h        |  27 +--
 src/MissionManager/StructureScanComplexItem.cc |   2 +-
 src/MissionManager/TransectStyleComplexItem.cc |   6 +-
 src/PlanView/CameraCalc.qml                    | 296 -------------------------
 src/PlanView/CameraCalcCamera.qml              |   4 -
 src/PlanView/CameraCalcGrid.qml                |   8 -
 src/PlanView/SurveyItemEditor.qml              | 125 +++--------
 src/QmlControls/QGroundControl/Controls/qmldir |   1 -
 12 files changed, 56 insertions(+), 539 deletions(-)
 delete mode 100644 src/PlanView/CameraCalc.qml

diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc
index 622c937..fa345bd 100644
--- a/qgroundcontrol.qrc
+++ b/qgroundcontrol.qrc
@@ -65,9 +65,8 @@
         <file alias="QGroundControl/Controls/AnalyzePage.qml">src/AnalyzeView/AnalyzePage.qml</file>
         <file alias="QGroundControl/Controls/AppMessages.qml">src/QmlControls/AppMessages.qml</file>
         <file alias="QGroundControl/Controls/AxisMonitor.qml">src/QmlControls/AxisMonitor.qml</file>
-        <file alias="QGroundControl/Controls/CameraCalc.qml">src/PlanView/CameraCalc.qml</file>
-		<file alias="QGroundControl/Controls/CameraCalcCamera.qml">src/PlanView/CameraCalcCamera.qml</file>
-		<file alias="QGroundControl/Controls/CameraCalcGrid.qml">src/PlanView/CameraCalcGrid.qml</file>
+        <file alias="QGroundControl/Controls/CameraCalcCamera.qml">src/PlanView/CameraCalcCamera.qml</file>
+        <file alias="QGroundControl/Controls/CameraCalcGrid.qml">src/PlanView/CameraCalcGrid.qml</file>
         <file alias="QGroundControl/Controls/CameraSection.qml">src/PlanView/CameraSection.qml</file>
         <file alias="QGroundControl/Controls/ClickableColor.qml">src/QmlControls/ClickableColor.qml</file>
         <file alias="QGroundControl/Controls/CorridorScanMapVisual.qml">src/PlanView/CorridorScanMapVisual.qml</file>
diff --git a/src/MissionManager/CameraCalc.cc b/src/MissionManager/CameraCalc.cc
index f937972..b7f612a 100644
--- a/src/MissionManager/CameraCalc.cc
+++ b/src/MissionManager/CameraCalc.cc
@@ -201,9 +201,8 @@ void CameraCalc::save(QJsonObject& json) const
     }
 }
 
-bool CameraCalc::load(const QJsonObject& json, bool forPresets, bool cameraSpecInPreset, QString& errorString)
+bool CameraCalc::load(const QJsonObject& json, QString& errorString)
 {
-    qDebug() << "CameraCalc::load" << forPresets << cameraSpecInPreset;
     QJsonObject v1Json = json;
 
     if (!json.contains(JsonHelper::jsonVersionKey)) {
@@ -238,7 +237,7 @@ bool CameraCalc::load(const QJsonObject& json, bool forPresets, bool cameraSpecI
         return false;
     }
 
-    _disableRecalc = !forPresets;
+    _disableRecalc = true;
 
     _distanceToSurfaceRelative = v1Json[distanceToSurfaceRelativeName].toBool();
 
@@ -259,36 +258,16 @@ bool CameraCalc::load(const QJsonObject& json, bool forPresets, bool cameraSpecI
         _sideOverlapFact.setRawValue        (v1Json[sideOverlapName].toDouble());
     }
 
-    if (forPresets) {
-        if (isManualCamera()) {
-            _distanceToSurfaceFact.setRawValue(v1Json[distanceToSurfaceName].toDouble());
-        } else {
-            if (_valueSetIsDistanceFact.rawValue().toBool()) {
-                _distanceToSurfaceFact.setRawValue(v1Json[distanceToSurfaceName].toDouble());
-            } else {
-                _imageDensityFact.setRawValue(v1Json[imageDensityName].toDouble());
-            }
+    _cameraNameFact.setRawValue                 (v1Json[cameraNameName].toString());
+    _adjustedFootprintSideFact.setRawValue      (v1Json[adjustedFootprintSideName].toDouble());
+    _adjustedFootprintFrontalFact.setRawValue   (v1Json[adjustedFootprintFrontalName].toDouble());
+    _distanceToSurfaceFact.setRawValue          (v1Json[distanceToSurfaceName].toDouble());
+    if (!isManualCamera()) {
+        _imageDensityFact.setRawValue(v1Json[imageDensityName].toDouble());
 
-            if (cameraSpecInPreset) {
-                _cameraNameFact.setRawValue(v1Json[cameraNameName].toString());
-                if (!CameraSpec::load(v1Json, errorString)) {
-                    _disableRecalc = false;
-                    return false;
-                }
-            }
-        }
-    } else {
-        _cameraNameFact.setRawValue                 (v1Json[cameraNameName].toString());
-        _adjustedFootprintSideFact.setRawValue      (v1Json[adjustedFootprintSideName].toDouble());
-        _adjustedFootprintFrontalFact.setRawValue   (v1Json[adjustedFootprintFrontalName].toDouble());
-        _distanceToSurfaceFact.setRawValue          (v1Json[distanceToSurfaceName].toDouble());
-        if (!isManualCamera()) {
-            _imageDensityFact.setRawValue(v1Json[imageDensityName].toDouble());
-
-            if (!CameraSpec::load(v1Json, errorString)) {
-                _disableRecalc = false;
-                return false;
-            }
+        if (!CameraSpec::load(v1Json, errorString)) {
+            _disableRecalc = false;
+            return false;
         }
     }
 
diff --git a/src/MissionManager/CameraCalc.h b/src/MissionManager/CameraCalc.h
index 01b96b8..1cd106b 100644
--- a/src/MissionManager/CameraCalc.h
+++ b/src/MissionManager/CameraCalc.h
@@ -70,7 +70,7 @@ public:
     void setDistanceToSurfaceRelative   (bool distanceToSurfaceRelative);
 
     void save(QJsonObject& json) const;
-    bool load(const QJsonObject& json, bool forPresets, bool cameraSpecInPreset, QString& errorString);
+    bool load(const QJsonObject& json, QString& errorString);
 
     static const char* cameraNameName;
     static const char* valueSetIsDistanceName;
diff --git a/src/MissionManager/ComplexMissionItem.cc b/src/MissionManager/ComplexMissionItem.cc
index 9c48b54..934b4d1 100644
--- a/src/MissionManager/ComplexMissionItem.cc
+++ b/src/MissionManager/ComplexMissionItem.cc
@@ -15,14 +15,9 @@
 const char* ComplexMissionItem::jsonComplexItemTypeKey = "complexItemType";
 
 const char* ComplexMissionItem::_presetSettingsKey =        "_presets";
-const char* ComplexMissionItem::_presetNameKey =            "complexItemPresetName";
-const char* ComplexMissionItem::_saveCameraInPresetKey =    "complexItemCameraSavedInPreset";
-const char* ComplexMissionItem::_builtInPresetKey =         "complexItemBuiltInPreset";
 
 ComplexMissionItem::ComplexMissionItem(Vehicle* vehicle, bool flyView, QObject* parent)
     : VisualMissionItem (vehicle, flyView, parent)
-    , _cameraInPreset   (true)
-    , _builtInPreset    (false)
 {
 
 }
@@ -31,10 +26,6 @@ const ComplexMissionItem& ComplexMissionItem::operator=(const ComplexMissionItem
 {
     VisualMissionItem::operator=(other);
 
-    _currentPreset =    other._currentPreset;
-    _cameraInPreset =   other._cameraInPreset;
-    _builtInPreset =    other._builtInPreset;
-
     return *this;
 }
 
@@ -61,39 +52,23 @@ void ComplexMissionItem::savePreset(const QString& name)
     qgcApp()->showMessage(tr("This Pattern does not support Presets."));
 }
 
-void ComplexMissionItem::clearCurrentPreset(void)
-{
-    _currentPreset.clear();
-    emit currentPresetChanged(_currentPreset);
-}
-
-void ComplexMissionItem::deleteCurrentPreset(void)
+void ComplexMissionItem::deletePreset(const QString& name)
 {
-    qDebug() << "deleteCurrentPreset" << _currentPreset;
-    if (!_currentPreset.isEmpty()) {
-        QSettings settings;
-
-        settings.beginGroup(presetsSettingsGroup());
-        settings.beginGroup(_presetSettingsKey);
-        settings.remove(_currentPreset);
-        emit presetNamesChanged();
+    QSettings settings;
 
-        clearCurrentPreset();
-    }
+    settings.beginGroup(presetsSettingsGroup());
+    settings.beginGroup(_presetSettingsKey);
+    settings.remove(name);
+    emit presetNamesChanged();
 }
 
 void ComplexMissionItem::_savePresetJson(const QString& name, QJsonObject& presetObject)
 {
-    presetObject[_presetNameKey] = name;
-
     QSettings settings;
     settings.beginGroup(presetsSettingsGroup());
     settings.beginGroup(_presetSettingsKey);
     settings.setValue(name, QJsonDocument(presetObject).toBinaryData());
     emit presetNamesChanged();
-
-    _currentPreset = name;
-    emit currentPresetChanged(name);
 }
 
 QJsonObject ComplexMissionItem::_loadPresetJson(const QString& name)
@@ -103,42 +78,3 @@ QJsonObject ComplexMissionItem::_loadPresetJson(const QString& name)
     settings.beginGroup(_presetSettingsKey);
     return QJsonDocument::fromBinaryData(settings.value(name).toByteArray()).object();
 }
-
-void ComplexMissionItem::_saveItem(QJsonObject& saveObject)
-{
-    qDebug() << "_saveItem" << _cameraInPreset;
-    saveObject[_presetNameKey] =            _currentPreset;
-    saveObject[_saveCameraInPresetKey] =    _cameraInPreset;
-    saveObject[_builtInPresetKey] =         _builtInPreset;
-}
-
-void ComplexMissionItem::_loadItem(const QJsonObject& saveObject)
-{
-    _currentPreset =    saveObject[_presetNameKey].toString();
-    _cameraInPreset =   saveObject[_saveCameraInPresetKey].toBool(false);
-    _builtInPreset =    saveObject[_builtInPresetKey].toBool(false);
-
-    if (!presetNames().contains(_currentPreset)) {
-        _currentPreset.clear();
-    }
-
-    emit cameraInPresetChanged  (_cameraInPreset);
-    emit currentPresetChanged   (_currentPreset);
-    emit builtInPresetChanged   (_builtInPreset);
-}
-
-void ComplexMissionItem::setCameraInPreset(bool cameraInPreset)
-{
-    if (cameraInPreset != _cameraInPreset) {
-        _cameraInPreset = cameraInPreset;
-        emit cameraInPresetChanged(_cameraInPreset);
-    }
-}
-
-void ComplexMissionItem::setBuiltInPreset(bool builtInPreset)
-{
-    if (builtInPreset != _builtInPreset) {
-        _builtInPreset = builtInPreset;
-        emit builtInPresetChanged(_builtInPreset);
-    }
-}
diff --git a/src/MissionManager/ComplexMissionItem.h b/src/MissionManager/ComplexMissionItem.h
index 111ffbb..49de903 100644
--- a/src/MissionManager/ComplexMissionItem.h
+++ b/src/MissionManager/ComplexMissionItem.h
@@ -27,9 +27,6 @@ public:
     Q_PROPERTY(double       complexDistance     READ complexDistance                            NOTIFY complexDistanceChanged)
     Q_PROPERTY(bool         presetsSupported    READ presetsSupported                           CONSTANT)
     Q_PROPERTY(QStringList  presetNames         READ presetNames                                NOTIFY presetNamesChanged)
-    Q_PROPERTY(QString      currentPreset       READ currentPreset                              NOTIFY currentPresetChanged)
-    Q_PROPERTY(bool         cameraInPreset      READ cameraInPreset     WRITE setCameraInPreset NOTIFY cameraInPresetChanged)
-    Q_PROPERTY(bool         builtInPreset       READ builtInPreset      WRITE setBuiltInPreset  NOTIFY builtInPresetChanged)
 
     /// @return The distance covered the complex mission item in meters.
     /// Signals complexDistanceChanged
@@ -50,8 +47,8 @@ public:
     ///     @param name User visible name for preset. Will replace existing preset if already exists.
     Q_INVOKABLE virtual void savePreset(const QString& name);
 
-    Q_INVOKABLE void clearCurrentPreset(void);
-    Q_INVOKABLE void deleteCurrentPreset(void);
+     Q_INVOKABLE void deletePreset(const QString& name);
+
 
     /// Get the point of complex mission item furthest away from a coordinate
     ///     @param other QGeoCoordinate to which distance is calculated
@@ -67,12 +64,7 @@ public:
     ///     Empty string signals no support for presets.
     virtual QString presetsSettingsGroup(void) { return QString(); }
 
-    bool    presetsSupported    (void) { return !presetsSettingsGroup().isEmpty(); }
-    QString currentPreset       (void) const { return _currentPreset; }
-    bool    cameraInPreset      (void) const { return _cameraInPreset; }
-    bool    builtInPreset       (void) const { return _builtInPreset; }
-    void    setCameraInPreset   (bool cameraInPreset);
-    void    setBuiltInPreset    (bool builtInPreset);
+    bool presetsSupported(void) { return !presetsSettingsGroup().isEmpty(); }
 
     /// This mission item attribute specifies the type of the complex item.
     static const char* jsonComplexItemTypeKey;
@@ -82,28 +74,15 @@ signals:
     void boundingCubeChanged        (void);
     void greatestDistanceToChanged  (void);
     void presetNamesChanged         (void);
-    void currentPresetChanged       (QString currentPreset);
-    void cameraInPresetChanged      (bool cameraInPreset);
-    void builtInPresetChanged       (bool builtInPreset);
 
 protected:
-    void        _saveItem       (QJsonObject& saveObject);
-    void        _loadItem       (const QJsonObject& saveObject);
     void        _savePresetJson (const QString& name, QJsonObject& presetObject);
     QJsonObject _loadPresetJson (const QString& name);
 
 
     QMap<QString, FactMetaData*> _metaDataMap;
 
-    QString         _currentPreset;
-    SettingsFact    _saveCameraInPresetFact;
-    bool            _cameraInPreset;
-    bool            _builtInPreset;
-
     static const char* _presetSettingsKey;
-    static const char* _presetNameKey;
-    static const char* _saveCameraInPresetKey;
-    static const char* _builtInPresetKey;
 };
 
 #endif
diff --git a/src/MissionManager/StructureScanComplexItem.cc b/src/MissionManager/StructureScanComplexItem.cc
index 8f4eb95..06b5276 100644
--- a/src/MissionManager/StructureScanComplexItem.cc
+++ b/src/MissionManager/StructureScanComplexItem.cc
@@ -213,7 +213,7 @@ bool StructureScanComplexItem::load(const QJsonObject& complexObject, int sequen
     setSequenceNumber(sequenceNumber);
 
     // Load CameraCalc first since it will trigger camera name change which will trounce gimbal angles
-    if (!_cameraCalc.load(complexObject[_jsonCameraCalcKey].toObject(), false /* forPresets */, false /* cameraSpecInPreset */, errorString)) {
+    if (!_cameraCalc.load(complexObject[_jsonCameraCalcKey].toObject(), errorString)) {
         return false;
     }
 
diff --git a/src/MissionManager/TransectStyleComplexItem.cc b/src/MissionManager/TransectStyleComplexItem.cc
index d80fae8..fcb9a42 100644
--- a/src/MissionManager/TransectStyleComplexItem.cc
+++ b/src/MissionManager/TransectStyleComplexItem.cc
@@ -134,8 +134,6 @@ void TransectStyleComplexItem::setDirty(bool dirty)
 
 void TransectStyleComplexItem::_save(QJsonObject& complexObject)
 {
-    ComplexMissionItem::_saveItem(complexObject);
-
     QJsonObject innerObject;
 
     innerObject[JsonHelper::jsonVersionKey] =       1;
@@ -189,8 +187,6 @@ void TransectStyleComplexItem::setSequenceNumber(int sequenceNumber)
 
 bool TransectStyleComplexItem::_load(const QJsonObject& complexObject, bool forPresets, QString& errorString)
 {
-    ComplexMissionItem::_loadItem(complexObject);
-
     QList<JsonHelper::KeyValidateInfo> keyInfoList = {
         { _jsonTransectStyleComplexItemKey, QJsonValue::Object, true },
     };
@@ -248,7 +244,7 @@ bool TransectStyleComplexItem::_load(const QJsonObject& complexObject, bool forP
     }
 
     // Load CameraCalc data
-    if (!_cameraCalc.load(innerObject[_jsonCameraCalcKey].toObject(), forPresets, cameraInPreset(), errorString)) {
+    if (!_cameraCalc.load(innerObject[_jsonCameraCalcKey].toObject(), errorString)) {
         return false;
     }
 
diff --git a/src/PlanView/CameraCalc.qml b/src/PlanView/CameraCalc.qml
deleted file mode 100644
index f730324..0000000
--- a/src/PlanView/CameraCalc.qml
+++ /dev/null
@@ -1,296 +0,0 @@
-import QtQuick          2.3
-import QtQuick.Controls 1.2
-import QtQuick.Layouts  1.2
-
-import QGroundControl                   1.0
-import QGroundControl.ScreenTools       1.0
-import QGroundControl.Controls          1.0
-import QGroundControl.FactControls      1.0
-import QGroundControl.Palette           1.0
-
-// Camera calculator section for mission item editors
-Column {
-    anchors.left:   parent.left
-    anchors.right:  parent.right
-    spacing:        _margin
-
-    visible: !usingPreset || !cameraSpecifiedInPreset
-
-    property var    cameraCalc
-    property bool   vehicleFlightIsFrontal:         true
-    property string distanceToSurfaceLabel
-    property int    distanceToSurfaceAltitudeMode:  QGroundControl.AltitudeModeNone
-    property string frontalDistanceLabel
-    property string sideDistanceLabel
-    property bool   usingPreset:                    false
-    property bool   cameraSpecifiedInPreset:        false
-
-    property real   _margin:            ScreenTools.defaultFontPixelWidth / 2
-    property string _cameraName:        cameraCalc.cameraName.value
-    property real   _fieldWidth:        ScreenTools.defaultFontPixelWidth * 10.5
-    property var    _cameraList:        [ ]
-    property var    _vehicle:           QGroundControl.multiVehicleManager.activeVehicle ? QGroundControl.multiVehicleManager.activeVehicle : QGroundControl.multiVehicleManager.offlineEditingVehicle
-    property var    _vehicleCameraList: _vehicle ? _vehicle.staticCameraList : []
-    property bool   _cameraComboFilled: false
-
-    readonly property int _gridTypeManual:          0
-    readonly property int _gridTypeCustomCamera:    1
-    readonly property int _gridTypeCamera:          2
-
-    Component.onCompleted: _fillCameraCombo()
-
-    on_CameraNameChanged: _updateSelectedCamera()
-
-    function _fillCameraCombo() {
-        _cameraComboFilled = true
-        _cameraList.push(cameraCalc.manualCameraName)
-        _cameraList.push(cameraCalc.customCameraName)
-        for (var i=0; i<_vehicle.staticCameraList.length; i++) {
-            _cameraList.push(_vehicle.staticCameraList[i].name)
-        }
-        gridTypeCombo.model = _cameraList
-        _updateSelectedCamera()
-    }
-
-    function _updateSelectedCamera() {
-        if (_cameraComboFilled) {
-            var knownCameraIndex = gridTypeCombo.find(_cameraName)
-            if (knownCameraIndex !== -1) {
-                gridTypeCombo.currentIndex = knownCameraIndex
-            } else {
-                console.log("Internal error: Known camera not found", _cameraName)
-                gridTypeCombo.currentIndex = _gridTypeCustomCamera
-            }
-        }
-    }
-
-    QGCPalette { id: qgcPal; colorGroupEnabled: true }
-
-    ExclusiveGroup {
-        id: cameraOrientationGroup
-    }
-
-    SectionHeader {
-        id:         cameraHeader
-        text:       qsTr("Camera")
-        showSpacer: false
-    }
-
-    Column {
-        anchors.left:   parent.left
-        anchors.right:  parent.right
-        spacing:        _margin
-        visible:        cameraHeader.checked
-
-        QGCComboBox {
-            id:             gridTypeCombo
-            anchors.left:   parent.left
-            anchors.right:  parent.right
-            model:          _cameraList
-            currentIndex:   -1
-            onActivated:    cameraCalc.cameraName.value = gridTypeCombo.textAt(index)
-        } // QGCComboxBox
-
-        // Camera based grid ui
-        Column {
-            anchors.left:   parent.left
-            anchors.right:  parent.right
-            spacing:        _margin
-            visible:        !cameraCalc.isManualCamera
-
-            Row {
-                spacing:                    _margin
-                anchors.horizontalCenter:   parent.horizontalCenter
-                visible:                    !cameraCalc.fixedOrientation.value
-
-                QGCRadioButton {
-                    width:          _editFieldWidth
-                    text:           "Landscape"
-                    checked:        !!cameraCalc.landscape.value
-                    onClicked:      cameraCalc.landscape.value = 1
-                }
-
-                QGCRadioButton {
-                    id:             cameraOrientationPortrait
-                    text:           "Portrait"
-                    checked:        !cameraCalc.landscape.value
-                    onClicked:      cameraCalc.landscape.value = 0
-                }
-            }
-
-            // Custom camera specs
-            Column {
-                id:             custCameraCol
-                anchors.left:   parent.left
-                anchors.right:  parent.right
-                spacing:        _margin
-                visible:        cameraCalc.isCustomCamera
-
-                RowLayout {
-                    anchors.left:   parent.left
-                    anchors.right:  parent.right
-                    spacing:        _margin
-                    Item { Layout.fillWidth: true }
-                    QGCLabel {
-                        Layout.preferredWidth:  _root._fieldWidth
-                        text:                   qsTr("Width")
-                    }
-                    QGCLabel {
-                        Layout.preferredWidth:  _root._fieldWidth
-                        text:                   qsTr("Height")
-                    }
-                }
-
-                RowLayout {
-                    anchors.left:   parent.left
-                    anchors.right:  parent.right
-                    spacing:        _margin
-                    QGCLabel { text: qsTr("Sensor"); Layout.fillWidth: true }
-                    FactTextField {
-                        Layout.preferredWidth:  _root._fieldWidth
-                        fact:                   cameraCalc.sensorWidth
-                    }
-                    FactTextField {
-                        Layout.preferredWidth:  _root._fieldWidth
-                        fact:                   cameraCalc.sensorHeight
-                    }
-                }
-
-                RowLayout {
-                    anchors.left:   parent.left
-                    anchors.right:  parent.right
-                    spacing:        _margin
-                    QGCLabel { text: qsTr("Image"); Layout.fillWidth: true }
-                    FactTextField {
-                        Layout.preferredWidth:  _root._fieldWidth
-                        fact:                   cameraCalc.imageWidth
-                    }
-                    FactTextField {
-                        Layout.preferredWidth:  _root._fieldWidth
-                        fact:                   cameraCalc.imageHeight
-                    }
-                }
-
-                RowLayout {
-                    anchors.left:   parent.left
-                    anchors.right:  parent.right
-                    spacing:        _margin
-                    QGCLabel {
-                        text:                   qsTr("Focal length")
-                        Layout.fillWidth:       true
-                    }
-                    FactTextField {
-                        Layout.preferredWidth:  _root._fieldWidth
-                        fact:                   cameraCalc.focalLength
-                    }
-                }
-
-            } // Column - custom camera specs
-
-            RowLayout {
-                anchors.left:   parent.left
-                anchors.right:  parent.right
-                spacing:        _margin
-                visible:        !usingPreset
-                Item { Layout.fillWidth: true }
-                QGCLabel {
-                    Layout.preferredWidth:  _root._fieldWidth
-                    text:                   qsTr("Front Lap")
-                }
-                QGCLabel {
-                    Layout.preferredWidth:  _root._fieldWidth
-                    text:                   qsTr("Side Lap")
-                }
-            }
-
-            RowLayout {
-                anchors.left:   parent.left
-                anchors.right:  parent.right
-                spacing:        _margin
-                visible:        !usingPreset
-                QGCLabel { text: qsTr("Overlap"); Layout.fillWidth: true }
-                FactTextField {
-                    Layout.preferredWidth:  _root._fieldWidth
-                    fact:                   cameraCalc.frontalOverlap
-                }
-                FactTextField {
-                    Layout.preferredWidth:  _root._fieldWidth
-                    fact:                   cameraCalc.sideOverlap
-                }
-            }
-
-            QGCLabel {
-                wrapMode:               Text.WordWrap
-                text:                   qsTr("Select one:")
-                Layout.preferredWidth:  parent.width
-                Layout.columnSpan:      2
-                visible:                !usingPreset
-            }
-
-            GridLayout {
-                anchors.left:   parent.left
-                anchors.right:  parent.right
-                columnSpacing:  _margin
-                rowSpacing:     _margin
-                columns:        2
-                visible:        !usingPreset
-
-                QGCRadioButton {
-                    id:                     fixedDistanceRadio
-                    text:                   distanceToSurfaceLabel
-                    checked:                !!cameraCalc.valueSetIsDistance.value
-                    onClicked:              cameraCalc.valueSetIsDistance.value = 1
-                }
-
-                AltitudeFactTextField {
-                    fact:                   cameraCalc.distanceToSurface
-                    altitudeMode:           distanceToSurfaceAltitudeMode
-                    enabled:                fixedDistanceRadio.checked
-                    Layout.fillWidth:       true
-                }
-
-                QGCRadioButton {
-                    id:                     fixedImageDensityRadio
-                    text:                   qsTr("Ground Res")
-                    checked:                !cameraCalc.valueSetIsDistance.value
-                    onClicked:              cameraCalc.valueSetIsDistance.value = 0
-                }
-
-                FactTextField {
-                    fact:                   cameraCalc.imageDensity
-                    enabled:                fixedImageDensityRadio.checked
-                    Layout.fillWidth:       true
-                }
-            }
-        } // Column - Camera spec based ui
-
-        // No camera spec ui
-        GridLayout {
-            anchors.left:   parent.left
-            anchors.right:  parent.right
-            columnSpacing:  _margin
-            rowSpacing:     _margin
-            columns:        2
-            visible:        cameraCalc.isManualCamera
-
-            QGCLabel { text: distanceToSurfaceLabel }
-            AltitudeFactTextField {
-                fact:               cameraCalc.distanceToSurface
-                altitudeMode:       distanceToSurfaceAltitudeMode
-                Layout.fillWidth:   true
-            }
-
-            QGCLabel { text: frontalDistanceLabel }
-            FactTextField {
-                Layout.fillWidth:   true
-                fact:               cameraCalc.adjustedFootprintFrontal
-            }
-
-            QGCLabel { text: sideDistanceLabel }
-            FactTextField {
-                Layout.fillWidth:   true
-                fact:               cameraCalc.adjustedFootprintSide
-            }
-        } // GridLayout
-    } // Column - Camera Section
-} // Column
diff --git a/src/PlanView/CameraCalcCamera.qml b/src/PlanView/CameraCalcCamera.qml
index d18eef7..089b003 100644
--- a/src/PlanView/CameraCalcCamera.qml
+++ b/src/PlanView/CameraCalcCamera.qml
@@ -14,16 +14,12 @@ Column {
     anchors.right:  parent.right
     spacing:        _margin
 
-    visible: !usingPreset || !cameraSpecifiedInPreset
-
     property var    cameraCalc
     property bool   vehicleFlightIsFrontal:         true
     property string distanceToSurfaceLabel
     property int    distanceToSurfaceAltitudeMode:  QGroundControl.AltitudeModeNone
     property string frontalDistanceLabel
     property string sideDistanceLabel
-    property bool   usingPreset:                    false
-    property bool   cameraSpecifiedInPreset:        false
 
     property real   _margin:            ScreenTools.defaultFontPixelWidth / 2
     property string _cameraName:        cameraCalc.cameraName.value
diff --git a/src/PlanView/CameraCalcGrid.qml b/src/PlanView/CameraCalcGrid.qml
index 65fb7de..04250e3 100644
--- a/src/PlanView/CameraCalcGrid.qml
+++ b/src/PlanView/CameraCalcGrid.qml
@@ -14,16 +14,12 @@ Column {
     anchors.right:  parent.right
     spacing:        _margin
 
-    visible: !usingPreset || !cameraSpecifiedInPreset
-
     property var    cameraCalc
     property bool   vehicleFlightIsFrontal:         true
     property string distanceToSurfaceLabel
     property int    distanceToSurfaceAltitudeMode:  QGroundControl.AltitudeModeNone
     property string frontalDistanceLabel
     property string sideDistanceLabel
-    property bool   usingPreset:                    false
-    property bool   cameraSpecifiedInPreset:        false
 
     property real   _margin:            ScreenTools.defaultFontPixelWidth / 2
     property string _cameraName:        cameraCalc.cameraName.value
@@ -49,7 +45,6 @@ Column {
             anchors.left:   parent.left
             anchors.right:  parent.right
             spacing:        _margin
-            visible:        !usingPreset
             Item { Layout.fillWidth: true }
             QGCLabel {
                 Layout.preferredWidth:  _root._fieldWidth
@@ -65,7 +60,6 @@ Column {
             anchors.left:   parent.left
             anchors.right:  parent.right
             spacing:        _margin
-            visible:        !usingPreset
             QGCLabel { text: qsTr("Overlap"); Layout.fillWidth: true }
             FactTextField {
                 Layout.preferredWidth:  _root._fieldWidth
@@ -82,7 +76,6 @@ Column {
             text:                   qsTr("Select one:")
             Layout.preferredWidth:  parent.width
             Layout.columnSpan:      2
-            visible:                !usingPreset
         }
 
         GridLayout {
@@ -91,7 +84,6 @@ Column {
             columnSpacing:  _margin
             rowSpacing:     _margin
             columns:        2
-            visible:        !usingPreset
 
             QGCRadioButton {
                 id:                     fixedDistanceRadio
diff --git a/src/PlanView/SurveyItemEditor.qml b/src/PlanView/SurveyItemEditor.qml
index e4a5fc7..d4a08de 100644
--- a/src/PlanView/SurveyItemEditor.qml
+++ b/src/PlanView/SurveyItemEditor.qml
@@ -28,8 +28,6 @@ Rectangle {
     property real   _fieldWidth:                ScreenTools.defaultFontPixelWidth * 10.5
     property var    _vehicle:                   QGroundControl.multiVehicleManager.activeVehicle ? QGroundControl.multiVehicleManager.activeVehicle : QGroundControl.multiVehicleManager.offlineEditingVehicle
     property real   _cameraMinTriggerInterval:  missionItem.cameraCalc.minTriggerInterval.rawValue
-    property string _currentPreset:             missionItem.currentPreset
-    property bool   _usingPreset:               _currentPreset !== ""
 
     function polygonCaptureStarted() {
         missionItem.clearPolygon()
@@ -94,8 +92,6 @@ Rectangle {
                                                     missionItem.cameraCalc.distanceToSurfaceRelative
                 frontalDistanceLabel:           qsTr("Trigger Dist")
                 sideDistanceLabel:              qsTr("Spacing")
-                usingPreset:                    _usingPreset
-                cameraSpecifiedInPreset:        missionItem.cameraInPreset
             }
 
             SectionHeader {
@@ -134,12 +130,10 @@ Rectangle {
 
                 QGCLabel {
                     text:       qsTr("Turnaround dist")
-                    visible:    !_usingPreset
                 }
                 FactTextField {
                     fact:               missionItem.turnAroundDistance
                     Layout.fillWidth:   true
-                    visible:            !_usingPreset
                 }
             }
 
@@ -152,7 +146,7 @@ Rectangle {
                 anchors.left:   parent.left
                 anchors.right:  parent.right
                 spacing:        _margin
-                visible:        transectsHeader.checked && !_usingPreset
+                visible:        transectsHeader.checked
 
                 /*
               Temporarily removed due to bug https://github.com/mavlink/qgroundcontrol/issues/7005
@@ -213,14 +207,13 @@ Rectangle {
                 id:         terrainHeader
                 text:       qsTr("Terrain")
                 checked:    missionItem.followTerrain
-                visible:    !_usingPreset
             }
 
             ColumnLayout {
                 anchors.left:   parent.left
                 anchors.right:  parent.right
                 spacing:        _margin
-                visible:        terrainHeader.checked && !_usingPreset
+                visible:        terrainHeader.checked
 
 
                 QGCCheckBox {
@@ -280,102 +273,53 @@ Rectangle {
                                                     missionItem.cameraCalc.distanceToSurfaceRelative
                 frontalDistanceLabel:           qsTr("Trigger Dist")
                 sideDistanceLabel:              qsTr("Spacing")
-                usingPreset:                    _usingPreset
-                cameraSpecifiedInPreset:        missionItem.cameraInPreset
             }
         } // Camera Column
 
-        Column {
+        ColumnLayout {
             anchors.left:       parent.left
             anchors.right:      parent.right
             spacing:            _margin
             visible:            tabBar.currentIndex == 2
 
+            QGCLabel {
+                Layout.fillWidth:   true
+                text:               qsTr("Presets")
+                wrapMode:           Text.WordWrap
+            }
+
             QGCComboBox {
                 id:                 presetCombo
-                anchors.left:       parent.left
-                anchors.right:      parent.right
-                model:              _presetList
-
-                property var _presetList:   []
-
-                readonly property int _indexCustom:         0
-                readonly property int _indexCreate:         1
-                readonly property int _indexDelete:         2
-                readonly property int _indexLabel:          3
-                readonly property int _indexFirstPreset:    4
-
-                Component.onCompleted: _updateList()
-
-                onActivated: {
-                    if (index == _indexCustom) {
-                        missionItem.clearCurrentPreset()
-                    } else if (index == _indexCreate) {
-                        mainWindow.showComponentDialog(savePresetDialog, qsTr("Save Preset"), mainWindow.showDialogDefaultWidth, StandardButton.Save | StandardButton.Cancel)
-                    } else if (index == _indexDelete) {
-                        if (missionItem.builtInPreset) {
-                            mainWindow.showMessage(qsTr("Delete Preset"), qsTr("This preset cannot be deleted."))
-                        } else {
-                            missionItem.deleteCurrentPreset()
-                        }
-                    } else if (index >= _indexFirstPreset) {
-                        missionItem.loadPreset(textAt(index))
-                    } else {
-                        _selectCurrentPreset()
-                    }
-                }
-
-                Connections {
-                    target: missionItem
-
-                    onPresetNamesChanged:   presetCombo._updateList()
-                    onCurrentPresetChanged: presetCombo._selectCurrentPreset()
-                }
-
-                // There is some major strangeness going on with programatically changing the index of a combo box in this scenario.
-                // If you just set currentIndex directly it will just change back 1o -1 magically. Has something to do with resetting
-                // model on the fly I think. But not sure. To work around I delay the currentIndex changes to let things unwind.
-                Timer {
-                    id:         delayedIndexChangeTimer
-                    interval:   10
-
-                    property int newIndex
+                Layout.fillWidth:   true
+                model:              missionItem.presetNames
+            }
 
-                    onTriggered:  presetCombo.currentIndex = newIndex
+            RowLayout {
+                Layout.fillWidth:   true
 
+                QGCButton {
+                    Layout.fillWidth:   true
+                    text:               qsTr("Apply Preset")
+                    enabled:            missionItem.presetNames.length != 0
+                    onClicked:          missionItem.loadPreset(presetCombo.textAt(presetCombo.currentIndex))
                 }
 
-                function delayedIndexChange(index) {
-                    delayedIndexChangeTimer.newIndex = index
-                    delayedIndexChangeTimer.start()
+                QGCButton {
+                    Layout.fillWidth:   true
+                    text:               qsTr("Delete Preset")
+                    enabled:            missionItem.presetNames.length != 0
+                    onClicked:          missionItem.deletePreset(presetCombo.textAt(presetCombo.currentIndex))
                 }
 
-                function _updateList() {
-                    _presetList = []
-                    _presetList.push(qsTr("Custom (specify all settings)"))
-                    _presetList.push(qsTr("Save Settings As Preset"))
-                    _presetList.push(qsTr("Delete Current Preset"))
-                    if (missionItem.presetNames.length !== 0) {
-                        _presetList.push(qsTr("Presets:"))
-                    }
+            }
 
-                    for (var i=0; i<missionItem.presetNames.length; i++) {
-                        _presetList.push(missionItem.presetNames[i])
-                    }
-                    model = _presetList
-                    _selectCurrentPreset()
-                }
+            Item { height: ScreenTools.defaultFontPixelHeight; width: 1 }
 
-                function _selectCurrentPreset() {
-                    if (_usingPreset) {
-                        var newIndex = find(_currentPreset)
-                        if (newIndex !== -1) {
-                            delayedIndexChange(newIndex)
-                            return
-                        }
-                    }
-                    delayedIndexChange(presetCombo._indexCustom)
-                }
+            QGCButton {
+                Layout.alignment:   Qt.AlignCenter
+                Layout.fillWidth:   true
+                text:               qsTr("Save Settings As New Preset")
+                onClicked:          mainWindow.showComponentDialog(savePresetDialog, qsTr("Save Preset"), mainWindow.showDialogDefaultWidth, StandardButton.Save | StandardButton.Cancel)
             }
         } // Camera Column
 
@@ -408,13 +352,6 @@ Rectangle {
                     QGCTextField {
                         id:                 presetNameField
                         Layout.fillWidth:   true
-                        text:               _currentPreset
-                    }
-
-                    QGCCheckBox {
-                        text:       qsTr("Save Camera In Preset")
-                        checked:    missionItem.cameraInPreset
-                        onClicked:  missionItem.cameraInPreset = checked
                     }
                 }
             }
diff --git a/src/QmlControls/QGroundControl/Controls/qmldir b/src/QmlControls/QGroundControl/Controls/qmldir
index 21f09c3..8373c30 100644
--- a/src/QmlControls/QGroundControl/Controls/qmldir
+++ b/src/QmlControls/QGroundControl/Controls/qmldir
@@ -3,7 +3,6 @@ Module QGroundControl.Controls
 AnalyzePage             1.0 AnalyzePage.qml
 AppMessages             1.0 AppMessages.qml
 AxisMonitor             1.0 AxisMonitor.qml
-CameraCalc              1.0 CameraCalc.qml
 CameraCalcCamera        1.0 CameraCalcCamera.qml
 CameraCalcGrid          1.0 CameraCalcGrid.qml
 APMSubMotorDisplay      1.0 APMSubMotorDisplay.qml