diff --git a/ChangeLog.md b/ChangeLog.md index 8949f05135d46d10676e2018aa2d71fae3a1f653..b71a0c7c1ec22f1b166362fe96a2f6c1ef4a1706 100644 --- a/ChangeLog.md +++ b/ChangeLog.md @@ -6,6 +6,7 @@ Note: This file only contains high level features or important fixes. ### 3.6.0 - Daily Build +* Plan/Pattern: Support named presets to simplify commonly used settings setup. Currently only supported by Survey. * ArduCopter: Handle 3.7 parameter name change from CH#_OPT to RC#_OPTION. * Improved support for flashing/connecting to ChibiOS bootloaders boards. * Making the camera API available to all firmwares, not just PX4. diff --git a/src/MissionManager/CameraCalc.cc b/src/MissionManager/CameraCalc.cc index c775c1b76f9733b486b2469b95fa21dc6b2557a7..3abf75a9e8f325d965424ee67d4df42de7b47e37 100644 --- a/src/MissionManager/CameraCalc.cc +++ b/src/MissionManager/CameraCalc.cc @@ -95,7 +95,7 @@ void CameraCalc::_cameraNameChanged(void) // Validate known camera name bool foundKnownCamera = false; - CameraMetaData* cameraMetaData = NULL; + CameraMetaData* cameraMetaData = nullptr; if (!isManualCamera() && !isCustomCamera()) { for (int cameraIndex=0; cameraIndex<_knownCameraList.count(); cameraIndex++) { cameraMetaData = _knownCameraList[cameraIndex].value(); @@ -201,11 +201,12 @@ void CameraCalc::save(QJsonObject& json) const } } -bool CameraCalc::load(const QJsonObject& json, QString& errorString) +bool CameraCalc::load(const QJsonObject& json, bool forPresets, bool cameraSpecInPreset, QString& errorString) { + qDebug() << "CameraCalc::load" << forPresets << cameraSpecInPreset; QJsonObject v1Json = json; - if (!v1Json.contains(JsonHelper::jsonVersionKey)) { + if (!json.contains(JsonHelper::jsonVersionKey)) { // Version 0 file. Differences from Version 1 for conversion: // JsonHelper::jsonVersionKey not stored // _jsonCameraSpecTypeKey stores CameraSpecType @@ -231,18 +232,13 @@ bool CameraCalc::load(const QJsonObject& json, QString& errorString) { adjustedFootprintSideName, QJsonValue::Double, true }, { adjustedFootprintFrontalName, QJsonValue::Double, true }, { distanceToSurfaceName, QJsonValue::Double, true }, - { distanceToSurfaceRelativeName, QJsonValue::Bool, true }, + { distanceToSurfaceRelativeName, QJsonValue::Bool, true }, }; if (!JsonHelper::validateKeys(v1Json, keyInfoList1, errorString)) { return false; } - _disableRecalc = true; - - _cameraNameFact.setRawValue (v1Json[cameraNameName].toString()); - _adjustedFootprintSideFact.setRawValue (v1Json[adjustedFootprintSideName].toDouble()); - _adjustedFootprintFrontalFact.setRawValue (v1Json[adjustedFootprintFrontalName].toDouble()); - _distanceToSurfaceFact.setRawValue (v1Json[distanceToSurfaceName].toDouble()); + _disableRecalc = !forPresets; _distanceToSurfaceRelative = v1Json[distanceToSurfaceRelativeName].toBool(); @@ -259,13 +255,40 @@ bool CameraCalc::load(const QJsonObject& json, QString& errorString) } _valueSetIsDistanceFact.setRawValue (v1Json[valueSetIsDistanceName].toBool()); - _imageDensityFact.setRawValue (v1Json[imageDensityName].toDouble()); _frontalOverlapFact.setRawValue (v1Json[frontalOverlapName].toDouble()); _sideOverlapFact.setRawValue (v1Json[sideOverlapName].toDouble()); + } - if (!CameraSpec::load(v1Json, errorString)) { - _disableRecalc = false; - return false; + 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()); + } + + 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; + } } } diff --git a/src/MissionManager/CameraCalc.h b/src/MissionManager/CameraCalc.h index 3d88b5902a35b8e9275b56b7c9e30caff7a8ec76..95eeb1195c0de0d9703c9ce6816bc8c001fead7b 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, QString& errorString); + bool load(const QJsonObject& json, bool forPresets, bool cameraSpecInPreset, QString& errorString); static const char* cameraNameName; static const char* valueSetIsDistanceName; diff --git a/src/MissionManager/ComplexMissionItem.cc b/src/MissionManager/ComplexMissionItem.cc index 44af71895fa2eb43d483f72186a3baab7fb606ab..a7682a85fb238444cc210ec5b5dda7339ccbc3cf 100644 --- a/src/MissionManager/ComplexMissionItem.cc +++ b/src/MissionManager/ComplexMissionItem.cc @@ -8,11 +8,20 @@ ****************************************************************************/ #include "ComplexMissionItem.h" +#include "QGCApplication.h" + +#include 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) + : VisualMissionItem (vehicle, flyView, parent) + , _cameraInPreset (true) { } @@ -21,5 +30,112 @@ const ComplexMissionItem& ComplexMissionItem::operator=(const ComplexMissionItem { VisualMissionItem::operator=(other); + _cameraInPreset = other._cameraInPreset; + return *this; } + +QStringList ComplexMissionItem::presetNames(void) +{ + QStringList names; + + QSettings settings; + + settings.beginGroup(presetsSettingsGroup()); + settings.beginGroup(_presetSettingsKey); + return settings.childKeys(); +} + +void ComplexMissionItem::loadPreset(const QString& name) +{ + Q_UNUSED(name); + qgcApp()->showMessage(tr("This Pattern does not support Presets.")); +} + +void ComplexMissionItem::savePreset(const QString& name) +{ + Q_UNUSED(name); + qgcApp()->showMessage(tr("This Pattern does not support Presets.")); +} + +void ComplexMissionItem::clearCurrentPreset(void) +{ + _currentPreset.clear(); + emit currentPresetChanged(_currentPreset); +} + +void ComplexMissionItem::deleteCurrentPreset(void) +{ + qDebug() << "deleteCurrentPreset" << _currentPreset; + if (!_currentPreset.isEmpty()) { + QSettings settings; + + settings.beginGroup(presetsSettingsGroup()); + settings.beginGroup(_presetSettingsKey); + settings.remove(_currentPreset); + emit presetNamesChanged(); + + clearCurrentPreset(); + } +} + +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) +{ + QSettings settings; + settings.beginGroup(presetsSettingsGroup()); + 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 71046d1d47d2508047f61a4927b846d723c2bb8d..111ffbb7101fd33336520483d696a169e4cc05ea 100644 --- a/src/MissionManager/ComplexMissionItem.h +++ b/src/MissionManager/ComplexMissionItem.h @@ -13,6 +13,8 @@ #include "VisualMissionItem.h" #include "QGCGeo.h" +#include + class ComplexMissionItem : public VisualMissionItem { Q_OBJECT @@ -22,7 +24,12 @@ public: const ComplexMissionItem& operator=(const ComplexMissionItem& other); - Q_PROPERTY(double complexDistance READ complexDistance NOTIFY complexDistanceChanged) + 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 @@ -35,12 +42,38 @@ public: /// @return true: load success, false: load failed, errorString set virtual bool load(const QJsonObject& complexObject, int sequenceNumber, QString& errorString) = 0; + /// Loads the specified preset into the complex item. + /// @param name Preset name. + Q_INVOKABLE virtual void loadPreset(const QString& name); + + /// Saves the current state of the complex item as the named preset. + /// @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); + /// Get the point of complex mission item furthest away from a coordinate /// @param other QGeoCoordinate to which distance is calculated /// @return the greatest distance from any point of the complex item to some coordinate /// Signals greatestDistanceToChanged virtual double greatestDistanceTo(const QGeoCoordinate &other) const = 0; + /// Returns the list of currently saved presets for this complex item type. + /// @param name User visible name for preset. Will replace existing preset if already exists. + virtual QStringList presetNames(void); + + /// Returns the name of the settings group for presets. + /// 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); + /// This mission item attribute specifies the type of the complex item. static const char* jsonComplexItemTypeKey; @@ -48,6 +81,29 @@ signals: void complexDistanceChanged (void); 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 _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/CorridorScanComplexItem.cc b/src/MissionManager/CorridorScanComplexItem.cc index 2d165d16e1af03a5a6447055dd9f9412a8e3b325..f253f8d8e74efc46c3bc127edb25e3435e39202c 100644 --- a/src/MissionManager/CorridorScanComplexItem.cc +++ b/src/MissionManager/CorridorScanComplexItem.cc @@ -62,7 +62,7 @@ void CorridorScanComplexItem::save(QJsonArray& planItems) { QJsonObject saveObject; - _save(saveObject); + TransectStyleComplexItem::_save(saveObject); saveObject[JsonHelper::jsonVersionKey] = 2; saveObject[VisualMissionItem::jsonTypeKey] = VisualMissionItem::jsonTypeComplexItemValue; @@ -115,7 +115,7 @@ bool CorridorScanComplexItem::load(const QJsonObject& complexObject, int sequenc setSequenceNumber(sequenceNumber); - if (!_load(complexObject, errorString)) { + if (!_load(complexObject, false /* forPresets */, errorString)) { _ignoreRecalc = false; return false; } diff --git a/src/MissionManager/StructureScanComplexItem.cc b/src/MissionManager/StructureScanComplexItem.cc index 8eae2d8ff6b988b0a9e198c0188f24b99a43049f..46c395d73eaa7207dbf89c441dbc49398af82d60 100644 --- a/src/MissionManager/StructureScanComplexItem.cc +++ b/src/MissionManager/StructureScanComplexItem.cc @@ -218,7 +218,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(), errorString)) { + if (!_cameraCalc.load(complexObject[_jsonCameraCalcKey].toObject(), false /* forPresets */, false /* cameraSpecInPreset */, errorString)) { return false; } diff --git a/src/MissionManager/SurveyComplexItem.cc b/src/MissionManager/SurveyComplexItem.cc index b26ab892b3e288fa62743c2c7d9bbedb008e9be3..f1aa771f0d1716ebfa175becbdf73d1c84d71ec5 100644 --- a/src/MissionManager/SurveyComplexItem.cc +++ b/src/MissionManager/SurveyComplexItem.cc @@ -108,7 +108,21 @@ void SurveyComplexItem::save(QJsonArray& planItems) { QJsonObject saveObject; - _save(saveObject); + _saveWorker(saveObject); + planItems.append(saveObject); +} + +void SurveyComplexItem::savePreset(const QString& name) +{ + QJsonObject saveObject; + + _saveWorker(saveObject); + _savePresetJson(name, saveObject); +} + +void SurveyComplexItem::_saveWorker(QJsonObject& saveObject) +{ + TransectStyleComplexItem::_save(saveObject); saveObject[JsonHelper::jsonVersionKey] = 5; saveObject[VisualMissionItem::jsonTypeKey] = VisualMissionItem::jsonTypeComplexItemValue; @@ -120,8 +134,15 @@ void SurveyComplexItem::save(QJsonArray& planItems) // Polygon shape _surveyAreaPolygon.saveToJson(saveObject); +} - planItems.append(saveObject); +void SurveyComplexItem::loadPreset(const QString& name) +{ + QString errorString; + + QJsonObject presetObject = _loadPresetJson(name); + _loadV4V5(presetObject, 0, errorString, 5, true /* forPresets */); + _rebuildTransects(); } bool SurveyComplexItem::load(const QJsonObject& complexObject, int sequenceNumber, QString& errorString) @@ -141,7 +162,7 @@ bool SurveyComplexItem::load(const QJsonObject& complexObject, int sequenceNumbe } if (version == 4 || version == 5) { - if (!_loadV4V5(complexObject, sequenceNumber, errorString, version)) { + if (!_loadV4V5(complexObject, sequenceNumber, errorString, version, false /* forPresets */)) { return false; } @@ -171,7 +192,7 @@ bool SurveyComplexItem::load(const QJsonObject& complexObject, int sequenceNumbe return true; } -bool SurveyComplexItem::_loadV4V5(const QJsonObject& complexObject, int sequenceNumber, QString& errorString, int version) +bool SurveyComplexItem::_loadV4V5(const QJsonObject& complexObject, int sequenceNumber, QString& errorString, int version, bool forPresets) { QList keyInfoList = { { VisualMissionItem::jsonTypeKey, QJsonValue::String, true }, @@ -197,16 +218,18 @@ bool SurveyComplexItem::_loadV4V5(const QJsonObject& complexObject, int sequence return false; } - _ignoreRecalc = true; + _ignoreRecalc = !forPresets; - setSequenceNumber(sequenceNumber); + if (!forPresets) { + setSequenceNumber(sequenceNumber); - if (!_surveyAreaPolygon.loadFromJson(complexObject, true /* required */, errorString)) { - _surveyAreaPolygon.clear(); - return false; + if (!_surveyAreaPolygon.loadFromJson(complexObject, true /* required */, errorString)) { + _surveyAreaPolygon.clear(); + return false; + } } - if (!_load(complexObject, errorString)) { + if (!TransectStyleComplexItem::_load(complexObject, forPresets, errorString)) { _ignoreRecalc = false; return false; } @@ -214,7 +237,7 @@ bool SurveyComplexItem::_loadV4V5(const QJsonObject& complexObject, int sequence _gridAngleFact.setRawValue (complexObject[_jsonGridAngleKey].toDouble()); _flyAlternateTransectsFact.setRawValue (complexObject[_jsonFlyAlternateTransectsKey].toBool(false)); - if(version == 5) { + if (version == 5) { _splitConcavePolygonsFact.setRawValue (complexObject[_jsonSplitConcavePolygonsKey].toBool(true)); } @@ -282,7 +305,7 @@ bool SurveyComplexItem::_loadV3(const QJsonObject& complexObject, int sequenceNu _turnAroundDistanceFact.setRawValue (gridObject[_jsonV3TurnaroundDistKey].toDouble()); if (gridObject.contains(_jsonEntryPointKey)) { - _entryPoint = gridObject[_jsonEntryPointKey].toDouble(); + _entryPoint = gridObject[_jsonEntryPointKey].toInt(); } else { _entryPoint = EntryLocationTopRight; } diff --git a/src/MissionManager/SurveyComplexItem.h b/src/MissionManager/SurveyComplexItem.h index eda8ef30b5956fa63592b1f51710616bbcb70fa2..6d1348fea700af9909eb678e908daaa1b3e81fc1 100644 --- a/src/MissionManager/SurveyComplexItem.h +++ b/src/MissionManager/SurveyComplexItem.h @@ -39,6 +39,9 @@ public: // Overrides from ComplexMissionItem bool load (const QJsonObject& complexObject, int sequenceNumber, QString& errorString) final; QString mapVisualQML (void) const final { return QStringLiteral("SurveyMapVisual.qml"); } + QString presetsSettingsGroup(void) { return settingsGroup; } + void savePreset (const QString& name); + void loadPreset (const QString& name); // Overrides from TransectStyleComplexItem void save (QJsonArray& planItems) final; @@ -114,7 +117,8 @@ private: double _turnaroundDistance(void) const; bool _hoverAndCaptureEnabled(void) const; bool _loadV3(const QJsonObject& complexObject, int sequenceNumber, QString& errorString); - bool _loadV4V5(const QJsonObject& complexObject, int sequenceNumber, QString& errorString, int version); + bool _loadV4V5(const QJsonObject& complexObject, int sequenceNumber, QString& errorString, int version, bool forPresets); + void _saveWorker(QJsonObject& complexObject); void _rebuildTransectsPhase1Worker(bool refly); void _rebuildTransectsPhase1WorkerSinglePolygon(bool refly); void _rebuildTransectsPhase1WorkerSplitPolygons(bool refly); diff --git a/src/MissionManager/TransectStyleComplexItem.cc b/src/MissionManager/TransectStyleComplexItem.cc index 156818403f047e31ea17807fb6b567ca7f8877f7..3941016ba9888a25b09b7605d90c356228b38e34 100644 --- a/src/MissionManager/TransectStyleComplexItem.cc +++ b/src/MissionManager/TransectStyleComplexItem.cc @@ -132,6 +132,8 @@ void TransectStyleComplexItem::setDirty(bool dirty) void TransectStyleComplexItem::_save(QJsonObject& complexObject) { + ComplexMissionItem::_saveItem(complexObject); + QJsonObject innerObject; innerObject[JsonHelper::jsonVersionKey] = 1; @@ -183,8 +185,9 @@ void TransectStyleComplexItem::setSequenceNumber(int sequenceNumber) } } -bool TransectStyleComplexItem::_load(const QJsonObject& complexObject, QString& errorString) +bool TransectStyleComplexItem::_load(const QJsonObject& complexObject, bool forPresets, QString& errorString) { + ComplexMissionItem::_loadItem(complexObject); QList keyInfoList = { { _jsonTransectStyleComplexItemKey, QJsonValue::Object, true }, @@ -211,8 +214,8 @@ bool TransectStyleComplexItem::_load(const QJsonObject& complexObject, QString& { hoverAndCaptureName, QJsonValue::Bool, true }, { refly90DegreesName, QJsonValue::Bool, true }, { _jsonCameraCalcKey, QJsonValue::Object, true }, - { _jsonVisualTransectPointsKey, QJsonValue::Array, true }, - { _jsonItemsKey, QJsonValue::Array, true }, + { _jsonVisualTransectPointsKey, QJsonValue::Array, !forPresets }, + { _jsonItemsKey, QJsonValue::Array, !forPresets }, { _jsonFollowTerrainKey, QJsonValue::Bool, true }, { _jsonCameraShotsKey, QJsonValue::Double, false }, // Not required since it was missing from initial implementation }; @@ -220,28 +223,30 @@ bool TransectStyleComplexItem::_load(const QJsonObject& complexObject, QString& return false; } - // Load visual transect points - if (!JsonHelper::loadGeoCoordinateArray(innerObject[_jsonVisualTransectPointsKey], false /* altitudeRequired */, _visualTransectPoints, errorString)) { - return false; - } - _coordinate = _visualTransectPoints.count() ? _visualTransectPoints.first().value() : QGeoCoordinate(); - _exitCoordinate = _visualTransectPoints.count() ? _visualTransectPoints.last().value() : QGeoCoordinate(); - - // Load generated mission items - _loadedMissionItemsParent = new QObject(this); - QJsonArray missionItemsJsonArray = innerObject[_jsonItemsKey].toArray(); - for (const QJsonValue& missionItemJson: missionItemsJsonArray) { - MissionItem* missionItem = new MissionItem(_loadedMissionItemsParent); - if (!missionItem->load(missionItemJson.toObject(), 0 /* sequenceNumber */, errorString)) { - _loadedMissionItemsParent->deleteLater(); - _loadedMissionItemsParent = NULL; + if (!forPresets) { + // Load visual transect points + if (!JsonHelper::loadGeoCoordinateArray(innerObject[_jsonVisualTransectPointsKey], false /* altitudeRequired */, _visualTransectPoints, errorString)) { return false; } - _loadedMissionItems.append(missionItem); + _coordinate = _visualTransectPoints.count() ? _visualTransectPoints.first().value() : QGeoCoordinate(); + _exitCoordinate = _visualTransectPoints.count() ? _visualTransectPoints.last().value() : QGeoCoordinate(); + + // Load generated mission items + _loadedMissionItemsParent = new QObject(this); + QJsonArray missionItemsJsonArray = innerObject[_jsonItemsKey].toArray(); + for (const QJsonValue missionItemJson: missionItemsJsonArray) { + MissionItem* missionItem = new MissionItem(_loadedMissionItemsParent); + if (!missionItem->load(missionItemJson.toObject(), 0 /* sequenceNumber */, errorString)) { + _loadedMissionItemsParent->deleteLater(); + _loadedMissionItemsParent = nullptr; + return false; + } + _loadedMissionItems.append(missionItem); + } } // Load CameraCalc data - if (!_cameraCalc.load(innerObject[_jsonCameraCalcKey].toObject(), errorString)) { + if (!_cameraCalc.load(innerObject[_jsonCameraCalcKey].toObject(), forPresets, cameraInPreset(), errorString)) { return false; } @@ -435,7 +440,7 @@ void TransectStyleComplexItem::_reallyQueryTransectsPathHeightInfo(void) // Let the signal fall on the floor disconnect(_terrainPolyPathQuery, &TerrainPolyPathQuery::terrainDataReceived, this, &TransectStyleComplexItem::_polyPathTerrainData); #endif - _terrainPolyPathQuery = NULL; + _terrainPolyPathQuery = nullptr; } // Append all transects into a single PolyPath query @@ -479,7 +484,7 @@ void TransectStyleComplexItem::_polyPathTerrainData(bool success, const QList 0 && _cameraMinTriggerInterval !== 0 && _cameraMinTriggerInterval > missionItem.timeBetweenShots } + QGCLabel { + text: qsTr("Presets") + } + + 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) { + rootQgcView.showDialog(savePresetDialog, qsTr("Save Preset"), rootQgcView.showDialogDefaultWidth, StandardButton.Save | StandardButton.Cancel) + } else if (index == _indexDelete) { + if (missionItem.builtInPreset) { + rootQgcView.showMessage(qsTr("Delete Preset"), qsTr("This preset cannot be deleted."), StandardButton.Ok) + } 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 + + onTriggered: presetCombo.currentIndex = newIndex + + } + + function delayedIndexChange(index) { + delayedIndexChangeTimer.newIndex = index + delayedIndexChangeTimer.start() + } + + 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