diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc index 335dc77ba08a9aa229fd39b1b9ee828b71c7a5ab..a5fa8a49a600991833600dee8980d41a4681f5ee 100644 --- a/src/MissionManager/MissionController.cc +++ b/src/MissionManager/MissionController.cc @@ -646,6 +646,21 @@ void MissionController::loadFromFile(const QString& filename) MissionController::_scanForAdditionalSettings(_visualItems, _activeVehicle); _initAllVisualItems(); + + QString filenameOnly = filename; + int lastSepIndex = filename.lastIndexOf(QStringLiteral("/")); + if (lastSepIndex != -1) { + filenameOnly = filename.right(filename.length() - lastSepIndex - 1); + } + QString extension = AppSettings::missionFileExtension; + if (filenameOnly.endsWith("." + extension)) { + filenameOnly = filenameOnly.left(filenameOnly.length() - extension.length() - 1); + } + + _settingsItem->missionName()->setRawValue(filenameOnly); + _settingsItem->setExistingMission(true); + + sendToVehicle(); } bool MissionController::loadItemsFromFile(Vehicle* vehicle, const QString& filename, QmlObjectListModel** visualItems) @@ -1577,3 +1592,25 @@ bool MissionController::missionInProgress(void) const { return _visualItems && _visualItems->count() > 1 && (!_visualItems->value(0)->isCurrentItem() && !_visualItems->value(1)->isCurrentItem()); } + +void MissionController::save(void) +{ + // Save to file if the mission is named + QString missionFullPath = _settingsItem->missionFullPath()->rawValue().toString(); + if (!missionFullPath.isEmpty()) { + saveToFile(missionFullPath); + } + + // Send to vehicle if we are connected + if (!_activeVehicle->isOfflineEditingVehicle()) { + sendToVehicle(); + } + + _settingsItem->setExistingMission(_visualItems->count() > 1 && !missionFullPath.isEmpty()); +} + +void MissionController::clearMission(void) +{ + removeAll(); + save(); +} diff --git a/src/MissionManager/MissionController.h b/src/MissionManager/MissionController.h index e07ca14e1d7acdd47b9ee6363c26388ba781c345..3b06b6c170a434141c99f4b041322a26263a5b08 100644 --- a/src/MissionManager/MissionController.h +++ b/src/MissionManager/MissionController.h @@ -88,6 +88,9 @@ public: /// Sends the mission items to the specified vehicle static void sendItemsToVehicle(Vehicle* vehicle, QmlObjectListModel* visualMissionItems); + Q_INVOKABLE void save(void); + Q_INVOKABLE void clearMission(void); + // Overrides from PlanElementController void start (bool editMode) final; void startStaticActiveVehicle (Vehicle* vehicle) final; diff --git a/src/MissionManager/MissionSettings.FactMetaData.json b/src/MissionManager/MissionSettings.FactMetaData.json index 52f47a47ca3a04607837418049a8fed405bfc1c4..ee2ca017cc4ed4379820fe102c7a3f1062c71777 100644 --- a/src/MissionManager/MissionSettings.FactMetaData.json +++ b/src/MissionManager/MissionSettings.FactMetaData.json @@ -19,8 +19,14 @@ "name": "MissionEndAction", "shortDescription": "The action to take when the mission completed.", "type": "uint32", - "enumStrings": "No action on mission completion,Loiter after mission completes,RTL after mission completes,Land after mission completes", - "enumValues": "0,1,2,3", + "enumStrings": "No action on mission end,Loiter after mission end,RTL after mission end", + "enumValues": "0,1,2", "defaultValue": 0 +}, +{ + "name": "MissionName", + "shortDescription": "Name for the mission.", + "type": "string", + "defaultValue": "" } ] diff --git a/src/MissionManager/MissionSettingsItem.cc b/src/MissionManager/MissionSettingsItem.cc index 56227449aa8d8158759ac75c1575de5ccec90897..7081306e0a91de856050534a638235c3ef9ac8f8 100644 --- a/src/MissionManager/MissionSettingsItem.cc +++ b/src/MissionManager/MissionSettingsItem.cc @@ -23,15 +23,20 @@ QGC_LOGGING_CATEGORY(MissionSettingsComplexItemLog, "MissionSettingsComplexItemL const char* MissionSettingsItem::jsonComplexItemTypeValue = "MissionSettings"; -const char* MissionSettingsItem::_plannedHomePositionAltitudeName = "PlannedHomePositionAltitude"; -const char* MissionSettingsItem::_missionFlightSpeedName = "FlightSpeed"; -const char* MissionSettingsItem::_missionEndActionName = "MissionEndAction"; +const char* MissionSettingsItem::_missionNameName = "MissionName"; +const char* MissionSettingsItem::_missionFullPathName = "MissionFullPath"; +const char* MissionSettingsItem::_plannedHomePositionAltitudeName = "PlannedHomePositionAltitude"; +const char* MissionSettingsItem::_missionFlightSpeedName = "FlightSpeed"; +const char* MissionSettingsItem::_missionEndActionName = "MissionEndAction"; QMap MissionSettingsItem::_metaDataMap; MissionSettingsItem::MissionSettingsItem(Vehicle* vehicle, QObject* parent) : ComplexMissionItem(vehicle, parent) + , _existingMission(false) , _specifyMissionFlightSpeed(false) + , _missionNameFact (0, _missionNameName, FactMetaData::valueTypeString) + , _missionFullPathFact (0, _missionFullPathName, FactMetaData::valueTypeString) , _plannedHomePositionAltitudeFact (0, _plannedHomePositionAltitudeName, FactMetaData::valueTypeDouble) , _missionFlightSpeedFact (0, _missionFlightSpeedName, FactMetaData::valueTypeDouble) , _missionEndActionFact (0, _missionEndActionName, FactMetaData::valueTypeUint32) @@ -44,10 +49,12 @@ MissionSettingsItem::MissionSettingsItem(Vehicle* vehicle, QObject* parent) _metaDataMap = FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/MissionSettings.FactMetaData.json"), NULL /* metaDataParent */); } + _missionNameFact.setMetaData (_metaDataMap[_missionNameName]); _plannedHomePositionAltitudeFact.setMetaData (_metaDataMap[_plannedHomePositionAltitudeName]); _missionFlightSpeedFact.setMetaData (_metaDataMap[_missionFlightSpeedName]); _missionEndActionFact.setMetaData (_metaDataMap[_missionEndActionName]); + _missionNameFact.setRawValue (_missionNameFact.rawDefaultValue()); _plannedHomePositionAltitudeFact.setRawValue (_plannedHomePositionAltitudeFact.rawDefaultValue()); _missionEndActionFact.setRawValue (_missionEndActionFact.rawDefaultValue()); @@ -58,6 +65,8 @@ MissionSettingsItem::MissionSettingsItem(Vehicle* vehicle, QObject* parent) setHomePositionSpecialCase(true); + connect(&_missionNameFact, &Fact::valueChanged, this, &MissionSettingsItem::_missionNameChanged); + connect(this, &MissionSettingsItem::specifyMissionFlightSpeedChanged, this, &MissionSettingsItem::_setDirtyAndUpdateLastSequenceNumber); connect(&_cameraSection, &CameraSection::missionItemCountChanged, this, &MissionSettingsItem::_setDirtyAndUpdateLastSequenceNumber); @@ -232,21 +241,6 @@ bool MissionSettingsItem::addMissionEndAction(QList& items, int se false, // isCurrentItem missionItemParent); break; - case MissionEndLand: - qCDebug(MissionSettingsComplexItemLog) << "Appending end action Land seqNum" << seqNum; - item = new MissionItem(seqNum, - MAV_CMD_NAV_LAND, - MAV_FRAME_GLOBAL_RELATIVE_ALT, - 0, // abort Altitude - 0, 0, // not used - 0, // yaw - lastWaypointCoord.latitude(), - lastWaypointCoord.longitude(), - 0, // altitude - true, // autoContinue - false, // isCurrentItem - missionItemParent); - break; case MissionEndRTL: qCDebug(MissionSettingsComplexItemLog) << "Appending end action RTL seqNum" << seqNum; item = new MissionItem(seqNum, @@ -351,14 +345,6 @@ bool MissionSettingsItem::scanForMissionSettings(QmlObjectListModel* visualItems } break; - case MAV_CMD_NAV_LAND: - if (missionItem.param1() == 0 && missionItem.param2() == 0 && missionItem.param3() == 0 && missionItem.param4() == 0 && missionItem.param7() == 0) { - qCDebug(MissionSettingsComplexItemLog) << "Scan: Found end action Land"; - settingsItem->missionEndAction()->setRawValue(MissionEndLand); - visualItems->removeAt(lastIndex)->deleteLater(); - } - break; - case MAV_CMD_NAV_RETURN_TO_LAUNCH: if (missionItem.param1() == 0 && missionItem.param2() == 0 && missionItem.param3() == 0 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) { qCDebug(MissionSettingsComplexItemLog) << "Scan: Found end action RTL"; @@ -429,3 +415,23 @@ void MissionSettingsItem::_updateAltitudeInCoordinate(QVariant value) emit exitCoordinateChanged(_plannedHomePositionCoordinate); } } + +void MissionSettingsItem::_missionNameChanged(QVariant value) +{ + QString missionDir = qgcApp()->toolbox()->settingsManager()->appSettings()->missionSavePath(); + QString missionName = value.toString(); + + if (missionName.isEmpty()) { + _missionFullPathFact.setRawValue(QString()); + } else { + _missionFullPathFact.setRawValue(missionDir + "/" + missionName); + } +} + +void MissionSettingsItem::setExistingMission(bool existingMission) +{ + if (existingMission != _existingMission) { + _existingMission = existingMission; + emit existingMissionChanged(existingMission ); + } +} diff --git a/src/MissionManager/MissionSettingsItem.h b/src/MissionManager/MissionSettingsItem.h index 976db7af33981df1f788f99acc4d57ab241fa47a..2ccb6343acc4310f695f1970c92095866f99555e 100644 --- a/src/MissionManager/MissionSettingsItem.h +++ b/src/MissionManager/MissionSettingsItem.h @@ -28,23 +28,29 @@ public: enum MissionEndAction { MissionEndNoAction, MissionEndLoiter, - MissionEndRTL, - MissionEndLand + MissionEndRTL }; Q_ENUMS(MissionEndAction) - Q_PROPERTY(bool specifyMissionFlightSpeed READ specifyMissionFlightSpeed WRITE setSpecifyMissionFlightSpeed NOTIFY specifyMissionFlightSpeedChanged) - Q_PROPERTY(Fact* missionFlightSpeed READ missionFlightSpeed CONSTANT) - Q_PROPERTY(Fact* missionEndAction READ missionEndAction CONSTANT) - Q_PROPERTY(Fact* plannedHomePositionAltitude READ plannedHomePositionAltitude CONSTANT) - Q_PROPERTY(QObject* cameraSection READ cameraSection CONSTANT) - - bool specifyMissionFlightSpeed (void) const { return _specifyMissionFlightSpeed; } + Q_PROPERTY(Fact* missionName READ missionName CONSTANT) + Q_PROPERTY(Fact* missionFullPath READ missionFullPath CONSTANT) + Q_PROPERTY(bool existingMission READ existingMission WRITE setExistingMission NOTIFY existingMissionChanged) + Q_PROPERTY(bool specifyMissionFlightSpeed READ specifyMissionFlightSpeed WRITE setSpecifyMissionFlightSpeed NOTIFY specifyMissionFlightSpeedChanged) + Q_PROPERTY(Fact* missionFlightSpeed READ missionFlightSpeed CONSTANT) + Q_PROPERTY(Fact* missionEndAction READ missionEndAction CONSTANT) + Q_PROPERTY(Fact* plannedHomePositionAltitude READ plannedHomePositionAltitude CONSTANT) + Q_PROPERTY(QObject* cameraSection READ cameraSection CONSTANT) + + Fact* missionName (void) { return &_missionNameFact; } + Fact* missionFullPath (void) { return &_missionFullPathFact; } Fact* plannedHomePositionAltitude (void) { return &_plannedHomePositionAltitudeFact; } Fact* missionFlightSpeed (void) { return &_missionFlightSpeedFact; } Fact* missionEndAction (void) { return &_missionEndActionFact; } + bool specifyMissionFlightSpeed (void) const { return _specifyMissionFlightSpeed; } + bool existingMission (void) const { return _existingMission; } void setSpecifyMissionFlightSpeed(bool specifyMissionFlightSpeed); + void setExistingMission(bool existingMission); QObject* cameraSection(void) { return &_cameraSection; } /// Scans the loaded items for settings items @@ -94,17 +100,22 @@ public: static const char* jsonComplexItemTypeValue; signals: - bool specifyMissionFlightSpeedChanged(bool specifyMissionFlightSpeed); + void specifyMissionFlightSpeedChanged(bool specifyMissionFlightSpeed); + void existingMissionChanged(bool existingMission); private slots: void _setDirtyAndUpdateLastSequenceNumber (void); void _setDirty (void); void _cameraSectionDirtyChanged (bool dirty); void _updateAltitudeInCoordinate (QVariant value); + void _missionNameChanged (QVariant value); private: + bool _existingMission; bool _specifyMissionFlightSpeed; QGeoCoordinate _plannedHomePositionCoordinate; // Does not include altitde + Fact _missionNameFact; + Fact _missionFullPathFact; Fact _plannedHomePositionAltitudeFact; Fact _missionFlightSpeedFact; Fact _missionEndActionFact; @@ -115,6 +126,8 @@ private: static QMap _metaDataMap; + static const char* _missionNameName; + static const char* _missionFullPathName; static const char* _plannedHomePositionAltitudeName; static const char* _missionFlightSpeedName; static const char* _missionEndActionName; diff --git a/src/PlanView/MissionItemEditor.qml b/src/PlanView/MissionItemEditor.qml index 17eed77ae0302640e6e598dfa7fdadd44c39b8d0..9542677ffa413f919f71b21e1e027b9440138608 100644 --- a/src/PlanView/MissionItemEditor.qml +++ b/src/PlanView/MissionItemEditor.qml @@ -28,7 +28,7 @@ Rectangle { property bool _currentItem: missionItem.isCurrentItem property color _outerTextColor: _currentItem ? "black" : qgcPal.text - property bool _noMissionItemsAdded: ListView.view.model.count == 1 + property bool _noMissionItemsAdded: ListView.view.model.count === 1 property real _sectionSpacer: ScreenTools.defaultFontPixelWidth / 2 // spacing between section headings readonly property real _editFieldWidth: Math.min(width - _margin * 2, ScreenTools.defaultFontPixelWidth * 12) diff --git a/src/PlanView/MissionSettingsEditor.qml b/src/PlanView/MissionSettingsEditor.qml index 573ff44639a4376cbf00c1be5a8dde9523463d19..e0b61195d51eda84cbd78f8f35f70ea5fd2db066 100644 --- a/src/PlanView/MissionSettingsEditor.qml +++ b/src/PlanView/MissionSettingsEditor.qml @@ -9,6 +9,7 @@ import QGroundControl.Controls 1.0 import QGroundControl.FactControls 1.0 import QGroundControl.Palette 1.0 import QGroundControl.SettingsManager 1.0 +import QGroundControl.Controllers 1.0 // Editor for Mission Settings Rectangle { @@ -19,6 +20,38 @@ Rectangle { visible: missionItem.isCurrentItem radius: _radius + property var _missionVehicle: missionController.vehicle + property bool _vehicleHasHomePosition: _missionVehicle.homePosition.isValid + property bool _offlineEditing: _missionVehicle.isOfflineEditingVehicle + property bool _showOfflineVehicleCombos: _offlineEditing && _multipleFirmware && _noMissionItemsAdded + property bool _showCruiseSpeed: !_missionVehicle.multiRotor + property bool _showHoverSpeed: _missionVehicle.multiRotor || _missionVehicle.vtol + property bool _multipleFirmware: QGroundControl.supportedFirmwareCount > 2 + property real _fieldWidth: ScreenTools.defaultFontPixelWidth * 16 + property bool _mobile: ScreenTools.isMobile + property var _savePath: QGroundControl.settingsManager.appSettings.missionSavePath + property var _fileExtension: QGroundControl.settingsManager.appSettings.missionFileExtension + property bool _newMissionAlreadyExists: false + property bool _noMissionName: missionItem.missionName.valueString === "" + property bool _showMissionList: _noMissionItemsAdded && (_noMissionName || _newMissionAlreadyExists) + property bool _existingMissionLoaded: missionItem.existingMission + + readonly property string _firmwareLabel: qsTr("Firmware") + readonly property string _vehicleLabel: qsTr("Vehicle") + + QGCPalette { id: qgcPal } + QFileDialogController { id: fileController } + + Connections { + target: missionItem.missionName + + onRawValueChanged: { + if (!_existingMissionLoaded) { + _newMissionAlreadyExists = !_noMissionName && fileController.fileExists(_savePath + "/" + missionItem.missionName.valueString + "." + _fileExtension) + } + } + } + Loader { id: deferedload active: valuesRect.visible @@ -33,21 +66,6 @@ Rectangle { id: valuesItem height: valuesColumn.height + (_margin * 2) - property var _missionVehicle: missionController.vehicle - property bool _vehicleHasHomePosition: _missionVehicle.homePosition.isValid - property bool _offlineEditing: _missionVehicle.isOfflineEditingVehicle - property bool _showOfflineVehicleCombos: _offlineEditing && _multipleFirmware && _noMissionItemsAdded - property bool _showCruiseSpeed: !_missionVehicle.multiRotor - property bool _showHoverSpeed: _missionVehicle.multiRotor || _missionVehicle.vtol - property bool _multipleFirmware: QGroundControl.supportedFirmwareCount > 2 - property real _fieldWidth: ScreenTools.defaultFontPixelWidth * 16 - property bool _mobile: ScreenTools.isMobile - - readonly property string _firmwareLabel: qsTr("Firmware") - readonly property string _vehicleLabel: qsTr("Vehicle") - - QGCPalette { id: qgcPal } - Column { id: valuesColumn anchors.left: parent.left @@ -55,176 +73,269 @@ Rectangle { anchors.top: parent.top spacing: _margin - SectionHeader { - id: plannedHomePositionSection - text: qsTr("Planned Home Position") - showSpacer: false - visible: !_vehicleHasHomePosition + QGCLabel { + text: qsTr("Mission name") + font.pointSize: ScreenTools.smallFontPointSize } - Column { + FactTextField { anchors.left: parent.left anchors.right: parent.right - spacing: _margin - visible: plannedHomePositionSection.checked && !_vehicleHasHomePosition - - GridLayout { - anchors.left: parent.left - anchors.right: parent.right - columnSpacing: ScreenTools.defaultFontPixelWidth - rowSpacing: columnSpacing - columns: 2 - - QGCLabel { - text: qsTr("Altitude") - } - FactTextField { - fact: missionItem.plannedHomePositionAltitude - Layout.fillWidth: true - } - } + fact: missionItem.missionName + visible: !_existingMissionLoaded + } - QGCLabel { - width: parent.width - wrapMode: Text.WordWrap - font.pointSize: ScreenTools.smallFontPointSize - text: qsTr("Actual position set by vehicle at flight time.") - horizontalAlignment: Text.AlignHCenter - } + QGCLabel { + text: missionItem.missionName.valueString + visible: _existingMissionLoaded + } - QGCButton { - text: qsTr("Set Home To Map Center") - onClicked: missionItem.coordinate = map.center - anchors.horizontalCenter: parent.horizontalCenter - } + QGCLabel { + text: qsTr("Mission already exists") + font.pointSize: ScreenTools.smallFontPointSize + color: qgcPal.warningText + visible: !_existingMissionLoaded && _newMissionAlreadyExists } - SectionHeader { - id: vehicleInfoSectionHeader - text: qsTr("Vehicle Info") - visible: _offlineEditing - checked: false + QGCButton { + text: qsTr("Clear mission") + visible: !_noMissionItemsAdded + onClicked: missionController.clearMission() } - GridLayout { - anchors.left: parent.left - anchors.right: parent.right - columnSpacing: ScreenTools.defaultFontPixelWidth - rowSpacing: columnSpacing - columns: 2 - visible: vehicleInfoSectionHeader.visible && vehicleInfoSectionHeader.checked - - QGCLabel { - text: _firmwareLabel - Layout.fillWidth: true - visible: _showOfflineVehicleCombos - } - FactComboBox { - fact: QGroundControl.settingsManager.appSettings.offlineEditingFirmwareType - indexModel: false - Layout.preferredWidth: _fieldWidth - visible: _showOfflineVehicleCombos - } + Loader { + anchors.left: parent.left + anchors.right: parent.right + sourceComponent: _showMissionList ? missionList : missionSettings + } + } // Column + } // Item + } // Component + } // Loader - QGCLabel { - text: _vehicleLabel - Layout.fillWidth: true - visible: _showOfflineVehicleCombos - } - FactComboBox { - fact: QGroundControl.settingsManager.appSettings.offlineEditingVehicleType - indexModel: false - Layout.preferredWidth: _fieldWidth - visible: _showOfflineVehicleCombos - } + Component { + id: missionList - QGCLabel { - text: qsTr("Cruise speed") - visible: _showCruiseSpeed - Layout.fillWidth: true - } - FactTextField { - fact: QGroundControl.settingsManager.appSettings.offlineEditingCruiseSpeed - visible: _showCruiseSpeed - Layout.preferredWidth: _fieldWidth - } + QGCFlickable { + anchors.left: parent.left + anchors.right: parent.right + height: missionColumn.height - QGCLabel { - text: qsTr("Hover speed") - visible: _showHoverSpeed - Layout.fillWidth: true - } - FactTextField { - fact: QGroundControl.settingsManager.appSettings.offlineEditingHoverSpeed - visible: _showHoverSpeed - Layout.preferredWidth: _fieldWidth - } - } // GridLayout + Column { + id: missionColumn + anchors.left: parent.left + anchors.right: parent.right + spacing: _margin + + SectionHeader { + text: qsTr("Load Mission") + showSpacer: false + } - SectionHeader { - id: missionDefaultsSectionHeader - text: qsTr("Mission Defaults") - checked: true + QGCButton { + anchors.left: parent.left + anchors.right: parent.right + text: qsTr("Load from Vehicle") + visible: !_offlineEditing + + onClicked: { + missionController.loadFromVehicle() } + } + + QGCLabel { + text: qsTr("No mission files") + visible: missionRepeater.model.length === 0 + } - Column { + Repeater { + id: missionRepeater + model: fileController.getFiles(_savePath, _fileExtension); + + QGCButton { anchors.left: parent.left anchors.right: parent.right - spacing: _margin - visible: missionDefaultsSectionHeader.checked - - GridLayout { - anchors.left: parent.left - anchors.right: parent.right - columnSpacing: ScreenTools.defaultFontPixelWidth - rowSpacing: columnSpacing - columns: 2 - - QGCLabel { - text: qsTr("Altitude") - } - FactTextField { - fact: QGroundControl.settingsManager.appSettings.defaultMissionItemAltitude - Layout.fillWidth: true - } - - QGCCheckBox { - id: flightSpeedCheckBox - text: qsTr("Flight speed") - visible: !_missionVehicle.vtol - checked: missionItem.specifyMissionFlightSpeed - onClicked: missionItem.specifyMissionFlightSpeed = checked - } - FactTextField { - Layout.fillWidth: true - fact: missionItem.missionFlightSpeed - visible: flightSpeedCheckBox.visible - enabled: flightSpeedCheckBox.checked - } - } // GridLayout - - FactComboBox { - anchors.left: parent.left - anchors.right: parent.right - fact: missionItem.missionEndAction - indexModel: false + text: modelData + + onClicked: { + missionController.loadFromFile(fileController.fullyQualifiedFilename(_savePath, modelData, _fileExtension)) } } + } + } + } + } + + Component { + id: missionSettings + + Column { + id: valuesColumn + anchors.left: parent.left + anchors.right: parent.right + anchors.top: parent.top + spacing: _margin + + SectionHeader { + id: missionDefaultsSectionHeader + text: qsTr("Mission Defaults") + checked: true + showSpacer: false + } + + Column { + anchors.left: parent.left + anchors.right: parent.right + spacing: _margin + visible: missionDefaultsSectionHeader.checked + + GridLayout { + anchors.left: parent.left + anchors.right: parent.right + columnSpacing: ScreenTools.defaultFontPixelWidth + rowSpacing: columnSpacing + columns: 2 + + QGCLabel { + text: qsTr("Waypoint alt") + } + FactTextField { + fact: QGroundControl.settingsManager.appSettings.defaultMissionItemAltitude + Layout.fillWidth: true + } - CameraSection { - checked: missionItem.cameraSection.settingsSpecified + QGCCheckBox { + id: flightSpeedCheckBox + text: qsTr("Flight speed") + visible: !_missionVehicle.vtol + checked: missionItem.specifyMissionFlightSpeed + onClicked: missionItem.specifyMissionFlightSpeed = checked + } + FactTextField { + Layout.fillWidth: true + fact: missionItem.missionFlightSpeed + visible: flightSpeedCheckBox.visible + enabled: flightSpeedCheckBox.checked } + } // GridLayout + + FactComboBox { + anchors.left: parent.left + anchors.right: parent.right + fact: missionItem.missionEndAction + indexModel: false + } + } + + CameraSection { + checked: missionItem.cameraSection.settingsSpecified + } + + SectionHeader { + id: vehicleInfoSectionHeader + text: qsTr("Vehicle Info") + visible: _offlineEditing + checked: false + } + + GridLayout { + anchors.left: parent.left + anchors.right: parent.right + columnSpacing: ScreenTools.defaultFontPixelWidth + rowSpacing: columnSpacing + columns: 2 + visible: vehicleInfoSectionHeader.visible && vehicleInfoSectionHeader.checked + + QGCLabel { + text: _firmwareLabel + Layout.fillWidth: true + visible: _showOfflineVehicleCombos + } + FactComboBox { + fact: QGroundControl.settingsManager.appSettings.offlineEditingFirmwareType + indexModel: false + Layout.preferredWidth: _fieldWidth + visible: _showOfflineVehicleCombos + } + + QGCLabel { + text: _vehicleLabel + Layout.fillWidth: true + visible: _showOfflineVehicleCombos + } + FactComboBox { + fact: QGroundControl.settingsManager.appSettings.offlineEditingVehicleType + indexModel: false + Layout.preferredWidth: _fieldWidth + visible: _showOfflineVehicleCombos + } + + QGCLabel { + text: qsTr("Cruise speed") + visible: _showCruiseSpeed + Layout.fillWidth: true + } + FactTextField { + fact: QGroundControl.settingsManager.appSettings.offlineEditingCruiseSpeed + visible: _showCruiseSpeed + Layout.preferredWidth: _fieldWidth + } + + QGCLabel { + text: qsTr("Hover speed") + visible: _showHoverSpeed + Layout.fillWidth: true + } + FactTextField { + fact: QGroundControl.settingsManager.appSettings.offlineEditingHoverSpeed + visible: _showHoverSpeed + Layout.preferredWidth: _fieldWidth + } + } // GridLayout + + SectionHeader { + id: plannedHomePositionSection + text: qsTr("Planned Home Position") + visible: !_vehicleHasHomePosition + checked: false + } + + Column { + anchors.left: parent.left + anchors.right: parent.right + spacing: _margin + visible: plannedHomePositionSection.checked && !_vehicleHasHomePosition + + GridLayout { + anchors.left: parent.left + anchors.right: parent.right + columnSpacing: ScreenTools.defaultFontPixelWidth + rowSpacing: columnSpacing + columns: 2 QGCLabel { - width: parent.width - wrapMode: Text.WordWrap - font.pointSize: ScreenTools.smallFontPointSize - text: qsTr("Speeds are only used for time calculations. Actual vehicle speed will not be affected.") - horizontalAlignment: Text.AlignHCenter - visible: _offlineEditing && _missionVehicle.vtol + text: qsTr("Altitude") } - } // Column - } // Item - } // Component - } // Loader + FactTextField { + fact: missionItem.plannedHomePositionAltitude + Layout.fillWidth: true + } + } + + QGCLabel { + width: parent.width + wrapMode: Text.WordWrap + font.pointSize: ScreenTools.smallFontPointSize + text: qsTr("Actual position set by vehicle at flight time.") + horizontalAlignment: Text.AlignHCenter + } + + QGCButton { + text: qsTr("Set Home To Map Center") + onClicked: missionItem.coordinate = map.center + anchors.horizontalCenter: parent.horizontalCenter + } + } + } // Column + } } // Rectangle diff --git a/src/PlanView/PlanToolBar.qml b/src/PlanView/PlanToolBar.qml index 21c575bfef3062d417a3ab5798b72c3d8715433b..e9d66f8ab8c1db6332d072a57f4d3717726290ed 100644 --- a/src/PlanView/PlanToolBar.qml +++ b/src/PlanView/PlanToolBar.qml @@ -80,26 +80,10 @@ Rectangle { checked: false onClicked: { + console.log("Leave plan clicked") checked = false - if (missionController.dirty) { - uploadPrompt.visible = true - } else { - showFlyView() - } - } - - MessageDialog { - id: uploadPrompt - title: _activeVehicle ? qsTr("Unsent changes") : qsTr("Unsaved changes") - text: qsTr("You have %1 changes to your mission. Are you sure you want to leave before you %2?").arg(_activeVehicle ? qsTr("unsent") : qsTr("unsaved")).arg(_activeVehicle ? qsTr("send the mission to the vehicle") : qsTr("save the mission to a file")) - standardButtons: StandardButton.Yes | StandardButton.No - - onNo: visible = false - - onYes: { - visible = false - showFlyView() - } + missionController.saveOnSwitch() + showFlyView() } } @@ -180,31 +164,5 @@ Rectangle { QGCLabel { text: "--" } } } - - QGCButton { - anchors.rightMargin: _margins - anchors.right: parent.right - anchors.verticalCenter: parent.verticalCenter - text: _activeVehicle ? qsTr("Upload") : qsTr("Save") - visible: missionDirty - primary: true - - onClicked: { - if (_activeVehicle) { - missionController.sendToVehicle() - } else { - missionController.saveToSelectedFile() - } - } - - NumberAnimation on opacity { - id: opacityAnimation - running: missionDirty - from: 0.5 - to: 1.0 - loops: Animation.Infinite - duration: 2000 - } - } } diff --git a/src/PlanView/PlanView.qml b/src/PlanView/PlanView.qml index 1bd2622aa9bc0d6ee7f404c8ea5a6dc7e6d96c1b..952e582d2af1f65bbe8b6023d80f8bf84bbe1c2b 100644 --- a/src/PlanView/PlanView.qml +++ b/src/PlanView/PlanView.qml @@ -103,15 +103,16 @@ QGCView { setCurrentItem(0) } + // Users is switching away from Plan View + function saveOnSwitch() { + save() + } + function loadFromSelectedFile() { fileDialog.title = qsTr("Select Mission File") fileDialog.selectExisting = true fileDialog.nameFilters = missionController.nameFilters fileDialog.openForLoad() - - // FIXME: Hmm - //mapFitFunctions.fitMapViewportToMissionItems() - //_currentMissionItem = _visualItems.get(0) } function saveToSelectedFile() { @@ -464,13 +465,12 @@ QGCView { // Plan Element selector (Mission/Fence/Rally) Row { id: planElementSelectorRow - anchors.topMargin: parent.height - ScreenTools.availableHeight + _margin - anchors.top: parent.top + anchors.top: toolStrip.top anchors.leftMargin: parent.width - _rightPanelWidth anchors.left: parent.left z: QGroundControl.zOrderWidgets spacing: _horizontalMargin - visible: QGroundControl.corePlugin.options.enablePlanViewSelector + visible: false // WIP: Temporarily remove - QGroundControl.corePlugin.options.enablePlanViewSelector readonly property real _buttonRadius: ScreenTools.defaultFontPixelHeight * 0.75 @@ -531,7 +531,7 @@ QGCView { // Mission Item Editor Item { id: missionItemEditor - anchors.topMargin: _margin + anchors.topMargin: planElementSelectorRow.visible ? _margin : 0 anchors.top: planElementSelectorRow.visible ? planElementSelectorRow.bottom : planElementSelectorRow.top anchors.bottom: parent.bottom anchors.right: parent.right @@ -673,10 +673,10 @@ QGCView { color: qgcPal.window title: qsTr("Plan") z: QGroundControl.zOrderWidgets - showAlternateIcon: [ false, false, _syncDropDownController.dirty, false, false, false ] - rotateImage: [ false, false, _syncDropDownController.syncInProgress, false, false, false ] - animateImage: [ false, false, _syncDropDownController.dirty, false, false, false ] - buttonEnabled: [ true, true, !_syncDropDownController.syncInProgress, true, true, true ] + showAlternateIcon: [ false, false, false, false, false ] + rotateImage: [ false, false, false, false, false ] + animateImage: [ false, false, false, false, false ] + buttonEnabled: [ true, true, true, true, true ] buttonVisible: [ true, true, true, true, _showZoom, _showZoom ] maxHeight: mapScale.y - toolStrip.y @@ -684,8 +684,6 @@ QGCView { property bool mySingleComplexItem: _singleComplexItem - onMySingleComplexItemChanged: console.log(model[1].dropPanelComponent) - model: [ { name: "Waypoint", @@ -697,12 +695,6 @@ QGCView { iconSource: "/qmlimages/MapDrawShape.svg", dropPanelComponent: _singleComplexItem ? undefined : patternDropPanel }, - { - name: "Sync", - iconSource: "/qmlimages/MapSync.svg", - alternateIconSource: "/qmlimages/MapSyncChanged.svg", - dropPanelComponent: syncDropPanel - }, { name: "Center", iconSource: "/qmlimages/MapCenter.svg", @@ -728,16 +720,10 @@ QGCView { addComplexItem(missionController.complexMissionItemNames[0]) } break - case 5: + case 3: editorMap.zoomLevel += 0.5 break - case 6: - editorMap.zoomLevel -= 0.5 - break - case 5: - editorMap.zoomLevel += 0.5 - break - case 6: + case 4: editorMap.zoomLevel -= 0.5 break } @@ -834,12 +820,12 @@ QGCView { columnSpacing: ScreenTools.defaultFontPixelWidth QGCButton { - text: qsTr("Send To Vehicle") + text: qsTr("Save") Layout.fillWidth: true - enabled: _activeVehicle && !_syncDropDownController.syncInProgress + enabled: !_syncDropDownController.syncInProgress onClicked: { dropPanel.hide() - _syncDropDownController.sendToVehicle() + _syncDropDownController.save() } } diff --git a/src/QmlControls/ParameterEditorDialog.qml b/src/QmlControls/ParameterEditorDialog.qml index c36fbf0d15001e37b232481df6d8595c6024c0bc..b2db0fb8c14f26f2a0008f64253fa202f9b486e8 100644 --- a/src/QmlControls/ParameterEditorDialog.qml +++ b/src/QmlControls/ParameterEditorDialog.qml @@ -200,6 +200,7 @@ QGCViewDialog { wrapMode: Text.WordWrap text: qsTr("Warning: Modifying values while vehicle is in flight can lead to vehicle instability and possible vehicle loss. ") + qsTr("Make sure you know what you are doing and double-check your values before Save!") + visible: fact.componentId != -1 } QGCCheckBox { diff --git a/src/QmlControls/QFileDialogController.cc b/src/QmlControls/QFileDialogController.cc index df3fb88ad871e46d11da4f582cd997dd1ec3eb26..a536cbf4a66e8f2578e2cd58f71a53d17e65273c 100644 --- a/src/QmlControls/QFileDialogController.cc +++ b/src/QmlControls/QFileDialogController.cc @@ -27,7 +27,7 @@ QStringList QFileDialogController::getFiles(const QString& directoryPath, const foreach (const QFileInfo& fileInfo, fileInfoList) { qCDebug(QFileDialogControllerLog) << "getFiles found" << fileInfo.baseName(); - files << fileInfo.baseName() + QStringLiteral(".") + fileExtension; + files << fileInfo.baseName(); } return files;