diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index 7abb20264c783c43cfe0107dc058bcf9cb719ac7..d4926a7890788219bdbf1326487748514c4cd737 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -472,6 +472,7 @@ HEADERS += \ src/MissionManager/MissionManager.h \ src/MissionManager/MissionSettingsItem.h \ src/MissionManager/PlanElementController.h \ + src/MissionManager/PlanMasterController.h \ src/MissionManager/QGCMapPolygon.h \ src/MissionManager/RallyPoint.h \ src/MissionManager/RallyPointController.h \ @@ -654,6 +655,7 @@ SOURCES += \ src/MissionManager/MissionManager.cc \ src/MissionManager/MissionSettingsItem.cc \ src/MissionManager/PlanElementController.cc \ + src/MissionManager/PlanMasterController.cc \ src/MissionManager/QGCMapPolygon.cc \ src/MissionManager/RallyPoint.cc \ src/MissionManager/RallyPointController.cc \ diff --git a/src/FlightDisplay/FlightDisplayView.qml b/src/FlightDisplay/FlightDisplayView.qml index 697a18c1177bbc86c9e0a18ab064def6443c0f7e..5340fe2c4640cc6c66d799d93ebb515f6038831d 100644 --- a/src/FlightDisplay/FlightDisplayView.qml +++ b/src/FlightDisplay/FlightDisplayView.qml @@ -38,14 +38,18 @@ QGCView { property bool activeVehicleJoystickEnabled: _activeVehicle ? _activeVehicle.joystickEnabled : false - property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle - property bool _mainIsMap: QGroundControl.videoManager.hasVideo ? QGroundControl.loadBoolGlobalSetting(_mainIsMapKey, true) : true - property bool _isPipVisible: QGroundControl.videoManager.hasVideo ? QGroundControl.loadBoolGlobalSetting(_PIPVisibleKey, true) : false - property real _savedZoomLevel: 0 - property real _margins: ScreenTools.defaultFontPixelWidth / 2 - property real _pipSize: mainWindow.width * 0.2 - property alias _guidedController: guidedActionsController - property alias _altitudeSlider: altitudeSlider + property var _planMasterController: masterController + property var _missionController: _planMasterController.missionController + property var _geoFenceController: _planMasterController.geoFenceController + property var _rallyPointController: _planMasterController.rallyPointController + property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle + property bool _mainIsMap: QGroundControl.videoManager.hasVideo ? QGroundControl.loadBoolGlobalSetting(_mainIsMapKey, true) : true + property bool _isPipVisible: QGroundControl.videoManager.hasVideo ? QGroundControl.loadBoolGlobalSetting(_PIPVisibleKey, true) : false + property real _savedZoomLevel: 0 + property real _margins: ScreenTools.defaultFontPixelWidth / 2 + property real _pipSize: mainWindow.width * 0.2 + property alias _guidedController: guidedActionsController + property alias _altitudeSlider: altitudeSlider readonly property bool isBackgroundDark: _mainIsMap ? (_flightMap ? _flightMap.isSatelliteMap : true) : true @@ -92,20 +96,14 @@ QGCView { } } - MissionController { - id: flyMissionController + PlanElemementMasterController { + id: masterController Component.onCompleted: start(false /* editMode */) - onResumeMissionReady: guidedActionsController.confirmAction(guidedActionsController.actionResumeMissionReady) - } - - GeoFenceController { - id: flyGeoFenceController - Component.onCompleted: start(false /* editMode */) } - RallyPointController { - id: flyRallyPointController - Component.onCompleted: start(false /* editMode */) + Connections { + target: _missionController + onResumeMissionReady: guidedActionsController.confirmAction(guidedActionsController.actionResumeMissionReady) } MessageDialog { @@ -116,7 +114,7 @@ QGCView { } Connections { - target: QGroundControl.multiVehicleManager + target: QGroundControl.multiVehicleManager onActiveVehicleChanged: px4JoystickCheck() } @@ -149,7 +147,7 @@ QGCView { vehicleWasArmed = true } } else { - if (promptForMissionRemove && (flyMissionController.containsItems || flyGeoFenceController.containsItems || flyRallyPointController.containsItems)) { + if (promptForMissionRemove && (_missionController.containsItems || _geoFenceController.containsItems || _rallyPointController.containsItems)) { root.showDialog(removeMissionDialogComponent, qsTr("Flight complete"), showDialogDefaultWidth, StandardButton.No | StandardButton.Yes) } promptForMissionRemove = false @@ -169,9 +167,9 @@ QGCView { message: qsTr("Do you want to remove the mission from the vehicle?") function accept() { - flyMissionController.removeAllFromVehicle() - flyGeoFenceController.removeAllFromVehicle() - flyRallyPointController.removeAllFromVehicle() + _missionController.removeAllFromVehicle() + _geoFenceController.removeAllFromVehicle() + _rallyPointController.removeAllFromVehicle() hideDialog() } @@ -214,9 +212,7 @@ QGCView { FlightDisplayViewMap { id: _flightMap anchors.fill: parent - missionController: flyMissionController - geoFenceController: flyGeoFenceController - rallyPointController: flyRallyPointController + planMasterController: masterController guidedActionsController: _guidedController flightWidgets: flightDisplayViewWidgets rightPanelWidth: ScreenTools.defaultFontPixelHeight * 9 @@ -320,7 +316,7 @@ QGCView { anchors.bottom: parent.bottom qgcView: root useLightColors: isBackgroundDark - missionController: _flightMap.missionController + missionController: _missionController visible: singleVehicleView.checked } @@ -511,7 +507,7 @@ QGCView { GuidedActionsController { id: guidedActionsController - missionController: flyMissionController + missionController: _missionController confirmDialog: guidedActionConfirm z: _flightVideoPipControl.z + 1 diff --git a/src/FlightDisplay/FlightDisplayViewMap.qml b/src/FlightDisplay/FlightDisplayViewMap.qml index 1ccd3ae4dd37b10caa214d38188420029409d172..943f6c3c5ead7a225202f5e3764ea47c1905a5fd 100644 --- a/src/FlightDisplay/FlightDisplayViewMap.qml +++ b/src/FlightDisplay/FlightDisplayViewMap.qml @@ -34,9 +34,7 @@ FlightMap { property alias scaleState: mapScale.state // The following properties must be set by the consumer - property var missionController - property var geoFenceController - property var rallyPointController + property var planMasterController property var guidedActionsController property var flightWidgets property var rightPanelWidth @@ -44,6 +42,10 @@ FlightMap { property rect centerViewport: Qt.rect(0, 0, width, height) + property var _planMasterController: planMasterController + property var _missionController: _planMasterController.missionController + property var _geoFenceController: _planMasterController.geoFenceController + property var _rallyPointController: _planMasterController.rallyPointController property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle property var _activeVehicleCoordinate: _activeVehicle ? _activeVehicle.coordinate : QtPositioning.coordinate() property var _gotoHereCoordinate: QtPositioning.coordinate() @@ -132,10 +134,10 @@ FlightMap { QGCMapPalette { id: mapPal; lightColors: isSatelliteMap } Connections { - target: missionController + target: _missionController onNewItemsFromVehicle: { - var visualItems = missionController.visualItems + var visualItems = _missionController.visualItems if (visualItems && visualItems.count != 1) { mapFitFunctions.fitMapViewportToMissionItems() firstVehiclePositionReceived = true @@ -151,9 +153,7 @@ FlightMap { id: mapFitFunctions map: _flightMap usePlannedHomePosition: false - mapMissionController: missionController - mapGeoFenceController: geoFenceController - mapRallyPointController: rallyPointController + planMasterController: _planMasterController property real leftToolWidth: toolStrip.x + toolStrip.width } @@ -188,7 +188,7 @@ FlightMap { // Add the mission item visuals to the map Repeater { - model: _mainIsMap ? missionController.visualItems : 0 + model: _mainIsMap ? _missionController.visualItems : 0 delegate: MissionItemMapVisual { map: flightMap @@ -198,12 +198,12 @@ FlightMap { // Add lines between waypoints MissionLineView { - model: _mainIsMap ? missionController.waypointLines : 0 + model: _mainIsMap ? _missionController.waypointLines : 0 } GeoFenceMapVisuals { map: flightMap - myGeoFenceController: geoFenceController + myGeoFenceController: _geoFenceController interactive: false planView: false homePosition: _activeVehicle && _activeVehicle.homePosition.isValid ? _activeVehicle.homePosition : undefined @@ -211,7 +211,7 @@ FlightMap { // Rally points on map MapItemView { - model: rallyPointController.points + model: _rallyPointController.points delegate: MapQuickItem { id: itemIndicator @@ -243,7 +243,7 @@ FlightMap { // Camera points MapItemView { - model: missionController.cameraPoints + model: _missionController.cameraPoints delegate: CameraTriggerIndicator { coordinate: object.coordinate diff --git a/src/FlightMap/Widgets/MapFitFunctions.qml b/src/FlightMap/Widgets/MapFitFunctions.qml index 527685b30b507b587047fcc3f302cfa83dbce636..728ca30f766ff9585cb3f0e1486a8cd70064ff1a 100644 --- a/src/FlightMap/Widgets/MapFitFunctions.qml +++ b/src/FlightMap/Widgets/MapFitFunctions.qml @@ -16,9 +16,11 @@ import QGroundControl 1.0 Item { property var map property bool usePlannedHomePosition ///< true: planned home position used for calculations, false: vehicle home position use for calculations - property var mapGeoFenceController - property var mapMissionController - property var mapRallyPointController + property var planMasterController + + property var _missionController: planMasterController.missionController + property var _geoFenceController: planMasterController.geoFenceController + property var _rallyPointController: planMasterController.rallyPointController property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle @@ -26,7 +28,7 @@ Item { var homePosition = QtPositioning.coordinate() var activeVehicle = QGroundControl.multiVehicleManager.activeVehicle if (usePlannedHomePosition) { - homePosition = mapMissionController.visualItems.get(0).coordinate + homePosition = _missionController.visualItems.get(0).coordinate } else if (activeVehicle) { homePosition = activeVehicle.homePosition } @@ -92,8 +94,8 @@ Item { if (homePosition.isValid) { coordList.push(homePosition) } - for (var i=1; i 2) { - for (var i=0; i 2) { + for (var i=0; i<_geoFenceController.mapPolygon.path.count; i++) { + coordList.push(_geoFenceController.mapPolygon.path[i]) } } } @@ -133,8 +135,8 @@ Item { } function addRallyItemCoordsForFit(coordList) { - for (var i=0; igeoFenceManager()->disconnect(this); + _activeVehicle = NULL; } -void GeoFenceController::_activeVehicleSet(void) +void GeoFenceController::activeVehicleSet(Vehicle* vehicle) { + _activeVehicle = vehicle; GeoFenceManager* geoFenceManager = _activeVehicle->geoFenceManager(); connect(geoFenceManager, &GeoFenceManager::breachReturnSupportedChanged, this, &GeoFenceController::breachReturnSupportedChanged); connect(geoFenceManager, &GeoFenceManager::circleEnabledChanged, this, &GeoFenceController::circleEnabledChanged); @@ -112,97 +114,40 @@ void GeoFenceController::_activeVehicleSet(void) _signalAll(); } -bool GeoFenceController::_loadJsonFile(QJsonDocument& jsonDoc, QString& errorString) +bool GeoFenceController::load(const QJsonObject& json, QString& errorString) { - QJsonObject json = jsonDoc.object(); + QString errorStr; + QString errorMessage = tr("GeoFence: %1"); - int fileVersion; - if (!JsonHelper::validateQGCJsonFile(json, - _jsonFileTypeValue, // expected file type - 1, // minimum supported version - 1, // maximum supported version - fileVersion, - errorString)) { + if (json.contains(_jsonBreachReturnKey) && + !JsonHelper::loadGeoCoordinate(json[_jsonBreachReturnKey], false /* altitudeRequired */, _breachReturnPoint, errorStr)) { + errorString = errorMessage.arg(errorStr); return false; } - if (!_activeVehicle->parameterManager()->loadFromJson(json, false /* required */, errorString)) { - return false; - } - - if (json.contains(_jsonBreachReturnKey) - && !JsonHelper::loadGeoCoordinate(json[_jsonBreachReturnKey], false /* altitudeRequired */, _breachReturnPoint, errorString)) { - return false; - } - - if (!_mapPolygon.loadFromJson(json, true, errorString)) { + if (!_mapPolygon.loadFromJson(json, true, errorStr)) { + errorString = errorMessage.arg(errorStr); return false; } _mapPolygon.setDirty(false); - - return true; -} - -void GeoFenceController::loadFromFile(const QString& filename) -{ - QString errorString; - - if (filename.isEmpty()) { - return; - } - - QFile file(filename); - - if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) { - errorString = file.errorString() + QStringLiteral(" ") + filename; - } else { - QJsonDocument jsonDoc; - QByteArray bytes = file.readAll(); - - _loadJsonFile(jsonDoc, errorString); - } - - if (!errorString.isEmpty()) { - qgcApp()->showMessage(errorString); - } + setDirty(false); _signalAll(); - setDirty(true); + + return true; } -void GeoFenceController::saveToFile(const QString& filename) +void GeoFenceController::save(QJsonObject& json) { - if (filename.isEmpty()) { - return; - } - - QString fenceFilename = filename; - if (!QFileInfo(filename).fileName().contains(".")) { - fenceFilename += QString(".%1").arg(AppSettings::fenceFileExtension); - } - - QFile file(fenceFilename); - - if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) { - qgcApp()->showMessage(file.errorString()); - } else { - QJsonObject fenceFileObject; // top level json object - - fenceFileObject[JsonHelper::jsonFileTypeKey] = _jsonFileTypeValue; - fenceFileObject[JsonHelper::jsonVersionKey] = 1; - fenceFileObject[JsonHelper::jsonGroundStationKey] = JsonHelper::jsonGroundStationValue; + json[JsonHelper::jsonVersionKey] = 1; + if (_breachReturnPoint.isValid()) { QJsonValue jsonBreachReturn; JsonHelper::saveGeoCoordinate(_breachReturnPoint, false /* writeAltitude */, jsonBreachReturn); - fenceFileObject[_jsonBreachReturnKey] = jsonBreachReturn; - - _mapPolygon.saveToJson(fenceFileObject); - - QJsonDocument saveDoc(fenceFileObject); - file.write(saveDoc.toJson()); + json[_jsonBreachReturnKey] = jsonBreachReturn; } - setDirty(false); + _mapPolygon.saveToJson(json); } void GeoFenceController::removeAll(void) @@ -323,11 +268,6 @@ void GeoFenceController::_loadComplete(const QGeoCoordinate& breachReturn, const emit loadComplete(); } -QString GeoFenceController::fileExtension(void) const -{ - return AppSettings::fenceFileExtension; -} - bool GeoFenceController::containsItems(void) const { return _mapPolygon.count() > 2; diff --git a/src/MissionManager/GeoFenceController.h b/src/MissionManager/GeoFenceController.h index ac4c311be9bb5e1175be5dfedbbf6b6b41069c4a..61ada74d552ff5c871c58bd8d263cf7af7005661 100644 --- a/src/MissionManager/GeoFenceController.h +++ b/src/MissionManager/GeoFenceController.h @@ -46,18 +46,18 @@ public: void start (bool editMode) final; void startStaticActiveVehicle (Vehicle* vehicle) final; + void save (QJsonObject& json) final; + bool load (const QJsonObject& json, QString& errorString) final; void loadFromVehicle (void) final; void sendToVehicle (void) final; - void loadFromFile (const QString& filename) final; - void saveToFile (const QString& filename) final; void removeAll (void) final; void removeAllFromVehicle (void) final; bool syncInProgress (void) const final; bool dirty (void) const final; void setDirty (bool dirty) final; bool containsItems (void) const final; - - QString fileExtension(void) const final; + void activeVehicleBeingRemoved (void) final; + void activeVehicleSet (Vehicle* vehicle) final; bool circleEnabled (void) const; Fact* circleRadiusFact (void) const; @@ -95,10 +95,6 @@ private slots: private: void _init(void); void _signalAll(void); - bool _loadJsonFile(QJsonDocument& jsonDoc, QString& errorString); - - void _activeVehicleBeingRemoved(void) final; - void _activeVehicleSet(void) final; bool _dirty; QGCMapPolygon _mapPolygon; diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc index f14d72d8250b84439a7299d1d34cb642ad67b294..496399d98141ec832b5f88cab4fe05b24cb88542 100644 --- a/src/MissionManager/MissionController.cc +++ b/src/MissionManager/MissionController.cc @@ -335,40 +335,7 @@ void MissionController::removeAll(void) _addMissionSettings(_activeVehicle, _visualItems, false /* addToCenter */); _initAllVisualItems(); _visualItems->setDirty(true); - _resetMissionFlightStatus(); - } -} - -bool MissionController::_loadJsonMissionFile(Vehicle* vehicle, const QByteArray& bytes, QmlObjectListModel* visualItems, QString& errorString) -{ - QJsonParseError jsonParseError; - QJsonDocument jsonDoc(QJsonDocument::fromJson(bytes, &jsonParseError)); - - if (jsonParseError.error != QJsonParseError::NoError) { - errorString = jsonParseError.errorString(); - return false; - } - QJsonObject json = jsonDoc.object(); - - // V1 file format has no file type key and version key is string. Convert to new format. - if (!json.contains(JsonHelper::jsonFileTypeKey)) { - json[JsonHelper::jsonFileTypeKey] = _jsonFileTypeValue; - } - - int fileVersion; - if (!JsonHelper::validateQGCJsonFile(json, - _jsonFileTypeValue, // expected file type - 1, // minimum supported version - 2, // maximum supported version - fileVersion, - errorString)) { - return false; - } - - if (fileVersion == 1) { - return _loadJsonMissionFileV1(vehicle, json, visualItems, errorString); - } else { - return _loadJsonMissionFileV2(vehicle, json, visualItems, errorString); + _resetMissionFlightStatus(); } } @@ -612,6 +579,32 @@ bool MissionController::_loadJsonMissionFileV2(Vehicle* vehicle, const QJsonObje return true; } +#if 0 +bool MissionController::_loadItemsFromJson(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString) +{ + // V1 file format has no file type key and version key is string. Convert to new format. + if (!json.contains(JsonHelper::jsonFileTypeKey)) { + json[JsonHelper::jsonFileTypeKey] = _jsonFileTypeValue; + } + + int fileVersion; + if (!JsonHelper::validateQGCJsonFile(json, + _jsonFileTypeValue, // expected file type + 1, // minimum supported version + 2, // maximum supported version + fileVersion, + errorString)) { + return false; + } + + if (fileVersion == 1) { + return _loadJsonMissionFileV1(_activeVehicle, json, visualItems, errorString); + } else { + return _loadJsonMissionFileV2(_activeVehicle, json, visualItems, errorString); + } +} +#endif + bool MissionController::_loadTextMissionFile(Vehicle* vehicle, QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString) { bool addPlannedHomePosition = false; @@ -662,12 +655,15 @@ bool MissionController::_loadTextMissionFile(Vehicle* vehicle, QTextStream& stre return true; } -void MissionController::loadFromFile(const QString& filename) +bool MissionController::load(const QJsonObject& json, QString& errorString) { - QmlObjectListModel* newVisualItems = NULL; + QString errorStr; + QString errorMessage = tr("Mission: %1"); + QmlObjectListModel* newVisualItems = new QmlObjectListModel(this); - if (!loadItemsFromFile(_activeVehicle, filename, &newVisualItems)) { - return; + if (!_loadJsonMissionFileV2(_activeVehicle, json, newVisualItems, errorStr)) { + errorString = errorMessage.arg(errorStr); + return false; } if (_visualItems) { @@ -690,117 +686,54 @@ void MissionController::loadFromFile(const QString& filename) // Needs a sync to vehicle setDirty(true); } -} - -bool MissionController::loadItemsFromFile(Vehicle* vehicle, const QString& filename, QmlObjectListModel** visualItems) -{ - *visualItems = NULL; - - QString errorString; - - if (filename.isEmpty()) { - return false; - } - - *visualItems = new QmlObjectListModel(); - - QFile file(filename); - - if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) { - errorString = file.errorString() + QStringLiteral(" ") + filename; - } else { - QByteArray bytes = file.readAll(); - QTextStream stream(&bytes); - - QString firstLine = stream.readLine(); - if (firstLine.contains(QRegExp("QGC.*WPL"))) { - stream.seek(0); - _loadTextMissionFile(vehicle, stream, *visualItems, errorString); - } else { - _loadJsonMissionFile(vehicle, bytes, *visualItems, errorString); - } - } - - if (!errorString.isEmpty()) { - (*visualItems)->deleteLater(); - - qgcApp()->showMessage(errorString); - return false; - } return true; } -void MissionController::saveToFile(const QString& filename) +void MissionController::save(QJsonObject& json) { - if (filename.isEmpty()) { - return; - } - - QString missionFilename = filename; - if (!QFileInfo(filename).fileName().contains(".")) { - missionFilename += QString(".%1").arg(AppSettings::missionFileExtension); - } + json[JsonHelper::jsonVersionKey] = _missionFileVersion; - QFile file(missionFilename); + // Mission settings - if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) { - qgcApp()->showMessage(tr("Mission save %1 : %2").arg(filename).arg(file.errorString())); - } else { - QJsonObject missionFileObject; // top level json object - - missionFileObject[JsonHelper::jsonVersionKey] = _missionFileVersion; - missionFileObject[JsonHelper::jsonGroundStationKey] = JsonHelper::jsonGroundStationValue; + MissionSettingsItem* settingsItem = _visualItems->value(0); + if (!settingsItem) { + qWarning() << "First item is not MissionSettingsItem"; + return; + } + QJsonValue coordinateValue; + JsonHelper::saveGeoCoordinate(settingsItem->coordinate(), true /* writeAltitude */, coordinateValue); + json[_jsonPlannedHomePositionKey] = coordinateValue; + json[_jsonFirmwareTypeKey] = _activeVehicle->firmwareType(); + json[_jsonVehicleTypeKey] = _activeVehicle->vehicleType(); + json[_jsonCruiseSpeedKey] = _activeVehicle->defaultCruiseSpeed(); + json[_jsonHoverSpeedKey] = _activeVehicle->defaultHoverSpeed(); - // Mission settings + // Save the visual items - MissionSettingsItem* settingsItem = _visualItems->value(0); - if (!settingsItem) { - qWarning() << "First item is not MissionSettingsItem"; - return; - } - QJsonValue coordinateValue; - JsonHelper::saveGeoCoordinate(settingsItem->coordinate(), true /* writeAltitude */, coordinateValue); - missionFileObject[_jsonPlannedHomePositionKey] = coordinateValue; - missionFileObject[_jsonFirmwareTypeKey] = _activeVehicle->firmwareType(); - missionFileObject[_jsonVehicleTypeKey] = _activeVehicle->vehicleType(); - missionFileObject[_jsonCruiseSpeedKey] = _activeVehicle->defaultCruiseSpeed(); - missionFileObject[_jsonHoverSpeedKey] = _activeVehicle->defaultHoverSpeed(); + QJsonArray rgJsonMissionItems; + for (int i=0; i<_visualItems->count(); i++) { + VisualMissionItem* visualItem = qobject_cast(_visualItems->get(i)); - // Save the visual items + visualItem->save(rgJsonMissionItems); + } - QJsonArray rgJsonMissionItems; - for (int i=0; i<_visualItems->count(); i++) { - VisualMissionItem* visualItem = qobject_cast(_visualItems->get(i)); + // Mission settings has a special case for end mission action + if (settingsItem) { + QList rgMissionItems; - visualItem->save(rgJsonMissionItems); + if (_convertToMissionItems(_visualItems, rgMissionItems, this /* missionItemParent */)) { + QJsonObject saveObject; + MissionItem* missionItem = rgMissionItems[rgMissionItems.count() - 1]; + missionItem->save(saveObject); + rgJsonMissionItems.append(saveObject); } - - // Mission settings has a special case for end mission action - if (settingsItem) { - QList rgMissionItems; - - if (_convertToMissionItems(_visualItems, rgMissionItems, this /* missionItemParent */)) { - QJsonObject saveObject; - MissionItem* missionItem = rgMissionItems[rgMissionItems.count() - 1]; - missionItem->save(saveObject); - rgJsonMissionItems.append(saveObject); - } - for (int i=0; ideleteLater(); - } + for (int i=0; ideleteLater(); } - - missionFileObject[_jsonItemsKey] = rgJsonMissionItems; - - QJsonDocument saveDoc(missionFileObject); - file.write(saveDoc.toJson()); } - // If we are connected to a real vehicle, don't clear dirty bit on saving to file since vehicle is still out of date - if (_activeVehicle->isOfflineEditingVehicle()) { - _visualItems->setDirty(false); - } + json[_jsonItemsKey] = rgJsonMissionItems; } void MissionController::_calcPrevWaypointValues(double homeAlt, VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference) @@ -1320,7 +1253,7 @@ void MissionController::_itemCommandChanged(void) _recalcWaypointLines(); } -void MissionController::_activeVehicleBeingRemoved(void) +void MissionController::activeVehicleBeingRemoved(void) { qCDebug(MissionControllerLog) << "MissionController::_activeVehicleBeingRemoved"; @@ -1337,10 +1270,14 @@ void MissionController::_activeVehicleBeingRemoved(void) // We always remove all items on vehicle change. This leaves a user model hole: // If the user has unsaved changes in the Plan view they will lose them removeAll(); + + _activeVehicle = NULL; } -void MissionController::_activeVehicleSet(void) +void MissionController::activeVehicleSet(Vehicle* activeVehicle) { + _activeVehicle = activeVehicle; + // We always remove all items on vehicle change. This leaves a user model hole: // If the user has unsaved changes in the Plan view they will lose them removeAll(); @@ -1529,11 +1466,6 @@ void MissionController::setDirty(bool dirty) } } -QString MissionController::fileExtension(void) const -{ - return AppSettings::missionFileExtension; -} - void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualItems, Vehicle* vehicle) { // First we look for a Fixed Wing Landing Pattern which is at the end diff --git a/src/MissionManager/MissionController.h b/src/MissionManager/MissionController.h index a0aa71d559c8a2aed0292278fcc6a4e27232122e..4e734574050df61b5bb191de8e6d5264dcfb705b 100644 --- a/src/MissionManager/MissionController.h +++ b/src/MissionManager/MissionController.h @@ -98,13 +98,6 @@ public: /// Updates the altitudes of the items in the current mission to the new default altitude Q_INVOKABLE void applyDefaultMissionAltitude(void); - /// Loads the mission items from the specified file - /// @param[in] vehicle Vehicle we are loading items for - /// @param[in] filename File to load from - /// @param[out] visualItems Visual items loaded, returns NULL if error - /// @return success/fail - static bool loadItemsFromFile(Vehicle* vehicle, const QString& filename, QmlObjectListModel** visualItems); - /// Sends the mission items to the specified vehicle static void sendItemsToVehicle(Vehicle* vehicle, QmlObjectListModel* visualMissionItems); @@ -113,18 +106,21 @@ public: // Overrides from PlanElementController void start (bool editMode) final; void startStaticActiveVehicle (Vehicle* vehicle) final; + void save (QJsonObject& json) final; + bool load (const QJsonObject& json, QString& errorString) final; void loadFromVehicle (void) final; void sendToVehicle (void) final; +#if 0 void loadFromFile (const QString& filename) final; - void saveToFile (const QString& filename) final; +#endif void removeAll (void) final; void removeAllFromVehicle (void) final; bool syncInProgress (void) const final; bool dirty (void) const final; void setDirty (bool dirty) final; bool containsItems (void) const final; - - QString fileExtension(void) const final; + void activeVehicleBeingRemoved (void) final; + void activeVehicleSet (Vehicle* vehicle) final; // Property accessors @@ -205,10 +201,7 @@ private: void _addHoverTime(double hoverTime, double hoverDistance, int waypointIndex); void _addCruiseTime(double cruiseTime, double cruiseDistance, int wayPointIndex); void _updateBatteryInfo(int waypointIndex); - - // Overrides from PlanElementController - void _activeVehicleBeingRemoved(void) final; - void _activeVehicleSet(void) final; + bool _loadItemsFromJson(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString); private: QmlObjectListModel* _visualItems; diff --git a/src/MissionManager/PlanElementController.cc b/src/MissionManager/PlanElementController.cc index a904796dbd7d5d3eb44ccd2a26c4388ef3b152ed..2f78148594e7af94bf43605795c5bfb0d7dc26d0 100644 --- a/src/MissionManager/PlanElementController.cc +++ b/src/MissionManager/PlanElementController.cc @@ -28,32 +28,9 @@ PlanElementController::~PlanElementController() void PlanElementController::start(bool editMode) { _editMode = editMode; - connect(_multiVehicleMgr, &MultiVehicleManager::activeVehicleChanged, this, &PlanElementController::_activeVehicleChanged); - _activeVehicleChanged(_multiVehicleMgr->activeVehicle()); } void PlanElementController::startStaticActiveVehicle(Vehicle* vehicle) { _editMode = false; - _activeVehicleChanged(vehicle); -} - -void PlanElementController::_activeVehicleChanged(Vehicle* activeVehicle) -{ - if (_activeVehicle) { - _activeVehicleBeingRemoved(); - _activeVehicle = NULL; - } - - if (activeVehicle) { - _activeVehicle = activeVehicle; - } else { - _activeVehicle = _multiVehicleMgr->offlineEditingVehicle(); - } - _activeVehicleSet(); - - // Whenever vehicle changes we need to update syncInProgress - emit syncInProgressChanged(syncInProgress()); - - emit vehicleChanged(_activeVehicle); } diff --git a/src/MissionManager/PlanElementController.h b/src/MissionManager/PlanElementController.h index 2d1e24ec0a28cf6b117d9d51614ec0ab61ff3504..c74ef71e6ed86a85957ee534e09f1e9be148565b 100644 --- a/src/MissionManager/PlanElementController.h +++ b/src/MissionManager/PlanElementController.h @@ -25,34 +25,35 @@ public: PlanElementController(QObject* parent = NULL); ~PlanElementController(); - Q_PROPERTY(bool containsItems READ containsItems NOTIFY containsItemsChanged) ///< true: Elemement is non-empty - Q_PROPERTY(bool syncInProgress READ syncInProgress NOTIFY syncInProgressChanged) ///< true: information is currently being saved/sent, false: no active save/send in progress - Q_PROPERTY(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged) ///< true: unsaved/sent changes are present, false: no changes since last save/send - Q_PROPERTY(QString fileExtension READ fileExtension CONSTANT) ///< Returns the file extention for plan element file type. - Q_PROPERTY(Vehicle* vehicle READ vehicle NOTIFY vehicleChanged) - - virtual QString fileExtension(void) const = 0; - + Q_PROPERTY(bool containsItems READ containsItems NOTIFY containsItemsChanged) ///< true: Elemement is non-empty + Q_PROPERTY(bool syncInProgress READ syncInProgress NOTIFY syncInProgressChanged) ///< true: information is currently being saved/sent, false: no active save/send in progress + Q_PROPERTY(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged) ///< true: unsaved/sent changes are present, false: no changes since last save/send + Q_PROPERTY(Vehicle* vehicle READ vehicle NOTIFY vehicleChanged) /// Should be called immediately upon Component.onCompleted. /// @param editMode true: controller being used in Plan view, false: controller being used in Fly view - Q_INVOKABLE virtual void start(bool editMode); + virtual void start(bool editMode); /// Starts the controller using a single static active vehicle. Will not track global active vehicle changes. - /// @param editMode true: controller being used in Plan view, false: controller being used in Fly view - Q_INVOKABLE virtual void startStaticActiveVehicle(Vehicle* vehicle); + virtual void startStaticActiveVehicle(Vehicle* vehicle); + + virtual void save(QJsonObject& json) = 0; + virtual bool load(const QJsonObject& json, QString& errorString) = 0; + virtual void loadFromVehicle(void) = 0; + virtual void sendToVehicle(void) = 0; + virtual void removeAll(void) = 0; ///< Removes all from controller only, synce required to remove from vehicle + virtual void removeAllFromVehicle(void) = 0; ///< Removes all from vehicle and controller - Q_INVOKABLE virtual void loadFromVehicle(void) = 0; - Q_INVOKABLE virtual void sendToVehicle(void) = 0; - Q_INVOKABLE virtual void loadFromFile(const QString& filename) = 0; - Q_INVOKABLE virtual void saveToFile(const QString& filename) = 0; - Q_INVOKABLE virtual void removeAll(void) = 0; ///< Removes all from controller only, synce required to remove from vehicle - Q_INVOKABLE virtual void removeAllFromVehicle(void) = 0; ///< Removes all from vehicle and controller + virtual bool containsItems (void) const = 0; + virtual bool syncInProgress (void) const = 0; + virtual bool dirty (void) const = 0; + virtual void setDirty (bool dirty) = 0; - virtual bool containsItems (void) const = 0; - virtual bool syncInProgress (void) const = 0; - virtual bool dirty (void) const = 0; - virtual void setDirty (bool dirty) = 0; + /// Called when the current active vehicle is about to be removed. Derived classes should override to implement custom behavior. + virtual void activeVehicleBeingRemoved(void) = 0; + + /// Called when a new active vehicle has been set. Derived classes should override to implement custom behavior. + virtual void activeVehicleSet(Vehicle* activeVehicle) = 0; Vehicle* vehicle(void) { return _activeVehicle; } @@ -66,17 +67,6 @@ protected: MultiVehicleManager* _multiVehicleMgr; Vehicle* _activeVehicle; ///< Currently active vehicle, can be disconnected offline editing vehicle bool _editMode; - - /// Called when the current active vehicle is about to be removed. Derived classes should override - /// to implement custom behavior. - virtual void _activeVehicleBeingRemoved(void) = 0; - - /// Called when a new active vehicle has been set. Derived classes should override - /// to implement custom behavior. - virtual void _activeVehicleSet(void) = 0; - -private slots: - void _activeVehicleChanged(Vehicle* activeVehicle); }; #endif diff --git a/src/MissionManager/PlanMasterController.cc b/src/MissionManager/PlanMasterController.cc new file mode 100644 index 0000000000000000000000000000000000000000..aae54fd9196703e33dc664dbeae3f1f98ad20ac6 --- /dev/null +++ b/src/MissionManager/PlanMasterController.cc @@ -0,0 +1,265 @@ +/**************************************************************************** + * + * (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 "PlanMasterController.h" +#include "QGCApplication.h" +#include "MultiVehicleManager.h" +#include "AppSettings.h" +#include "JsonHelper.h" + +#include + +const int PlanMasterController::_planFileVersion = 1; +const char* PlanMasterController::_planFileType = "Plan"; +const char* PlanMasterController::_jsonMissionObjectKey = "mission"; +const char* PlanMasterController::_jsonGeoFenceObjectKey = "geoFence"; +const char* PlanMasterController::_jsonRallyPointsObjectKey = "rallyPoints"; + +PlanMasterController::PlanMasterController(QObject* parent) + : QObject(parent) + , _multiVehicleMgr(qgcApp()->toolbox()->multiVehicleManager()) + , _activeVehicle(_multiVehicleMgr->offlineEditingVehicle()) + , _editMode(false) +{ + connect(&_missionController, &MissionController::dirtyChanged, this, &PlanMasterController::dirtyChanged); + connect(&_geoFenceController, &GeoFenceController::dirtyChanged, this, &PlanMasterController::dirtyChanged); + connect(&_rallyPointController, &RallyPointController::dirtyChanged, this, &PlanMasterController::dirtyChanged); + + connect(&_missionController, &MissionController::containsItemsChanged, this, &PlanMasterController::containsItemsChanged); + connect(&_geoFenceController, &GeoFenceController::containsItemsChanged, this, &PlanMasterController::containsItemsChanged); + connect(&_rallyPointController, &RallyPointController::containsItemsChanged, this, &PlanMasterController::containsItemsChanged); + + connect(&_missionController, &MissionController::syncInProgressChanged, this, &PlanMasterController::syncInProgressChanged); + connect(&_geoFenceController, &GeoFenceController::syncInProgressChanged, this, &PlanMasterController::syncInProgressChanged); + connect(&_rallyPointController, &RallyPointController::syncInProgressChanged, this, &PlanMasterController::syncInProgressChanged); +} + +PlanMasterController::~PlanMasterController() +{ + +} + +void PlanMasterController::start(bool editMode) +{ + _editMode = editMode; + _missionController.start(editMode); + _geoFenceController.start(editMode); + _rallyPointController.start(editMode); + + connect(_multiVehicleMgr, &MultiVehicleManager::activeVehicleChanged, this, &PlanMasterController::_activeVehicleChanged); + _activeVehicleChanged(_multiVehicleMgr->activeVehicle()); +} + +void PlanMasterController::startStaticActiveVehicle(Vehicle* vehicle) +{ + _editMode = false; + _missionController.startStaticActiveVehicle(vehicle); + _geoFenceController.startStaticActiveVehicle(vehicle); + _rallyPointController.startStaticActiveVehicle(vehicle); + _activeVehicleChanged(vehicle); +} + +void PlanMasterController::_activeVehicleChanged(Vehicle* activeVehicle) +{ + if (_activeVehicle) { + _missionController.activeVehicleBeingRemoved(); + _geoFenceController.activeVehicleBeingRemoved(); + _rallyPointController.activeVehicleBeingRemoved(); + _activeVehicle = NULL; + } + + if (activeVehicle) { + _activeVehicle = activeVehicle; + } else { + _activeVehicle = _multiVehicleMgr->offlineEditingVehicle(); + } + _missionController.activeVehicleSet(_activeVehicle); + _geoFenceController.activeVehicleSet(_activeVehicle); + _rallyPointController.activeVehicleSet(_activeVehicle); + + // Whenever vehicle changes we need to update syncInProgress + emit syncInProgressChanged(syncInProgress()); + + emit vehicleChanged(_activeVehicle); +} + +void PlanMasterController::loadFromVehicle(void) +{ + // FIXME: Hack implementation + _missionController.loadFromVehicle(); + _geoFenceController.loadFromVehicle(); + _rallyPointController.loadFromVehicle(); +} + +void PlanMasterController::sendToVehicle(void) +{ + // FIXME: Hack implementation + _missionController.sendToVehicle(); + _geoFenceController.sendToVehicle(); + _rallyPointController.sendToVehicle(); +} + + +void PlanMasterController::loadFromFile(const QString& filename) +{ + QString errorString; + QString errorMessage = tr("Error reading Plan file (%1). %2").arg(filename).arg("%1"); + + if (filename.isEmpty()) { + return; + } + + QFile file(filename); + + if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) { + errorString = file.errorString() + QStringLiteral(" ") + filename; + return; + } + + QJsonDocument jsonDoc; + QByteArray bytes = file.readAll(); + + if (!JsonHelper::isJsonFile(bytes, jsonDoc, errorString)) { + qgcApp()->showMessage(errorMessage.arg(errorString)); + return; + } + + int version; + QJsonObject json = jsonDoc.object(); + if (!JsonHelper::validateQGCJsonFile(json, _planFileType, _planFileVersion, _planFileVersion, version, errorString)) { + qgcApp()->showMessage(errorMessage.arg(errorString)); + return; + } + + QList rgKeyInfo = { + { _jsonMissionObjectKey, QJsonValue::Object, true }, + { _jsonGeoFenceObjectKey, QJsonValue::Object, true }, + { _jsonRallyPointsObjectKey, QJsonValue::Object, true }, + }; + if (!JsonHelper::validateKeys(json, rgKeyInfo, errorString)) { + qgcApp()->showMessage(errorMessage.arg(errorString)); + return; + } + + if (!_missionController.load(json[_jsonMissionObjectKey].toObject(), errorString) || + !_geoFenceController.load(json[_jsonGeoFenceObjectKey].toObject(), errorString) || + !_rallyPointController.load(json[_jsonRallyPointsObjectKey].toObject(), errorString)) { + qgcApp()->showMessage(errorMessage.arg(errorString)); + return; + } + setDirty(true); +} + +void PlanMasterController::saveToFile(const QString& filename) +{ + if (filename.isEmpty()) { + return; + } + + QString planFilename = filename; + if (!QFileInfo(filename).fileName().contains(".")) { + planFilename += QString(".%1").arg(fileExtension()); + } + + QFile file(planFilename); + + if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) { + qgcApp()->showMessage(tr("Plan save error %1 : %2").arg(filename).arg(file.errorString())); + } else { + QJsonObject planJson; + QJsonObject missionJson; + QJsonObject fenceJson; + QJsonObject rallyJson; + + JsonHelper::saveQGCJsonFileHeader(planJson, _planFileType, _planFileVersion); + _missionController.save(missionJson); + _geoFenceController.save(fenceJson); + _rallyPointController.save(rallyJson); + planJson[_jsonMissionObjectKey] = missionJson; + planJson[_jsonGeoFenceObjectKey] = fenceJson; + planJson[_jsonRallyPointsObjectKey] = rallyJson; + + QJsonDocument saveDoc(planJson); + file.write(saveDoc.toJson()); + } + + // If we are connected to a real vehicle, don't clear dirty bit on saving to file since vehicle is still out of date + if (_activeVehicle->isOfflineEditingVehicle()) { + setDirty(false); + } +} + +void PlanMasterController::removeAll(void) +{ + +} + +void PlanMasterController::removeAllFromVehicle(void) +{ + _missionController.removeAllFromVehicle(); + _geoFenceController.removeAllFromVehicle(); + _rallyPointController.removeAllFromVehicle(); +} + +bool PlanMasterController::containsItems(void) const +{ + return _missionController.containsItems() || _geoFenceController.containsItems() || _rallyPointController.containsItems(); +} + +bool PlanMasterController::syncInProgress(void) const +{ + return _missionController.syncInProgress() || _geoFenceController.syncInProgress() || _rallyPointController.syncInProgress(); +} + +bool PlanMasterController::dirty(void) const +{ + return _missionController.dirty() || _geoFenceController.dirty() || _rallyPointController.dirty(); +} + +void PlanMasterController::setDirty(bool dirty) +{ + _missionController.setDirty(dirty); + _geoFenceController.setDirty(dirty); + _rallyPointController.setDirty(dirty); +} + +QString PlanMasterController::fileExtension(void) const +{ + return AppSettings::planFileExtension; +} + +QStringList PlanMasterController::loadNameFilters(void) const +{ + QStringList filters; + + filters << tr("Plan Files (*.%1)").arg(AppSettings::planFileExtension) << + tr("Mission Files (*.%1)").arg(AppSettings::missionFileExtension) << + tr("Waypoint Files (*.waypoints)") << + tr("All Files (*.*)"); + return filters; +} + + +QStringList PlanMasterController::saveNameFilters(void) const +{ + QStringList filters; + + filters << tr("Plan Files (*.%1)").arg(fileExtension()) << tr("All Files (*.*)"); + return filters; +} + +void PlanMasterController::sendPlanToVehicle(Vehicle* vehicle, const QString& filename) +{ + // Use a transient PlanMasterController to accomplish this + PlanMasterController* controller = new PlanMasterController(); + controller->startStaticActiveVehicle(vehicle); + controller->loadFromFile(filename); + delete controller; +} + diff --git a/src/MissionManager/PlanMasterController.h b/src/MissionManager/PlanMasterController.h new file mode 100644 index 0000000000000000000000000000000000000000..6484b8356625dfa7a32fa64cff01d8e1f0c6bae5 --- /dev/null +++ b/src/MissionManager/PlanMasterController.h @@ -0,0 +1,96 @@ +/**************************************************************************** + * + * (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. + * + ****************************************************************************/ + +#pragma once + +#include + +#include "MissionController.h" +#include "GeoFenceController.h" +#include "RallyPointController.h" +#include "Vehicle.h" +#include "MultiVehicleManager.h" + +/// Master controller for mission, fence, rally +class PlanMasterController : public QObject +{ + Q_OBJECT + +public: + PlanMasterController(QObject* parent = NULL); + ~PlanMasterController(); + + Q_PROPERTY(MissionController* missionController READ missionController CONSTANT) + Q_PROPERTY(GeoFenceController* geoFenceController READ geoFenceController CONSTANT) + Q_PROPERTY(RallyPointController* rallyPointController READ rallyPointController CONSTANT) + + Q_PROPERTY(bool containsItems READ containsItems NOTIFY containsItemsChanged) ///< true: Elemement is non-empty + Q_PROPERTY(bool syncInProgress READ syncInProgress NOTIFY syncInProgressChanged) ///< true: Information is currently being saved/sent, false: no active save/send in progress + Q_PROPERTY(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged) ///< true: Unsaved/sent changes are present, false: no changes since last save/send + Q_PROPERTY(Vehicle* vehicle READ vehicle NOTIFY vehicleChanged) + Q_PROPERTY(QString fileExtension READ fileExtension CONSTANT) ///< File extention for missions + Q_PROPERTY(QStringList loadNameFilters READ loadNameFilters CONSTANT) ///< File filter list loading plan files + Q_PROPERTY(QStringList saveNameFilters READ saveNameFilters CONSTANT) ///< File filter list saving plan files + + /// Should be called immediately upon Component.onCompleted. + /// @param editMode true: controller being used in Plan view, false: controller being used in Fly view + Q_INVOKABLE virtual void start(bool editMode); + + /// Starts the controller using a single static active vehicle. Will not track global active vehicle changes. + Q_INVOKABLE virtual void startStaticActiveVehicle(Vehicle* vehicle); + + /// Sends a plan to the specified file + /// @param[in] vehicle Vehicle we are sending a plan to + /// @param[in] filename Plan file to load + static void sendPlanToVehicle(Vehicle* vehicle, const QString& filename); + + Q_INVOKABLE void loadFromVehicle(void); + Q_INVOKABLE void sendToVehicle(void); + Q_INVOKABLE void loadFromFile(const QString& filename); + Q_INVOKABLE void saveToFile(const QString& filename); + Q_INVOKABLE void removeAll(void); ///< Removes all from controller only, synce required to remove from vehicle + Q_INVOKABLE void removeAllFromVehicle(void); ///< Removes all from vehicle and controller + + MissionController* missionController(void) { return &_missionController; } + GeoFenceController* geoFenceController(void) { return &_geoFenceController; } + RallyPointController* rallyPointController(void) { return &_rallyPointController; } + + bool containsItems (void) const; + bool syncInProgress (void) const; + bool dirty (void) const; + void setDirty (bool dirty); + QString fileExtension (void) const; + QStringList loadNameFilters (void) const; + QStringList saveNameFilters (void) const; + + Vehicle* vehicle(void) { return _activeVehicle; } + +signals: + void containsItemsChanged (bool containsItems); + void syncInProgressChanged (bool syncInProgress); + void dirtyChanged (bool dirty); + void vehicleChanged (Vehicle* vehicle); + +private slots: + void _activeVehicleChanged(Vehicle* activeVehicle); + +private: + MultiVehicleManager* _multiVehicleMgr; + Vehicle* _activeVehicle; ///< Currently active vehicle, can be disconnected offline editing vehicle + bool _editMode; + MissionController _missionController; + GeoFenceController _geoFenceController; + RallyPointController _rallyPointController; + + static const int _planFileVersion; + static const char* _planFileType; + static const char* _jsonMissionObjectKey; + static const char* _jsonGeoFenceObjectKey; + static const char* _jsonRallyPointsObjectKey; +}; diff --git a/src/MissionManager/RallyPointController.cc b/src/MissionManager/RallyPointController.cc index 0e1a375e71e909f2f20279e130f79638f12bf0b2..bfc447af37c63e7cf789dff271ea4e9864a012c8 100644 --- a/src/MissionManager/RallyPointController.cc +++ b/src/MissionManager/RallyPointController.cc @@ -49,14 +49,16 @@ RallyPointController::~RallyPointController() } -void RallyPointController::_activeVehicleBeingRemoved(void) +void RallyPointController::activeVehicleBeingRemoved(void) { _activeVehicle->rallyPointManager()->disconnect(this); _points.clearAndDeleteContents(); + _activeVehicle = NULL; } -void RallyPointController::_activeVehicleSet(void) +void RallyPointController::activeVehicleSet(Vehicle* activeVehicle) { + _activeVehicle = activeVehicle; RallyPointManager* rallyPointManager = _activeVehicle->rallyPointManager(); connect(rallyPointManager, &RallyPointManager::loadComplete, this, &RallyPointController::_loadComplete); connect(rallyPointManager, &RallyPointManager::inProgressChanged, this, &RallyPointController::syncInProgressChanged); @@ -67,32 +69,23 @@ void RallyPointController::_activeVehicleSet(void) emit rallyPointsSupportedChanged(rallyPointsSupported()); } -bool RallyPointController::_loadJsonFile(QJsonDocument& jsonDoc, QString& errorString) +bool RallyPointController::load(const QJsonObject& json, QString& errorString) { - QJsonObject json = jsonDoc.object(); - - int fileVersion; - if (!JsonHelper::validateQGCJsonFile(json, - _jsonFileTypeValue, // expected file type - 1, // minimum supported version - 1, // maximum supported version - fileVersion, - errorString)) { - return false; - } + QString errorStr; + QString errorMessage = tr("Rally: %1"); // Check for required keys QStringList requiredKeys = { _jsonPointsKey }; - if (!JsonHelper::validateRequiredKeys(json, requiredKeys, errorString)) { + if (!JsonHelper::validateRequiredKeys(json, requiredKeys, errorStr)) { + errorString = errorMessage.arg(errorStr); return false; } - // Load points - QList rgPoints; - if (!JsonHelper::loadGeoCoordinateArray(json[_jsonPointsKey], true /* altitudeRequired */, rgPoints, errorString)) { + if (!JsonHelper::loadGeoCoordinateArray(json[_jsonPointsKey], true /* altitudeRequired */, rgPoints, errorStr)) { + errorString = errorMessage.arg(errorStr); return false; - } + } _points.clearAndDeleteContents(); QObjectList pointList; for (int i=0; ishowMessage("Rall Point file is in incorrect format."); - return; - } - } - - if (!errorString.isEmpty()) { - qgcApp()->showMessage(errorString); - } - - setDirty(true); + setDirty(false); _setFirstPointCurrent(); + + return true; } -void RallyPointController::saveToFile(const QString& filename) +void RallyPointController::save(QJsonObject& json) { - if (filename.isEmpty()) { - return; - } - - QString rallyFilename = filename; - if (!QFileInfo(filename).fileName().contains(".")) { - rallyFilename += QString(".%1").arg(AppSettings::rallyPointFileExtension); - } - - QFile file(rallyFilename); - - if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) { - qgcApp()->showMessage(file.errorString()); - } else { - QJsonObject jsonObject; + json[JsonHelper::jsonVersionKey] = 1; - jsonObject[JsonHelper::jsonFileTypeKey] = _jsonFileTypeValue; - jsonObject[JsonHelper::jsonVersionKey] = 1; - jsonObject[JsonHelper::jsonGroundStationKey] = JsonHelper::jsonGroundStationValue; - - QJsonArray rgPoints; - QJsonValue jsonPoint; - for (int i=0; i<_points.count(); i++) { - JsonHelper::saveGeoCoordinate(qobject_cast(_points[i])->coordinate(), true /* writeAltitude */, jsonPoint); - rgPoints.append(jsonPoint); - } - jsonObject[_jsonPointsKey] = QJsonValue(rgPoints); - - QJsonDocument saveDoc(jsonObject); - file.write(saveDoc.toJson()); + QJsonArray rgPoints; + QJsonValue jsonPoint; + for (int i=0; i<_points.count(); i++) { + JsonHelper::saveGeoCoordinate(qobject_cast(_points[i])->coordinate(), true /* writeAltitude */, jsonPoint); + rgPoints.append(jsonPoint); } - - setDirty(false); + json[_jsonPointsKey] = QJsonValue(rgPoints); } void RallyPointController::removeAll(void) @@ -234,11 +173,6 @@ void RallyPointController::_loadComplete(const QList rgPoints) emit loadComplete(); } -QString RallyPointController::fileExtension(void) const -{ - return AppSettings::rallyPointFileExtension; -} - void RallyPointController::addPoint(QGeoCoordinate point) { double defaultAlt; diff --git a/src/MissionManager/RallyPointController.h b/src/MissionManager/RallyPointController.h index 54e37a151ca54fb7e5f752a5be2ae860418675a3..6d0858c3491250aa843fe1e51c6689f9085f7cfb 100644 --- a/src/MissionManager/RallyPointController.h +++ b/src/MissionManager/RallyPointController.h @@ -37,18 +37,18 @@ public: Q_INVOKABLE void addPoint(QGeoCoordinate point); Q_INVOKABLE void removePoint(QObject* rallyPoint); + void save (QJsonObject& json) final; + bool load (const QJsonObject& json, QString& errorString) final; void loadFromVehicle (void) final; void sendToVehicle (void) final; - void loadFromFile (const QString& filename) final; - void saveToFile (const QString& filename) final; void removeAll (void) final; void removeAllFromVehicle (void) final; bool syncInProgress (void) const final; bool dirty (void) const final { return _dirty; } void setDirty (bool dirty) final; bool containsItems (void) const final; - - QString fileExtension(void) const final; + void activeVehicleBeingRemoved (void) final; + void activeVehicleSet (Vehicle* vehicle) final; bool rallyPointsSupported (void) const; QmlObjectListModel* points (void) { return &_points; } @@ -68,11 +68,6 @@ private slots: void _updateContainsItems(void); private: - bool _loadJsonFile(QJsonDocument& jsonDoc, QString& errorString); - - void _activeVehicleBeingRemoved(void) final; - void _activeVehicleSet(void) final; - bool _dirty; QmlObjectListModel _points; QObject* _currentRallyPoint; diff --git a/src/PlanView/MissionItemEditor.qml b/src/PlanView/MissionItemEditor.qml index ecf928a6e37208afc043a67637d02a750bf6ccc3..eaa8c8c64a60bad904d63e41853ccaf518221806 100644 --- a/src/PlanView/MissionItemEditor.qml +++ b/src/PlanView/MissionItemEditor.qml @@ -19,9 +19,10 @@ Rectangle { color: _currentItem ? qgcPal.primaryButton : qgcPal.windowShade radius: _radius - property var map ///< Map control - property var missionItem ///< MissionItem associated with this editor - property bool readOnly ///< true: read only view, false: full editing view + property var map ///< Map control + property var missionController + property var missionItem ///< MissionItem associated with this editor + property bool readOnly ///< true: read only view, false: full editing view property var rootQgcView signal clicked diff --git a/src/PlanView/PlanToolBar.qml b/src/PlanView/PlanToolBar.qml index 3570554c09412bbd85d3caddbac2528f96dabc59..fbfc757b4089a27cc551cb2e042a9ca20e9f76c5 100644 --- a/src/PlanView/PlanToolBar.qml +++ b/src/PlanView/PlanToolBar.qml @@ -23,21 +23,22 @@ Rectangle { signal showFlyView - property var missionController + property var planMasterController property var currentMissionItem ///< Mission item to display status for - property var missionItems: _controllerValid ? missionController.visualItems : undefined - property real missionDistance: _controllerValid ? missionController.missionDistance : NaN - property real missionTime: _controllerValid ? missionController.missionTime : NaN - property real missionMaxTelemetry: _controllerValid ? missionController.missionMaxTelemetry : NaN - property bool missionDirty: _controllerValid ? missionController.dirty : false + property var missionItems: _controllerValid ? planMasterController.missionController.visualItems : undefined + property real missionDistance: _controllerValid ? planMasterController.missionController.missionDistance : NaN + property real missionTime: _controllerValid ? planMasterController.missionController.missionTime : NaN + property real missionMaxTelemetry: _controllerValid ? planMasterController.missionController.missionMaxTelemetry : NaN + property bool missionDirty: _controllerValid ? planMasterController.missionController.dirty : false + property bool _controllerValid: planMasterController != undefined property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle + property var _controllerDirty: planMasterController ? planMasterController.dirty : false + property var _controllerSyncInProgress: planMasterController ? planMasterController.syncInProgress : false property bool _statusValid: currentMissionItem != undefined property bool _missionValid: missionItems != undefined - property bool _controllerValid: missionController != undefined - property bool _manualUpload: QGroundControl.settingsManager.appSettings.automaticMissionUpload.rawValue == 0 property real _dataFontSize: ScreenTools.defaultFontPointSize property real _largeValueWidth: ScreenTools.defaultFontPixelWidth * 8 @@ -54,8 +55,8 @@ Rectangle { property real _missionDistance: _missionValid ? missionDistance : NaN property real _missionMaxTelemetry: _missionValid ? missionMaxTelemetry : NaN property real _missionTime: _missionValid ? missionTime : NaN - property int _batteryChangePoint: _controllerValid ? missionController.batteryChangePoint : -1 - property int _batteriesRequired: _controllerValid ? missionController.batteriesRequired : -1 + property int _batteryChangePoint: _controllerValid ? planMasterController.missionController.batteryChangePoint : -1 + property int _batteriesRequired: _controllerValid ? planMasterController.missionController.batteriesRequired : -1 property string _distanceText: isNaN(_distance) ? "-.-" : QGroundControl.metersToAppSettingsDistanceUnits(_distance).toFixed(1) + " " + QGroundControl.appSettingsDistanceUnitsString property string _altDifferenceText: isNaN(_altDifference) ? "-.-" : QGroundControl.metersToAppSettingsDistanceUnits(_altDifference).toFixed(1) + " " + QGroundControl.appSettingsDistanceUnitsString @@ -104,9 +105,7 @@ Rectangle { checked: false onClicked: { checked = false - if (missionController.uploadOnSwitch()) { - showFlyView() - } + showFlyView() } } } @@ -245,17 +244,17 @@ Rectangle { anchors.rightMargin: _margins anchors.right: parent.right anchors.verticalCenter: parent.verticalCenter - text: missionController ? (missionController.dirty ? qsTr("Upload Required") : qsTr("Upload")) : "" - enabled: _activeVehicle && !missionController.syncInProgress - visible: _activeVehicle && _manualUpload - onClicked: missionController.upload() + text: _controllerDirty ? qsTr("Upload Required") : qsTr("Upload") + enabled: _activeVehicle && !_controllerSyncInProgress + visible: _activeVehicle + onClicked: planMasterController.upload() PropertyAnimation on opacity { easing.type: Easing.OutQuart from: 0.5 to: 1 loops: Animation.Infinite - running: missionController ? missionController.dirty : false + running: _controllerDirty alwaysRunToEnd: true duration: 2000 } diff --git a/src/PlanView/PlanView.qml b/src/PlanView/PlanView.qml index 84dddc109ecc2bf5eeabb8d7301eb78bad92528f..5e3e41943afd8a12f4ee404abd951da24a3341e0 100644 --- a/src/PlanView/PlanView.qml +++ b/src/PlanView/PlanView.qml @@ -42,19 +42,18 @@ QGCView { readonly property real _toolButtonTopMargin: parent.height - ScreenTools.availableHeight + (ScreenTools.defaultFontPixelHeight / 2) readonly property var _defaultVehicleCoordinate: QtPositioning.coordinate(37.803784, -122.462276) - property var _visualItems: missionController.visualItems + property var _planMasterController: masterController + property var _missionController: _planMasterController.missionController + property var _geoFenceController: _planMasterController.geoFenceController + property var _rallyPointController: _planMasterController.rallyPointController + property var _visualItems: _missionController.visualItems property var _currentMissionItem property int _currentMissionIndex: 0 property bool _lightWidgetBorders: editorMap.isSatelliteMap property bool _addWaypointOnClick: false - property bool _singleComplexItem: missionController.complexMissionItemNames.length === 1 + property bool _singleComplexItem: _missionController.complexMissionItemNames.length === 1 property real _toolbarHeight: _qgcView.height - ScreenTools.availableHeight property int _editingLayer: _layerMission - property bool _autoSync: QGroundControl.settingsManager.appSettings.automaticMissionUpload.rawValue != 0 - property bool _switchToFlyAfterUpload: false - - /// The controller which should be called for load/save, send to/from vehicle calls - property var _syncDropDownController: missionController readonly property int _layerMission: 1 readonly property int _layerGeoFence: 2 @@ -62,7 +61,7 @@ QGCView { readonly property string _armedVehicleUploadPrompt: qsTr("Vehicle is currently armed. Do you want to upload the mission to the vehicle?") Component.onCompleted: { - toolbar.missionController = Qt.binding(function () { return missionController }) + toolbar.planMasterController = Qt.binding(function () { return _planMasterController }) toolbar.currentMissionItem = Qt.binding(function () { return _currentMissionItem }) } @@ -71,11 +70,11 @@ QGCView { coordinate.latitude = coordinate.latitude.toFixed(_decimalPlaces) coordinate.longitude = coordinate.longitude.toFixed(_decimalPlaces) coordinate.altitude = coordinate.altitude.toFixed(_decimalPlaces) - insertComplexMissionItem(complexItemName, coordinate, missionController.visualItems.count) + insertComplexMissionItem(complexItemName, coordinate, _missionController.visualItems.count) } function insertComplexMissionItem(complexItemName, coordinate, index) { - var sequenceNumber = missionController.insertComplexMissionItem(complexItemName, coordinate, index) + var sequenceNumber = _missionController.insertComplexMissionItem(complexItemName, coordinate, index) setCurrentItem(sequenceNumber, true) } @@ -88,9 +87,7 @@ QGCView { id: mapFitFunctions map: editorMap usePlannedHomePosition: true - mapGeoFenceController: geoFenceController - mapMissionController: missionController - mapRallyPointController: rallyPointController + planMasterController: _planMasterController } Connections { @@ -111,7 +108,7 @@ QGCView { function accept() { hideDialog() - missionController.applyDefaultMissionAltitude() + _missionController.applyDefaultMissionAltitude() } } } @@ -141,83 +138,51 @@ QGCView { text: qsTr("Pause and Upload") onClicked: { _activeVehicle.flightMode = _activeVehicle.pauseFlightMode - missionController.sendToVehicle() - hideDialog() - if (_switchToFlyAfterUpload) { - toolbar.showFlyView() - } - } - } - - QGCButton { - text: qsTr("Exit planning (no upload)") - visible: _switchToFlyAfterUpload - onClicked: { + _missionController.sendToVehicle() hideDialog() - toolbar.showFlyView() } } } } } - MissionController { - id: missionController - - property var nameFilters: [ qsTr("Mission Files (*.%1)").arg(missionController.fileExtension) , qsTr("All Files (*.*)") ] + PlanElemementMasterController { + id: masterController Component.onCompleted: { start(true /* editMode */) setCurrentItem(0, true) } - function _denyUpload(switchToFly) { + function upload() { if (_activeVehicle && _activeVehicle.armed && _activeVehicle.flightMode === _activeVehicle.missionFlightMode) { - _switchToFlyAfterUpload = switchToFly - _qgcView.showDialog(activeMissionUploadDialogComponent, qsTr("Mission Upload"), _qgcView.showDialogDefaultWidth, StandardButton.Cancel) - return true + _qgcView.showDialog(activeMissionUploadDialogComponent, qsTr("Plan Upload"), _qgcView.showDialogDefaultWidth, StandardButton.Cancel) } else { - return false - } - } - - // Users is switching away from Plan View - function uploadOnSwitch() { - if (missionController.dirty && _autoSync) { - if (_denyUpload(true /* switchToFly */)) { - return false - } else { - sendToVehicle() - } - } - return true - } - - function upload() { - if (!_denyUpload(false /* switchToFly */)) { sendToVehicle() } } function loadFromSelectedFile() { - fileDialog.title = qsTr("Select Mission File") + fileDialog.title = qsTr("Select Plan File") fileDialog.selectExisting = true - fileDialog.nameFilters = missionController.nameFilters + fileDialog.nameFilters = masterController.loadNameFilters fileDialog.openForLoad() } function saveToSelectedFile() { - fileDialog.title = qsTr("Save Mission") + fileDialog.title = qsTr("Save Plan") fileDialog.selectExisting = false - fileDialog.nameFilters = missionController.nameFilters + fileDialog.nameFilters = masterController.saveNameFilters fileDialog.openForSave() } function fitViewportToItems() { mapFitFunctions.fitMapViewportToMissionItems() } + } - onVisualItemsChanged: itemDragger.clearItem() + Connections { + target: _missionController onNewItemsFromVehicle: { if (_visualItems && _visualItems.count != 1) { @@ -227,76 +192,6 @@ QGCView { } } - GeoFenceController { - id: geoFenceController - - property var nameFilters: [ qsTr("GeoFence Files (*.%1)").arg(geoFenceController.fileExtension) , qsTr("All Files (*.*)") ] - - Component.onCompleted: start(true /* editMode */) - - function saveToSelectedFile() { - fileDialog.title = qsTr("Save GeoFence") - fileDialog.selectExisting = false - fileDialog.nameFilters = geoFenceController.nameFilters - fileDialog.openForSave() - } - - function loadFromSelectedFile() { - fileDialog.title = qsTr("Select GeoFence File") - fileDialog.selectExisting = true - fileDialog.nameFilters = geoFenceController.nameFilters - fileDialog.openForLoad() - ///mapFitFunctions.fitMapViewportToFenceItems() - } - - function fitViewportToItems() { - mapFitFunctions.fitMapViewportToFenceItems() - } - - function upload() { - sendToVehicle() - } - } - - RallyPointController { - id: rallyPointController - - property var nameFilters: [ qsTr("Rally Point Files (*.%1)").arg(rallyPointController.fileExtension) , qsTr("All Files (*.*)") ] - - onCurrentRallyPointChanged: { - if (_editingLayer == _layerRallyPoints && !currentRallyPoint) { - itemDragger.visible = false - itemDragger.coordinateItem = undefined - itemDragger.mapCoordinateIndicator = undefined - } - } - - Component.onCompleted: start(true /* editMode */) - - function saveToSelectedFile() { - fileDialog.title = qsTr("Save Rally Points") - fileDialog.selectExisting = false - fileDialog.nameFilters = rallyPointController.nameFilters - fileDialog.openForSave() - } - - function loadFromSelectedFile() { - fileDialog.title = qsTr("Select Rally Point File") - fileDialog.selectExisting = true - fileDialog.nameFilters = rallyPointController.nameFilters - fileDialog.openForLoad() - //mapFitFunctions.fitMapViewportToRallyItems() - } - - function fitViewportToItems() { - mapFitFunctions.fitMapViewportToRallyItems() - } - - function upload() { - sendToVehicle() - } - } - QGCPalette { id: qgcPal; colorGroupEnabled: enabled } ExclusiveGroup { @@ -326,7 +221,7 @@ QGCView { /// @param coordinate Location to insert item /// @param index Insert item at this index function insertSimpleMissionItem(coordinate, index) { - var sequenceNumber = missionController.insertSimpleMissionItem(coordinate, index) + var sequenceNumber = _missionController.insertSimpleMissionItem(coordinate, index) setCurrentItem(sequenceNumber, true) } @@ -336,16 +231,16 @@ QGCView { id: fileDialog qgcView: _qgcView folder: QGroundControl.settingsManager.appSettings.missionSavePath - fileExtension: _syncDropDownController.fileExtension + fileExtension: masterController.fileExtension onAcceptedForSave: { - _syncDropDownController.saveToFile(file) + masterController.saveToFile(file) close() } onAcceptedForLoad: { - _syncDropDownController.loadFromFile(file) - _syncDropDownController.fitViewportToItems() + masterController.loadFromFile(file) + masterController.fitViewportToItems() setCurrentItem(0, true) close() } @@ -361,7 +256,7 @@ QGCView { if (toIndex == 0) { toIndex = 1 } - missionController.moveMissionItem(_moveDialogMissionItemIndex, toIndex) + _missionController.moveMissionItem(_moveDialogMissionItemIndex, toIndex) hideDialog() } @@ -437,71 +332,21 @@ QGCView { switch (_editingLayer) { case _layerMission: if (_addWaypointOnClick) { - insertSimpleMissionItem(coordinate, missionController.visualItems.count) + insertSimpleMissionItem(coordinate, _missionController.visualItems.count) } break case _layerRallyPoints: - if (rallyPointController.rallyPointsSupported) { - rallyPointController.addPoint(coordinate) + if (_rallyPointController.rallyPointsSupported) { + _rallyPointController.addPoint(coordinate) } break } } } - // We use this item to support dragging since dragging a MapQuickItem just doesn't seem to work - Rectangle { - id: itemDragger - x: mapCoordinateIndicator ? (mapCoordinateIndicator.x + mapCoordinateIndicator.anchorPoint.x - (itemDragger.width / 2)) : 100 - y: mapCoordinateIndicator ? (mapCoordinateIndicator.y + mapCoordinateIndicator.anchorPoint.y - (itemDragger.height / 2)) : 100 - width: ScreenTools.defaultFontPixelHeight * 3 - height: ScreenTools.defaultFontPixelHeight * 3 - color: "transparent" - visible: false - z: QGroundControl.zOrderMapItems + 1 // Above item icons - - property var coordinateItem - property var mapCoordinateIndicator - property bool preventCoordinateBindingLoop: false - - onXChanged: liveDrag() - onYChanged: liveDrag() - - function liveDrag() { - if (!itemDragger.preventCoordinateBindingLoop && Drag.active) { - var point = Qt.point(itemDragger.x + (itemDragger.width / 2), itemDragger.y + (itemDragger.height / 2)) - var coordinate = editorMap.toCoordinate(point, false /* clipToViewPort */) - coordinate.altitude = itemDragger.coordinateItem.coordinate.altitude - itemDragger.preventCoordinateBindingLoop = true - itemDragger.coordinateItem.coordinate = coordinate - itemDragger.preventCoordinateBindingLoop = false - } - } - - function clearItem() { - itemDragger.visible = false - itemDragger.coordinateItem = undefined - itemDragger.mapCoordinateIndicator = undefined - } - - Drag.active: itemDrag.drag.active - Drag.hotSpot.x: width / 2 - Drag.hotSpot.y: height / 2 - - MouseArea { - id: itemDrag - anchors.fill: parent - drag.target: parent - drag.minimumX: 0 - drag.minimumY: 0 - drag.maximumX: itemDragger.parent.width - parent.width - drag.maximumY: itemDragger.parent.height - parent.height - } - } - // Add the mission item visuals to the map Repeater { - model: missionController.visualItems + model: _missionController.visualItems delegate: MissionItemMapVisual { map: editorMap @@ -511,7 +356,7 @@ QGCView { // Add lines between waypoints MissionLineView { - model: _editingLayer == _layerMission ? missionController.waypointLines : undefined + model: _editingLayer == _layerMission ? _missionController.waypointLines : undefined } // Add the vehicles to the map @@ -529,15 +374,15 @@ QGCView { GeoFenceMapVisuals { map: editorMap - myGeoFenceController: geoFenceController + myGeoFenceController: _geoFenceController interactive: _editingLayer == _layerGeoFence - homePosition: missionController.plannedHomePosition + homePosition: _missionController.plannedHomePosition planView: true } RallyPointMapVisuals { map: editorMap - myRallyPointController: rallyPointController + myRallyPointController: _rallyPointController interactive: _editingLayer == _layerRallyPoints planView: true } @@ -551,10 +396,10 @@ QGCView { color: qgcPal.window title: qsTr("Plan") z: QGroundControl.zOrderWidgets - showAlternateIcon: [ false, false, !_autoSync && _syncDropDownController.dirty, false, false, false ] - rotateImage: [ false, false, _syncDropDownController.syncInProgress, false, false, false ] - animateImage: [ false, false, !_autoSync && _syncDropDownController.dirty, false, false, false ] - buttonEnabled: [ true, true, !_syncDropDownController.syncInProgress, true, true, true ] + showAlternateIcon: [ false, false, !_autoSync && masterController.dirty, false, false, false ] + rotateImage: [ false, false, masterController.syncInProgress, false, false, false ] + animateImage: [ false, false, !_autoSync && masterController.dirty, false, false, false ] + buttonEnabled: [ true, true, !masterController.syncInProgress, true, true, true ] buttonVisible: [ true, true, true, true, _showZoom, _showZoom ] maxHeight: mapScale.y - toolStrip.y @@ -567,7 +412,7 @@ QGCView { toggle: true }, { - name: _singleComplexItem ? missionController.complexMissionItemNames[0] : "Pattern", + name: _singleComplexItem ? _missionController.complexMissionItemNames[0] : "Pattern", iconSource: "/qmlimages/MapDrawShape.svg", dropPanelComponent: _singleComplexItem ? undefined : patternDropPanel }, @@ -599,7 +444,7 @@ QGCView { break case 1: if (_singleComplexItem) { - addComplexItem(missionController.complexMissionItemNames[0]) + addComplexItem(_missionController.complexMissionItemNames[0]) } break case 4: @@ -645,15 +490,12 @@ QGCView { switch (current) { case planElementMission: _editingLayer = _layerMission - _syncDropDownController = missionController break case planElementGeoFence: _editingLayer = _layerGeoFence - _syncDropDownController = geoFenceController break case planElementRallyPoints: _editingLayer = _layerRallyPoints - _syncDropDownController = rallyPointController break } } @@ -707,26 +549,26 @@ QGCView { anchors.fill: parent spacing: _margin / 2 orientation: ListView.Vertical - model: missionController.visualItems + model: _missionController.visualItems cacheBuffer: Math.max(height * 2, 0) clip: true currentIndex: _currentMissionIndex highlightMoveDuration: 250 delegate: MissionItemEditor { - map: editorMap - missionItem: object - width: parent.width - readOnly: false - rootQgcView: _qgcView + map: editorMap + missionController: _missionController + missionItem: object + width: parent.width + readOnly: false + rootQgcView: _qgcView onClicked: setCurrentItem(object.sequenceNumber, false) onRemove: { var removeIndex = index - itemDragger.clearItem() - missionController.removeMissionItem(removeIndex) - if (removeIndex >= missionController.visualItems.count) { + _missionController.removeMissionItem(removeIndex) + if (removeIndex >= _missionController.visualItems.count) { removeIndex-- } _currentMissionIndex = -1 @@ -746,7 +588,7 @@ QGCView { anchors.left: parent.left anchors.right: parent.right availableHeight: ScreenTools.availableHeight - myGeoFenceController: geoFenceController + myGeoFenceController: _geoFenceController flightMap: editorMap visible: _editingLayer == _layerGeoFence } @@ -760,7 +602,7 @@ QGCView { anchors.left: parent.left anchors.right: parent.right visible: _editingLayer == _layerRallyPoints - controller: rallyPointController + controller: _rallyPointController } RallyPointItemEditor { @@ -769,9 +611,9 @@ QGCView { anchors.top: rallyPointHeader.bottom anchors.left: parent.left anchors.right: parent.right - visible: _editingLayer == _layerRallyPoints && rallyPointController.points.count - rallyPoint: rallyPointController.currentRallyPoint - controller: rallyPointController + visible: _editingLayer == _layerRallyPoints && _rallyPointController.points.count + rallyPoint: _rallyPointController.currentRallyPoint + controller: _rallyPointController } } // Right panel @@ -790,7 +632,7 @@ QGCView { anchors.left: parent.left anchors.right: rightPanel.left anchors.bottom: parent.bottom - missionItems: missionController.visualItems + missionItems: _missionController.visualItems visible: _editingLayer === _layerMission && !ScreenTools.isShortScreen } } // QGCViewPanel @@ -802,7 +644,7 @@ QGCView { message: qsTr("You have unsaved/unsent changes. Loading from the Vehicle will lose these changes. Are you sure you want to load from the Vehicle?") function accept() { hideDialog() - _syncDropDownController.loadFromVehicle() + masterController.loadFromVehicle() } } } @@ -814,7 +656,7 @@ QGCView { message: qsTr("You have unsaved/unsent changes. Loading a from a file will lose these changes. Are you sure you want to load from a file?") function accept() { hideDialog() - _syncDropDownController.loadFromSelectedFile() + masterController.loadFromSelectedFile() } } } @@ -824,8 +666,7 @@ QGCView { QGCViewMessage { message: qsTr("Are you sure you want to remove all items? This will also remove all items from the vehicle.") function accept() { - itemDragger.clearItem() - _syncDropDownController.removeAllFromVehicle() + masterController.removeAllFromVehicle() hideDialog() } } @@ -851,7 +692,7 @@ QGCView { QGCLabel { text: qsTr("Create complex pattern:") } Repeater { - model: missionController.complexMissionItemNames + model: _missionController.complexMissionItemNames QGCButton { text: modelData @@ -878,7 +719,7 @@ QGCView { QGCLabel { width: sendSaveGrid.width wrapMode: Text.WordWrap - text: _syncDropDownController.dirty ? + text: masterController.dirty ? qsTr("You have unsaved changes. You should upload to your vehicle, or save to a file:") : qsTr("Sync:") } @@ -893,23 +734,23 @@ QGCView { QGCButton { text: qsTr("Upload") Layout.fillWidth: true - enabled: _activeVehicle && !_syncDropDownController.syncInProgress + enabled: _activeVehicle && !masterController.syncInProgress onClicked: { dropPanel.hide() - _syncDropDownController.upload() + masterController.upload() } } QGCButton { text: qsTr("Download") Layout.fillWidth: true - enabled: _activeVehicle && !_syncDropDownController.syncInProgress + enabled: _activeVehicle && !masterController.syncInProgress onClicked: { dropPanel.hide() - if (_syncDropDownController.dirty) { + if (masterController.dirty) { _qgcView.showDialog(syncLoadFromVehicleOverwrite, columnHolder._overwriteText, _qgcView.showDialogDefaultWidth, StandardButton.Yes | StandardButton.Cancel) } else { - _syncDropDownController.loadFromVehicle() + masterController.loadFromVehicle() } } } @@ -917,23 +758,23 @@ QGCView { QGCButton { text: qsTr("Save To File...") Layout.fillWidth: true - enabled: !_syncDropDownController.syncInProgress + enabled: !masterController.syncInProgress onClicked: { dropPanel.hide() - _syncDropDownController.saveToSelectedFile() + masterController.saveToSelectedFile() } } QGCButton { text: qsTr("Load From File...") Layout.fillWidth: true - enabled: !_syncDropDownController.syncInProgress + enabled: !masterController.syncInProgress onClicked: { dropPanel.hide() - if (_syncDropDownController.dirty) { + if (masterController.dirty) { _qgcView.showDialog(syncLoadFromFileOverwrite, columnHolder._overwriteText, _qgcView.showDialogDefaultWidth, StandardButton.Yes | StandardButton.Cancel) } else { - _syncDropDownController.loadFromSelectedFile() + masterController.loadFromSelectedFile() } } } @@ -947,14 +788,6 @@ QGCView { } } } - - FactCheckBox { - text: qsTr("Automatic upload to vehicle") - fact: autoSyncFact - visible: autoSyncFact.visible - - property Fact autoSyncFact: QGroundControl.settingsManager.appSettings.automaticMissionUpload - } } } } // QGCVIew diff --git a/src/QGCApplication.cc b/src/QGCApplication.cc index d4b453f8ba6fc1157557d6aa196346987148a477..e6dddcb82d3381bd64ed8c9fb58f8e806dd604a1 100644 --- a/src/QGCApplication.cc +++ b/src/QGCApplication.cc @@ -64,9 +64,7 @@ #include "QGroundControlQmlGlobal.h" #include "FlightMapSettings.h" #include "CoordinateVector.h" -#include "MissionController.h" -#include "GeoFenceController.h" -#include "RallyPointController.h" +#include "PlanMasterController.h" #include "VideoManager.h" #include "VideoSurface.h" #include "VideoReceiver.h" @@ -384,6 +382,7 @@ void QGCApplication::_initCommon(void) qmlRegisterType ("QGroundControl.Controllers", 1, 0, "ParameterEditorController"); qmlRegisterType ("QGroundControl.Controllers", 1, 0, "ESP8266ComponentController"); qmlRegisterType ("QGroundControl.Controllers", 1, 0, "ScreenToolsController"); + qmlRegisterType ("QGroundControl.Controllers", 1, 0, "PlanElemementMasterController"); qmlRegisterType ("QGroundControl.Controllers", 1, 0, "MissionController"); qmlRegisterType ("QGroundControl.Controllers", 1, 0, "GeoFenceController"); qmlRegisterType ("QGroundControl.Controllers", 1, 0, "RallyPointController"); diff --git a/src/Settings/AppSettings.cc b/src/Settings/AppSettings.cc index ef027eeb62665293a7b07f91aadaff813ac661eb..80f616188a807497003fd2435a31dfd26fc35ea8 100644 --- a/src/Settings/AppSettings.cc +++ b/src/Settings/AppSettings.cc @@ -34,6 +34,7 @@ const char* AppSettings::autoLoadMissionsName = "AutoLoa const char* AppSettings::automaticMissionUploadName = "AutomaticMissionUpload"; const char* AppSettings::parameterFileExtension = "params"; +const char* AppSettings::planFileExtension = "plan"; const char* AppSettings::missionFileExtension = "mission"; const char* AppSettings::fenceFileExtension = "fence"; const char* AppSettings::rallyPointFileExtension = "rally"; diff --git a/src/Settings/AppSettings.h b/src/Settings/AppSettings.h index 0aeb61b3b1b6979d64b98e09013a238b4ad051e5..bc98a51f05d4fb2427022ceb91303df79c690919 100644 --- a/src/Settings/AppSettings.h +++ b/src/Settings/AppSettings.h @@ -40,6 +40,7 @@ public: Q_PROPERTY(QString parameterSavePath READ parameterSavePath NOTIFY savePathsChanged) Q_PROPERTY(QString telemetrySavePath READ telemetrySavePath NOTIFY savePathsChanged) + Q_PROPERTY(QString planFileExtension MEMBER planFileExtension CONSTANT) Q_PROPERTY(QString missionFileExtension MEMBER missionFileExtension CONSTANT) Q_PROPERTY(QString parameterFileExtension MEMBER parameterFileExtension CONSTANT) Q_PROPERTY(QString telemetryFileExtension MEMBER telemetryFileExtension CONSTANT) @@ -86,6 +87,7 @@ public: // Application wide file extensions static const char* parameterFileExtension; + static const char* planFileExtension; static const char* missionFileExtension; static const char* fenceFileExtension; static const char* rallyPointFileExtension; diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 71537edeaa5cd61e099590e3af88d5a6da9f1006..a4eb9e205fd4038f52f067875519a915289eafe2 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -17,6 +17,7 @@ #include "JoystickManager.h" #include "MissionManager.h" #include "MissionController.h" +#include "PlanMasterController.h" #include "GeoFenceManager.h" #include "RallyPointManager.h" #include "CoordinateVector.h" @@ -1627,11 +1628,10 @@ void Vehicle::_startMissionRequest(void) if (_settingsManager->appSettings()->autoLoadMissions()->rawValue().toBool()) { QString missionAutoLoadDirPath = _settingsManager->appSettings()->missionSavePath(); if (!missionAutoLoadDirPath.isEmpty()) { - QmlObjectListModel* visualItems = NULL; QDir missionAutoLoadDir(missionAutoLoadDirPath); - QString autoloadFilename = missionAutoLoadDir.absoluteFilePath(tr("AutoLoad%1.%2").arg(_id).arg(AppSettings::missionFileExtension)); - if (MissionController::loadItemsFromFile(this, autoloadFilename, &visualItems)) { - MissionController::sendItemsToVehicle(this, visualItems); + QString autoloadFilename = missionAutoLoadDir.absoluteFilePath(tr("AutoLoad%1.%2").arg(_id).arg(AppSettings::planFileExtension)); + if (QFile(autoloadFilename).exists()) { + PlanMasterController::sendPlanToVehicle(this, autoloadFilename); return; } }