From e8e93b4fc20c79953a0a517ce6b8877219cb2cec Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Wed, 8 Mar 2017 20:01:02 -0800 Subject: [PATCH] All survey Facts are now SettingsFacts --- qgroundcontrol.qrc | 2 +- src/MissionEditor/SurveyItemEditor.qml | 113 +++++--------- src/MissionManager/Survey.FactMetaData.json | 102 ------------- src/MissionManager/Survey.SettingsGroup.json | 151 +++++++++++++++++++ src/MissionManager/SurveyMissionItem.cc | 151 ++++++++----------- src/MissionManager/SurveyMissionItem.h | 126 ++++++++-------- 6 files changed, 322 insertions(+), 323 deletions(-) delete mode 100644 src/MissionManager/Survey.FactMetaData.json create mode 100644 src/MissionManager/Survey.SettingsGroup.json diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc index 41746308e..d00c76c07 100644 --- a/qgroundcontrol.qrc +++ b/qgroundcontrol.qrc @@ -189,11 +189,11 @@ src/Vehicle/VibrationFact.json src/Settings/App.SettingsGroup.json src/Settings/AutoConnect.SettingsGroup.json + src/MissionManager/Survey.SettingsGroup.json src/Settings/Units.SettingsGroup.json src/Settings/Video.SettingsGroup.json src/MissionManager/RallyPoint.FactMetaData.json src/MissionManager/FWLandingPattern.FactMetaData.json - src/MissionManager/Survey.FactMetaData.json src/comm/USBBoardInfo.json src/Vehicle/TemperatureFact.json diff --git a/src/MissionEditor/SurveyItemEditor.qml b/src/MissionEditor/SurveyItemEditor.qml index 26a613660..438e4ea0c 100644 --- a/src/MissionEditor/SurveyItemEditor.qml +++ b/src/MissionEditor/SurveyItemEditor.qml @@ -39,12 +39,16 @@ Rectangle { _cameraList.push(_vehicle.cameraList[i].name) } gridTypeCombo.model = _cameraList - if (missionItem.manualGrid) { + if (missionItem.manualGrid.value) { gridTypeCombo.currentIndex = _gridTypeManual } else { - var index = gridTypeCombo.find(missionItem.camera) + var index = -1 + for (index=0; index<_cameraList.length; index++) { + if (_cameraList[index] == missionItem.camera.value) { + break; + } + } if (index == -1) { - console.log("Couldn't find camera", missionItem.camera) gridTypeCombo.currentIndex = _gridTypeManual } else { gridTypeCombo.currentIndex = index @@ -73,13 +77,13 @@ Rectangle { var gridSpacing var cameraTriggerDistance - if (missionItem.fixedValueIsAltitude) { + if (missionItem.fixedValueIsAltitude.value) { groundResolution = (altitude * sensorWidth * 100) / (imageWidth * focalLength) } else { altitude = (imageWidth * groundResolution * focalLength) / (sensorWidth * 100) } - if (cameraOrientationLandscape.checked) { + if (missionItem.cameraOrientationLandscape.value) { imageSizeSideGround = (imageWidth * groundResolution) / 100 imageSizeFrontGround = (imageHeight * groundResolution) / 100 } else { @@ -90,7 +94,7 @@ Rectangle { gridSpacing = imageSizeSideGround * ( (100-sideOverlap) / 100 ) cameraTriggerDistance = imageSizeFrontGround * ( (100-frontalOverlap) / 100 ) - if (missionItem.fixedValueIsAltitude) { + if (missionItem.fixedValueIsAltitude.value) { missionItem.groundResolution.rawValue = groundResolution } else { missionItem.gridAltitude.rawValue = altitude @@ -99,48 +103,6 @@ Rectangle { missionItem.cameraTriggerDistance.rawValue = cameraTriggerDistance } - /* - function recalcFromMissionValues() { - var focalLength = missionItem.cameraFocalLength.rawValue - var sensorWidth = missionItem.cameraSensorWidth.rawValue - var sensorHeight = missionItem.cameraSensorHeight.rawValue - var imageWidth = missionItem.cameraResolutionWidth.rawValue - var imageHeight = missionItem.cameraResolutionHeight.rawValue - - var altitude = missionItem.gridAltitude.rawValue - var gridSpacing = missionItem.gridSpacing.rawValue - var cameraTriggerDistance = missionItem.cameraTriggerDistance.rawValue - - if (focalLength <= 0.0 || sensorWidth <= 0.0 || sensorHeight <= 0.0 || imageWidth < 0 || imageHeight < 0 || altitude < 0.0 || gridSpacing < 0.0 || cameraTriggerDistance < 0.0) { - missionItem.groundResolution.rawValue = 0 - missionItem.sideOverlap = 0 - missionItem.frontalOverlap = 0 - return - } - - var groundResolution - var imageSizeSideGround //size in side (non flying) direction of the image on the ground - var imageSizeFrontGround //size in front (flying) direction of the image on the ground - - groundResolution = (altitude * sensorWidth * 100) / (imageWidth * focalLength) - - if (cameraOrientationLandscape.checked) { - imageSizeSideGround = (imageWidth * gsd) / 100 - imageSizeFrontGround = (imageHeight * gsd) / 100 - } else { - imageSizeSideGround = (imageHeight * gsd) / 100 - imageSizeFrontGround = (imageWidth * gsd) / 100 - } - - var sideOverlap = (imageSizeSideGround == 0 ? 0 : 100 - (gridSpacing*100 / imageSizeSideGround)) - var frontOverlap = (imageSizeFrontGround == 0 ? 0 : 100 - (cameraTriggerDistance*100 / imageSizeFrontGround)) - - missionItem.groundResolution.rawValue = groundResolution - missionItem.sideOverlap.rawValue = sideOverlap - missionItem.frontalOverlap.rawValue = frontOverlap - } - */ - function polygonCaptureStarted() { missionItem.clearPolygon() } @@ -163,12 +125,6 @@ Rectangle { Connections { target: missionItem - onCameraValueChanged: { - if (gridTypeCombo.currentIndex >= _gridTypeCustomCamera && !_noCameraValueRecalc) { - recalcFromCameraValues() - } - } - onIsCurrentItemChanged: { if (!missionItem.isCurrentItem) { polygonEditor.cancelPolygonEdit() @@ -176,11 +132,21 @@ Rectangle { } } + Connections { + target: missionItem.camera + + onValueChanged: { + if (gridTypeCombo.currentIndex >= _gridTypeCustomCamera && !_noCameraValueRecalc) { + recalcFromCameraValues() + } + } + } + Connections { target: missionItem.gridAltitude onValueChanged: { - if (gridTypeCombo.currentIndex >= _gridTypeCustomCamera && missionItem.fixedValueIsAltitude && !_noCameraValueRecalc) { + if (gridTypeCombo.currentIndex >= _gridTypeCustomCamera && missionItem.fixedValueIsAltitude.value && !_noCameraValueRecalc) { recalcFromCameraValues() } } @@ -217,13 +183,13 @@ Rectangle { onActivated: { if (index == _gridTypeManual) { - missionItem.manualGrid = true + missionItem.manualGrid.value = true } else if (index == _gridTypeCustomCamera) { - missionItem.manualGrid = false - missionItem.camera = gridTypeCombo.textAt(index) + missionItem.manualGrid.value = false + missionItem.camera.value = gridTypeCombo.textAt(index) } else { - missionItem.manualGrid = false - missionItem.camera = gridTypeCombo.textAt(index) + missionItem.manualGrid.value = false + missionItem.camera.value = gridTypeCombo.textAt(index) _noCameraValueRecalc = true var listIndex = index - _gridTypeCamera missionItem.cameraSensorWidth.rawValue = _vehicleCameraList[listIndex].sensorWidth @@ -259,17 +225,19 @@ Rectangle { anchors.horizontalCenter: parent.horizontalCenter QGCRadioButton { - id: cameraOrientationLandscape width: _editFieldWidth text: "Landscape" - checked: true + checked: missionItem.cameraOrientationLandscape.value == 1 exclusiveGroup: cameraOrientationGroup + onClicked: missionItem.cameraOrientationLandscape.value = 1 } QGCRadioButton { id: cameraOrientationPortrait text: "Portrait" + checked: missionItem.cameraOrientationLandscape.value == 0 exclusiveGroup: cameraOrientationGroup + onClicked: missionItem.cameraOrientationLandscape.value = 0 } } @@ -428,9 +396,9 @@ Rectangle { QGCRadioButton { id: fixedAltitudeRadio text: qsTr("Altitude:") - checked: missionItem.fixedValueIsAltitude + checked: missionItem.fixedValueIsAltitude.value exclusiveGroup: fixedValueGroup - onClicked: missionItem.fixedValueIsAltitude = true + onClicked: missionItem.fixedValueIsAltitude.value = 1 Layout.fillWidth: true anchors.verticalCenter: parent.verticalCenter } @@ -451,9 +419,9 @@ Rectangle { QGCRadioButton { id: fixedGroundResolutionRadio text: qsTr("Ground res:") - checked: !missionItem.fixedValueIsAltitude + checked: !missionItem.fixedValueIsAltitude.value exclusiveGroup: fixedValueGroup - onClicked: missionItem.fixedValueIsAltitude = false + onClicked: missionItem.fixedValueIsAltitude.value = 0 Layout.fillWidth: true anchors.verticalCenter: parent.verticalCenter } @@ -491,11 +459,10 @@ Rectangle { factList: [ missionItem.gridAngle, missionItem.gridSpacing, missionItem.gridAltitude, missionItem.turnaroundDist ] } - QGCCheckBox { + FactCheckBox { anchors.left: parent.left text: qsTr("Relative altitude") - checked: missionItem.gridAltitudeRelative - onClicked: missionItem.gridAltitudeRelative = checked + fact: missionItem.gridAltitudeRelative } QGCLabel { text: qsTr("Camera") } @@ -512,19 +479,17 @@ Rectangle { anchors.right: parent.right spacing: _margin - QGCCheckBox { - id: cameraTrigger + FactCheckBox { anchors.baseline: cameraTriggerDistanceField.baseline text: qsTr("Trigger Distance:") - checked: missionItem.cameraTrigger - onClicked: missionItem.cameraTrigger = checked + fact: missionItem.cameraTrigger } FactTextField { id: cameraTriggerDistanceField Layout.fillWidth: true fact: missionItem.cameraTriggerDistance - enabled: missionItem.cameraTrigger + enabled: missionItem.cameraTrigger.value } } } diff --git a/src/MissionManager/Survey.FactMetaData.json b/src/MissionManager/Survey.FactMetaData.json deleted file mode 100644 index bb341a643..000000000 --- a/src/MissionManager/Survey.FactMetaData.json +++ /dev/null @@ -1,102 +0,0 @@ -[ -{ - "name": "Altitude", - "shortDescription": "Altitude for all waypoints within the grid.", - "type": "double", - "units": "m", - "decimalPlaces": 1 -}, -{ - "name": "Grid angle", - "shortDescription": "Angle for parallel lines of grid.", - "type": "double", - "units": "deg", - "decimalPlaces": 1 -}, -{ - "name": "Grid spacing", - "shortDescription": "Amount of spacing in between parallel grid lines.", - "type": "double", - "decimalPlaces": 2, - "min": 0.1, - "units": "m" -}, -{ - "name": "Turnaround dist", - "shortDescription": "Amount of additional distance to add outside the grid area for vehicle turnaround.", - "type": "double", - "decimalPlaces": 2, - "min": 0, - "units": "m" -}, -{ - "name": "Ground resolution", - "shortDescription": "Resolution of image in relationship to ground distance.", - "type": "double", - "decimalPlaces": 2, - "min": 0, - "units": "cm/px" -}, -{ - "name": "Frontal overlap", - "shortDescription": "Amount of overlap between images in the forward facing direction.", - "type": "double", - "decimalPlaces": 0, - "max": 75, - "units": "%" -}, -{ - "name": "Side overlap", - "shortDescription": "Amount of overlap between images in the side facing direction.", - "type": "double", - "decimalPlaces": 0, - "max": 75, - "units": "%" -}, -{ - "name": "Camera sensor width", - "shortDescription": "Amount of overlap between images in the side facing direction.", - "type": "double", - "decimalPlaces": 2, - "min": 1, - "units": "mm" -}, -{ - "name": "Camera sensor height", - "shortDescription": "Amount of overlap between images in the side facing direction.", - "type": "double", - "decimalPlaces": 2, - "min": 1, - "units": "mm" -}, -{ - "name": "Camera resolution width", - "shortDescription": "Amount of overlap between images in the side facing direction.", - "type": "uint32", - "min": 1, - "units": "px" -}, -{ - "name": "Camera resolution height", - "shortDescription": "Amount of overlap between images in the side facing direction.", - "type": "uint32", - "min": 1, - "units": "px" -}, -{ - "name": "Focal length", - "shortDescription": "Amount of overlap between images in the side facing direction.", - "type": "double", - "decimalPlaces": 1, - "min": 1, - "units": "mm" -}, -{ - "name": "Camera trigger distance", - "shortDescription": "Distance between each triggering of the camera.", - "type": "double", - "decimalPlaces": 2, - "min": 0.1, - "units": "m" -} -] diff --git a/src/MissionManager/Survey.SettingsGroup.json b/src/MissionManager/Survey.SettingsGroup.json new file mode 100644 index 000000000..42f8704fb --- /dev/null +++ b/src/MissionManager/Survey.SettingsGroup.json @@ -0,0 +1,151 @@ +[ +{ + "name": "ManualGrid", + "shortDescription": "Specify all parameters for grid generation.", + "type": "bool", + "defaultValue": 1 +}, +{ + "name": "GridAltitude", + "shortDescription": "Altitude for all waypoints within the grid.", + "type": "double", + "units": "m", + "decimalPlaces": 1, + "defaultValue": 50 +}, +{ + "name": "GridAltitudeRelative", + "shortDescription": "Altitude for all waypoints within the grid is relative to home.", + "type": "bool", + "defaultValue": 1 +}, +{ + "name": "GridAngle", + "shortDescription": "Angle for parallel lines of grid.", + "type": "double", + "units": "deg", + "decimalPlaces": 1, + "defaultValue": 0 +}, +{ + "name": "GridSpacing", + "shortDescription": "Amount of spacing in between parallel grid lines.", + "type": "double", + "decimalPlaces": 2, + "min": 0.1, + "units": "m", + "defaultValue": 30 +}, +{ + "name": "TurnaroundDist", + "shortDescription": "Amount of additional distance to add outside the grid area for vehicle turnaround.", + "type": "double", + "decimalPlaces": 2, + "min": 0, + "units": "m", + "defaultValue": 30 +}, +{ + "name": "GroundResolution", + "shortDescription": "Resolution of image in relationship to ground distance.", + "type": "double", + "decimalPlaces": 2, + "min": 0, + "units": "cm/px", + "defaultValue": 3 +}, +{ + "name": "FrontalOverlap", + "shortDescription": "Amount of overlap between images in the forward facing direction.", + "type": "double", + "decimalPlaces": 0, + "max": 85, + "units": "%", + "defaultValue": 10 +}, +{ + "name": "SideOverlap", + "shortDescription": "Amount of overlap between images in the side facing direction.", + "type": "double", + "decimalPlaces": 0, + "max": 85, + "units": "%", + "defaultValue": 10 +}, +{ + "name": "CameraSensorWidth", + "shortDescription": "Amount of overlap between images in the side facing direction.", + "type": "double", + "decimalPlaces": 2, + "min": 1, + "units": "mm", + "defaultValue": 6.17 +}, +{ + "name": "CameraSensorHeight", + "shortDescription": "Amount of overlap between images in the side facing direction.", + "type": "double", + "decimalPlaces": 2, + "min": 1, + "units": "mm", + "defaultValue": 4.55 +}, +{ + "name": "CameraResolutionWidth", + "shortDescription": "Camera resolution width.", + "type": "uint32", + "min": 1, + "units": "px", + "defaultValue": 4000 +}, +{ + "name": "CameraResolutionHeight", + "shortDescription": "Camera resolution height.", + "type": "uint32", + "min": 1, + "units": "px", + "defaultValue": 3000 +}, +{ + "name": "CameraFocalLength", + "shortDescription": "Focal length of camera lens.", + "type": "double", + "decimalPlaces": 1, + "min": 1, + "units": "mm", + "defaultValue": 4.5 +}, +{ + "name": "CameraTrigger", + "shortDescription": "Trigger the camera based on distance.", + "type": "bool", + "defaultValue": 0 +}, +{ + "name": "CameraTriggerDistance", + "shortDescription": "Distance between each triggering of the camera.", + "type": "double", + "decimalPlaces": 2, + "min": 0.1, + "units": "m", + "defaultValue": 25 +}, +{ + "name": "CameraOrientationLandscape", + "shortDescription": "Camera on vehicle is in landscape orientation.", + "type": "bool", + "defaultValue": 1 +}, +{ + "name": "FixedValueIsAltitude", + "shortDescription": "The altitude is kep constant while ground resolution changes.", + "type": "bool", + "defaultValue": 0 +}, +{ + "name": "Camera", + "shortDescription": "Camera selected for Survey.", + "type": "string", + "defaultValue": "" +} +] diff --git a/src/MissionManager/SurveyMissionItem.cc b/src/MissionManager/SurveyMissionItem.cc index 954fc3cf2..caacc4197 100644 --- a/src/MissionManager/SurveyMissionItem.cc +++ b/src/MissionManager/SurveyMissionItem.cc @@ -43,82 +43,61 @@ const char* SurveyMissionItem::_jsonManualGridKey = "manualGrid" const char* SurveyMissionItem::_jsonCameraOrientationLandscapeKey = "orientationLandscape"; const char* SurveyMissionItem::_jsonFixedValueIsAltitudeKey = "fixedValueIsAltitude"; -const char* SurveyMissionItem::_gridAltitudeFactName = "Altitude"; -const char* SurveyMissionItem::_gridAngleFactName = "Grid angle"; -const char* SurveyMissionItem::_gridSpacingFactName = "Grid spacing"; -const char* SurveyMissionItem::_turnaroundDistFactName = "Turnaround dist"; -const char* SurveyMissionItem::_cameraTriggerDistanceFactName = "Camera trigger distance"; -const char* SurveyMissionItem::_groundResolutionFactName = "Ground resolution"; -const char* SurveyMissionItem::_frontalOverlapFactName = "Frontal overlap"; -const char* SurveyMissionItem::_sideOverlapFactName = "Side overlap"; -const char* SurveyMissionItem::_cameraSensorWidthFactName = "Camera sensor width"; -const char* SurveyMissionItem::_cameraSensorHeightFactName = "Camera sensor height"; -const char* SurveyMissionItem::_cameraResolutionWidthFactName = "Camera resolution width"; -const char* SurveyMissionItem::_cameraResolutionHeightFactName = "Camera resolution height"; -const char* SurveyMissionItem::_cameraFocalLengthFactName = "Focal length"; - -QMap SurveyMissionItem::_metaDataMap; +const char* SurveyMissionItem::settingsGroup = "Survey"; +const char* SurveyMissionItem::manualGridName = "ManualGrid"; +const char* SurveyMissionItem::gridAltitudeName = "GridAltitude"; +const char* SurveyMissionItem::gridAltitudeRelativeName = "GridAltitudeRelative"; +const char* SurveyMissionItem::gridAngleName = "GridAngle"; +const char* SurveyMissionItem::gridSpacingName = "GridSpacing"; +const char* SurveyMissionItem::turnaroundDistName = "TurnaroundDist"; +const char* SurveyMissionItem::cameraTriggerDistanceName = "CameraTriggerDistance"; +const char* SurveyMissionItem::groundResolutionName = "GroundResolution"; +const char* SurveyMissionItem::frontalOverlapName = "FrontalOverlap"; +const char* SurveyMissionItem::sideOverlapName = "SideOverlap"; +const char* SurveyMissionItem::cameraSensorWidthName = "CameraSensorWidth"; +const char* SurveyMissionItem::cameraSensorHeightName = "CameraSensorHeight"; +const char* SurveyMissionItem::cameraResolutionWidthName = "CameraResolutionWidth"; +const char* SurveyMissionItem::cameraResolutionHeightName = "CameraResolutionHeight"; +const char* SurveyMissionItem::cameraFocalLengthName = "CameraFocalLength"; +const char* SurveyMissionItem::cameraTriggerName = "CameraTrigger"; +const char* SurveyMissionItem::cameraOrientationLandscapeName = "CameraOrientationLandscape"; +const char* SurveyMissionItem::fixedValueIsAltitudeName = "FixedValueIsAltitude"; +const char* SurveyMissionItem::cameraName = "Camera"; SurveyMissionItem::SurveyMissionItem(Vehicle* vehicle, QObject* parent) : ComplexMissionItem(vehicle, parent) , _sequenceNumber(0) , _dirty(false) - , _cameraTrigger(true) - , _gridAltitudeRelative(true) - , _manualGrid(true) - , _cameraOrientationLandscape(true) - , _fixedValueIsAltitude(false) , _surveyDistance(0.0) , _cameraShots(0) , _coveredArea(0.0) , _timeBetweenShots(0.0) - , _gridAltitudeFact (0, _gridAltitudeFactName, FactMetaData::valueTypeDouble) - , _gridAngleFact (0, _gridAngleFactName, FactMetaData::valueTypeDouble) - , _gridSpacingFact (0, _gridSpacingFactName, FactMetaData::valueTypeDouble) - , _turnaroundDistFact (0, _turnaroundDistFactName, FactMetaData::valueTypeDouble) - , _cameraTriggerDistanceFact (0, _cameraTriggerDistanceFactName, FactMetaData::valueTypeDouble) - , _groundResolutionFact (0, _groundResolutionFactName, FactMetaData::valueTypeDouble) - , _frontalOverlapFact (0, _frontalOverlapFactName, FactMetaData::valueTypeDouble) - , _sideOverlapFact (0, _sideOverlapFactName, FactMetaData::valueTypeDouble) - , _cameraSensorWidthFact (0, _cameraSensorWidthFactName, FactMetaData::valueTypeDouble) - , _cameraSensorHeightFact (0, _cameraSensorHeightFactName, FactMetaData::valueTypeDouble) - , _cameraResolutionWidthFact (0, _cameraResolutionWidthFactName, FactMetaData::valueTypeUint32) - , _cameraResolutionHeightFact (0, _cameraResolutionHeightFactName, FactMetaData::valueTypeUint32) - , _cameraFocalLengthFact (0, _cameraFocalLengthFactName, FactMetaData::valueTypeDouble) + , _metaDataMap(FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/Survey.SettingsGroup.json"), this)) + , _manualGridFact (settingsGroup, _metaDataMap[manualGridName]) + , _gridAltitudeFact (settingsGroup, _metaDataMap[gridAltitudeName]) + , _gridAltitudeRelativeFact (settingsGroup, _metaDataMap[gridAltitudeRelativeName]) + , _gridAngleFact (settingsGroup, _metaDataMap[gridAngleName]) + , _gridSpacingFact (settingsGroup, _metaDataMap[gridSpacingName]) + , _turnaroundDistFact (settingsGroup, _metaDataMap[turnaroundDistName]) + , _cameraTriggerFact (settingsGroup, _metaDataMap[cameraTriggerName]) + , _cameraTriggerDistanceFact (settingsGroup, _metaDataMap[cameraTriggerDistanceName]) + , _groundResolutionFact (settingsGroup, _metaDataMap[groundResolutionName]) + , _frontalOverlapFact (settingsGroup, _metaDataMap[frontalOverlapName]) + , _sideOverlapFact (settingsGroup, _metaDataMap[sideOverlapName]) + , _cameraSensorWidthFact (settingsGroup, _metaDataMap[cameraSensorWidthName]) + , _cameraSensorHeightFact (settingsGroup, _metaDataMap[cameraSensorHeightName]) + , _cameraResolutionWidthFact (settingsGroup, _metaDataMap[cameraResolutionWidthName]) + , _cameraResolutionHeightFact (settingsGroup, _metaDataMap[cameraResolutionHeightName]) + , _cameraFocalLengthFact (settingsGroup, _metaDataMap[cameraFocalLengthName]) + , _cameraOrientationLandscapeFact (settingsGroup, _metaDataMap[cameraOrientationLandscapeName]) + , _fixedValueIsAltitudeFact (settingsGroup, _metaDataMap[fixedValueIsAltitudeName]) + , _cameraFact (settingsGroup, _metaDataMap[cameraName]) { _editorQml = "qrc:/qml/SurveyItemEditor.qml"; - if (_metaDataMap.isEmpty()) { - _metaDataMap = FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/Survey.FactMetaData.json"), NULL /* metaDataParent */); - } - - _gridAltitudeFact.setRawValue(50); - _gridSpacingFact.setRawValue(30); - _turnaroundDistFact.setRawValue((_vehicle && _vehicle->multiRotor()) ? 0 : 60); - _cameraTriggerDistanceFact.setRawValue(25); - _groundResolutionFact.setRawValue(3); - _frontalOverlapFact.setRawValue(10); - _sideOverlapFact.setRawValue(10); - - _cameraSensorWidthFact.setRawValue(6.17); - _cameraSensorHeightFact.setRawValue(4.55); - _cameraResolutionWidthFact.setRawValue(4000); - _cameraResolutionHeightFact.setRawValue(3000); - _cameraFocalLengthFact.setRawValue(4.5); - - _gridAltitudeFact.setMetaData(_metaDataMap[_gridAltitudeFactName]); - _gridAngleFact.setMetaData(_metaDataMap[_gridAngleFactName]); - _gridSpacingFact.setMetaData(_metaDataMap[_gridSpacingFactName]); - _turnaroundDistFact.setMetaData(_metaDataMap[_turnaroundDistFactName]); - _cameraTriggerDistanceFact.setMetaData(_metaDataMap[_cameraTriggerDistanceFactName]); - _groundResolutionFact.setMetaData(_metaDataMap[_groundResolutionFactName]); - _frontalOverlapFact.setMetaData(_metaDataMap[_frontalOverlapFactName]); - _sideOverlapFact.setMetaData(_metaDataMap[_sideOverlapFactName]); - _cameraSensorWidthFact.setMetaData(_metaDataMap[_cameraSensorWidthFactName]); - _cameraSensorHeightFact.setMetaData(_metaDataMap[_cameraSensorHeightFactName]); - _cameraResolutionWidthFact.setMetaData(_metaDataMap[_cameraResolutionWidthFactName]); - _cameraResolutionHeightFact.setMetaData(_metaDataMap[_cameraResolutionHeightFactName]); - _cameraFocalLengthFact.setMetaData(_metaDataMap[_cameraFocalLengthFactName]); + if (_vehicle->multiRotor()) { + _turnaroundDistFact.setRawValue(0); + } connect(&_gridSpacingFact, &Fact::valueChanged, this, &SurveyMissionItem::_generateGrid); connect(&_gridAngleFact, &Fact::valueChanged, this, &SurveyMissionItem::_generateGrid); @@ -136,7 +115,7 @@ SurveyMissionItem::SurveyMissionItem(Vehicle* vehicle, QObject* parent) connect(&_cameraResolutionHeightFact, &Fact::valueChanged, this, &SurveyMissionItem::_cameraValueChanged); connect(&_cameraFocalLengthFact, &Fact::valueChanged, this, &SurveyMissionItem::_cameraValueChanged); - connect(this, &SurveyMissionItem::cameraTriggerChanged, this, &SurveyMissionItem::_cameraTriggerChanged); + connect(&_cameraTriggerFact, &Fact::valueChanged, this, &SurveyMissionItem::_cameraTriggerChanged); connect(&_cameraTriggerDistanceFact, &Fact::valueChanged, this, &SurveyMissionItem::timeBetweenShotsChanged); @@ -222,7 +201,7 @@ int SurveyMissionItem::lastSequenceNumber(void) const if (_gridPoints.count()) { lastSeq += _gridPoints.count() - 1; - if (_cameraTrigger) { + if (_cameraTriggerFact.rawValue().toBool()) { // Account for two trigger messages lastSeq += 2; } @@ -252,27 +231,27 @@ void SurveyMissionItem::save(QJsonObject& saveObject) const saveObject[JsonHelper::jsonVersionKey] = 3; saveObject[VisualMissionItem::jsonTypeKey] = VisualMissionItem::jsonTypeComplexItemValue; saveObject[ComplexMissionItem::jsonComplexItemTypeKey] = jsonComplexItemTypeValue; - saveObject[_jsonCameraTriggerKey] = _cameraTrigger; - saveObject[_jsonManualGridKey] = _manualGrid; - saveObject[_jsonFixedValueIsAltitudeKey] = _fixedValueIsAltitude; + saveObject[_jsonCameraTriggerKey] = _cameraTriggerFact.rawValue().toBool(); + saveObject[_jsonManualGridKey] = _manualGridFact.rawValue().toBool(); + saveObject[_jsonFixedValueIsAltitudeKey] = _fixedValueIsAltitudeFact.rawValue().toBool(); - if (_cameraTrigger) { + if (_cameraTriggerFact.rawValue().toBool()) { saveObject[_jsonCameraTriggerDistanceKey] = _cameraTriggerDistanceFact.rawValue().toDouble(); } QJsonObject gridObject; gridObject[_jsonGridAltitudeKey] = _gridAltitudeFact.rawValue().toDouble(); - gridObject[_jsonGridAltitudeRelativeKey] = _gridAltitudeRelative; + gridObject[_jsonGridAltitudeRelativeKey] = _gridAltitudeRelativeFact.rawValue().toBool(); gridObject[_jsonGridAngleKey] = _gridAngleFact.rawValue().toDouble(); gridObject[_jsonGridSpacingKey] = _gridSpacingFact.rawValue().toDouble(); gridObject[_jsonTurnaroundDistKey] = _turnaroundDistFact.rawValue().toDouble(); saveObject[_jsonGridObjectKey] = gridObject; - if (!_manualGrid) { + if (!_manualGridFact.rawValue().toBool()) { QJsonObject cameraObject; - cameraObject[_jsonCameraNameKey] = _camera; - cameraObject[_jsonCameraOrientationLandscapeKey] = _cameraOrientationLandscape; + cameraObject[_jsonCameraNameKey] = _cameraFact.rawValue().toString(); + cameraObject[_jsonCameraOrientationLandscapeKey] = _cameraOrientationLandscapeFact.rawValue().toBool(); cameraObject[_jsonCameraSensorWidthKey] = _cameraSensorWidthFact.rawValue().toDouble(); cameraObject[_jsonCameraSensorHeightKey] = _cameraSensorHeightFact.rawValue().toDouble(); cameraObject[_jsonCameraResolutionWidthKey] = _cameraResolutionWidthFact.rawValue().toDouble(); @@ -368,10 +347,10 @@ bool SurveyMissionItem::load(const QJsonObject& complexObject, int sequenceNumbe setSequenceNumber(sequenceNumber); - _manualGrid = v2Object[_jsonManualGridKey].toBool(true); - _cameraTrigger = v2Object[_jsonCameraTriggerKey].toBool(false); - _fixedValueIsAltitude = v2Object[_jsonFixedValueIsAltitudeKey].toBool(true); - _gridAltitudeRelative = v2Object[_jsonGridAltitudeRelativeKey].toBool(true); + _manualGridFact.setRawValue (v2Object[_jsonManualGridKey].toBool(true)); + _cameraTriggerFact.setRawValue (v2Object[_jsonCameraTriggerKey].toBool(false)); + _fixedValueIsAltitudeFact.setRawValue (v2Object[_jsonFixedValueIsAltitudeKey].toBool(true)); + _gridAltitudeRelativeFact.setRawValue (v2Object[_jsonGridAltitudeRelativeKey].toBool(true)); QList gridKeyInfoList = { { _jsonGridAltitudeKey, QJsonValue::Double, true }, @@ -389,7 +368,7 @@ bool SurveyMissionItem::load(const QJsonObject& complexObject, int sequenceNumbe _gridSpacingFact.setRawValue (gridObject[_jsonGridSpacingKey].toDouble()); _turnaroundDistFact.setRawValue (gridObject[_jsonTurnaroundDistKey].toDouble()); - if (_cameraTrigger) { + if (_cameraTriggerFact.rawValue().toBool()) { if (!v2Object.contains(_jsonCameraTriggerDistanceKey)) { errorString = tr("%1 but %2 is missing").arg("cameraTrigger = true").arg("cameraTriggerDistance"); return false; @@ -397,7 +376,7 @@ bool SurveyMissionItem::load(const QJsonObject& complexObject, int sequenceNumbe _cameraTriggerDistanceFact.setRawValue(v2Object[_jsonCameraTriggerDistanceKey].toDouble()); } - if (!_manualGrid) { + if (!_manualGridFact.rawValue().toBool()) { if (!v2Object.contains(_jsonCameraObjectKey)) { errorString = tr("%1 but %2 object is missing").arg("manualGrid = false").arg("camera"); return false; @@ -428,8 +407,8 @@ bool SurveyMissionItem::load(const QJsonObject& complexObject, int sequenceNumbe return false; } - _camera = cameraObject[_jsonCameraNameKey].toString(); - _cameraOrientationLandscape = cameraObject[_jsonCameraOrientationLandscapeKey].toBool(true); + _cameraFact.setRawValue(cameraObject[_jsonCameraNameKey].toString()); + _cameraOrientationLandscapeFact.setRawValue(cameraObject[_jsonCameraOrientationLandscapeKey].toBool(true)); _groundResolutionFact.setRawValue (cameraObject[_jsonGroundResolutionKey].toDouble()); _frontalOverlapFact.setRawValue (cameraObject[_jsonFrontalOverlapKey].toInt()); @@ -781,7 +760,7 @@ QmlObjectListModel* SurveyMissionItem::getMissionItems(void) const MissionItem* item = new MissionItem(seqNum++, // sequence number MAV_CMD_NAV_WAYPOINT, // MAV_CMD - _gridAltitudeRelative ? MAV_FRAME_GLOBAL_RELATIVE_ALT : MAV_FRAME_GLOBAL, // MAV_FRAME + _gridAltitudeRelativeFact.rawValue().toBool() ? MAV_FRAME_GLOBAL_RELATIVE_ALT : MAV_FRAME_GLOBAL, // MAV_FRAME 0.0, 0.0, 0.0, 0.0, // param 1-4 coord.latitude(), coord.longitude(), @@ -791,7 +770,7 @@ QmlObjectListModel* SurveyMissionItem::getMissionItems(void) const pMissionItems); // parent - allow delete on pMissionItems to delete everthing pMissionItems->append(item); - if (_cameraTrigger && i == 0) { + if (_cameraTriggerFact.rawValue().toBool() && i == 0) { // Turn on camera MissionItem* item = new MissionItem(seqNum++, // sequence number MAV_CMD_DO_SET_CAM_TRIGG_DIST, // MAV_CMD @@ -805,7 +784,7 @@ QmlObjectListModel* SurveyMissionItem::getMissionItems(void) const } } - if (_cameraTrigger) { + if (_cameraTriggerFact.rawValue().toBool()) { // Turn off camera MissionItem* item = new MissionItem(seqNum++, // sequence number MAV_CMD_DO_SET_CAM_TRIGG_DIST, // MAV_CMD @@ -832,7 +811,7 @@ void SurveyMissionItem::_cameraTriggerChanged(void) int SurveyMissionItem::cameraShots(void) const { - return _cameraTrigger ? _cameraShots : 0; + return _cameraTriggerFact.rawValue().toBool() ? _cameraShots : 0; } void SurveyMissionItem::_cameraValueChanged(void) diff --git a/src/MissionManager/SurveyMissionItem.h b/src/MissionManager/SurveyMissionItem.h index 303222ff9..cb00ec5ce 100644 --- a/src/MissionManager/SurveyMissionItem.h +++ b/src/MissionManager/SurveyMissionItem.h @@ -13,7 +13,7 @@ #include "ComplexMissionItem.h" #include "MissionItem.h" -#include "Fact.h" +#include "SettingsFact.h" #include "QGCLoggingCategory.h" Q_DECLARE_LOGGING_CATEGORY(SurveyMissionItemLog) @@ -26,11 +26,11 @@ public: SurveyMissionItem(Vehicle* vehicle, QObject* parent = NULL); Q_PROPERTY(Fact* gridAltitude READ gridAltitude CONSTANT) - Q_PROPERTY(bool gridAltitudeRelative MEMBER _gridAltitudeRelative NOTIFY gridAltitudeRelativeChanged) + Q_PROPERTY(Fact* gridAltitudeRelative READ gridAltitudeRelative CONSTANT) Q_PROPERTY(Fact* gridAngle READ gridAngle CONSTANT) Q_PROPERTY(Fact* gridSpacing READ gridSpacing CONSTANT) Q_PROPERTY(Fact* turnaroundDist READ turnaroundDist CONSTANT) - Q_PROPERTY(bool cameraTrigger MEMBER _cameraTrigger NOTIFY cameraTriggerChanged) + Q_PROPERTY(Fact* cameraTrigger READ cameraTrigger CONSTANT) Q_PROPERTY(Fact* cameraTriggerDistance READ cameraTriggerDistance CONSTANT) Q_PROPERTY(Fact* groundResolution READ groundResolution CONSTANT) Q_PROPERTY(Fact* frontalOverlap READ frontalOverlap CONSTANT) @@ -40,15 +40,16 @@ public: Q_PROPERTY(Fact* cameraResolutionWidth READ cameraResolutionWidth CONSTANT) Q_PROPERTY(Fact* cameraResolutionHeight READ cameraResolutionHeight CONSTANT) Q_PROPERTY(Fact* cameraFocalLength READ cameraFocalLength CONSTANT) + Q_PROPERTY(Fact* fixedValueIsAltitude READ fixedValueIsAltitude CONSTANT) + Q_PROPERTY(Fact* cameraOrientationLandscape READ cameraOrientationLandscape CONSTANT) + Q_PROPERTY(Fact* manualGrid READ manualGrid CONSTANT) + Q_PROPERTY(Fact* camera READ camera CONSTANT) + + Q_PROPERTY(double timeBetweenShots READ timeBetweenShots NOTIFY timeBetweenShotsChanged) Q_PROPERTY(QVariantList polygonPath READ polygonPath NOTIFY polygonPathChanged) Q_PROPERTY(QVariantList gridPoints READ gridPoints NOTIFY gridPointsChanged) Q_PROPERTY(int cameraShots READ cameraShots NOTIFY cameraShotsChanged) Q_PROPERTY(double coveredArea READ coveredArea NOTIFY coveredAreaChanged) - Q_PROPERTY(bool fixedValueIsAltitude MEMBER _fixedValueIsAltitude NOTIFY fixedValueIsAltitudeChanged) - Q_PROPERTY(bool cameraOrientationLandscape MEMBER _cameraOrientationLandscape NOTIFY cameraOrientationLandscapeChanged) - Q_PROPERTY(bool manualGrid MEMBER _manualGrid NOTIFY manualGridChanged) - Q_PROPERTY(QString camera MEMBER _camera NOTIFY cameraChanged) - Q_PROPERTY(double timeBetweenShots READ timeBetweenShots NOTIFY timeBetweenShotsChanged) Q_INVOKABLE void clearPolygon(void); Q_INVOKABLE void addPolygonCoordinate(const QGeoCoordinate coordinate); @@ -57,10 +58,13 @@ public: QVariantList polygonPath(void) { return _polygonPath; } QVariantList gridPoints (void) { return _gridPoints; } + Fact* manualGrid (void) { return &_manualGridFact; } Fact* gridAltitude (void) { return &_gridAltitudeFact; } + Fact* gridAltitudeRelative (void) { return &_gridAltitudeRelativeFact; } Fact* gridAngle (void) { return &_gridAngleFact; } Fact* gridSpacing (void) { return &_gridSpacingFact; } Fact* turnaroundDist (void) { return &_turnaroundDistFact; } + Fact* cameraTrigger (void) { return &_cameraTriggerFact; } Fact* cameraTriggerDistance (void) { return &_cameraTriggerDistanceFact; } Fact* groundResolution (void) { return &_groundResolutionFact; } Fact* frontalOverlap (void) { return &_frontalOverlapFact; } @@ -70,6 +74,9 @@ public: Fact* cameraResolutionWidth (void) { return &_cameraResolutionWidthFact; } Fact* cameraResolutionHeight (void) { return &_cameraResolutionHeightFact; } Fact* cameraFocalLength (void) { return &_cameraFocalLengthFact; } + Fact* cameraOrientationLandscape(void) { return &_cameraOrientationLandscapeFact; } + Fact* fixedValueIsAltitude (void) { return &_fixedValueIsAltitudeFact; } + Fact* camera (void) { return &_cameraFact; } int cameraShots(void) const; double coveredArea(void) const { return _coveredArea; } @@ -100,8 +107,8 @@ public: int sequenceNumber (void) const final { return _sequenceNumber; } double flightSpeed (void) final { return std::numeric_limits::quiet_NaN(); } - bool coordinateHasRelativeAltitude (void) const final { return _gridAltitudeRelative; } - bool exitCoordinateHasRelativeAltitude (void) const final { return _gridAltitudeRelative; } + bool coordinateHasRelativeAltitude (void) const final { return _gridAltitudeRelativeFact.rawValue().toBool(); } + bool exitCoordinateHasRelativeAltitude (void) const final { return _gridAltitudeRelativeFact.rawValue().toBool(); } bool exitCoordinateSameAsEntry (void) const final { return false; } void setDirty (bool dirty) final; @@ -112,22 +119,35 @@ public: static const char* jsonComplexItemTypeValue; + static const char* settingsGroup; + static const char* manualGridName; + static const char* gridAltitudeName; + static const char* gridAltitudeRelativeName; + static const char* gridAngleName; + static const char* gridSpacingName; + static const char* turnaroundDistName; + static const char* cameraTriggerDistanceName; + static const char* groundResolutionName; + static const char* frontalOverlapName; + static const char* sideOverlapName; + static const char* cameraSensorWidthName; + static const char* cameraSensorHeightName; + static const char* cameraResolutionWidthName; + static const char* cameraResolutionHeightName; + static const char* cameraFocalLengthName; + static const char* cameraTriggerName; + static const char* cameraOrientationLandscapeName; + static const char* fixedValueIsAltitudeName; + static const char* cameraName; + signals: - void polygonPathChanged (void); - void altitudeChanged (double altitude); - void gridAngleChanged (double gridAngle); - void gridPointsChanged (void); - void cameraTriggerChanged (bool cameraTrigger); - void gridAltitudeRelativeChanged (bool gridAltitudeRelative); - void cameraShotsChanged (int cameraShots); - void coveredAreaChanged (double coveredArea); - void cameraValueChanged (void); - void fixedValueIsAltitudeChanged (bool fixedValueIsAltitude); - void gridTypeChanged (QString gridType); - void cameraOrientationLandscapeChanged (bool cameraOrientationLandscape); - void cameraChanged (QString camera); - void manualGridChanged (bool manualGrid); - void timeBetweenShotsChanged (void); + void polygonPathChanged (void); + void gridPointsChanged (void); + void cameraShotsChanged (int cameraShots); + void coveredAreaChanged (double coveredArea); + void cameraValueChanged (void); + void gridTypeChanged (QString gridType); + void timeBetweenShotsChanged (void); private slots: void _cameraTriggerChanged(void); @@ -155,12 +175,6 @@ private: QGeoCoordinate _coordinate; QGeoCoordinate _exitCoordinate; double _altitude; - bool _cameraTrigger; - bool _gridAltitudeRelative; - bool _manualGrid; - QString _camera; - bool _cameraOrientationLandscape; - bool _fixedValueIsAltitude; double _surveyDistance; int _cameraShots; @@ -168,21 +182,27 @@ private: double _timeBetweenShots; double _cruiseSpeed; - Fact _gridAltitudeFact; - Fact _gridAngleFact; - Fact _gridSpacingFact; - Fact _turnaroundDistFact; - Fact _cameraTriggerDistanceFact; - Fact _groundResolutionFact; - Fact _frontalOverlapFact; - Fact _sideOverlapFact; - Fact _cameraSensorWidthFact; - Fact _cameraSensorHeightFact; - Fact _cameraResolutionWidthFact; - Fact _cameraResolutionHeightFact; - Fact _cameraFocalLengthFact; - - static QMap _metaDataMap; + QMap _metaDataMap; + + SettingsFact _manualGridFact; + SettingsFact _gridAltitudeFact; + SettingsFact _gridAltitudeRelativeFact; + SettingsFact _gridAngleFact; + SettingsFact _gridSpacingFact; + SettingsFact _turnaroundDistFact; + SettingsFact _cameraTriggerFact; + SettingsFact _cameraTriggerDistanceFact; + SettingsFact _groundResolutionFact; + SettingsFact _frontalOverlapFact; + SettingsFact _sideOverlapFact; + SettingsFact _cameraSensorWidthFact; + SettingsFact _cameraSensorHeightFact; + SettingsFact _cameraResolutionWidthFact; + SettingsFact _cameraResolutionHeightFact; + SettingsFact _cameraFocalLengthFact; + SettingsFact _cameraOrientationLandscapeFact; + SettingsFact _fixedValueIsAltitudeFact; + SettingsFact _cameraFact; static const char* _jsonPolygonObjectKey; static const char* _jsonGridObjectKey; @@ -206,20 +226,6 @@ private: static const char* _jsonCameraNameKey; static const char* _jsonCameraOrientationLandscapeKey; static const char* _jsonFixedValueIsAltitudeKey; - - static const char* _gridAltitudeFactName; - static const char* _gridAngleFactName; - static const char* _gridSpacingFactName; - static const char* _turnaroundDistFactName; - static const char* _cameraTriggerDistanceFactName; - static const char* _groundResolutionFactName; - static const char* _frontalOverlapFactName; - static const char* _sideOverlapFactName; - static const char* _cameraSensorWidthFactName; - static const char* _cameraSensorHeightFactName; - static const char* _cameraResolutionWidthFactName; - static const char* _cameraResolutionHeightFactName; - static const char* _cameraFocalLengthFactName; }; #endif -- 2.22.0