Commit 1c5b78f5 authored by Don Gagne's avatar Don Gagne

parent 68b26ee2
...@@ -6,6 +6,7 @@ Note: This file only contains high level features or important fixes. ...@@ -6,6 +6,7 @@ Note: This file only contains high level features or important fixes.
### 3.6.0 - Daily Build ### 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. * ArduCopter: Handle 3.7 parameter name change from CH#_OPT to RC#_OPTION.
* Improved support for flashing/connecting to ChibiOS bootloaders boards. * Improved support for flashing/connecting to ChibiOS bootloaders boards.
* Making the camera API available to all firmwares, not just PX4. * Making the camera API available to all firmwares, not just PX4.
......
...@@ -95,7 +95,7 @@ void CameraCalc::_cameraNameChanged(void) ...@@ -95,7 +95,7 @@ void CameraCalc::_cameraNameChanged(void)
// Validate known camera name // Validate known camera name
bool foundKnownCamera = false; bool foundKnownCamera = false;
CameraMetaData* cameraMetaData = NULL; CameraMetaData* cameraMetaData = nullptr;
if (!isManualCamera() && !isCustomCamera()) { if (!isManualCamera() && !isCustomCamera()) {
for (int cameraIndex=0; cameraIndex<_knownCameraList.count(); cameraIndex++) { for (int cameraIndex=0; cameraIndex<_knownCameraList.count(); cameraIndex++) {
cameraMetaData = _knownCameraList[cameraIndex].value<CameraMetaData*>(); cameraMetaData = _knownCameraList[cameraIndex].value<CameraMetaData*>();
...@@ -201,11 +201,12 @@ void CameraCalc::save(QJsonObject& json) const ...@@ -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; QJsonObject v1Json = json;
if (!v1Json.contains(JsonHelper::jsonVersionKey)) { if (!json.contains(JsonHelper::jsonVersionKey)) {
// Version 0 file. Differences from Version 1 for conversion: // Version 0 file. Differences from Version 1 for conversion:
// JsonHelper::jsonVersionKey not stored // JsonHelper::jsonVersionKey not stored
// _jsonCameraSpecTypeKey stores CameraSpecType // _jsonCameraSpecTypeKey stores CameraSpecType
...@@ -231,18 +232,13 @@ bool CameraCalc::load(const QJsonObject& json, QString& errorString) ...@@ -231,18 +232,13 @@ bool CameraCalc::load(const QJsonObject& json, QString& errorString)
{ adjustedFootprintSideName, QJsonValue::Double, true }, { adjustedFootprintSideName, QJsonValue::Double, true },
{ adjustedFootprintFrontalName, QJsonValue::Double, true }, { adjustedFootprintFrontalName, QJsonValue::Double, true },
{ distanceToSurfaceName, QJsonValue::Double, true }, { distanceToSurfaceName, QJsonValue::Double, true },
{ distanceToSurfaceRelativeName, QJsonValue::Bool, true }, { distanceToSurfaceRelativeName, QJsonValue::Bool, true },
}; };
if (!JsonHelper::validateKeys(v1Json, keyInfoList1, errorString)) { if (!JsonHelper::validateKeys(v1Json, keyInfoList1, errorString)) {
return false; return false;
} }
_disableRecalc = true; _disableRecalc = !forPresets;
_cameraNameFact.setRawValue (v1Json[cameraNameName].toString());
_adjustedFootprintSideFact.setRawValue (v1Json[adjustedFootprintSideName].toDouble());
_adjustedFootprintFrontalFact.setRawValue (v1Json[adjustedFootprintFrontalName].toDouble());
_distanceToSurfaceFact.setRawValue (v1Json[distanceToSurfaceName].toDouble());
_distanceToSurfaceRelative = v1Json[distanceToSurfaceRelativeName].toBool(); _distanceToSurfaceRelative = v1Json[distanceToSurfaceRelativeName].toBool();
...@@ -259,13 +255,40 @@ bool CameraCalc::load(const QJsonObject& json, QString& errorString) ...@@ -259,13 +255,40 @@ bool CameraCalc::load(const QJsonObject& json, QString& errorString)
} }
_valueSetIsDistanceFact.setRawValue (v1Json[valueSetIsDistanceName].toBool()); _valueSetIsDistanceFact.setRawValue (v1Json[valueSetIsDistanceName].toBool());
_imageDensityFact.setRawValue (v1Json[imageDensityName].toDouble());
_frontalOverlapFact.setRawValue (v1Json[frontalOverlapName].toDouble()); _frontalOverlapFact.setRawValue (v1Json[frontalOverlapName].toDouble());
_sideOverlapFact.setRawValue (v1Json[sideOverlapName].toDouble()); _sideOverlapFact.setRawValue (v1Json[sideOverlapName].toDouble());
}
if (!CameraSpec::load(v1Json, errorString)) { if (forPresets) {
_disableRecalc = false; if (isManualCamera()) {
return false; _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;
}
} }
} }
......
...@@ -70,7 +70,7 @@ public: ...@@ -70,7 +70,7 @@ public:
void setDistanceToSurfaceRelative (bool distanceToSurfaceRelative); void setDistanceToSurfaceRelative (bool distanceToSurfaceRelative);
void save(QJsonObject& json) const; 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* cameraNameName;
static const char* valueSetIsDistanceName; static const char* valueSetIsDistanceName;
......
...@@ -8,11 +8,20 @@ ...@@ -8,11 +8,20 @@
****************************************************************************/ ****************************************************************************/
#include "ComplexMissionItem.h" #include "ComplexMissionItem.h"
#include "QGCApplication.h"
#include <QSettings>
const char* ComplexMissionItem::jsonComplexItemTypeKey = "complexItemType"; 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) 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 ...@@ -21,5 +30,112 @@ const ComplexMissionItem& ComplexMissionItem::operator=(const ComplexMissionItem
{ {
VisualMissionItem::operator=(other); VisualMissionItem::operator=(other);
_cameraInPreset = other._cameraInPreset;
return *this; 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);
}
}
...@@ -13,6 +13,8 @@ ...@@ -13,6 +13,8 @@
#include "VisualMissionItem.h" #include "VisualMissionItem.h"
#include "QGCGeo.h" #include "QGCGeo.h"
#include <QSettings>
class ComplexMissionItem : public VisualMissionItem class ComplexMissionItem : public VisualMissionItem
{ {
Q_OBJECT Q_OBJECT
...@@ -22,7 +24,12 @@ public: ...@@ -22,7 +24,12 @@ public:
const ComplexMissionItem& operator=(const ComplexMissionItem& other); 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. /// @return The distance covered the complex mission item in meters.
/// Signals complexDistanceChanged /// Signals complexDistanceChanged
...@@ -35,12 +42,38 @@ public: ...@@ -35,12 +42,38 @@ public:
/// @return true: load success, false: load failed, errorString set /// @return true: load success, false: load failed, errorString set
virtual bool load(const QJsonObject& complexObject, int sequenceNumber, QString& errorString) = 0; 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 /// Get the point of complex mission item furthest away from a coordinate
/// @param other QGeoCoordinate to which distance is calculated /// @param other QGeoCoordinate to which distance is calculated
/// @return the greatest distance from any point of the complex item to some coordinate /// @return the greatest distance from any point of the complex item to some coordinate
/// Signals greatestDistanceToChanged /// Signals greatestDistanceToChanged
virtual double greatestDistanceTo(const QGeoCoordinate &other) const = 0; 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. /// This mission item attribute specifies the type of the complex item.
static const char* jsonComplexItemTypeKey; static const char* jsonComplexItemTypeKey;
...@@ -48,6 +81,29 @@ signals: ...@@ -48,6 +81,29 @@ signals:
void complexDistanceChanged (void); void complexDistanceChanged (void);
void boundingCubeChanged (void); void boundingCubeChanged (void);
void greatestDistanceToChanged (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 #endif
...@@ -62,7 +62,7 @@ void CorridorScanComplexItem::save(QJsonArray& planItems) ...@@ -62,7 +62,7 @@ void CorridorScanComplexItem::save(QJsonArray& planItems)
{ {
QJsonObject saveObject; QJsonObject saveObject;
_save(saveObject); TransectStyleComplexItem::_save(saveObject);
saveObject[JsonHelper::jsonVersionKey] = 2; saveObject[JsonHelper::jsonVersionKey] = 2;
saveObject[VisualMissionItem::jsonTypeKey] = VisualMissionItem::jsonTypeComplexItemValue; saveObject[VisualMissionItem::jsonTypeKey] = VisualMissionItem::jsonTypeComplexItemValue;
...@@ -115,7 +115,7 @@ bool CorridorScanComplexItem::load(const QJsonObject& complexObject, int sequenc ...@@ -115,7 +115,7 @@ bool CorridorScanComplexItem::load(const QJsonObject& complexObject, int sequenc
setSequenceNumber(sequenceNumber); setSequenceNumber(sequenceNumber);
if (!_load(complexObject, errorString)) { if (!_load(complexObject, false /* forPresets */, errorString)) {
_ignoreRecalc = false; _ignoreRecalc = false;
return false; return false;
} }
......
...@@ -218,7 +218,7 @@ bool StructureScanComplexItem::load(const QJsonObject& complexObject, int sequen ...@@ -218,7 +218,7 @@ bool StructureScanComplexItem::load(const QJsonObject& complexObject, int sequen
setSequenceNumber(sequenceNumber); setSequenceNumber(sequenceNumber);
// Load CameraCalc first since it will trigger camera name change which will trounce gimbal angles // 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; return false;
} }
......
...@@ -108,7 +108,21 @@ void SurveyComplexItem::save(QJsonArray& planItems) ...@@ -108,7 +108,21 @@ void SurveyComplexItem::save(QJsonArray& planItems)
{ {
QJsonObject saveObject; 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[JsonHelper::jsonVersionKey] = 5;
saveObject[VisualMissionItem::jsonTypeKey] = VisualMissionItem::jsonTypeComplexItemValue; saveObject[VisualMissionItem::jsonTypeKey] = VisualMissionItem::jsonTypeComplexItemValue;
...@@ -120,8 +134,15 @@ void SurveyComplexItem::save(QJsonArray& planItems) ...@@ -120,8 +134,15 @@ void SurveyComplexItem::save(QJsonArray& planItems)
// Polygon shape // Polygon shape
_surveyAreaPolygon.saveToJson(saveObject); _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) bool SurveyComplexItem::load(const QJsonObject& complexObject, int sequenceNumber, QString& errorString)
...@@ -141,7 +162,7 @@ bool SurveyComplexItem::load(const QJsonObject& complexObject, int sequenceNumbe ...@@ -141,7 +162,7 @@ bool SurveyComplexItem::load(const QJsonObject& complexObject, int sequenceNumbe
} }
if (version == 4 || version == 5) { if (version == 4 || version == 5) {
if (!_loadV4V5(complexObject, sequenceNumber, errorString, version)) { if (!_loadV4V5(complexObject, sequenceNumber, errorString, version, false /* forPresets */)) {
return false; return false;
} }
...@@ -171,7 +192,7 @@ bool SurveyComplexItem::load(const QJsonObject& complexObject, int sequenceNumbe ...@@ -171,7 +192,7 @@ bool SurveyComplexItem::load(const QJsonObject& complexObject, int sequenceNumbe
return true; 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<JsonHelper::KeyValidateInfo> keyInfoList = { QList<JsonHelper::KeyValidateInfo> keyInfoList = {
{ VisualMissionItem::jsonTypeKey, QJsonValue::String, true }, { VisualMissionItem::jsonTypeKey, QJsonValue::String, true },
...@@ -197,16 +218,18 @@ bool SurveyComplexItem::_loadV4V5(const QJsonObject& complexObject, int sequence ...@@ -197,16 +218,18 @@ bool SurveyComplexItem::_loadV4V5(const QJsonObject& complexObject, int sequence
return false; return false;
} }
_ignoreRecalc = true; _ignoreRecalc = !forPresets;
setSequenceNumber(sequenceNumber); if (!forPresets) {
setSequenceNumber(sequenceNumber);
if (!_surveyAreaPolygon.loadFromJson(complexObject, true /* required */, errorString)) { if (!_surveyAreaPolygon.loadFromJson(complexObject, true /* required */, errorString)) {
_surveyAreaPolygon.clear(); _surveyAreaPolygon.clear();
return false; return false;
}
} }
if (!_load(complexObject, errorString)) { if (!TransectStyleComplexItem::_load(complexObject, forPresets, errorString)) {
_ignoreRecalc = false; _ignoreRecalc = false;
return false; return false;
} }
...@@ -214,7 +237,7 @@ bool SurveyComplexItem::_loadV4V5(const QJsonObject& complexObject, int sequence ...@@ -214,7 +237,7 @@ bool SurveyComplexItem::_loadV4V5(const QJsonObject& complexObject, int sequence
_gridAngleFact.setRawValue (complexObject[_jsonGridAngleKey].toDouble()); _gridAngleFact.setRawValue (complexObject[_jsonGridAngleKey].toDouble());
_flyAlternateTransectsFact.setRawValue (complexObject[_jsonFlyAlternateTransectsKey].toBool(false)); _flyAlternateTransectsFact.setRawValue (complexObject[_jsonFlyAlternateTransectsKey].toBool(false));
if(version == 5) { if (version == 5) {
_splitConcavePolygonsFact.setRawValue (complexObject[_jsonSplitConcavePolygonsKey].toBool(true)); _splitConcavePolygonsFact.setRawValue (complexObject[_jsonSplitConcavePolygonsKey].toBool(true));
} }
...@@ -282,7 +305,7 @@ bool SurveyComplexItem::_loadV3(const QJsonObject& complexObject, int sequenceNu ...@@ -282,7 +305,7 @@ bool SurveyComplexItem::_loadV3(const QJsonObject& complexObject, int sequenceNu
_turnAroundDistanceFact.setRawValue (gridObject[_jsonV3TurnaroundDistKey].toDouble()); _turnAroundDistanceFact.setRawValue (gridObject[_jsonV3TurnaroundDistKey].toDouble());
if (gridObject.contains(_jsonEntryPointKey)) { if (gridObject.contains(_jsonEntryPointKey)) {
_entryPoint = gridObject[_jsonEntryPointKey].toDouble(); _entryPoint = gridObject[_jsonEntryPointKey].toInt();
} else { } else {
_entryPoint = EntryLocationTopRight; _entryPoint = EntryLocationTopRight;
} }
......
...@@ -39,6 +39,9 @@ public: ...@@ -39,6 +39,9 @@ public:
// Overrides from ComplexMissionItem // Overrides from ComplexMissionItem
bool load (const QJsonObject& complexObject, int sequenceNumber, QString& errorString) final; bool load (const QJsonObject& complexObject, int sequenceNumber, QString& errorString) final;
QString mapVisualQML (void) const final { return QStringLiteral("SurveyMapVisual.qml"); } 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 // Overrides from TransectStyleComplexItem
void save (QJsonArray& planItems) final; void save (QJsonArray& planItems) final;
...@@ -114,7 +117,8 @@ private: ...@@ -114,7 +117,8 @@ private:
double _turnaroundDistance(void) const; double _turnaroundDistance(void) const;
bool _hoverAndCaptureEnabled(void) const; bool _hoverAndCaptureEnabled(void) const;
bool _loadV3(const QJsonObject& complexObject, int sequenceNumber, QString& errorString); 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 _rebuildTransectsPhase1Worker(bool refly);
void _rebuildTransectsPhase1WorkerSinglePolygon(bool refly); void _rebuildTransectsPhase1WorkerSinglePolygon(bool refly);
void _rebuildTransectsPhase1WorkerSplitPolygons(bool refly); void _rebuildTransectsPhase1WorkerSplitPolygons(bool refly);
......
...@@ -132,6 +132,8 @@ void TransectStyleComplexItem::setDirty(bool dirty) ...@@ -132,6 +132,8 @@ void TransectStyleComplexItem::setDirty(bool dirty)
void TransectStyleComplexItem::_save(QJsonObject& complexObject) void TransectStyleComplexItem::_save(QJsonObject& complexObject)
{ {
ComplexMissionItem::_saveItem(complexObject);
QJsonObject innerObject; QJsonObject innerObject;
innerObject[JsonHelper::jsonVersionKey] = 1; innerObject[JsonHelper::jsonVersionKey] = 1;
...@@ -183,8 +185,9 @@ void TransectStyleComplexItem::setSequenceNumber(int sequenceNumber) ...@@ -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<JsonHelper::KeyValidateInfo> keyInfoList = { QList<JsonHelper::KeyValidateInfo> keyInfoList = {
{ _jsonTransectStyleComplexItemKey, QJsonValue::Object, true }, { _jsonTransectStyleComplexItemKey, QJsonValue::Object, true },
...@@ -211,8 +214,8 @@ bool TransectStyleComplexItem::_load(const QJsonObject& complexObject, QString& ...@@ -211,8 +214,8 @@ bool TransectStyleComplexItem::_load(const QJsonObject& complexObject, QString&
{ hoverAndCaptureName, QJsonValue::Bool, true }, { hoverAndCaptureName, QJsonValue::Bool, true },
{ refly90DegreesName, QJsonValue::Bool, true }, { refly90DegreesName, QJsonValue::Bool, true },
{ _jsonCameraCalcKey, QJsonValue::Object, true }, { _jsonCameraCalcKey, QJsonValue::Object, true },
{ _jsonVisualTransectPointsKey, QJsonValue::Array, true }, { _jsonVisualTransectPointsKey, QJsonValue::Array, !forPresets },
{ _jsonItemsKey, QJsonValue::Array, true }, { _jsonItemsKey, QJsonValue::Array, !forPresets },
{ _jsonFollowTerrainKey, QJsonValue::Bool, true }, { _jsonFollowTerrainKey, QJsonValue::Bool, true },
{ _jsonCameraShotsKey, QJsonValue::Double, false }, // Not required since it was missing from initial implementation { _jsonCameraShotsKey, QJsonValue::Double, false }, // Not required since it was missing from initial implementation
}; };
...@@ -220,28 +223,30 @@ bool TransectStyleComplexItem::_load(const QJsonObject& complexObject, QString& ...@@ -220,28 +223,30 @@ bool TransectStyleComplexItem::_load(const QJsonObject& complexObject, QString&
return false; return false;
} }
// Load visual transect points if (!forPresets) {
if (!JsonHelper::loadGeoCoordinateArray(innerObject[_jsonVisualTransectPointsKey], false /* altitudeRequired */, _visualTransectPoints, errorString)) { // Load visual transect points
return false; if (!JsonHelper::loadGeoCoordinateArray(innerObject[_jsonVisualTransectPointsKey], false /* altitudeRequired */, _visualTransectPoints, errorString)) {
}
_coordinate = _visualTransectPoints.count() ? _visualTransectPoints.first().value<QGeoCoordinate>() : QGeoCoordinate();
_exitCoordinate = _visualTransectPoints.count() ? _visualTransectPoints.last().value<QGeoCoordinate>() : 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;
return false; return false;
} }
_loadedMissionItems.append(missionItem); _coordinate = _visualTransectPoints.count() ? _visualTransectPoints.first().value<QGeoCoordinate>() : QGeoCoordinate();
_exitCoordinate = _visualTransectPoints.count() ? _visualTransectPoints.last().value<QGeoCoordinate>() : 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 // Load CameraCalc data
if (!_cameraCalc.load(innerObject[_jsonCameraCalcKey].toObject(), errorString)) { if (!_cameraCalc.load(innerObject[_jsonCameraCalcKey].toObject(), forPresets, cameraInPreset(), errorString)) {
return false; return false;
} }
...@@ -435,7 +440,7 @@ void TransectStyleComplexItem::_reallyQueryTransectsPathHeightInfo(void) ...@@ -435,7 +440,7 @@ void TransectStyleComplexItem::_reallyQueryTransectsPathHeightInfo(void)