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.
### 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.
......
......@@ -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<CameraMetaData*>();
......@@ -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;
}
}
}
......
......@@ -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;
......
......@@ -8,11 +8,20 @@
****************************************************************************/
#include "ComplexMissionItem.h"
#include "QGCApplication.h"
#include <QSettings>
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);
}
}
......@@ -13,6 +13,8 @@
#include "VisualMissionItem.h"
#include "QGCGeo.h"
#include <QSettings>
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<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
......@@ -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;
}
......
......@@ -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;
}
......
......@@ -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<JsonHelper::KeyValidateInfo> 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;
}
......
......@@ -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);
......
......@@ -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<JsonHelper::KeyValidateInfo> 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>() : 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;
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>() : 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
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<Te
qWarning() << "TransectStyleComplexItem::_polyPathTerrainData _terrainPolyPathQuery != sender()";
}
disconnect(_terrainPolyPathQuery, &TerrainPolyPathQuery::terrainDataReceived, this, &TransectStyleComplexItem::_polyPathTerrainData);
_terrainPolyPathQuery = NULL;
_terrainPolyPathQuery = nullptr;
}
bool TransectStyleComplexItem::readyForSave(void) const
......
......@@ -141,7 +141,7 @@ protected:
virtual void _recalcCameraShots (void) = 0;
void _save (QJsonObject& saveObject);
bool _load (const QJsonObject& complexObject, QString& errorString);
bool _load (const QJsonObject& complexObject, bool forPresets, QString& errorString);
void _setExitCoordinate (const QGeoCoordinate& coordinate);
void _setCameraShots (int cameraShots);
double _triggerDistance (void) const;
......
......@@ -14,37 +14,53 @@ 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 int _cameraIndex: 1
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: {
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
var knownCameraIndex = gridTypeCombo.find(cameraCalc.cameraName.value)
if (knownCameraIndex !== -1) {
gridTypeCombo.currentIndex = knownCameraIndex
} else {
console.log("Internal error: Known camera not found", cameraCalc.cameraName.value)
gridTypeCombo.currentIndex = _gridTypeCustomCamera
_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
}
}
}
......@@ -179,6 +195,7 @@ Column {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
visible: !usingPreset
Item { Layout.fillWidth: true }
QGCLabel {
Layout.preferredWidth: _root._fieldWidth
......@@ -194,6 +211,7 @@ 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
......@@ -210,6 +228,7 @@ Column {
text: qsTr("Select one:")
Layout.preferredWidth: parent.width
Layout.columnSpan: 2
visible: !usingPreset
}
GridLayout {
......@@ -218,6 +237,7 @@ Column {
columnSpacing: _margin
rowSpacing: _margin
columns: 2
visible: !usingPreset
QGCRadioButton {
id: fixedDistanceRadio
......@@ -248,33 +268,6 @@ Column {
Layout.fillWidth: true
}
}
// Calculated values
/*
Taking these out for now since they take up so much space. May come back at a later time.
GridLayout {
anchors.left: parent.left
anchors.right: parent.right
columnSpacing: _margin
rowSpacing: _margin
columns: 2
QGCLabel { text: frontalDistanceLabel }
FactTextField {
Layout.fillWidth: true
fact: cameraCalc.adjustedFootprintFrontal
enabled: false
}
QGCLabel { text: sideDistanceLabel }
FactTextField {
Layout.fillWidth: true
fact: cameraCalc.adjustedFootprintSide
enabled: false
}
} // GridLayout
*/
} // Column - Camera spec based ui
// No camera spec ui
......
import QtQuick 2.3
import QtQuick.Controls 1.2
import QtQuick.Controls.Styles 1.4
import QtQuick.Dialogs 1.2
import QtQuick.Extras 1.4
import QtQuick.Layouts 1.2
......@@ -29,6 +28,8 @@ 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()
......@@ -66,6 +67,97 @@ Rectangle {
visible: missionItem.cameraShots > 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<missionItem.presetNames.length; i++) {
_presetList.push(missionItem.presetNames[i])
}
model = _presetList
_selectCurrentPreset()
}
function _selectCurrentPreset() {
if (_usingPreset) {
var newIndex = find(_currentPreset)
if (newIndex !== -1) {
delayedIndexChange(newIndex)
return
}
}
delayedIndexChange(presetCombo._indexCustom)
}
}
CameraCalc {
cameraCalc: missionItem.cameraCalc
vehicleFlightIsFrontal: true
......@@ -73,6 +165,8 @@ Rectangle {
distanceToSurfaceAltitudeMode: missionItem.followTerrain ? QGroundControl.AltitudeModeAboveTerrain : QGroundControl.AltitudeModeRelative
frontalDistanceLabel: qsTr("Trigger Dist")
sideDistanceLabel: qsTr("Spacing")
usingPreset: _usingPreset
cameraSpecifiedInPreset: missionItem.cameraInPreset
}
SectionHeader {
......@@ -109,23 +203,27 @@ Rectangle {
updateValueWhileDragging: true
}
QGCLabel { text: qsTr("Turnaround dist") }
QGCLabel {
text: qsTr("Turnaround dist")
visible: !_usingPreset
}
FactTextField {
fact: missionItem.turnAroundDistance
Layout.fillWidth: true
visible: !_usingPreset
}
}
QGCButton {
text: qsTr("Rotate Entry Point")
onClicked: missionItem.rotateEntryPoint();
}
ColumnLayout {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
visible: transectsHeader.checked
QGCButton {
text: qsTr("Rotate Entry Point")
onClicked: missionItem.rotateEntryPoint();
}
visible: transectsHeader.checked && !_usingPreset
/*
Temporarily removed due to bug https://github.com/mavlink/qgroundcontrol/issues/7005
......@@ -187,13 +285,15 @@ 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
visible: terrainHeader.checked && !_usingPreset
QGCCheckBox {
id: followsTerrainCheckBox
......@@ -236,4 +336,45 @@ Rectangle {
TransectStyleComplexItemStats { }
} // Column
Component {
id: savePresetDialog
QGCViewDialog {
function accept() {
if (presetNameField.text != "") {
missionItem.savePreset(presetNameField.text)
hideDialog()
}
}
ColumnLayout {
anchors.left: parent.left
anchors.right: parent.right
spacing: ScreenTools.defaultFontPixelHeight
QGCLabel {
Layout.fillWidth: true
text: qsTr("Save the current settings as a named preset.")
wrapMode: Text.WordWrap
}
QGCLabel {
text: qsTr("Preset Name")
}
QGCTextField {
id: presetNameField
Layout.fillWidth: true
text: _currentPreset
}
QGCCheckBox {
text: qsTr("Save Camera In Preset")
checked: missionItem.cameraInPreset
onClicked: missionItem.cameraInPreset = checked
}
}
}
}
} // Rectangle
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment