diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index cd15835b5544319c252d1bfa7f1028f87b528002..24767838277cdefbf333863a04a94b560d7f57f7 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -449,6 +449,7 @@ HEADERS += \ src/JsonHelper.h \ src/LogCompressor.h \ src/MG.h \ + src/MissionManager/CameraSection.h \ src/MissionManager/ComplexMissionItem.h \ src/MissionManager/FixedWingLandingComplexItem.h \ src/MissionManager/GeoFenceController.h \ @@ -626,6 +627,7 @@ SOURCES += \ src/Joystick/JoystickManager.cc \ src/JsonHelper.cc \ src/LogCompressor.cc \ + src/MissionManager/CameraSection.cc \ src/MissionManager/ComplexMissionItem.cc \ src/MissionManager/FixedWingLandingComplexItem.cc \ src/MissionManager/GeoFenceController.cc \ diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc index 2b8bff4655ee0f44e7d7bf323a6961fa191b0366..a9e7c8e9853bbfba734cb44aa4b0b2795410f3a2 100644 --- a/qgroundcontrol.qrc +++ b/qgroundcontrol.qrc @@ -49,6 +49,7 @@ src/VehicleSetup/PX4FlowSensor.qml src/AnalyzeView/AnalyzePage.qml src/QmlControls/AppMessages.qml + src/MissionEditor/CameraSection.qml src/QmlControls/ClickableColor.qml src/QmlControls/DropButton.qml src/QmlControls/ExclusiveGroupItem.qml @@ -192,6 +193,7 @@ src/MissionManager/RallyPoint.FactMetaData.json src/MissionManager/FWLandingPattern.FactMetaData.json src/comm/USBBoardInfo.json + src/MissionManager/CameraSection.FactMetaData.json src/MissionManager/MissionSettings.FactMetaData.json src/Vehicle/VehicleFact.json src/Vehicle/BatteryFact.json diff --git a/src/MissionEditor/CameraSection.qml b/src/MissionEditor/CameraSection.qml new file mode 100644 index 0000000000000000000000000000000000000000..602f57718884c1a947fc48fe202dcdce3d38f6dc --- /dev/null +++ b/src/MissionEditor/CameraSection.qml @@ -0,0 +1,108 @@ +import QtQuick 2.3 +import QtQuick.Controls 1.2 +import QtQuick.Layouts 1.2 + +import QGroundControl 1.0 +import QGroundControl.ScreenTools 1.0 +import QGroundControl.Controls 1.0 +import QGroundControl.FactControls 1.0 +import QGroundControl.Palette 1.0 + +// Camera section for mission item editors +Column { + anchors.left: parent.left + anchors.right: parent.right + spacing: _margin + + property alias exclusiveGroup: cameraSectionHeader.exclusiveGroup + property alias showSpacer: cameraSectionHeader.showSpacer + property alias checked: cameraSectionHeader.checked + + property var _camera: missionItem.cameraSection + property real _fieldWidth: ScreenTools.defaultFontPixelWidth * 16 + property real _margin: ScreenTools.defaultFontPixelWidth / 2 + + SectionHeader { + id: cameraSectionHeader + text: qsTr("Camera") + checked: false + } + + Column { + anchors.left: parent.left + anchors.right: parent.right + spacing: _margin + visible: cameraSectionHeader.checked + + FactComboBox { + id: cameraActionCombo + anchors.left: parent.left + anchors.right: parent.right + fact: _camera.cameraAction + indexModel: false + } + + RowLayout { + anchors.left: parent.left + anchors.right: parent.right + spacing: ScreenTools.defaultFontPixelWidth + visible: cameraActionCombo.currentIndex == 1 + + QGCLabel { + text: qsTr("Time") + Layout.fillWidth: true + } + FactTextField { + fact: _camera.cameraPhotoIntervalTime + Layout.preferredWidth: _fieldWidth + } + } + + RowLayout { + anchors.left: parent.left + anchors.right: parent.right + spacing: ScreenTools.defaultFontPixelWidth + visible: cameraActionCombo.currentIndex == 2 + + QGCLabel { + text: qsTr("Distance") + Layout.fillWidth: true + } + FactTextField { + fact: _camera.cameraPhotoIntervalDistance + Layout.preferredWidth: _fieldWidth + } + } + + GridLayout { + anchors.left: parent.left + anchors.right: parent.right + columnSpacing: ScreenTools.defaultFontPixelWidth / 2 + rowSpacing: 0 + columns: 3 + + Item { width: 1; height: 1 } + QGCLabel { text: qsTr("Pitch") } + QGCLabel { text: qsTr("Yaw") } + + QGCCheckBox { + id: gimbalCheckBox + text: qsTr("Gimbal") + checked: _camera.specifyGimbal + onClicked: _camera.specifyGimbal = checked + Layout.fillWidth: true + } + FactTextField { + fact: _camera.gimbalPitch + implicitWidth: ScreenTools.defaultFontPixelWidth * 9 + enabled: gimbalCheckBox.checked + } + + FactTextField { + fact: _camera.gimbalYaw + implicitWidth: ScreenTools.defaultFontPixelWidth * 9 + enabled: gimbalCheckBox.checked + } + } + } +} diff --git a/src/MissionEditor/MissionEditor.qml b/src/MissionEditor/MissionEditor.qml index 77e218b1a2b5e600878e76e985ae340c73a57b65..efc0a33c37f2622690a294eecb79132f08540684 100644 --- a/src/MissionEditor/MissionEditor.qml +++ b/src/MissionEditor/MissionEditor.qml @@ -579,7 +579,7 @@ QGCView { spacing: _margin / 2 orientation: ListView.Vertical model: missionController.visualItems - cacheBuffer: height * 2 + cacheBuffer: Math.max(height * 2, 0) clip: true currentIndex: _currentMissionIndex highlightMoveDuration: 250 diff --git a/src/MissionEditor/MissionSettingsEditor.qml b/src/MissionEditor/MissionSettingsEditor.qml index a2af6bbeb71b733449ff55a2b6f281321f85326f..2c532ab5b008171ecbbf1009357473c436b8166c 100644 --- a/src/MissionEditor/MissionSettingsEditor.qml +++ b/src/MissionEditor/MissionSettingsEditor.qml @@ -19,12 +19,6 @@ Rectangle { visible: missionItem.isCurrentItem radius: _radius - ExclusiveGroup { - id: sectionHeaderExclusiverGroup - } - - property ExclusiveGroup sectionHeaderGroup: ScreenTools.isShortScreen ? sectionHeaderExclusiverGroup : null - Loader { id: deferedload active: valuesRect.visible @@ -64,7 +58,6 @@ Rectangle { id: plannedHomePositionSection text: qsTr("Planned Home Position") showSpacer: false - exclusiveGroup: sectionHeaderGroup } Column { @@ -125,7 +118,6 @@ Rectangle { text: qsTr("Vehicle Info") visible: _multipleFirmware && _showOfflineEditingCombos checked: false - exclusiveGroup: sectionHeaderGroup } GridLayout { @@ -183,7 +175,6 @@ Rectangle { id: missionDefaultsSectionHeader text: qsTr("Mission Defaults") checked: false - exclusiveGroup: sectionHeaderGroup } Column { @@ -233,89 +224,8 @@ Rectangle { */ } - SectionHeader { - id: cameraSectionHeader - text: qsTr("Camera") - checked: false - exclusiveGroup: sectionHeaderGroup - } - - Column { - anchors.left: parent.left - anchors.right: parent.right - spacing: _margin - visible: cameraSectionHeader.checked - - FactComboBox { - id: cameraActionCombo - anchors.left: parent.left - anchors.right: parent.right - fact: missionItem.cameraAction - indexModel: false - } - - RowLayout { - anchors.left: parent.left - anchors.right: parent.right - spacing: ScreenTools.defaultFontPixelWidth - visible: cameraActionCombo.currentIndex == 1 - - QGCLabel { - text: qsTr("Time") - Layout.fillWidth: true - } - FactTextField { - fact: missionItem.cameraPhotoIntervalTime - Layout.preferredWidth: _fieldWidth - } - } - - RowLayout { - anchors.left: parent.left - anchors.right: parent.right - spacing: ScreenTools.defaultFontPixelWidth - visible: cameraActionCombo.currentIndex == 2 - - QGCLabel { - text: qsTr("Distance") - Layout.fillWidth: true - } - FactTextField { - fact: missionItem.cameraPhotoIntervalDistance - Layout.preferredWidth: _fieldWidth - } - } - - GridLayout { - anchors.left: parent.left - anchors.right: parent.right - columnSpacing: 0 - rowSpacing: 0 - columns: 3 - - Item { width: 1; height: 1 } - QGCLabel { text: qsTr("Pitch") } - QGCLabel { text: qsTr("Yaw") } - - QGCCheckBox { - id: gimbalCheckBox - text: qsTr("Gimbal") - checked: missionItem.specifyGimbal - onClicked: missionItem.specifyGimbal = checked - Layout.fillWidth: true - } - FactTextField { - fact: missionItem.gimbalPitch - implicitWidth: ScreenTools.defaultFontPixelWidth * 9 - enabled: gimbalCheckBox.checked - } - - FactTextField { - fact: missionItem.gimbalYaw - implicitWidth: ScreenTools.defaultFontPixelWidth * 9 - enabled: gimbalCheckBox.checked - } - } + CameraSection { + checked: missionItem.cameraSection.settingsSpecified } QGCLabel { diff --git a/src/MissionEditor/SectionHeader.qml b/src/MissionEditor/SectionHeader.qml index 36beba4459251cd780dabb2ab45cdbe3c9e1cad0..f39ce133b532b8ef47f6a59b0d0703d7e41ecee4 100644 --- a/src/MissionEditor/SectionHeader.qml +++ b/src/MissionEditor/SectionHeader.qml @@ -1,6 +1,7 @@ import QtQuick 2.3 import QtQuick.Controls 1.2 import QtQuick.Layouts 1.2 +import QtGraphicalEffects 1.0 import QGroundControl.ScreenTools 1.0 import QGroundControl.Palette 1.0 @@ -41,10 +42,14 @@ QGCMouseArea { id: label Layout.fillWidth: true - Image { + QGCColoredImage { + id: image + width: label.height / 2 + height: width anchors.right: parent.right anchors.verticalCenter: parent.verticalCenter source: "/qmlimages/arrow-down.png" + color: qgcPal.text visible: !_root.checked } } diff --git a/src/MissionEditor/SimpleItemEditor.qml b/src/MissionEditor/SimpleItemEditor.qml index 8ce994eeef98e01c1062d8374ded6871edf4a892..6f33ee3f2b18a39f6528d68b88f9a9bae5d355d8 100644 --- a/src/MissionEditor/SimpleItemEditor.qml +++ b/src/MissionEditor/SimpleItemEditor.qml @@ -27,6 +27,7 @@ Rectangle { anchors.left: valuesRect.left anchors.right: valuesRect.right anchors.top: valuesRect.top + sourceComponent: Component { Item { id: valuesItem @@ -114,6 +115,11 @@ Rectangle { fact: object } } + + CameraSection { + checked: missionItem.cameraSection.settingsSpecified + visible: missionItem.cameraSection.available + } } // Column } // Item } // Component diff --git a/src/MissionManager/CameraSection.FactMetaData.json b/src/MissionManager/CameraSection.FactMetaData.json new file mode 100644 index 0000000000000000000000000000000000000000..d60c7243f7f7b0c423d4d9a049a64751a516ba37 --- /dev/null +++ b/src/MissionManager/CameraSection.FactMetaData.json @@ -0,0 +1,48 @@ +[ +{ + "name": "CameraAction", + "shortDescription": "Specify whether the camera should take photos or video", + "type": "uint32", + "enumStrings": "Continue current action,Take photos (time),Take photos (distance),Take video", + "enumValues": "0,1,2,3", + "defaultValue": 0 +}, +{ + "name": "CameraPhotoIntervalDistance", + "shortDescription": "Specify the distance between each photo", + "type": "double", + "units": "m", + "min": 0, + "decimalPlaces": 1, + "defaultValue": 1 +}, +{ + "name": "CameraPhotoIntervalTime", + "shortDescription": "Specify the time between each photo", + "type": "uint32", + "units": "secs", + "min": 1, + "decimalPlaces": 0, + "defaultValue": 10 +}, +{ + "name": "GimbalPitch", + "shortDescription": "Gimbal pitch rotation.", + "type": "double", + "units": "deg", + "min": 0.0, + "max": 360.0, + "decimalPlaces": 0, + "defaultValue": 0 +}, +{ + "name": "GimbalYaw", + "shortDescription": "Gimbal yaw rotation.", + "type": "double", + "units": "deg", + "min": 0.0, + "max": 360.0, + "decimalPlaces": 0, + "defaultValue": 0 +} +] diff --git a/src/MissionManager/CameraSection.cc b/src/MissionManager/CameraSection.cc new file mode 100644 index 0000000000000000000000000000000000000000..ef20d26270ccccf49d0a73175c8abb310d44ab68 --- /dev/null +++ b/src/MissionManager/CameraSection.cc @@ -0,0 +1,256 @@ +/**************************************************************************** + * + * (c) 2009-2016 QGROUNDCONTROL PROJECT + * + * QGroundControl is licensed according to the terms in the file + * COPYING.md in the root of the source code directory. + * + ****************************************************************************/ + +#include "CameraSection.h" +#include "SimpleMissionItem.h" + +QGC_LOGGING_CATEGORY(CameraSectionLog, "CameraSectionLog") + +const char* CameraSection::_gimbalPitchName = "GimbalPitch"; +const char* CameraSection::_gimbalYawName = "GimbalYaw"; +const char* CameraSection::_cameraActionName = "CameraAction"; +const char* CameraSection::_cameraPhotoIntervalDistanceName = "CameraPhotoIntervalDistance"; +const char* CameraSection::_cameraPhotoIntervalTimeName = "CameraPhotoIntervalTime"; + +QMap CameraSection::_metaDataMap; + +CameraSection::CameraSection(QObject* parent) + : QObject(parent) + , _available(false) + , _settingsSpecified(false) + , _specifyGimbal(false) + , _gimbalYawFact (0, _gimbalYawName, FactMetaData::valueTypeDouble) + , _gimbalPitchFact (0, _gimbalPitchName, FactMetaData::valueTypeDouble) + , _cameraActionFact (0, _cameraActionName, FactMetaData::valueTypeDouble) + , _cameraPhotoIntervalDistanceFact (0, _cameraPhotoIntervalDistanceName, FactMetaData::valueTypeDouble) + , _cameraPhotoIntervalTimeFact (0, _cameraPhotoIntervalTimeName, FactMetaData::valueTypeUint32) + , _dirty(false) +{ + if (_metaDataMap.isEmpty()) { + _metaDataMap = FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/CameraSection.FactMetaData.json"), NULL /* metaDataParent */); + } + + _gimbalPitchFact.setMetaData (_metaDataMap[_gimbalPitchName]); + _gimbalYawFact.setMetaData (_metaDataMap[_gimbalYawName]); + _cameraActionFact.setMetaData (_metaDataMap[_cameraActionName]); + _cameraPhotoIntervalDistanceFact.setMetaData (_metaDataMap[_cameraPhotoIntervalDistanceName]); + _cameraPhotoIntervalTimeFact.setMetaData (_metaDataMap[_cameraPhotoIntervalTimeName]); + + _gimbalPitchFact.setRawValue (_gimbalPitchFact.rawDefaultValue()); + _gimbalYawFact.setRawValue (_gimbalYawFact.rawDefaultValue()); + _cameraActionFact.setRawValue (_cameraActionFact.rawDefaultValue()); + _cameraPhotoIntervalDistanceFact.setRawValue (_cameraPhotoIntervalDistanceFact.rawDefaultValue()); + _cameraPhotoIntervalTimeFact.setRawValue (_cameraPhotoIntervalTimeFact.rawDefaultValue()); + + connect(this, &CameraSection::specifyGimbalChanged, this, &CameraSection::_setDirtyAndUpdateMissionItemCount); + connect(&_cameraActionFact, &Fact::valueChanged, this, &CameraSection::_setDirtyAndUpdateMissionItemCount); + + connect(&_gimbalPitchFact, &Fact::valueChanged, this, &CameraSection::_setDirty); + connect(&_gimbalYawFact, &Fact::valueChanged, this, &CameraSection::_setDirty); + connect(&_cameraPhotoIntervalDistanceFact, &Fact::valueChanged, this, &CameraSection::_setDirty); + connect(&_cameraPhotoIntervalTimeFact, &Fact::valueChanged, this, &CameraSection::_setDirty); +} + +void CameraSection::setSpecifyGimbal(bool specifyGimbal) +{ + if (specifyGimbal != _specifyGimbal) { + _specifyGimbal = specifyGimbal; + emit specifyGimbalChanged(specifyGimbal); + } +} + +int CameraSection::missionItemCount(void) const +{ + int itemCount = 0; + + if (_specifyGimbal) { + itemCount++; + } + if (_cameraActionFact.rawValue().toInt() != CameraActionNone) { + itemCount++; + } + + return itemCount; +} + +void CameraSection::setDirty(bool dirty) +{ + if (_dirty != dirty) { + _dirty = dirty; + emit dirtyChanged(_dirty); + } +} + +void CameraSection::appendMissionItems(QList& items, QObject* missionItemParent, int nextSequenceNumber) +{ + // IMPORTANT NOTE: If anything changes here you must also change CameraSection::scanForMissionSettings + + if (_specifyGimbal) { + MissionItem* item = new MissionItem(nextSequenceNumber++, + MAV_CMD_DO_MOUNT_CONTROL, + MAV_FRAME_MISSION, + _gimbalPitchFact.rawValue().toDouble(), + 0, // Gimbal roll + _gimbalYawFact.rawValue().toDouble(), + 0, 0, 0, // param 4-6 not used + MAV_MOUNT_MODE_MAVLINK_TARGETING, + true, // autoContinue + false, // isCurrentItem + missionItemParent); + items.append(item); + } + + if (_cameraActionFact.rawValue().toInt() != CameraActionNone) { + MissionItem* item = NULL; + + switch (_cameraActionFact.rawValue().toInt()) { + case TakePhotosIntervalTime: + item = new MissionItem(nextSequenceNumber++, + MAV_CMD_IMAGE_START_CAPTURE, + MAV_FRAME_MISSION, + _cameraPhotoIntervalTimeFact.rawValue().toInt(), // Interval + 0, // Unlimited photo count + -1, // Max resolution + 0, 0, // param 4-5 not used + 0, // Camera ID + 0, // param 7 not used + true, // autoContinue + false, // isCurrentItem + missionItemParent); + break; + + case TakePhotoIntervalDistance: + item = new MissionItem(nextSequenceNumber++, + MAV_CMD_DO_SET_CAM_TRIGG_DIST, + MAV_FRAME_MISSION, + _cameraPhotoIntervalDistanceFact.rawValue().toDouble(), // Trigger distance + 0, 0, 0, 0, 0, 0, // param 2-7 not used + true, // autoContinue + false, // isCurrentItem + missionItemParent); + break; + + case TakeVideo: + item = new MissionItem(nextSequenceNumber++, + MAV_CMD_VIDEO_START_CAPTURE, + MAV_FRAME_MISSION, + 0, // Camera ID + -1, // Max fps + -1, // Max resolution + 0, 0, 0, 0, // param 5-7 not used + true, // autoContinue + false, // isCurrentItem + missionItemParent); + break; + } + if (item) { + items.append(item); + } + } +} + +bool CameraSection::scanForCameraSection(QmlObjectListModel* visualItems, int scanIndex) +{ + bool foundGimbal = false; + bool foundCameraAction = false; + bool stopLooking = false; + + qCDebug(CameraSectionLog) << "CameraSection::scanForCameraSection" << visualItems->count() << scanIndex; + + // Scan through the initial mission items for possible mission settings + + while (!stopLooking && visualItems->count() > scanIndex) { + SimpleMissionItem* item = visualItems->value(scanIndex); + if (!item) { + // We hit a complex item there can be no more possible mission settings + return foundGimbal || foundCameraAction; + } + MissionItem& missionItem = item->missionItem(); + + qCDebug(CameraSectionLog) << item->command() << missionItem.param1() << missionItem.param2() << missionItem.param3() << missionItem.param4() << missionItem.param5() << missionItem.param6() << missionItem.param7() ; + + // See CameraSection::appendMissionItems for specs on what compomises a known camera section item + + switch ((MAV_CMD)item->command()) { + case MAV_CMD_DO_MOUNT_CONTROL: + if (!foundGimbal && missionItem.param2() == 0 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == MAV_MOUNT_MODE_MAVLINK_TARGETING) { + foundGimbal = true; + setSpecifyGimbal(true); + gimbalPitch()->setRawValue(missionItem.param1()); + gimbalYaw()->setRawValue(missionItem.param3()); + visualItems->removeAt(scanIndex)->deleteLater(); + } else { + stopLooking = true; + } + break; + + case MAV_CMD_IMAGE_START_CAPTURE: + if (!foundCameraAction && missionItem.param1() != 0 && missionItem.param2() == 0 && missionItem.param3() == -1 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) { + foundCameraAction = true; + cameraAction()->setRawValue(TakePhotosIntervalTime); + cameraPhotoIntervalTime()->setRawValue(missionItem.param1()); + visualItems->removeAt(scanIndex)->deleteLater(); + } else { + stopLooking = true; + } + break; + + case MAV_CMD_DO_SET_CAM_TRIGG_DIST: + if (!foundCameraAction && missionItem.param1() != 0 && missionItem.param2() == 0 && missionItem.param3() == 0 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) { + foundCameraAction = true; + cameraAction()->setRawValue(TakePhotoIntervalDistance); + cameraPhotoIntervalDistance()->setRawValue(missionItem.param1()); + visualItems->removeAt(scanIndex)->deleteLater(); + } else { + stopLooking = true; + } + break; + + case MAV_CMD_VIDEO_START_CAPTURE: + if (!foundCameraAction && missionItem.param1() == 0 && missionItem.param2() == -1 && missionItem.param3() == -1 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) { + foundCameraAction = true; + cameraAction()->setRawValue(TakeVideo); + visualItems->removeAt(scanIndex)->deleteLater(); + } else { + stopLooking = true; + } + break; + + default: + stopLooking = true; + break; + } + } + + qCDebug(CameraSectionLog) << foundGimbal << foundCameraAction; + + _settingsSpecified = foundGimbal || foundCameraAction; + emit settingsSpecifiedChanged(_settingsSpecified); + + return foundGimbal || foundCameraAction; +} + +void CameraSection::_setDirty(void) +{ + setDirty(true); +} + +void CameraSection::_setDirtyAndUpdateMissionItemCount(void) +{ + emit missionItemCountChanged(missionItemCount()); + setDirty(true); +} + +void CameraSection::setAvailable(bool available) +{ + if (_available != available) { + _available = available; + emit availableChanged(available); + } +} diff --git a/src/MissionManager/CameraSection.h b/src/MissionManager/CameraSection.h new file mode 100644 index 0000000000000000000000000000000000000000..902e48dee25b2150ef80f3f68c34e99f23edee99 --- /dev/null +++ b/src/MissionManager/CameraSection.h @@ -0,0 +1,103 @@ +/**************************************************************************** + * + * (c) 2009-2016 QGROUNDCONTROL PROJECT + * + * QGroundControl is licensed according to the terms in the file + * COPYING.md in the root of the source code directory. + * + ****************************************************************************/ + +#ifndef CameraSection_H +#define CameraSection_H + +#include "ComplexMissionItem.h" +#include "MissionItem.h" +#include "Fact.h" + +Q_DECLARE_LOGGING_CATEGORY(CameraSectionLog) + +class CameraSection : public QObject +{ + Q_OBJECT + +public: + CameraSection(QObject* parent = NULL); + + enum CameraAction { + CameraActionNone, + TakePhotosIntervalTime, + TakePhotoIntervalDistance, + TakeVideo + }; + Q_ENUMS(CameraAction) + + Q_PROPERTY(bool available READ available WRITE setAvailable NOTIFY availableChanged) + Q_PROPERTY(bool settingsSpecified MEMBER _settingsSpecified NOTIFY settingsSpecifiedChanged) + Q_PROPERTY(bool specifyGimbal READ specifyGimbal WRITE setSpecifyGimbal NOTIFY specifyGimbalChanged) + Q_PROPERTY(Fact* gimbalPitch READ gimbalPitch CONSTANT) + Q_PROPERTY(Fact* gimbalYaw READ gimbalYaw CONSTANT) + Q_PROPERTY(Fact* cameraAction READ cameraAction CONSTANT) + Q_PROPERTY(Fact* cameraPhotoIntervalTime READ cameraPhotoIntervalTime CONSTANT) + Q_PROPERTY(Fact* cameraPhotoIntervalDistance READ cameraPhotoIntervalDistance CONSTANT) + + bool available (void) const { return _available; } + void setAvailable (bool available); + bool specifyGimbal (void) const { return _specifyGimbal; } + Fact* gimbalYaw (void) { return &_gimbalYawFact; } + Fact* gimbalPitch (void) { return &_gimbalPitchFact; } + Fact* cameraAction (void) { return &_cameraActionFact; } + Fact* cameraPhotoIntervalTime (void) { return &_cameraPhotoIntervalTimeFact; } + Fact* cameraPhotoIntervalDistance (void) { return &_cameraPhotoIntervalDistanceFact; } + + /// Scans the loaded items for the section items + /// @param visualItems Item list + /// @param scanIndex Index to start scanning from + /// @return true: camera section found + bool scanForCameraSection(QmlObjectListModel* visualItems, int scanIndex); + + /// Appends the mission items associated with this section + /// @param items List to append to + /// @param missionItemParent QObject parent for created MissionItems + /// @param nextSequenceNumber Sequence number for first item + void appendMissionItems(QList& items, QObject* missionItemParent, int nextSequenceNumber); + + void setSpecifyGimbal (bool specifyGimbal); + bool dirty (void) const { return _dirty; } + void setDirty (bool dirty); + + /// Returns the number of mission items represented by this section. + /// Signals: missionItemCountChanged on change + int missionItemCount(void) const; + +signals: + void availableChanged (bool available); + void settingsSpecifiedChanged (bool settingsSpecified); + void dirtyChanged (bool dirty); + bool specifyGimbalChanged (bool specifyGimbal); + void missionItemCountChanged (int missionItemCount); + +private slots: + void _setDirty(void); + void _setDirtyAndUpdateMissionItemCount(void); + +private: + bool _available; + bool _settingsSpecified; + bool _specifyGimbal; + Fact _gimbalYawFact; + Fact _gimbalPitchFact; + Fact _cameraActionFact; + Fact _cameraPhotoIntervalDistanceFact; + Fact _cameraPhotoIntervalTimeFact; + bool _dirty; + + static QMap _metaDataMap; + + static const char* _gimbalPitchName; + static const char* _gimbalYawName; + static const char* _cameraActionName; + static const char* _cameraPhotoIntervalDistanceName; + static const char* _cameraPhotoIntervalTimeName; +}; + +#endif diff --git a/src/MissionManager/ComplexMissionItem.h b/src/MissionManager/ComplexMissionItem.h index ad512e6eed13b4aa119a2f69bd5d76668b35b337..ce2a483065efe50f857e45af10616e6825c7ae5a 100644 --- a/src/MissionManager/ComplexMissionItem.h +++ b/src/MissionManager/ComplexMissionItem.h @@ -21,19 +21,11 @@ public: const ComplexMissionItem& operator=(const ComplexMissionItem& other); - Q_PROPERTY(int lastSequenceNumber READ lastSequenceNumber NOTIFY lastSequenceNumberChanged) Q_PROPERTY(double complexDistance READ complexDistance NOTIFY complexDistanceChanged) /// @return The distance covered the complex mission item in meters. virtual double complexDistance(void) const = 0; - /// @return The last sequence number used by this item. Takes into account child items of the complex item - virtual int lastSequenceNumber(void) const = 0; - - /// Returns the mission items associated with the complex item. Caller is responsible for freeing. Calling - /// delete on returned QmlObjectListModel will free all memory including internal items. - virtual QmlObjectListModel* getMissionItems(void) const = 0; - /// Load the complex mission item from Json /// @param complexObject Complex mission item json object /// @param sequenceNumber Sequence number for first MISSION_ITEM in survey @@ -53,8 +45,7 @@ public: static const char* jsonComplexItemTypeKey; signals: - void lastSequenceNumberChanged (int lastSequenceNumber); - void complexDistanceChanged (double complexDistance); + void complexDistanceChanged(double complexDistance); }; #endif diff --git a/src/MissionManager/FixedWingLandingComplexItem.cc b/src/MissionManager/FixedWingLandingComplexItem.cc index be080026bd0c741673ecb3a79ad362c5b02daa92..e748394ef4cf80685dab739b68d623260329089a 100644 --- a/src/MissionManager/FixedWingLandingComplexItem.cc +++ b/src/MissionManager/FixedWingLandingComplexItem.cc @@ -105,7 +105,7 @@ void FixedWingLandingComplexItem::setDirty(bool dirty) } } -void FixedWingLandingComplexItem::save(QJsonArray& missionItems) const +void FixedWingLandingComplexItem::save(QJsonArray& missionItems) { QJsonObject saveObject; @@ -203,10 +203,8 @@ bool FixedWingLandingComplexItem::specifiesCoordinate(void) const return true; } -QmlObjectListModel* FixedWingLandingComplexItem::getMissionItems(void) const +void FixedWingLandingComplexItem::appendMissionItems(QList& items, QObject* missionItemParent) { - QmlObjectListModel* pMissionItems = new QmlObjectListModel; - int seqNum = _sequenceNumber; MissionItem* item = new MissionItem(seqNum++, // sequence number @@ -215,8 +213,8 @@ QmlObjectListModel* FixedWingLandingComplexItem::getMissionItems(void) const 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, // param 1-7 true, // autoContinue false, // isCurrentItem - pMissionItems); // parent - allow delete on pMissionItems to delete everthing - pMissionItems->append(item); + missionItemParent); + items.append(item); float loiterRadius = _loiterRadiusFact.rawValue().toDouble() * (_loiterClockwise ? 1.0 : -1.0); item = new MissionItem(seqNum++, @@ -231,8 +229,8 @@ QmlObjectListModel* FixedWingLandingComplexItem::getMissionItems(void) const _loiterAltitudeFact.rawValue().toDouble(), true, // autoContinue false, // isCurrentItem - pMissionItems); // parent - allow delete on pMissionItems to delete everthing - pMissionItems->append(item); + missionItemParent); + items.append(item); item = new MissionItem(seqNum++, MAV_CMD_NAV_LAND, @@ -243,10 +241,8 @@ QmlObjectListModel* FixedWingLandingComplexItem::getMissionItems(void) const _landingAltitudeFact.rawValue().toDouble(), true, // autoContinue false, // isCurrentItem - pMissionItems); // parent - allow delete on pMissionItems to delete everthing - pMissionItems->append(item); - - return pMissionItems; + missionItemParent); + items.append(item); } double FixedWingLandingComplexItem::complexDistance(void) const diff --git a/src/MissionManager/FixedWingLandingComplexItem.h b/src/MissionManager/FixedWingLandingComplexItem.h index 208202bb0936ca72c18f4ca58fc00ace0edfcdef..c2a352baf043108adaf36919e6b0123a54273221 100644 --- a/src/MissionManager/FixedWingLandingComplexItem.h +++ b/src/MissionManager/FixedWingLandingComplexItem.h @@ -53,7 +53,6 @@ public: double complexDistance (void) const final; int lastSequenceNumber (void) const final; - QmlObjectListModel* getMissionItems (void) const final; bool load (const QJsonObject& complexObject, int sequenceNumber, QString& errorString) final; double greatestDistanceTo (const QGeoCoordinate &other) const final; void setCruiseSpeed (double cruiseSpeed) final; @@ -72,6 +71,7 @@ public: QGeoCoordinate exitCoordinate (void) const final { return _landingCoordinate; } int sequenceNumber (void) const final { return _sequenceNumber; } double flightSpeed (void) final { return std::numeric_limits::quiet_NaN(); } + void appendMissionItems (QList& items, QObject* missionItemParent) final; bool coordinateHasRelativeAltitude (void) const final { return true; } bool exitCoordinateHasRelativeAltitude (void) const final { return true; } @@ -80,7 +80,7 @@ public: void setDirty (bool dirty) final; void setCoordinate (const QGeoCoordinate& coordinate) final { setLoiterCoordinate(coordinate); } void setSequenceNumber (int sequenceNumber) final; - void save (QJsonArray& missionItems) const final; + void save (QJsonArray& missionItems) final; static const char* jsonComplexItemTypeValue; diff --git a/src/MissionManager/MavCmdInfoCommon.json b/src/MissionManager/MavCmdInfoCommon.json index ab845fbf4ae77cb2c5a3eb4435c69abe8cf6d758..4aa25b46f0e3959673630f65f7dc0e27904bbb73 100644 --- a/src/MissionManager/MavCmdInfoCommon.json +++ b/src/MissionManager/MavCmdInfoCommon.json @@ -32,6 +32,7 @@ "specifiesCoordinate": true, "friendlyEdit": true, "category": "Basic", + "cameraSection": true, "param1": { "label": "Hold", "units": "secs", diff --git a/src/MissionManager/MissionCommandUIInfo.cc b/src/MissionManager/MissionCommandUIInfo.cc index 7c955e734c328904838536c7ccceb4e05d11c7d6..af747eade9fa6034e1b6d1bdf4163f96d1a10404 100644 --- a/src/MissionManager/MissionCommandUIInfo.cc +++ b/src/MissionManager/MissionCommandUIInfo.cc @@ -35,8 +35,10 @@ const char* MissionCommandUIInfo::_paramRemoveJsonKey = "paramRemove"; const char* MissionCommandUIInfo::_rawNameJsonKey = "rawName"; const char* MissionCommandUIInfo::_standaloneCoordinateJsonKey = "standaloneCoordinate"; const char* MissionCommandUIInfo::_specifiesCoordinateJsonKey = "specifiesCoordinate"; +const char* MissionCommandUIInfo::_specifiesAltitudeOnlyJsonKey = "specifiesAltitudeOnly"; const char* MissionCommandUIInfo::_unitsJsonKey = "units"; const char* MissionCommandUIInfo::_commentJsonKey = "comment"; +const char* MissionCommandUIInfo::_cameraSectionJsonKey = "cameraSection"; const char* MissionCommandUIInfo::_advancedCategory = "Advanced"; MissionCmdParamInfo::MissionCmdParamInfo(QObject* parent) @@ -143,7 +145,7 @@ bool MissionCommandUIInfo::isStandaloneCoordinate(void) const } } -bool MissionCommandUIInfo::specifiesCoordinate (void) const +bool MissionCommandUIInfo::specifiesCoordinate(void) const { if (_infoMap.contains(_specifiesCoordinateJsonKey)) { return _infoMap[_specifiesCoordinateJsonKey].toBool(); @@ -152,6 +154,24 @@ bool MissionCommandUIInfo::specifiesCoordinate (void) const } } +bool MissionCommandUIInfo::specifiesAltitudeOnly(void) const +{ + if (_infoMap.contains(_specifiesAltitudeOnlyJsonKey)) { + return _infoMap[_specifiesAltitudeOnlyJsonKey].toBool(); + } else { + return false; + } +} + +bool MissionCommandUIInfo::cameraSection(void) const +{ + if (_infoMap.contains(_cameraSectionJsonKey)) { + return _infoMap[_cameraSectionJsonKey].toBool(); + } else { + return false; + } +} + void MissionCommandUIInfo::_overrideInfo(MissionCommandUIInfo* uiInfo) { // Override info values @@ -187,7 +207,7 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ QStringList allKeys; allKeys << _idJsonKey << _rawNameJsonKey << _friendlyNameJsonKey << _descriptionJsonKey << _standaloneCoordinateJsonKey << _specifiesCoordinateJsonKey <<_friendlyEditJsonKey << _param1JsonKey << _param2JsonKey << _param3JsonKey << _param4JsonKey << _param5JsonKey << _param6JsonKey << _param7JsonKey - << _paramRemoveJsonKey << _categoryJsonKey; + << _paramRemoveJsonKey << _categoryJsonKey << _cameraSectionJsonKey<< _specifiesAltitudeOnlyJsonKey; // Look for unknown keys in top level object foreach (const QString& key, jsonObject.keys()) { @@ -219,7 +239,7 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ QList types; types << QJsonValue::Double << QJsonValue::String << QJsonValue::String<< QJsonValue::String << QJsonValue::Bool << QJsonValue::Bool << QJsonValue::Bool << QJsonValue::Object << QJsonValue::Object << QJsonValue::Object << QJsonValue::Object << QJsonValue::Object << QJsonValue::Object << QJsonValue::Object - << QJsonValue::String << QJsonValue::String; + << QJsonValue::String << QJsonValue::String << QJsonValue::Bool << QJsonValue::Bool; if (!JsonHelper::validateKeyTypes(jsonObject, allKeys, types, internalError)) { errorString = _loadErrorString(internalError); return false; @@ -247,9 +267,15 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ if (jsonObject.contains(_specifiesCoordinateJsonKey)) { _infoMap[_specifiesCoordinateJsonKey] = jsonObject.value(_specifiesCoordinateJsonKey).toVariant(); } + if (jsonObject.contains(_specifiesAltitudeOnlyJsonKey)) { + _infoMap[_specifiesAltitudeOnlyJsonKey] = jsonObject.value(_specifiesAltitudeOnlyJsonKey).toBool(); + } if (jsonObject.contains(_friendlyEditJsonKey)) { _infoMap[_friendlyEditJsonKey] = jsonObject.value(_friendlyEditJsonKey).toVariant(); } + if (jsonObject.contains(_cameraSectionJsonKey)) { + _infoMap[_cameraSectionJsonKey] = jsonObject.value(_cameraSectionJsonKey).toVariant(); + } if (jsonObject.contains(_paramRemoveJsonKey)) { QStringList indexList = jsonObject.value(_paramRemoveJsonKey).toString().split(QStringLiteral(",")); foreach (const QString& indexString, indexList) { diff --git a/src/MissionManager/MissionCommandUIInfo.h b/src/MissionManager/MissionCommandUIInfo.h index 2f67faa62d2eff4a2ee86f34b03c8f33d3213b3f..e543531d95ba28c77a8f104fc21b00646e4d6c2c 100644 --- a/src/MissionManager/MissionCommandUIInfo.h +++ b/src/MissionManager/MissionCommandUIInfo.h @@ -90,8 +90,10 @@ private: /// friendlyName string rawName Short description of command /// description string Long description of command /// specifiesCoordinate bool false true: Command specifies a lat/lon/alt coordinate +/// specifiesAltitudeOnly bool false true: Command specifies an altitude only (no coordinate) /// standaloneCoordinate bool false true: Vehicle does not fly through coordinate associated with command (exampl: ROI) /// friendlyEdit bool false true: Command supports friendly editing dialog, false: Command supports 'Show all values" style editing only +/// cameraSection bool false true: Camera section of additional settings is added to editor /// category string Advanced Category which this command belongs to /// paramRemove string Used by an override to remove params, example: "1,3" will remove params 1 and 3 on the override /// param[1-7] object MissionCommandParamInfo object @@ -112,7 +114,9 @@ public: Q_PROPERTY(QString rawName READ rawName CONSTANT) Q_PROPERTY(bool isStandaloneCoordinate READ isStandaloneCoordinate CONSTANT) Q_PROPERTY(bool specifiesCoordinate READ specifiesCoordinate CONSTANT) + Q_PROPERTY(bool specifiesAltitudeOnly READ specifiesAltitudeOnly CONSTANT) Q_PROPERTY(int command READ intCommand CONSTANT) + Q_PROPERTY(bool cameraSection READ cameraSection CONSTANT) MAV_CMD command(void) const { return _command; } int intCommand(void) const { return (int)_command; } @@ -124,6 +128,8 @@ public: QString rawName (void) const; bool isStandaloneCoordinate (void) const; bool specifiesCoordinate (void) const; + bool specifiesAltitudeOnly (void) const; + bool cameraSection (void) const; /// Load the data in the object from the specified json /// @param jsonObject Json object to load from @@ -178,8 +184,10 @@ private: static const char* _rawNameJsonKey; static const char* _standaloneCoordinateJsonKey; static const char* _specifiesCoordinateJsonKey; + static const char* _specifiesAltitudeOnlyJsonKey; static const char* _unitsJsonKey; - static const char* _commentJsonKey; + static const char* _commentJsonKey; + static const char* _cameraSectionJsonKey; static const char* _advancedCategory; friend class MissionCommandTree; diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc index 613f194aa70f47b934e3da134a76b1b8775b0d59..fba71fa76bcb5d19335cc462b3c46d7d0f97b6c1 100644 --- a/src/MissionManager/MissionController.cc +++ b/src/MissionManager/MissionController.cc @@ -126,8 +126,7 @@ void MissionController::_newMissionItemsAvailableFromVehicle(void) _missionItemsRequested = false; if (_editMode) { - // Scan for mission settings - MissionSettingsComplexItem::scanForMissionSettings(_visualItems, _activeVehicle); + MissionController::_scanForAdditionalSettings(_visualItems, _activeVehicle); } _initAllVisualItems(); @@ -159,16 +158,8 @@ void MissionController::sendItemsToVehicle(Vehicle* vehicle, QmlObjectListModel* for (int i=0; icount(); i++) { VisualMissionItem* visualItem = qobject_cast(visualMissionItems->get(i)); - if (visualItem->isSimpleItem()) { - missionItems.append(new MissionItem(qobject_cast(visualItem)->missionItem())); - } else { - ComplexMissionItem* complexItem = qobject_cast(visualItem); - QmlObjectListModel* complexMissionItems = complexItem->getMissionItems(); - for (int j=0; jcount(); j++) { - missionItems.append(new MissionItem(*qobject_cast(complexMissionItems->get(j)))); - } - complexMissionItems->deleteLater(); - } + + visualItem->appendMissionItems(missionItems, NULL); } vehicle->missionManager()->writeMissionItems(missionItems); @@ -185,13 +176,8 @@ int MissionController::_nextSequenceNumber(void) qWarning() << "Internal error: Empty visual item list"; return 0; } else { - VisualMissionItem* lastItem = qobject_cast(_visualItems->get(_visualItems->count() - 1)); - - if (lastItem->isSimpleItem()) { - return lastItem->sequenceNumber() + 1; - } else { - return qobject_cast(lastItem)->lastSequenceNumber() + 1; - } + VisualMissionItem* lastItem = _visualItems->value(_visualItems->count() - 1); + return lastItem->lastSequenceNumber() + 1; } } @@ -374,12 +360,11 @@ bool MissionController::_loadJsonMissionFileV1(Vehicle* vehicle, const QJsonObje SimpleMissionItem* item = new SimpleMissionItem(vehicle, visualItems); if (item->load(itemObject, itemObject["id"].toInt(), errorString)) { qCDebug(MissionControllerLog) << "Json load: adding simple item expectedSequence:actualSequence" << nextSequenceNumber << item->sequenceNumber(); + nextSequenceNumber = item->lastSequenceNumber() + 1; visualItems->append(item); } else { return false; } - - nextSequenceNumber++; } } while (nextSimpleItemIndex < itemArray.count() || nextComplexItemIndex < surveyItems.count()); @@ -465,7 +450,8 @@ bool MissionController::_loadJsonMissionFileV2(Vehicle* vehicle, const QJsonObje if (itemType == VisualMissionItem::jsonTypeSimpleItemValue) { qCDebug(MissionControllerLog) << "Loading MISSION_ITEM: nextSequenceNumber" << nextSequenceNumber; SimpleMissionItem* simpleItem = new SimpleMissionItem(vehicle, visualItems); - if (simpleItem->load(itemObject, nextSequenceNumber++, errorString)) { + if (simpleItem->load(itemObject, nextSequenceNumber, errorString)) { + nextSequenceNumber = simpleItem->lastSequenceNumber() + 1; visualItems->append(simpleItem); } else { return false; @@ -612,7 +598,7 @@ void MissionController::loadFromFile(const QString& filename) _addMissionSettings(_activeVehicle, _visualItems, true /* addToCenter */); } - MissionSettingsComplexItem::scanForMissionSettings(_visualItems, _activeVehicle); + MissionController::_scanForAdditionalSettings(_visualItems, _activeVehicle); _initAllVisualItems(); } @@ -1062,16 +1048,8 @@ void MissionController::_recalcSequence(void) for (int i=0; i<_visualItems->count(); i++) { VisualMissionItem* item = qobject_cast(_visualItems->get(i)); - item->setSequenceNumber(sequenceNumber++); - if (!item->isSimpleItem()) { - ComplexMissionItem* complexItem = qobject_cast(item); - - if (complexItem) { - sequenceNumber = complexItem->lastSequenceNumber() + 1; - } else { - qWarning() << "isSimpleItem == false, yet not ComplexMissionItem"; - } - } + item->setSequenceNumber(sequenceNumber); + sequenceNumber = item->lastSequenceNumber() + 1; } } @@ -1158,6 +1136,7 @@ void MissionController::_initVisualItem(VisualMissionItem* visualItem) connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged, this, &MissionController::_recalcWaypointLines); connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged, this, &MissionController::_recalcWaypointLines); connect(visualItem, &VisualMissionItem::flightSpeedChanged, this, &MissionController::_recalcAltitudeRangeBearing); + connect(visualItem, &VisualMissionItem::lastSequenceNumberChanged, this, &MissionController::_recalcSequence); if (visualItem->isSimpleItem()) { // We need to track commandChanged on simple item since recalc has special handling for takeoff command @@ -1168,10 +1147,12 @@ void MissionController::_initVisualItem(VisualMissionItem* visualItem) qWarning() << "isSimpleItem == true, yet not SimpleMissionItem"; } } else { - // We need to track changes of lastSequenceNumber so we can recalc sequence numbers for subsequence items ComplexMissionItem* complexItem = qobject_cast(visualItem); - connect(complexItem, &ComplexMissionItem::lastSequenceNumberChanged, this, &MissionController::_recalcSequence); - connect(complexItem, &ComplexMissionItem::complexDistanceChanged, this, &MissionController::_recalcAltitudeRangeBearing); + if (complexItem) { + connect(complexItem, &ComplexMissionItem::complexDistanceChanged, this, &MissionController::_recalcAltitudeRangeBearing); + } else { + qWarning() << "ComplexMissionItem not found"; + } } } @@ -1472,7 +1453,7 @@ QString MissionController::fileExtension(void) const return QGCApplication::missionFileExtension; } -double MissionController::cruiseSpeed(void) const +double MissionController::cruiseSpeed(void) const { if (_activeVehicle) { return _activeVehicle->cruiseSpeed(); @@ -1481,7 +1462,7 @@ double MissionController::cruiseSpeed(void) const } } -double MissionController::hoverSpeed(void) const +double MissionController::hoverSpeed(void) const { if (_activeVehicle) { return _activeVehicle->hoverSpeed(); @@ -1489,3 +1470,27 @@ double MissionController::hoverSpeed(void) const return 0.0f; } } + +void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualItems, Vehicle* vehicle) +{ + int scanIndex = 0; + while (scanIndex < visualItems->count()) { + VisualMissionItem* visualItem = visualItems->value(scanIndex); + + qCDebug(MissionControllerLog) << "MissionController::_scanForAdditionalSettings count:scanIndex" << visualItems->count() << scanIndex; + + MissionSettingsComplexItem* settingsItem = qobject_cast(visualItem); + if (settingsItem && settingsItem->scanForMissionSettings(visualItems, scanIndex, vehicle)) { + continue; + } + + SimpleMissionItem* simpleItem = qobject_cast(visualItem); + if (simpleItem && simpleItem->cameraSection()->available()) { + scanIndex++; + simpleItem->scanForSections(visualItems, scanIndex, vehicle); + continue; + } + + scanIndex++; + } +} diff --git a/src/MissionManager/MissionController.h b/src/MissionManager/MissionController.h index 9e4447a8441661e0edd3fec92069170afa80f26a..16f1e3ff504dea95c289b5a9930f1f99e399d34f 100644 --- a/src/MissionManager/MissionController.h +++ b/src/MissionManager/MissionController.h @@ -160,6 +160,7 @@ private: void _setMissionCruiseDistance(double missionCruiseDistance); void _setMissionCruiseTime(double missionCruiseTime); void _setMissionMaxTelemetry(double missionMaxTelemetry); + static void _scanForAdditionalSettings(QmlObjectListModel* visualItems, Vehicle* vehicle); // Overrides from PlanElementController void _activeVehicleBeingRemoved(void) final; diff --git a/src/MissionManager/MissionSettings.FactMetaData.json b/src/MissionManager/MissionSettings.FactMetaData.json index 78905484bcd0a30366f4f9d997f53543e3e71c79..37d71da65e0534ddc745bcd955172acd9782b872 100644 --- a/src/MissionManager/MissionSettings.FactMetaData.json +++ b/src/MissionManager/MissionSettings.FactMetaData.json @@ -29,52 +29,6 @@ "min": 0, "decimalPlaces": 1 }, -{ - "name": "CameraAction", - "shortDescription": "Specify whether the camera should take photos or video", - "type": "uint32", - "enumStrings": "No camera action,Take photos (time),Take photos (distance),Take video", - "enumValues": "0,1,2,3", - "defaultValue": 0 -}, -{ - "name": "CameraPhotoIntervalDistance", - "shortDescription": "Specify the distance between each photo", - "type": "double", - "units": "m", - "min": 0, - "decimalPlaces": 1, - "defaultValue": 1 -}, -{ - "name": "CameraPhotoIntervalTime", - "shortDescription": "Specify the time between each photo", - "type": "uint32", - "units": "secs", - "min": 1, - "decimalPlaces": 0, - "defaultValue": 10 -}, -{ - "name": "GimbalPitch", - "shortDescription": "Gimbal pitch rotation.", - "type": "double", - "units": "deg", - "min": 0.0, - "max": 360.0, - "decimalPlaces": 0, - "defaultValue": 0 -}, -{ - "name": "GimbalYaw", - "shortDescription": "Gimbal yaw rotation.", - "type": "double", - "units": "deg", - "min": 0.0, - "max": 360.0, - "decimalPlaces": 0, - "defaultValue": 0 -}, { "name": "MissionEndAction", "shortDescription": "The action to take when the mission completed.", diff --git a/src/MissionManager/MissionSettingsComplexItem.cc b/src/MissionManager/MissionSettingsComplexItem.cc index f53f6ccad36675450197dcedfbb54d89c527d47a..d44b92e144fda27d818297f870a5b0350941253b 100644 --- a/src/MissionManager/MissionSettingsComplexItem.cc +++ b/src/MissionManager/MissionSettingsComplexItem.cc @@ -26,11 +26,6 @@ const char* MissionSettingsComplexItem::_plannedHomePositionLatitudeName = "Pla const char* MissionSettingsComplexItem::_plannedHomePositionLongitudeName = "PlannedHomePositionLongitude"; const char* MissionSettingsComplexItem::_plannedHomePositionAltitudeName = "PlannedHomePositionAltitude"; const char* MissionSettingsComplexItem::_missionFlightSpeedName = "FlightSpeed"; -const char* MissionSettingsComplexItem::_gimbalPitchName = "GimbalPitch"; -const char* MissionSettingsComplexItem::_gimbalYawName = "GimbalYaw"; -const char* MissionSettingsComplexItem::_cameraActionName = "CameraAction"; -const char* MissionSettingsComplexItem::_cameraPhotoIntervalDistanceName = "CameraPhotoIntervalDistance"; -const char* MissionSettingsComplexItem::_cameraPhotoIntervalTimeName = "CameraPhotoIntervalTime"; const char* MissionSettingsComplexItem::_missionEndActionName = "MissionEndAction"; QMap MissionSettingsComplexItem::_metaDataMap; @@ -38,16 +33,10 @@ QMap MissionSettingsComplexItem::_metaDataMap; MissionSettingsComplexItem::MissionSettingsComplexItem(Vehicle* vehicle, QObject* parent) : ComplexMissionItem(vehicle, parent) , _specifyMissionFlightSpeed(false) - , _specifyGimbal(false) , _plannedHomePositionLatitudeFact (0, _plannedHomePositionLatitudeName, FactMetaData::valueTypeDouble) , _plannedHomePositionLongitudeFact (0, _plannedHomePositionLongitudeName, FactMetaData::valueTypeDouble) , _plannedHomePositionAltitudeFact (0, _plannedHomePositionAltitudeName, FactMetaData::valueTypeDouble) , _missionFlightSpeedFact (0, _missionFlightSpeedName, FactMetaData::valueTypeDouble) - , _gimbalYawFact (0, _gimbalYawName, FactMetaData::valueTypeDouble) - , _gimbalPitchFact (0, _gimbalPitchName, FactMetaData::valueTypeDouble) - , _cameraActionFact (0, _cameraActionName, FactMetaData::valueTypeDouble) - , _cameraPhotoIntervalDistanceFact (0, _cameraPhotoIntervalDistanceName, FactMetaData::valueTypeDouble) - , _cameraPhotoIntervalTimeFact (0, _cameraPhotoIntervalTimeName, FactMetaData::valueTypeUint32) , _missionEndActionFact (0, _missionEndActionName, FactMetaData::valueTypeUint32) , _sequenceNumber(0) , _dirty(false) @@ -62,21 +51,11 @@ MissionSettingsComplexItem::MissionSettingsComplexItem(Vehicle* vehicle, QObject _plannedHomePositionLongitudeFact.setMetaData (_metaDataMap[_plannedHomePositionLongitudeName]); _plannedHomePositionAltitudeFact.setMetaData (_metaDataMap[_plannedHomePositionAltitudeName]); _missionFlightSpeedFact.setMetaData (_metaDataMap[_missionFlightSpeedName]); - _gimbalPitchFact.setMetaData (_metaDataMap[_gimbalPitchName]); - _gimbalYawFact.setMetaData (_metaDataMap[_gimbalYawName]); - _cameraActionFact.setMetaData (_metaDataMap[_cameraActionName]); - _cameraPhotoIntervalDistanceFact.setMetaData (_metaDataMap[_cameraPhotoIntervalDistanceName]); - _cameraPhotoIntervalTimeFact.setMetaData (_metaDataMap[_cameraPhotoIntervalTimeName]); _missionEndActionFact.setMetaData (_metaDataMap[_missionEndActionName]); _plannedHomePositionLatitudeFact.setRawValue (_plannedHomePositionLatitudeFact.rawDefaultValue()); _plannedHomePositionLongitudeFact.setRawValue (_plannedHomePositionLongitudeFact.rawDefaultValue()); _plannedHomePositionAltitudeFact.setRawValue (_plannedHomePositionAltitudeFact.rawDefaultValue()); - _gimbalPitchFact.setRawValue (_gimbalPitchFact.rawDefaultValue()); - _gimbalYawFact.setRawValue (_gimbalYawFact.rawDefaultValue()); - _cameraActionFact.setRawValue (_cameraActionFact.rawDefaultValue()); - _cameraPhotoIntervalDistanceFact.setRawValue (_cameraPhotoIntervalDistanceFact.rawDefaultValue()); - _cameraPhotoIntervalTimeFact.setRawValue (_cameraPhotoIntervalTimeFact.rawDefaultValue()); _missionEndActionFact.setRawValue (_missionEndActionFact.rawDefaultValue()); // FIXME: Flight speed default value correctly based firmware parameter if online @@ -86,19 +65,17 @@ MissionSettingsComplexItem::MissionSettingsComplexItem(Vehicle* vehicle, QObject setHomePositionSpecialCase(true); - connect(this, &MissionSettingsComplexItem::specifyMissionFlightSpeedChanged, this, &MissionSettingsComplexItem::_setDirtyAndUpdateLastSequenceNumber); - connect(this, &MissionSettingsComplexItem::specifyGimbalChanged, this, &MissionSettingsComplexItem::_setDirtyAndUpdateLastSequenceNumber); + connect(this, &MissionSettingsComplexItem::specifyMissionFlightSpeedChanged, this, &MissionSettingsComplexItem::_setDirtyAndUpdateLastSequenceNumber); + connect(&_cameraSection, &CameraSection::missionItemCountChanged, this, &MissionSettingsComplexItem::_setDirtyAndUpdateLastSequenceNumber); connect(&_plannedHomePositionLatitudeFact, &Fact::valueChanged, this, &MissionSettingsComplexItem::_setDirtyAndUpdateCoordinate); connect(&_plannedHomePositionLongitudeFact, &Fact::valueChanged, this, &MissionSettingsComplexItem::_setDirtyAndUpdateCoordinate); connect(&_plannedHomePositionAltitudeFact, &Fact::valueChanged, this, &MissionSettingsComplexItem::_setDirtyAndUpdateCoordinate); + connect(&_missionFlightSpeedFact, &Fact::valueChanged, this, &MissionSettingsComplexItem::_setDirty); - connect(&_gimbalPitchFact, &Fact::valueChanged, this, &MissionSettingsComplexItem::_setDirty); - connect(&_gimbalYawFact, &Fact::valueChanged, this, &MissionSettingsComplexItem::_setDirty); - connect(&_cameraActionFact, &Fact::valueChanged, this, &MissionSettingsComplexItem::_setDirtyAndUpdateLastSequenceNumber); - connect(&_cameraPhotoIntervalDistanceFact, &Fact::valueChanged, this, &MissionSettingsComplexItem::_setDirty); - connect(&_cameraPhotoIntervalTimeFact, &Fact::valueChanged, this, &MissionSettingsComplexItem::_setDirty); connect(&_missionEndActionFact, &Fact::valueChanged, this, &MissionSettingsComplexItem::_setDirty); + + connect(&_cameraSection, &CameraSection::dirtyChanged, this, &MissionSettingsComplexItem::_cameraSectionDirtyChanged); } @@ -110,14 +87,6 @@ void MissionSettingsComplexItem::setSpecifyMissionFlightSpeed(bool specifyMissio } } -void MissionSettingsComplexItem::setSpecifyGimbal(bool specifyGimbal) -{ - if (specifyGimbal != _specifyGimbal) { - _specifyGimbal = specifyGimbal; - emit specifyGimbalChanged(specifyGimbal); - } -} - int MissionSettingsComplexItem::lastSequenceNumber(void) const { int lastSequenceNumber = _sequenceNumber + 1; // +1 for planned home position @@ -125,12 +94,7 @@ int MissionSettingsComplexItem::lastSequenceNumber(void) const if (_specifyMissionFlightSpeed) { lastSequenceNumber++; } - if (_specifyGimbal) { - lastSequenceNumber++; - } - if (_cameraActionFact.rawValue().toInt() != CameraActionNone) { - lastSequenceNumber++; - } + lastSequenceNumber += _cameraSection.missionItemCount(); return lastSequenceNumber; } @@ -143,20 +107,21 @@ void MissionSettingsComplexItem::setDirty(bool dirty) } } -void MissionSettingsComplexItem::save(QJsonArray& missionItems) const +void MissionSettingsComplexItem::save(QJsonArray& missionItems) { - QmlObjectListModel* items = getMissionItems(); + QList items; + + appendMissionItems(items, this); // First item show be planned home position, we are not reponsible for save/load // Remained we just output as is - for (int i=1; icount(); i++) { - MissionItem* item = items->value(i); + for (int i=1; isave(saveObject); missionItems.append(saveObject); + item->deleteLater(); } - - items->deleteLater(); } void MissionSettingsComplexItem::setSequenceNumber(int sequenceNumber) @@ -173,52 +138,7 @@ bool MissionSettingsComplexItem::load(const QJsonObject& complexObject, int sequ Q_UNUSED(complexObject); Q_UNUSED(sequenceNumber); Q_UNUSED(errorString); -#if 0 - QList keyInfoList = { - { JsonHelper::jsonVersionKey, QJsonValue::Double, true }, - { VisualMissionItem::jsonTypeKey, QJsonValue::String, true }, - { ComplexMissionItem::jsonComplexItemTypeKey, QJsonValue::String, true }, - { _jsonLoiterCoordinateKey, QJsonValue::Array, true }, - { _jsonLoiterRadiusKey, QJsonValue::Double, true }, - { _jsonLoiterClockwiseKey, QJsonValue::Bool, true }, - { _jsonLoiterAltitudeRelativeKey, QJsonValue::Bool, true }, - { _jsonLandingCoordinateKey, QJsonValue::Array, true }, - { _jsonLandingAltitudeRelativeKey, QJsonValue::Bool, true }, - }; - if (!JsonHelper::validateKeys(complexObject, keyInfoList, errorString)) { - return false; - } - - QString itemType = complexObject[VisualMissionItem::jsonTypeKey].toString(); - QString complexType = complexObject[ComplexMissionItem::jsonComplexItemTypeKey].toString(); - if (itemType != VisualMissionItem::jsonTypeComplexItemValue || complexType != jsonComplexItemTypeValue) { - errorString = tr("QGroundControl does not support loading this complex mission item type: %1:2").arg(itemType).arg(complexType); - return false; - } - - setSequenceNumber(sequenceNumber); - - QGeoCoordinate coordinate; - if (!JsonHelper::loadGeoCoordinate(complexObject[_jsonLoiterCoordinateKey], true /* altitudeRequired */, coordinate, errorString)) { - return false; - } - _loiterCoordinate = coordinate; - _loiterAltitudeFact.setRawValue(coordinate.altitude()); - if (!JsonHelper::loadGeoCoordinate(complexObject[_jsonLandingCoordinateKey], true /* altitudeRequired */, coordinate, errorString)) { - return false; - } - _landingCoordinate = coordinate; - _landingAltitudeFact.setRawValue(coordinate.altitude()); - - _loiterRadiusFact.setRawValue(complexObject[_jsonLoiterRadiusKey].toDouble()); - _loiterClockwise = complexObject[_jsonLoiterClockwiseKey].toBool(); - _loiterAltitudeRelative = complexObject[_jsonLoiterAltitudeRelativeKey].toBool(); - _landingAltitudeRelative = complexObject[_jsonLandingAltitudeRelativeKey].toBool(); - - _landingCoordSet = true; - _recalcFromHeadingAndDistanceChange(); -#endif return true; } @@ -233,13 +153,11 @@ bool MissionSettingsComplexItem::specifiesCoordinate(void) const return false; } -QmlObjectListModel* MissionSettingsComplexItem::getMissionItems(void) const +void MissionSettingsComplexItem::appendMissionItems(QList& items, QObject* missionItemParent) { - QmlObjectListModel* pMissionItems = new QmlObjectListModel; - int seqNum = _sequenceNumber; - // IMPORTANT NOTE: If anything changed here you just also change MissionSettingsComplexItem::scanForMissionSettings + // IMPORTANT NOTE: If anything changes here you must also change MissionSettingsComplexItem::scanForMissionSettings // Planned home position MissionItem* item = new MissionItem(seqNum++, @@ -254,23 +172,8 @@ QmlObjectListModel* MissionSettingsComplexItem::getMissionItems(void) const _plannedHomePositionAltitudeFact.rawValue().toDouble(), true, // autoContinue false, // isCurrentItem - pMissionItems); // parent - allow delete on pMissionItems to delete everthing - pMissionItems->append(item); - - if (_specifyGimbal) { - MissionItem* item = new MissionItem(seqNum++, - MAV_CMD_DO_MOUNT_CONTROL, - MAV_FRAME_MISSION, - _gimbalPitchFact.rawValue().toDouble(), - 0, // Gimbal roll - _gimbalYawFact.rawValue().toDouble(), - 0, 0, 0, // param 4-6 not used - MAV_MOUNT_MODE_MAVLINK_TARGETING, - true, // autoContinue - false, // isCurrentItem - pMissionItems); // parent - allow delete on pMissionItems to delete everthing - pMissionItems->append(item); - } + missionItemParent); + items.append(item); if (_specifyMissionFlightSpeed) { qDebug() << _missionFlightSpeedFact.rawValue().toDouble(); @@ -284,152 +187,78 @@ QmlObjectListModel* MissionSettingsComplexItem::getMissionItems(void) const 0, 0, 0, // param 5-7 not used true, // autoContinue false, // isCurrentItem - pMissionItems); // parent - allow delete on pMissionItems to delete everthing - pMissionItems->append(item); + missionItemParent); + items.append(item); } - if (_cameraActionFact.rawValue().toInt() != CameraActionNone) { - MissionItem* item = NULL; - - switch (_cameraActionFact.rawValue().toInt()) { - case TakePhotosIntervalTime: - item = new MissionItem(seqNum++, - MAV_CMD_IMAGE_START_CAPTURE, - MAV_FRAME_MISSION, - _cameraPhotoIntervalTimeFact.rawValue().toInt(), // Interval - 0, // Unlimited photo count - -1, // Max resolution - 0, 0, // param 4-5 not used - 0, // Camera ID - 0, // param 7 not used - true, // autoContinue - false, // isCurrentItem - pMissionItems); // parent - allow delete on pMissionItems to delete everthing - break; - case TakePhotoIntervalDistance: - item = new MissionItem(seqNum++, - MAV_CMD_DO_SET_CAM_TRIGG_DIST, - MAV_FRAME_MISSION, - _cameraPhotoIntervalDistanceFact.rawValue().toDouble(), // Trigger distance - 0, 0, 0, 0, 0, 0, // param 2-7 not used - true, // autoContinue - false, // isCurrentItem - pMissionItems); // parent - allow delete on pMissionItems to delete everthing - break; - case TakeVideo: - item = new MissionItem(seqNum++, - MAV_CMD_VIDEO_START_CAPTURE, - MAV_FRAME_MISSION, - 0, // Camera ID - -1, // Max fps - -1, // Max resolution - 0, 0, 0, 0, // param 5-7 not used - true, // autoContinue - false, // isCurrentItem - pMissionItems); // parent - allow delete on pMissionItems to delete everthing - break; - } - if (item) { - pMissionItems->append(item); - } - } - - return pMissionItems; + _cameraSection.appendMissionItems(items, missionItemParent, seqNum); } -void MissionSettingsComplexItem::scanForMissionSettings(QmlObjectListModel* visualItems, Vehicle* vehicle) +bool MissionSettingsComplexItem::scanForMissionSettings(QmlObjectListModel* visualItems, int scanIndex, Vehicle* vehicle) { - bool foundGimbal = false; bool foundSpeed = false; - bool foundCameraAction = false; + bool foundCameraSection = false; + bool stopLooking = false; + + qCDebug(MissionSettingsComplexItemLog) << "MissionSettingsComplexItem::scanForMissionSettings count:scanIndex" << visualItems->count() << scanIndex; - MissionSettingsComplexItem* settingsItem = visualItems->value(0); + MissionSettingsComplexItem* settingsItem = visualItems->value(scanIndex); if (!settingsItem) { - qWarning() << "First item is not MissionSettingsComplexItem"; - return; + qWarning() << "Item specified by scanIndex not MissionSettingsComplexItem"; + return false; } // Scan through the initial mission items for possible mission settings - while (visualItems->count()> 1) { - SimpleMissionItem* item = visualItems->value(1); + scanIndex++; + while (!stopLooking && visualItems->count() > 1) { + SimpleMissionItem* item = visualItems->value(scanIndex); if (!item) { - // We hit a complex item there can be no more possible mission settings - return; + // We hit a complex item, there can be no more possible mission settings + break; } MissionItem& missionItem = item->missionItem(); - // See MissionSettingsComplexItem::getMissionItems for specs on what compomises a known mission settings + qCDebug(MissionSettingsComplexItemLog) << item->command() << missionItem.param1() << missionItem.param2() << missionItem.param3() << missionItem.param4() << missionItem.param5() << missionItem.param6() << missionItem.param7() ; - switch ((MAV_CMD)item->command()) { - case MAV_CMD_DO_MOUNT_CONTROL: - if (!foundGimbal && missionItem.param2() == 0 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == MAV_MOUNT_MODE_MAVLINK_TARGETING) { - foundGimbal = true; - settingsItem->setSpecifyGimbal(true); - settingsItem->gimbalPitch()->setRawValue(missionItem.param1()); - settingsItem->gimbalYaw()->setRawValue(missionItem.param3()); - visualItems->removeAt(1)->deleteLater(); - } else { - return; - } - break; + // See MissionSettingsComplexItem::getMissionItems for specs on what compomises a known mission setting + switch ((MAV_CMD)item->command()) { case MAV_CMD_DO_CHANGE_SPEED: if (!foundSpeed && missionItem.param3() == -1 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) { if (vehicle->multiRotor()) { if (missionItem.param1() != 1) { - return; + stopLooking = true; + break; } } else { if (missionItem.param1() != 0) { - return; + stopLooking = true; + break; } } foundSpeed = true; settingsItem->setSpecifyMissionFlightSpeed(true); settingsItem->missionFlightSpeed()->setRawValue(missionItem.param2()); - visualItems->removeAt(1)->deleteLater(); - } else { - return; + visualItems->removeAt(scanIndex)->deleteLater(); + continue; } + stopLooking = true; break; - case MAV_CMD_IMAGE_START_CAPTURE: - if (!foundCameraAction && missionItem.param1() != 0 && missionItem.param2() == 0 && missionItem.param3() == -1 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) { - foundCameraAction = true; - settingsItem->cameraAction()->setRawValue(TakePhotosIntervalTime); - settingsItem->cameraPhotoIntervalTime()->setRawValue(missionItem.param1()); - visualItems->removeAt(1)->deleteLater(); - } else { - return; - } - break; - - case MAV_CMD_DO_SET_CAM_TRIGG_DIST: - if (!foundCameraAction && missionItem.param1() != 0 && missionItem.param2() == 0 && missionItem.param3() == 0 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) { - foundCameraAction = true; - settingsItem->cameraAction()->setRawValue(TakePhotoIntervalDistance); - settingsItem->cameraPhotoIntervalDistance()->setRawValue(missionItem.param1()); - visualItems->removeAt(1)->deleteLater(); - } else { - return; - } - break; - - case MAV_CMD_VIDEO_START_CAPTURE: - if (!foundCameraAction && missionItem.param1() == 0 && missionItem.param2() == -1 && missionItem.param3() == -1 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) { - foundCameraAction = true; - settingsItem->cameraAction()->setRawValue(TakeVideo); - visualItems->removeAt(1)->deleteLater(); - } else { - return; + default: + if (!foundCameraSection) { + if (settingsItem->_cameraSection.scanForCameraSection(visualItems, scanIndex)) { + foundCameraSection = true; + continue; + } } + stopLooking = true; break; - - default: - return; } } + + return foundSpeed || foundCameraSection; } double MissionSettingsComplexItem::complexDistance(void) const @@ -474,3 +303,10 @@ QGeoCoordinate MissionSettingsComplexItem::coordinate(void) const { return QGeoCoordinate(_plannedHomePositionLatitudeFact.rawValue().toDouble(), _plannedHomePositionLongitudeFact.rawValue().toDouble(), _plannedHomePositionAltitudeFact.rawValue().toDouble()); } + +void MissionSettingsComplexItem::_cameraSectionDirtyChanged(bool dirty) +{ + if (dirty) { + setDirty(true); + } +} diff --git a/src/MissionManager/MissionSettingsComplexItem.h b/src/MissionManager/MissionSettingsComplexItem.h index 5386b18a68ccdd92602aee928a4771a81fd9d295..7011a616c95b69697e670aaed2199885d8563a08 100644 --- a/src/MissionManager/MissionSettingsComplexItem.h +++ b/src/MissionManager/MissionSettingsComplexItem.h @@ -14,6 +14,7 @@ #include "MissionItem.h" #include "Fact.h" #include "QGCLoggingCategory.h" +#include "CameraSection.h" Q_DECLARE_LOGGING_CATEGORY(MissionSettingsComplexItemLog) @@ -32,51 +33,31 @@ public: }; Q_ENUMS(MissionEndAction) - enum CameraAction { - CameraActionNone, - TakePhotosIntervalTime, - TakePhotoIntervalDistance, - TakeVideo - }; - Q_ENUMS(CameraAction) - Q_PROPERTY(bool specifyMissionFlightSpeed READ specifyMissionFlightSpeed WRITE setSpecifyMissionFlightSpeed NOTIFY specifyMissionFlightSpeedChanged) Q_PROPERTY(Fact* missionFlightSpeed READ missionFlightSpeed CONSTANT) - Q_PROPERTY(bool specifyGimbal READ specifyGimbal WRITE setSpecifyGimbal NOTIFY specifyGimbalChanged) - Q_PROPERTY(Fact* gimbalPitch READ gimbalPitch CONSTANT) - Q_PROPERTY(Fact* gimbalYaw READ gimbalYaw CONSTANT) - Q_PROPERTY(Fact* cameraAction READ cameraAction CONSTANT) - Q_PROPERTY(Fact* cameraPhotoIntervalTime READ cameraPhotoIntervalTime CONSTANT) - Q_PROPERTY(Fact* cameraPhotoIntervalDistance READ cameraPhotoIntervalDistance CONSTANT) Q_PROPERTY(Fact* missionEndAction READ missionEndAction CONSTANT) Q_PROPERTY(Fact* plannedHomePositionLatitude READ plannedHomePositionLatitude CONSTANT) Q_PROPERTY(Fact* plannedHomePositionLongitude READ plannedHomePositionLongitude CONSTANT) Q_PROPERTY(Fact* plannedHomePositionAltitude READ plannedHomePositionAltitude CONSTANT) + Q_PROPERTY(QObject* cameraSection READ cameraSection CONSTANT) bool specifyMissionFlightSpeed (void) const { return _specifyMissionFlightSpeed; } - bool specifyGimbal (void) const { return _specifyGimbal; } Fact* plannedHomePositionLatitude (void) { return &_plannedHomePositionLatitudeFact; } Fact* plannedHomePositionLongitude(void) { return &_plannedHomePositionLongitudeFact; } Fact* plannedHomePositionAltitude (void) { return &_plannedHomePositionAltitudeFact; } Fact* missionFlightSpeed (void) { return &_missionFlightSpeedFact; } - Fact* gimbalYaw (void) { return &_gimbalYawFact; } - Fact* gimbalPitch (void) { return &_gimbalPitchFact; } - Fact* cameraAction (void) { return &_cameraActionFact; } - Fact* cameraPhotoIntervalTime (void) { return &_cameraPhotoIntervalTimeFact; } - Fact* cameraPhotoIntervalDistance (void) { return &_cameraPhotoIntervalDistanceFact; } Fact* missionEndAction (void) { return &_missionEndActionFact; } - void setSpecifyMissionFlightSpeed (bool specifyMissionFlightSpeed); - void setSpecifyGimbal (bool specifyGimbal); + void setSpecifyMissionFlightSpeed(bool specifyMissionFlightSpeed); + QObject* cameraSection(void) { return &_cameraSection; } - /// Scans the loaded items for the settings items - static void scanForMissionSettings(QmlObjectListModel* visualItems, Vehicle* vehicle); + /// Scans the loaded items for settings items + static bool scanForMissionSettings(QmlObjectListModel* visualItems, int scanIndex, Vehicle* vehicl); // Overrides from ComplexMissionItem double complexDistance (void) const final; int lastSequenceNumber (void) const final; - QmlObjectListModel* getMissionItems (void) const final; bool load (const QJsonObject& complexObject, int sequenceNumber, QString& errorString) final; double greatestDistanceTo (const QGeoCoordinate &other) const final; void setCruiseSpeed (double cruiseSpeed) final; @@ -95,6 +76,7 @@ public: QGeoCoordinate exitCoordinate (void) const final { return coordinate(); } int sequenceNumber (void) const final { return _sequenceNumber; } double flightSpeed (void) final { return std::numeric_limits::quiet_NaN(); } + void appendMissionItems (QList& items, QObject* missionItemParent) final; bool coordinateHasRelativeAltitude (void) const final { return true; } bool exitCoordinateHasRelativeAltitude (void) const final { return true; } @@ -103,32 +85,27 @@ public: void setDirty (bool dirty) final; void setCoordinate (const QGeoCoordinate& coordinate) final; void setSequenceNumber (int sequenceNumber) final; - void save (QJsonArray& missionItems) const final; + void save (QJsonArray& missionItems) final; static const char* jsonComplexItemTypeValue; signals: - bool specifyMissionFlightSpeedChanged (bool specifyMissionFlightSpeed); - bool specifyGimbalChanged (bool specifyGimbal); + bool specifyMissionFlightSpeedChanged(bool specifyMissionFlightSpeed); private slots: void _setDirtyAndUpdateLastSequenceNumber(void); void _setDirtyAndUpdateCoordinate(void); void _setDirty(void); + void _cameraSectionDirtyChanged(bool dirty); private: - bool _specifyMissionFlightSpeed; - bool _specifyGimbal; - Fact _plannedHomePositionLatitudeFact; - Fact _plannedHomePositionLongitudeFact; - Fact _plannedHomePositionAltitudeFact; - Fact _missionFlightSpeedFact; - Fact _gimbalYawFact; - Fact _gimbalPitchFact; - Fact _cameraActionFact; - Fact _cameraPhotoIntervalDistanceFact; - Fact _cameraPhotoIntervalTimeFact; - Fact _missionEndActionFact; + bool _specifyMissionFlightSpeed; + Fact _plannedHomePositionLatitudeFact; + Fact _plannedHomePositionLongitudeFact; + Fact _plannedHomePositionAltitudeFact; + Fact _missionFlightSpeedFact; + Fact _missionEndActionFact; + CameraSection _cameraSection; int _sequenceNumber; bool _dirty; @@ -139,11 +116,6 @@ private: static const char* _plannedHomePositionLongitudeName; static const char* _plannedHomePositionAltitudeName; static const char* _missionFlightSpeedName; - static const char* _gimbalPitchName; - static const char* _gimbalYawName; - static const char* _cameraActionName; - static const char* _cameraPhotoIntervalDistanceName; - static const char* _cameraPhotoIntervalTimeName; static const char* _missionEndActionName; }; diff --git a/src/MissionManager/SimpleMissionItem.cc b/src/MissionManager/SimpleMissionItem.cc index 1ead1b36e0dd9b2805b8a611388c77042f534c1a..406fbc212ca9c517ebb947674410ad203b524ec7 100644 --- a/src/MissionManager/SimpleMissionItem.cc +++ b/src/MissionManager/SimpleMissionItem.cc @@ -50,6 +50,8 @@ static const struct EnumInfo_s _rgMavFrameInfo[] = { SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, QObject* parent) : VisualMissionItem(vehicle, parent) , _rawEdit(false) + , _dirty(false) + , _cameraSection(NULL) , _commandTree(qgcApp()->toolbox()->missionCommandTree()) , _altitudeRelativeToHomeFact (0, "Altitude is relative to home", FactMetaData::valueTypeUint32) , _supportedCommandFact (0, "Command:", FactMetaData::valueTypeUint32) @@ -69,10 +71,15 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, QObject* parent) _setupMetaData(); _connectSignals(); + _updateCameraSection(); setDefaultsForCommand(); connect(&_missionItem, &MissionItem::flightSpeedChanged, this, &SimpleMissionItem::flightSpeedChanged); + + connect(this, &SimpleMissionItem::sequenceNumberChanged, this, &SimpleMissionItem::lastSequenceNumberChanged); + connect(this, &SimpleMissionItem::cameraSectionChanged, this, &SimpleMissionItem::_setDirtyFromSignal); + connect(this, &SimpleMissionItem::cameraSectionChanged, this, &SimpleMissionItem::_updateLastSequenceNumber); } SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, const MissionItem& missionItem, QObject* parent) @@ -80,6 +87,7 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, const MissionItem& missio , _missionItem(missionItem) , _rawEdit(false) , _dirty(false) + , _cameraSection(NULL) , _commandTree(qgcApp()->toolbox()->missionCommandTree()) , _altitudeRelativeToHomeFact (0, "Altitude is relative to home", FactMetaData::valueTypeUint32) , _supportedCommandFact (0, "Command:", FactMetaData::valueTypeUint32) @@ -99,6 +107,7 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, const MissionItem& missio _setupMetaData(); _connectSignals(); + _updateCameraSection(); _syncFrameToAltitudeRelativeToHome(); } @@ -108,6 +117,7 @@ SimpleMissionItem::SimpleMissionItem(const SimpleMissionItem& other, QObject* pa , _missionItem(other._vehicle) , _rawEdit(false) , _dirty(false) + , _cameraSection(NULL) , _commandTree(qgcApp()->toolbox()->missionCommandTree()) , _altitudeRelativeToHomeFact (0, "Altitude is relative to home", FactMetaData::valueTypeUint32) , _supportedCommandFact (0, "Command:", FactMetaData::valueTypeUint32) @@ -122,6 +132,7 @@ SimpleMissionItem::SimpleMissionItem(const SimpleMissionItem& other, QObject* pa _setupMetaData(); _connectSignals(); + _updateCameraSection(); *this = other; } @@ -240,11 +251,19 @@ SimpleMissionItem::~SimpleMissionItem() { } -void SimpleMissionItem::save(QJsonArray& missionItems) const +void SimpleMissionItem::save(QJsonArray& missionItems) { - QJsonObject itemObject; - _missionItem.save(itemObject); - missionItems.append(itemObject); + QList items; + + appendMissionItems(items, this); + + for (int i=0; isave(saveObject); + missionItems.append(saveObject); + item->deleteLater(); + } } bool SimpleMissionItem::load(QTextStream &loadStream) @@ -489,13 +508,10 @@ void SimpleMissionItem::setRawEdit(bool rawEdit) void SimpleMissionItem::setDirty(bool dirty) { - if (!_homePositionSpecialCase || !dirty) { - // Home position never affects dirty bit - + if (!_homePositionSpecialCase || (_dirty != dirty)) { _dirty = dirty; - // We want to emit dirtyChanged even if _dirty didn't change. This can be handy signal for - // any value within the item changing. - emit dirtyChanged(_dirty); + _cameraSection->setDirty(false); + emit dirtyChanged(dirty); } } @@ -584,6 +600,7 @@ void SimpleMissionItem::setCommand(MavlinkQmlSingleton::Qml_MAV_CMD command) { if ((MAV_CMD)command != _missionItem.command()) { _missionItem.setCommand((MAV_CMD)command); + _updateCameraSection(); } } @@ -608,3 +625,64 @@ double SimpleMissionItem::flightSpeed(void) { return missionItem().flightSpeed(); } + +void SimpleMissionItem::scanForSections(QmlObjectListModel* visualItems, int scanIndex, Vehicle* vehicle) +{ + Q_UNUSED(vehicle); + + qDebug() << "SimpleMissionItem::scanForSections" << scanIndex << _cameraSection->available(); + + if (_cameraSection->available()) { + bool sectionFound = _cameraSection->scanForCameraSection(visualItems, scanIndex); + qDebug() << sectionFound; + } +} + +void SimpleMissionItem::_updateCameraSection(void) +{ + if (_cameraSection) { + // Remove previous section + _cameraSection->deleteLater(); + _cameraSection = NULL; + } + + // Add new section + _cameraSection = new CameraSection(this); + const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_vehicle, (MAV_CMD)command()); + if (uiInfo && uiInfo->cameraSection()) { + _cameraSection->setAvailable(true); + } + + connect(_cameraSection, &CameraSection::dirtyChanged, this, &SimpleMissionItem::_cameraSectionDirtyChanged); + connect(_cameraSection, &CameraSection::availableChanged, this, &SimpleMissionItem::_updateLastSequenceNumber); + connect(_cameraSection, &CameraSection::missionItemCountChanged, this, &SimpleMissionItem::_updateLastSequenceNumber); + + emit cameraSectionChanged(_cameraSection); +} + +int SimpleMissionItem::lastSequenceNumber(void) const +{ + return sequenceNumber() + (_cameraSection ? _cameraSection->missionItemCount() : 0); +} + +void SimpleMissionItem::_updateLastSequenceNumber(void) +{ + emit lastSequenceNumberChanged(lastSequenceNumber()); +} + +void SimpleMissionItem::_cameraSectionDirtyChanged(bool dirty) +{ + if (dirty) { + setDirty(true); + } +} + +void SimpleMissionItem::appendMissionItems(QList& items, QObject* missionItemParent) +{ + int seqNum = sequenceNumber(); + + items.append(new MissionItem(missionItem(), missionItemParent)); + seqNum++; + + _cameraSection->appendMissionItems(items, missionItemParent, seqNum); +} diff --git a/src/MissionManager/SimpleMissionItem.h b/src/MissionManager/SimpleMissionItem.h index df09b63c16d0fb52f82079577de20b56713a24f0..ce1af09ae9a5d359a567178c834e26becf3a903c 100644 --- a/src/MissionManager/SimpleMissionItem.h +++ b/src/MissionManager/SimpleMissionItem.h @@ -14,6 +14,7 @@ #include "VisualMissionItem.h" #include "MissionItem.h" #include "MissionCommandTree.h" +#include "CameraSection.h" /// A SimpleMissionItem is used to represent a single MissionItem to the ui. class SimpleMissionItem : public VisualMissionItem @@ -35,18 +36,27 @@ public: Q_PROPERTY(bool rawEdit READ rawEdit WRITE setRawEdit NOTIFY rawEditChanged) ///< true: raw item editing with all params Q_PROPERTY(bool relativeAltitude READ relativeAltitude NOTIFY frameChanged) + /// Optional sections + Q_PROPERTY(QObject* cameraSection READ cameraSection NOTIFY cameraSectionChanged) + // These properties are used to display the editing ui Q_PROPERTY(QmlObjectListModel* checkboxFacts READ checkboxFacts NOTIFY uiModelChanged) Q_PROPERTY(QmlObjectListModel* comboboxFacts READ comboboxFacts NOTIFY uiModelChanged) Q_PROPERTY(QmlObjectListModel* textFieldFacts READ textFieldFacts NOTIFY uiModelChanged) + /// Scans the loaded items for additional section settings + /// @param visualItems List of all visual items + /// @param scanIndex Index to start scanning from + /// @param vehicle Vehicle associated with this mission + void scanForSections(QmlObjectListModel* visualItems, int scanIndex, Vehicle* vehicle); + // Property accesors QString category (void) const; MavlinkQmlSingleton::Qml_MAV_CMD command(void) const { return (MavlinkQmlSingleton::Qml_MAV_CMD)_missionItem._commandFact.cookedValue().toInt(); } bool friendlyEditAllowed (void) const; bool rawEdit (void) const; - + CameraSection* cameraSection (void) { return _cameraSection; } QmlObjectListModel* textFieldFacts (void); QmlObjectListModel* checkboxFacts (void); @@ -69,6 +79,7 @@ public: bool relativeAltitude(void) { return _missionItem.frame() == MAV_FRAME_GLOBAL_RELATIVE_ALT; } MissionItem& missionItem(void) { return _missionItem; } + const MissionItem& missionItem(void) const { return _missionItem; } // Overrides from VisualMissionItem @@ -84,6 +95,7 @@ public: int sequenceNumber (void) const final { return _missionItem.sequenceNumber(); } double flightSpeed (void) final; QString mapVisualQML (void) const final { return QStringLiteral("SimpleItemMapVisual.qml"); } + void appendMissionItems (QList& items, QObject* missionItemParent) final; bool coordinateHasRelativeAltitude (void) const final { return _missionItem.relativeAltitude(); } bool exitCoordinateHasRelativeAltitude (void) const final { return coordinateHasRelativeAltitude(); } @@ -92,7 +104,8 @@ public: void setDirty (bool dirty) final; void setCoordinate (const QGeoCoordinate& coordinate) final; void setSequenceNumber (int sequenceNumber) final; - void save (QJsonArray& missionItems) const final; + int lastSequenceNumber (void) const final; + void save (QJsonArray& missionItems) final; public slots: void setDefaultsForCommand(void); @@ -104,9 +117,11 @@ signals: void headingDegreesChanged (double heading); void rawEditChanged (bool rawEdit); void uiModelChanged (void); + void cameraSectionChanged (QObject* cameraSection); private slots: void _setDirtyFromSignal(void); + void _cameraSectionDirtyChanged(bool dirty); void _sendCommandChanged(void); void _sendCoordinateChanged(void); void _sendFrameChanged(void); @@ -114,17 +129,21 @@ private slots: void _sendUiModelChanged(void); void _syncAltitudeRelativeToHomeToFrame(const QVariant& value); void _syncFrameToAltitudeRelativeToHome(void); + void _updateLastSequenceNumber(void); private: void _clearParamMetaData(void); void _connectSignals(void); void _setupMetaData(void); + void _updateCameraSection(void); private: MissionItem _missionItem; bool _rawEdit; bool _dirty; + CameraSection* _cameraSection; + MissionCommandTree* _commandTree; Fact _altitudeRelativeToHomeFact; diff --git a/src/MissionManager/SurveyMissionItem.cc b/src/MissionManager/SurveyMissionItem.cc index f6db04b6a4bbc1ed6648991d31e6b49e094a0ea5..e9f68eb85424d7ab411880261a324aa2cd4271d1 100644 --- a/src/MissionManager/SurveyMissionItem.cc +++ b/src/MissionManager/SurveyMissionItem.cc @@ -294,7 +294,7 @@ void SurveyMissionItem::setDirty(bool dirty) } } -void SurveyMissionItem::save(QJsonArray& missionItems) const +void SurveyMissionItem::save(QJsonArray& missionItems) { QJsonObject saveObject; @@ -822,11 +822,10 @@ void SurveyMissionItem::_gridGenerator(const QList& polygonPoints, QLi } } -QmlObjectListModel* SurveyMissionItem::getMissionItems(void) const +void SurveyMissionItem::appendMissionItems(QList& items, QObject* missionItemParent) { - QmlObjectListModel* pMissionItems = new QmlObjectListModel; - int seqNum = _sequenceNumber; + for (int i=0; i<_gridPoints.count(); i++) { QGeoCoordinate coord = _gridPoints[i].value(); double altitude = _gridAltitudeFact.rawValue().toDouble(); @@ -840,8 +839,8 @@ QmlObjectListModel* SurveyMissionItem::getMissionItems(void) const altitude, true, // autoContinue false, // isCurrentItem - pMissionItems); // parent - allow delete on pMissionItems to delete everthing - pMissionItems->append(item); + missionItemParent); + items.append(item); if (_cameraTriggerFact.rawValue().toBool() && i == 0) { // Turn on camera @@ -852,8 +851,8 @@ QmlObjectListModel* SurveyMissionItem::getMissionItems(void) const 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, // param 2-7 true, // autoContinue false, // isCurrentItem - pMissionItems); // parent - allow delete on pMissionItems to delete everthing - pMissionItems->append(item); + missionItemParent); + items.append(item); } } @@ -866,11 +865,9 @@ QmlObjectListModel* SurveyMissionItem::getMissionItems(void) const 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, // param 2-7 true, // autoContinue false, // isCurrentItem - pMissionItems); // parent - allow delete on pMissionItems to delete everthing - pMissionItems->append(item); + missionItemParent); + items.append(item); } - - return pMissionItems; } void SurveyMissionItem::_cameraTriggerChanged(void) diff --git a/src/MissionManager/SurveyMissionItem.h b/src/MissionManager/SurveyMissionItem.h index 4fddb63d0267b2cec7b2b5de168793783bec22d6..389cb4744ff5098285c8823cb1b4dee9aaaca95b 100644 --- a/src/MissionManager/SurveyMissionItem.h +++ b/src/MissionManager/SurveyMissionItem.h @@ -98,7 +98,6 @@ public: double complexDistance (void) const final { return _surveyDistance; } int lastSequenceNumber (void) const final; - QmlObjectListModel* getMissionItems (void) const final; bool load (const QJsonObject& complexObject, int sequenceNumber, QString& errorString) final; double greatestDistanceTo (const QGeoCoordinate &other) const final; void setCruiseSpeed (double cruiseSpeed) final; @@ -118,6 +117,7 @@ public: QGeoCoordinate exitCoordinate (void) const final { return _exitCoordinate; } int sequenceNumber (void) const final { return _sequenceNumber; } double flightSpeed (void) final { return std::numeric_limits::quiet_NaN(); } + void appendMissionItems (QList& items, QObject* missionItemParent) final; bool coordinateHasRelativeAltitude (void) const final { return _gridAltitudeRelativeFact.rawValue().toBool(); } bool exitCoordinateHasRelativeAltitude (void) const final { return _gridAltitudeRelativeFact.rawValue().toBool(); } @@ -127,7 +127,7 @@ public: void setCoordinate (const QGeoCoordinate& coordinate) final; void setSequenceNumber (int sequenceNumber) final; void setTurnaroundDist (double dist) { _turnaroundDistFact.setRawValue(dist); } - void save (QJsonArray& missionItems) const final; + void save (QJsonArray& missionItems) final; static const char* jsonComplexItemTypeValue; diff --git a/src/MissionManager/VisualMissionItem.h b/src/MissionManager/VisualMissionItem.h index 0b381102e22ea8d349677c82b1bbdb60c3601c47..17f2de5f82bc4baf827339681c2262d6bc3fe026 100644 --- a/src/MissionManager/VisualMissionItem.h +++ b/src/MissionManager/VisualMissionItem.h @@ -27,6 +27,8 @@ #include "QmlObjectListModel.h" #include "Vehicle.h" +class MissionItem; + // Abstract base class for all Simple and Complex visual mission objects. class VisualMissionItem : public QObject { @@ -132,14 +134,20 @@ public: virtual void setDirty (bool dirty) = 0; virtual void setCoordinate (const QGeoCoordinate& coordinate) = 0; virtual void setSequenceNumber (int sequenceNumber) = 0; + virtual int lastSequenceNumber (void) const = 0; /// Save the item(s) in Json format /// @param missionItems Current set of mission items, new items should be appended to the end - virtual void save(QJsonArray& missionItems) const = 0; + virtual void save(QJsonArray& missionItems) = 0; /// @return The QML resource file which contains the control which visualizes the item on the map. virtual QString mapVisualQML(void) const = 0; + /// Returns the mission items associated with the complex item. Caller is responsible for freeing. + /// @param items List to append to + /// @param missionItemParent Parent object for newly created MissionItems + virtual void appendMissionItems(QList& items, QObject* missionItemParent) = 0; + static const char* jsonTypeKey; ///< Json file attribute which specifies the item type static const char* jsonTypeSimpleItemValue; ///< Item type is MISSION_ITEM static const char* jsonTypeComplexItemValue; ///< Item type is Complex Item @@ -162,6 +170,7 @@ signals: void specifiesCoordinateChanged (void); void isStandaloneCoordinateChanged (void); void flightSpeedChanged (double flightSpeed); + void lastSequenceNumberChanged (int sequenceNumber); void coordinateHasRelativeAltitudeChanged (bool coordinateHasRelativeAltitude); void exitCoordinateHasRelativeAltitudeChanged (bool exitCoordinateHasRelativeAltitude); diff --git a/src/QmlControls/QGCComboBox.qml b/src/QmlControls/QGCComboBox.qml index ce734073fed9f8b94f65ea90b421563a938bddc9..473eff1abd7432691f0bfa84083f200203715b5a 100644 --- a/src/QmlControls/QGCComboBox.qml +++ b/src/QmlControls/QGCComboBox.qml @@ -27,13 +27,15 @@ ComboBox { border.color: control._qgcPal.buttonText } - Image { - id: imageItem - source: "/qmlimages/arrow-down.png" + QGCColoredImage { + id: image + width: ScreenTools.defaultFontPixelHeight / 2 + height: width anchors.verticalCenter: parent.verticalCenter - anchors.right: parent.right - anchors.rightMargin: dropDownButtonWidth / 2 - opacity: control.enabled ? 0.6 : 0.3 + anchors.right: parent.right + anchors.rightMargin: dropDownButtonWidth / 2 + source: "/qmlimages/arrow-down.png" + color: qgcPal.text } } } diff --git a/src/QmlControls/QGroundControl.Controls.qmldir b/src/QmlControls/QGroundControl.Controls.qmldir index b4fbe4801d450aebcb425c81c7d8f8abbb626599..1359b5e55bf7dd80bb2bd0ff76b2c7afd3a200af 100644 --- a/src/QmlControls/QGroundControl.Controls.qmldir +++ b/src/QmlControls/QGroundControl.Controls.qmldir @@ -2,6 +2,7 @@ Module QGroundControl.Controls AnalyzePage 1.0 AnalyzePage.qml AppMessages 1.0 AppMessages.qml +CameraSection 1.0 CameraSection.qml ClickableColor 1.0 ClickableColor.qml DropButton 1.0 DropButton.qml DropPanel 1.0 DropPanel.qml diff --git a/src/QmlControls/arrow-down.png b/src/QmlControls/arrow-down.png index c20f6256b35d278a0f4c45f660fb48d06acfbac0..407e2c231c4627864b31ea20942281ee298b12bf 100644 Binary files a/src/QmlControls/arrow-down.png and b/src/QmlControls/arrow-down.png differ