diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index 083cd9f419e3e90d93baa55c44bcf5ef9087d17f..f6e14e54d0cfc5e1ba614c8cb0c85f3660e37625 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -307,7 +307,7 @@ INCLUDEPATH += \ src/FollowMe \ src/GPS \ src/Joystick \ - src/MissionEditor \ + src/PlanView \ src/MissionManager \ src/PositionManager \ src/QmlControls \ @@ -462,7 +462,7 @@ HEADERS += \ src/MissionManager/MissionController.h \ src/MissionManager/MissionItem.h \ src/MissionManager/MissionManager.h \ - src/MissionManager/MissionSettingsComplexItem.h \ + src/MissionManager/MissionSettingsItem.h \ src/MissionManager/PlanElementController.h \ src/MissionManager/QGCMapPolygon.h \ src/MissionManager/RallyPoint.h \ @@ -640,7 +640,7 @@ SOURCES += \ src/MissionManager/MissionController.cc \ src/MissionManager/MissionItem.cc \ src/MissionManager/MissionManager.cc \ - src/MissionManager/MissionSettingsComplexItem.cc \ + src/MissionManager/MissionSettingsItem.cc \ src/MissionManager/PlanElementController.cc \ src/MissionManager/QGCMapPolygon.cc \ src/MissionManager/RallyPoint.cc \ diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc index aa36354606c5fa37d483b1e61dd0b826ddc16024..aa2e73503f8c87e09c2383dfed9c803665ab692c 100644 --- a/qgroundcontrol.qrc +++ b/qgroundcontrol.qrc @@ -36,7 +36,7 @@ src/ui/MainWindowInner.qml src/ui/MainWindowNative.qml src/ui/preferences/MavlinkSettings.qml - src/MissionEditor/MissionEditor.qml + src/PlanView/PlanView.qml src/AutoPilotPlugins/Common/MixersComponent.qml src/ui/preferences/MockLink.qml src/ui/preferences/MockLinkSettings.qml @@ -47,32 +47,32 @@ src/VehicleSetup/PX4FlowSensor.qml src/AnalyzeView/AnalyzePage.qml src/QmlControls/AppMessages.qml - src/MissionEditor/CameraSection.qml + src/PlanView/CameraSection.qml src/QmlControls/ClickableColor.qml src/QmlControls/DropButton.qml src/QmlControls/ExclusiveGroupItem.qml src/QmlControls/FactSliderPanel.qml src/QmlControls/FlightModeDropdown.qml src/QmlControls/FlightModeMenu.qml - src/MissionEditor/FWLandingPatternMapVisual.qml - src/MissionEditor/GeoFenceEditor.qml - src/MissionEditor/GeoFenceMapVisuals.qml + src/PlanView/FWLandingPatternMapVisual.qml + src/PlanView/GeoFenceEditor.qml + src/PlanView/GeoFenceMapVisuals.qml src/QmlControls/IndicatorButton.qml src/QmlControls/JoystickThumbPad.qml src/ui/toolbar/MainToolBar.qml src/ui/toolbar/MainToolBarIndicators.qml src/QmlControls/MissionCommandDialog.qml - src/MissionEditor/MissionItemEditor.qml + src/PlanView/MissionItemEditor.qml src/QmlControls/MissionItemIndexLabel.qml - src/MissionEditor/MissionItemMapVisual.qml - src/MissionEditor/MissionItemStatus.qml - src/MissionEditor/MissionSettingsMapVisual.qml + src/PlanView/MissionItemMapVisual.qml + src/PlanView/MissionItemStatus.qml + src/PlanView/MissionSettingsMapVisual.qml src/QmlControls/ModeSwitchDisplay.qml src/QmlControls/MultiRotorMotorDisplay.qml src/QmlControls/OfflineMapButton.qml src/QmlControls/ParameterEditor.qml src/QmlControls/ParameterEditorDialog.qml - src/MissionEditor/PlanToolBar.qml + src/PlanView/PlanToolBar.qml src/QmlControls/QGCButton.qml src/QmlControls/QGCCheckBox.qml src/QmlControls/QGCColoredImage.qml @@ -98,17 +98,17 @@ src/QmlControls/QGCViewMessage.qml src/QmlControls/QGCViewPanel.qml src/QmlControls/QGroundControl.Controls.qmldir - src/MissionEditor/RallyPointEditorHeader.qml - src/MissionEditor/RallyPointItemEditor.qml + src/PlanView/RallyPointEditorHeader.qml + src/PlanView/RallyPointItemEditor.qml src/QmlControls/RCChannelMonitor.qml src/QmlControls/RoundButton.qml - src/MissionEditor/SectionHeader.qml + src/PlanView/SectionHeader.qml src/AutoPilotPlugins/Common/SetupPage.qml src/ui/toolbar/SignalStrength.qml - src/MissionEditor/SimpleItemMapVisual.qml + src/PlanView/SimpleItemMapVisual.qml src/QmlControls/SliderSwitch.qml src/QmlControls/SubMenuButton.qml - src/MissionEditor/SurveyMapVisual.qml + src/PlanView/SurveyMapVisual.qml src/QmlControls/VehicleRotationCal.qml src/QmlControls/VehicleSummaryRow.qml src/QmlControls/ToolStrip.qml @@ -147,7 +147,7 @@ src/FlightMap/Widgets/QGCCompassWidget.qml src/FlightMap/Widgets/QGCInstrumentWidget.qml src/FlightMap/Widgets/QGCInstrumentWidgetAlternate.qml - src/MissionEditor/QGCMapPolygonControls.qml + src/PlanView/QGCMapPolygonControls.qml src/FlightMap/Widgets/QGCPitchIndicator.qml src/FlightMap/QGCVideoBackground.qml src/FlightMap/qmldir @@ -168,10 +168,10 @@ src/ui/preferences/SerialSettings.qml src/VehicleSetup/SetupParameterEditor.qml src/VehicleSetup/SetupView.qml - src/MissionEditor/SimpleItemEditor.qml - src/MissionEditor/SurveyItemEditor.qml - src/MissionEditor/FWLandingPatternEditor.qml - src/MissionEditor/MissionSettingsEditor.qml + src/PlanView/SimpleItemEditor.qml + src/PlanView/SurveyItemEditor.qml + src/PlanView/FWLandingPatternEditor.qml + src/PlanView/MissionSettingsEditor.qml src/ui/preferences/TcpSettings.qml src/test.qml src/ui/preferences/UdpSettings.qml diff --git a/src/FlightDisplay/FlightDisplayViewMap.qml b/src/FlightDisplay/FlightDisplayViewMap.qml index 8ffe0b386e7f582cbf179119ada27609e0d32b50..82eae699ecb1804dfa5742731a25238d936496ab 100644 --- a/src/FlightDisplay/FlightDisplayViewMap.qml +++ b/src/FlightDisplay/FlightDisplayViewMap.qml @@ -34,42 +34,54 @@ FlightMap { property var qgcView ///< QGCView control which contains this map property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle - property bool _activeVehicleCoordinateValid: _activeVehicle ? _activeVehicle.coordinateValid : false - property var activeVehicleCoordinate: _activeVehicle ? _activeVehicle.coordinate : QtPositioning.coordinate() + property var _activeVehicleCoordinate: _activeVehicle ? _activeVehicle.coordinate : QtPositioning.coordinate() property var _gotoHereCoordinate: QtPositioning.coordinate() property int _retaskSequence: 0 property real _toolButtonTopMargin: parent.height - ScreenTools.availableHeight + (ScreenTools.defaultFontPixelHeight / 2) property bool _disableVehicleTracking: false property bool _keepVehicleCentered: _mainIsMap ? false : true - property bool _followVehicleSetting: true ///< User facing setting for follow vehicle - property bool _followVehicle: _followVehicleSetting && _activeVehicleCoordinateValid ///< Control map follow vehicle functionality - property bool _firstVehiclePosition: true + property bool _firstVehiclePositionReceived: false + property bool _userPanned: false Component.onCompleted: { QGroundControl.flightMapPosition = center QGroundControl.flightMapZoom = zoomLevel + possibleCenterToGCSPosition() } + // Track last known map position and zoom in settings onZoomLevelChanged: QGroundControl.flightMapZoom = zoomLevel + onCenterChanged: QGroundControl.flightMapPosition = center - // When the user pans the map we leave things alone until the panRecenterTimer fires + // We move the map to the gcs position id: + // - We don't have a vehicle position yet + // - The user has not futzed with the map + onGcsPositionChanged: possibleCenterToGCSPosition() + + function possibleCenterToGCSPosition() { + if (!_firstVehiclePositionReceived && !_userPanned && gcsPosition.isValid) { + center = gcsPosition + } + } + + // When the user pans the map we stop responding to vehicle coordinate updates until the panRecenterTimer fires Connections { target: gesture onPanFinished: { + _userPanned = true _disableVehicleTracking = true panRecenterTimer.start() } onFlickFinished: { + _userPanned = true _disableVehicleTracking = true panRecenterTimer.start() } } - onCenterChanged: QGroundControl.flightMapPosition = center - function pointInRect(point, rect) { return point.x > rect.x && point.x < rect.x + rect.width && @@ -100,22 +112,22 @@ FlightMap { } function recenterNeeded() { - var vehiclePoint = flightMap.fromCoordinate(activeVehicleCoordinate, false /* clipToViewport */) + var vehiclePoint = flightMap.fromCoordinate(_activeVehicleCoordinate, false /* clipToViewport */) var centerViewport = Qt.rect(0, 0, width, height) return !pointInRect(vehiclePoint, centerViewport) } function updateMapToVehiclePosition() { - if (_followVehicle && !_disableVehicleTracking) { + if (_activeVehicleCoordinate.isValid && !_disableVehicleTracking) { if (_keepVehicleCentered) { - _firstVehiclePosition = true - flightMap.center = activeVehicleCoordinate + _firstVehiclePositionReceived = true + flightMap.center = _activeVehicleCoordinate } else { - if (_firstVehiclePosition) { - _firstVehiclePosition = false - flightMap.center = activeVehicleCoordinate + if (!_firstVehiclePositionReceived) { + _firstVehiclePositionReceived = true + flightMap.center = _activeVehicleCoordinate } else if (recenterNeeded()) { - animatedMapRecenter(flightMap.center, activeVehicleCoordinate) + animatedMapRecenter(flightMap.center, _activeVehicleCoordinate) } } } @@ -266,10 +278,6 @@ FlightMap { CenterMapDropPanel { map: _flightMap fitFunctions: mapFitFunctions - showFollowVehicle: true - followVehicle: _followVehicleSetting - - onFollowVehicleChanged: _followVehicleSetting = followVehicle } } diff --git a/src/FlightMap/FlightMap.qml b/src/FlightMap/FlightMap.qml index 2641008a7ba820dd9e2b25ea842f771eb23c24d8..4b4c290a3d58d55711a7c973eb79e54cf114752b 100644 --- a/src/FlightMap/FlightMap.qml +++ b/src/FlightMap/FlightMap.qml @@ -7,13 +7,6 @@ * ****************************************************************************/ - -/** - * @file - * @brief QGC Map Background - * @author Gus Grubba - */ - import QtQuick 2.3 import QtQuick.Controls 1.2 import QtLocation 5.3 @@ -27,34 +20,21 @@ import QGroundControl.ScreenTools 1.0 import QGroundControl.MultiVehicleManager 1.0 import QGroundControl.Vehicle 1.0 import QGroundControl.Mavlink 1.0 +import QGroundControl.QGCPositionManager 1.0 Map { id: _map + zoomLevel: QGroundControl.flightMapZoom + center: QGroundControl.flightMapPosition + gesture.flickDeceleration: 3000 + plugin: Plugin { name: "QGroundControl" } + property string mapName: 'defaultMap' property bool isSatelliteMap: activeMapType.name.indexOf("Satellite") > -1 || activeMapType.name.indexOf("Hybrid") > -1 + property var gcsPosition: QtPositioning.coordinate() readonly property real maxZoomLevel: 20 - property variant scaleLengths: [5, 10, 25, 50, 100, 150, 250, 500, 1000, 2000, 5000, 10000, 20000, 50000, 100000, 200000, 500000, 1000000, 2000000] - - function formatDistance(meters) - { - var dist = Math.round(meters) - if (dist > 1000 ){ - if (dist > 100000){ - dist = Math.round(dist / 1000) - } - else{ - dist = Math.round(dist / 100) - dist = dist / 10 - } - dist = dist + " km" - } - else{ - dist = dist + " m" - } - return dist - } function setVisibleRegion(region) { // This works around a bug on Qt where if you set a visibleRegion and then the user moves or zooms the map @@ -64,13 +44,18 @@ Map { _map.visibleRegion = region } - zoomLevel: 18 - center: QGroundControl.lastKnownHomePosition - gesture.flickDeceleration: 3000 + ExclusiveGroup { id: mapTypeGroup } - plugin: Plugin { name: "QGroundControl" } + // Update ground station position + Connections { + target: QGroundControl.qgcPositionManger - ExclusiveGroup { id: mapTypeGroup } + onLastPositionUpdated: { + if (valid && lastPosition.latitude && Math.abs(lastPosition.latitude) > 0.001 && lastPosition.longitude && Math.abs(lastPosition.longitude) > 0.001) { + gcsPosition = QtPositioning.coordinate(lastPosition.latitude,lastPosition.longitude) + } + } + } function updateActiveMapType() { var settings = QGroundControl.settingsManager.flightMapSettings @@ -99,10 +84,10 @@ Map { MapQuickItem { anchorPoint.x: sourceItem.anchorPointX anchorPoint.y: sourceItem.anchorPointY - visible: mainWindow.gcsPosition.isValid - coordinate: mainWindow.gcsPosition + visible: gcsPosition.isValid + coordinate: gcsPosition sourceItem: MissionItemIndexLabel { - label: "Q" + label: "Q" } } } // Map diff --git a/src/FlightMap/Widgets/CenterMapDropPanel.qml b/src/FlightMap/Widgets/CenterMapDropPanel.qml index 59652180c2d8b5b61138235070b381024939699a..5c6485562fe00cd7719153877395b19e44104040 100644 --- a/src/FlightMap/Widgets/CenterMapDropPanel.qml +++ b/src/FlightMap/Widgets/CenterMapDropPanel.qml @@ -25,8 +25,6 @@ ColumnLayout { property var fitFunctions property bool showMission: true property bool showAllItems: true - property bool showFollowVehicle: false - property bool followVehicle: false property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle @@ -70,7 +68,7 @@ ColumnLayout { QGCButton { text: qsTr("Current Location") Layout.fillWidth: true - enabled: mainWindow.gcsPosition.isValid && !followVehicleCheckBox.checked + enabled: mainWindow.gcsPosition.isValid onClicked: { dropPanel.hide() @@ -81,23 +79,11 @@ ColumnLayout { QGCButton { text: qsTr("Vehicle") Layout.fillWidth: true - enabled: _activeVehicle && _activeVehicle.latitude != 0 && _activeVehicle.longitude != 0 && !followVehicleCheckBox.checked + enabled: _activeVehicle && _activeVehicle.coordinate.isValid onClicked: { dropPanel.hide() map.center = activeVehicle.coordinate } } - - QGCCheckBox { - id: followVehicleCheckBox - text: qsTr("Follow Vehicle") - checked: followVehicle - visible: showFollowVehicle - - onClicked: { - dropPanel.hide() - root.followVehicle = checked - } - } } // Column diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc index 6a6d89cedda1aeac9bb161c76e75a41dc3091113..a140f98deaca2ab5b7c173fb4177f66af095c348 100644 --- a/src/MissionManager/MissionController.cc +++ b/src/MissionManager/MissionController.cc @@ -21,7 +21,7 @@ #include "ParameterManager.h" #include "QGroundControlQmlGlobal.h" #include "SettingsManager.h" -#include "MissionSettingsComplexItem.h" +#include "MissionSettingsItem.h" #ifndef __mobile__ #include "MainWindow.h" @@ -49,6 +49,7 @@ const int MissionController::_missionFileVersion = 2; MissionController::MissionController(QObject *parent) : PlanElementController(parent) , _visualItems(NULL) + , _settingsItem(NULL) , _firstItemsFromVehicle(false) , _missionItemsRequested(false) , _queuedSend(false) @@ -117,7 +118,7 @@ void MissionController::_newMissionItemsAvailableFromVehicle(bool removeAllReque if (_activeVehicle->firmwarePlugin()->sendHomePositionToVehicle() && newMissionItems.count() != 0) { // First item is fake home position _addMissionSettings(_activeVehicle, newControllerMissionItems, false /* addToCenter */); - MissionSettingsComplexItem* settingsItem = newControllerMissionItems->value(0); + MissionSettingsItem* settingsItem = newControllerMissionItems->value(0); if (!settingsItem) { qWarning() << "First item is not settings item"; return; @@ -133,10 +134,11 @@ void MissionController::_newMissionItemsAvailableFromVehicle(bool removeAllReque _deinitAllVisualItems(); _visualItems->deleteLater(); + _settingsItem = NULL; _visualItems = newControllerMissionItems; if (!_activeVehicle->firmwarePlugin()->sendHomePositionToVehicle() || _visualItems->count() == 0) { - _addMissionSettings(_activeVehicle, _visualItems, true /* addToCenter */); + _addMissionSettings(_activeVehicle, _visualItems, _visualItems->count() > 0 /* addToCenter */); } _missionItemsRequested = false; @@ -187,7 +189,7 @@ bool MissionController::_convertToMissionItems(QmlObjectListModel* visualMission } // Mission settings has a special case for end mission action - MissionSettingsComplexItem* settingsItem = visualMissionItems->value(0); + MissionSettingsItem* settingsItem = visualMissionItems->value(0); if (settingsItem) { endActionSet = settingsItem->addMissionEndAction(rgMissionItems, lastSeqNum + 1, missionItemParent); } @@ -289,6 +291,7 @@ void MissionController::removeAll(void) if (_visualItems) { _deinitAllVisualItems(); _visualItems->deleteLater(); + _settingsItem = NULL; _visualItems = new QmlObjectListModel(this); _addMissionSettings(_activeVehicle, _visualItems, false /* addToCenter */); _initAllVisualItems(); @@ -412,7 +415,7 @@ bool MissionController::_loadJsonMissionFileV1(Vehicle* vehicle, const QJsonObje SimpleMissionItem* item = new SimpleMissionItem(vehicle, visualItems); if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0, errorString)) { - MissionSettingsComplexItem* settingsItem = new MissionSettingsComplexItem(vehicle, visualItems); + MissionSettingsItem* settingsItem = new MissionSettingsItem(vehicle, visualItems); settingsItem->setCoordinate(item->coordinate()); visualItems->insert(0, settingsItem); item->deleteLater(); @@ -459,7 +462,7 @@ bool MissionController::_loadJsonMissionFileV2(Vehicle* vehicle, const QJsonObje settingsManager->appSettings()->offlineEditingHoverSpeed()->setRawValue(json[_jsonHoverSpeedKey].toDouble()); } - MissionSettingsComplexItem* settingsItem = new MissionSettingsComplexItem(vehicle, visualItems); + MissionSettingsItem* settingsItem = new MissionSettingsItem(vehicle, visualItems); settingsItem->setCoordinate(homeCoordinate); visualItems->insert(0, settingsItem); qCDebug(MissionControllerLog) << "plannedHomePosition" << homeCoordinate; @@ -523,9 +526,9 @@ bool MissionController::_loadJsonMissionFileV2(Vehicle* vehicle, const QJsonObje nextSequenceNumber = landingItem->lastSequenceNumber() + 1; qCDebug(MissionControllerLog) << "FW Landing Pattern load complete: nextSequenceNumber" << nextSequenceNumber; visualItems->append(landingItem); - } else if (complexItemType == MissionSettingsComplexItem::jsonComplexItemTypeValue) { + } else if (complexItemType == MissionSettingsItem::jsonComplexItemTypeValue) { qCDebug(MissionControllerLog) << "Loading Mission Settings: nextSequenceNumber" << nextSequenceNumber; - MissionSettingsComplexItem* settingsItem = new MissionSettingsComplexItem(vehicle, visualItems); + MissionSettingsItem* settingsItem = new MissionSettingsItem(vehicle, visualItems); if (!settingsItem->load(itemObject, nextSequenceNumber++, errorString)) { return false; } @@ -630,6 +633,7 @@ void MissionController::loadFromFile(const QString& filename) if (_visualItems) { _deinitAllVisualItems(); _visualItems->deleteLater(); + _settingsItem = NULL; } _visualItems = newVisualItems; @@ -719,9 +723,9 @@ void MissionController::saveToFile(const QString& filename) // Mission settings - MissionSettingsComplexItem* settingsItem = _visualItems->value(0); + MissionSettingsItem* settingsItem = _visualItems->value(0); if (!settingsItem) { - qWarning() << "First item is not MissionSettingsComplexItem"; + qWarning() << "First item is not MissionSettingsItem"; return; } QJsonValue coordinateValue; @@ -828,13 +832,7 @@ void MissionController::_recalcWaypointLines(void) bool firstCoordinateItem = true; VisualMissionItem* lastCoordinateItem = qobject_cast(_visualItems->get(0)); - MissionSettingsComplexItem* settingsItem = qobject_cast(lastCoordinateItem); - - if (!settingsItem) { - qWarning() << "First item is not MissionSettingsComplexItem"; - } - - bool showHomePosition = settingsItem->showHomePosition(); + bool showHomePosition = _settingsItem->coordinate().isValid(); qCDebug(MissionControllerLog) << "_recalcWaypointLines"; @@ -859,7 +857,7 @@ void MissionController::_recalcWaypointLines(void) if (!item->isStandaloneCoordinate()) { firstCoordinateItem = false; VisualItemPair pair(lastCoordinateItem, item); - if (lastCoordinateItem != settingsItem || (showHomePosition && linkBackToHome)) { + if (lastCoordinateItem != _settingsItem || (showHomePosition && linkBackToHome)) { if (old_table.contains(pair)) { // Do nothing, this segment already exists and is wired up _linesTable[pair] = old_table.take(pair); @@ -911,13 +909,8 @@ void MissionController::_recalcMissionFlightStatus() bool firstCoordinateItem = true; VisualMissionItem* lastCoordinateItem = qobject_cast(_visualItems->get(0)); - MissionSettingsComplexItem* settingsItem = qobject_cast(lastCoordinateItem); - if (!settingsItem) { - qWarning() << "First item is not MissionSettingsComplexItem"; - } - - bool showHomePosition = settingsItem->showHomePosition(); + bool showHomePosition = _settingsItem->coordinate().isValid(); qCDebug(MissionControllerLog) << "_recalcMissionFlightStatus"; @@ -932,8 +925,8 @@ void MissionController::_recalcMissionFlightStatus() double minAltSeen = 0.0; double maxAltSeen = 0.0; - const double homePositionAltitude = settingsItem->coordinate().altitude(); - minAltSeen = maxAltSeen = settingsItem->coordinate().altitude(); + const double homePositionAltitude = _settingsItem->coordinate().altitude(); + minAltSeen = maxAltSeen = _settingsItem->coordinate().altitude(); double lastVehicleYaw = 0; @@ -1050,7 +1043,7 @@ void MissionController::_recalcMissionFlightStatus() if (!item->isStandaloneCoordinate()) { firstCoordinateItem = false; - if (lastCoordinateItem != settingsItem || linkBackToHome) { + if (lastCoordinateItem != _settingsItem || linkBackToHome) { // This is a subsequent waypoint or we are forcing the first waypoint back to home double azimuth, distance, altDifference; @@ -1060,7 +1053,7 @@ void MissionController::_recalcMissionFlightStatus() item->setDistance(distance); _missionFlightStatus.totalDistance += distance; - _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, _calcDistanceToHome(item, settingsItem)); + _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, _calcDistanceToHome(item, _settingsItem)); // Calculate time/distance double hoverTime = distance / _missionFlightStatus.hoverSpeed; @@ -1093,7 +1086,7 @@ void MissionController::_recalcMissionFlightStatus() // Add in distance/time inside complex items as well double distance = complexItem->complexDistance(); _missionFlightStatus.totalDistance += distance; - _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, complexItem->greatestDistanceTo(settingsItem->exitCoordinate())); + _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, complexItem->greatestDistanceTo(complexItem->exitCoordinate())); double hoverTime = _missionFlightStatus.totalDistance / _missionFlightStatus.hoverSpeed; double cruiseTime = _missionFlightStatus.totalDistance / _missionFlightStatus.cruiseSpeed; @@ -1191,8 +1184,26 @@ void MissionController::_recalcChildItems(void) } } +void MissionController::_setPlannedHomePositionFromFirstCoordinate(void) +{ + if (_settingsItem->coordinate().isValid()) { + return; + } + + // Set the planned home position to be a deltae from first coordinate + for (int i=1; i<_visualItems->count(); i++) { + VisualMissionItem* item = _visualItems->value(i); + + if (item->specifiesCoordinate()) { + _settingsItem->setCoordinate(item->coordinate().atDistanceAndAzimuth(30, 0)); + } + } +} + + void MissionController::_recalcAll(void) { + _setPlannedHomePositionFromFirstCoordinate(); _recalcSequence(); _recalcChildItems(); _recalcWaypointLines(); @@ -1201,27 +1212,20 @@ void MissionController::_recalcAll(void) /// Initializes a new set of mission items void MissionController::_initAllVisualItems(void) { - MissionSettingsComplexItem* settingsItem = NULL; - // Setup home position at index 0 - settingsItem = qobject_cast(_visualItems->get(0)); - if (!settingsItem) { - qWarning() << "First item not MissionSettingsComplexItem"; + _settingsItem = qobject_cast(_visualItems->get(0)); + if (!_settingsItem) { + qWarning() << "First item not MissionSettingsItem"; return; } + _settingsItem->setIsCurrentItem(true); - settingsItem->setShowHomePosition(_editMode); - settingsItem->setIsCurrentItem(true); - - if (!_editMode && _activeVehicle && _activeVehicle->homePositionAvailable()) { - settingsItem->setCoordinate(_activeVehicle->homePosition()); - settingsItem->setShowHomePosition(true); + if (!_editMode && _activeVehicle) { + _settingsItem->setCoordinate(_activeVehicle->homePosition()); } - emit plannedHomePositionChanged(plannedHomePosition()); - - connect(settingsItem, &VisualMissionItem::coordinateChanged, this, &MissionController::_homeCoordinateChanged); + connect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll); for (int i=0; i<_visualItems->count(); i++) { VisualMissionItem* item = qobject_cast(_visualItems->get(i)); @@ -1298,7 +1302,6 @@ void MissionController::_activeVehicleBeingRemoved(void) disconnect(missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionController::_newMissionItemsAvailableFromVehicle); disconnect(missionManager, &MissionManager::inProgressChanged, this, &MissionController::_inProgressChanged); disconnect(missionManager, &MissionManager::currentItemChanged, this, &MissionController::_currentMissionItemChanged); - disconnect(_activeVehicle, &Vehicle::homePositionAvailableChanged, this, &MissionController::_activeVehicleHomePositionAvailableChanged); disconnect(_activeVehicle, &Vehicle::homePositionChanged, this, &MissionController::_activeVehicleHomePositionChanged); // We always remove all items on vehicle change. This leaves a user model hole: @@ -1317,7 +1320,6 @@ void MissionController::_activeVehicleSet(void) connect(missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionController::_newMissionItemsAvailableFromVehicle); connect(missionManager, &MissionManager::inProgressChanged, this, &MissionController::_inProgressChanged); connect(missionManager, &MissionManager::currentItemChanged, this, &MissionController::_currentMissionItemChanged); - connect(_activeVehicle, &Vehicle::homePositionAvailableChanged, this, &MissionController::_activeVehicleHomePositionAvailableChanged); connect(_activeVehicle, &Vehicle::homePositionChanged, this, &MissionController::_activeVehicleHomePositionChanged); connect(_activeVehicle, &Vehicle::defaultCruiseSpeedChanged, this, &MissionController::_recalcMissionFlightStatus); connect(_activeVehicle, &Vehicle::defaultHoverSpeedChanged, this, &MissionController::_recalcMissionFlightStatus); @@ -1330,40 +1332,18 @@ void MissionController::_activeVehicleSet(void) } _activeVehicleHomePositionChanged(_activeVehicle->homePosition()); - _activeVehicleHomePositionAvailableChanged(_activeVehicle->homePositionAvailable()); emit complexMissionItemNamesChanged(); } -void MissionController::_activeVehicleHomePositionAvailableChanged(bool homePositionAvailable) -{ - if (!_editMode && _visualItems) { - MissionSettingsComplexItem* settingsItem = qobject_cast(_visualItems->get(0)); - - if (settingsItem) { - settingsItem->setShowHomePosition(homePositionAvailable); - emit plannedHomePositionChanged(plannedHomePosition()); - _recalcWaypointLines(); - } else { - qWarning() << "First item is not MissionSettingsComplexItem"; - } - } -} - void MissionController::_activeVehicleHomePositionChanged(const QGeoCoordinate& homePosition) { - if (!_editMode && _visualItems) { - MissionSettingsComplexItem* settingsItem = qobject_cast(_visualItems->get(0)); + if (_visualItems) { + MissionSettingsItem* settingsItem = qobject_cast(_visualItems->get(0)); if (settingsItem) { - if (settingsItem->coordinate() != homePosition) { - settingsItem->setCoordinate(homePosition); - settingsItem->setShowHomePosition(true); - qCDebug(MissionControllerLog) << "Home position update" << homePosition; - emit plannedHomePositionChanged(plannedHomePosition()); - _recalcWaypointLines(); - } + settingsItem->setCoordinate(homePosition); } else { - qWarning() << "First item is not MissionSettingsComplexItem"; + qWarning() << "First item is not MissionSettingsItem"; } } } @@ -1479,46 +1459,44 @@ double MissionController::_normalizeLon(double lon) /// Add the Mission Settings complex item to the front of the items void MissionController::_addMissionSettings(Vehicle* vehicle, QmlObjectListModel* visualItems, bool addToCenter) { - bool homePositionSet = false; + MissionSettingsItem* settingsItem = new MissionSettingsItem(vehicle, visualItems); - MissionSettingsComplexItem* settingsItem = new MissionSettingsComplexItem(vehicle, visualItems); visualItems->insert(0, settingsItem); - if (visualItems->count() > 1 && addToCenter) { - double north = 0.0; - double south = 0.0; - double east = 0.0; - double west = 0.0; - bool firstCoordSet = false; - - for (int i=1; icount(); i++) { - VisualMissionItem* item = qobject_cast(visualItems->get(i)); - if (item->specifiesCoordinate()) { - if (firstCoordSet) { - double lat = _normalizeLat(item->coordinate().latitude()); - double lon = _normalizeLon(item->coordinate().longitude()); - north = fmax(north, lat); - south = fmin(south, lat); - east = fmax(east, lon); - west = fmin(west, lon); - } else { - firstCoordSet = true; - north = _normalizeLat(item->coordinate().latitude()); - south = north; - east = _normalizeLon(item->coordinate().longitude()); - west = east; + if (addToCenter) { + if (visualItems->count() > 1) { + double north = 0.0; + double south = 0.0; + double east = 0.0; + double west = 0.0; + bool firstCoordSet = false; + + for (int i=1; icount(); i++) { + VisualMissionItem* item = qobject_cast(visualItems->get(i)); + if (item->specifiesCoordinate()) { + if (firstCoordSet) { + double lat = _normalizeLat(item->coordinate().latitude()); + double lon = _normalizeLon(item->coordinate().longitude()); + north = fmax(north, lat); + south = fmin(south, lat); + east = fmax(east, lon); + west = fmin(west, lon); + } else { + firstCoordSet = true; + north = _normalizeLat(item->coordinate().latitude()); + south = north; + east = _normalizeLon(item->coordinate().longitude()); + west = east; + } } } - } - if (firstCoordSet) { - homePositionSet = true; - settingsItem->setCoordinate(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0)); + if (firstCoordSet) { + settingsItem->setCoordinate(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0)); + } } - } - - if (!homePositionSet) { - settingsItem->setCoordinate(qgcApp()->lastKnownHomePosition()); + } else { + settingsItem->setCoordinate(vehicle->homePosition()); } } @@ -1554,24 +1532,6 @@ void MissionController::setDirty(bool dirty) } } -QGeoCoordinate MissionController::plannedHomePosition(void) -{ - if (_visualItems && _visualItems->count() > 0) { - MissionSettingsComplexItem* settingsItem = qobject_cast(_visualItems->get(0)); - if (settingsItem && settingsItem->showHomePosition()) { - return settingsItem->coordinate(); - } - } - - return QGeoCoordinate(); -} - -void MissionController::_homeCoordinateChanged(void) -{ - emit plannedHomePositionChanged(plannedHomePosition()); - _recalcMissionFlightStatus(); -} - QString MissionController::fileExtension(void) const { return QGCApplication::missionFileExtension; @@ -1585,7 +1545,7 @@ void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualIte qCDebug(MissionControllerLog) << "MissionController::_scanForAdditionalSettings count:scanIndex" << visualItems->count() << scanIndex; - MissionSettingsComplexItem* settingsItem = qobject_cast(visualItem); + MissionSettingsItem* settingsItem = qobject_cast(visualItem); if (settingsItem && settingsItem->scanForMissionSettings(visualItems, scanIndex, vehicle)) { continue; } diff --git a/src/MissionManager/MissionController.h b/src/MissionManager/MissionController.h index 9cc6689d72e2a23f9f708f0ee1b356475f44799a..55da4fcb4b91ecf0e2c4f81ce1ab5f2adaa1362e 100644 --- a/src/MissionManager/MissionController.h +++ b/src/MissionManager/MissionController.h @@ -22,6 +22,7 @@ class CoordinateVector; class VisualMissionItem; class MissionItem; +class MissionSettingsItem; Q_DECLARE_LOGGING_CATEGORY(MissionControllerLog) @@ -50,7 +51,6 @@ public: } MissionFlightStatus_t; // Mission settings - Q_PROPERTY(QGeoCoordinate plannedHomePosition READ plannedHomePosition NOTIFY plannedHomePositionChanged) Q_PROPERTY(QmlObjectListModel* visualItems READ visualItems NOTIFY visualItemsChanged) Q_PROPERTY(QmlObjectListModel* waypointLines READ waypointLines NOTIFY waypointLinesChanged) Q_PROPERTY(QStringList complexMissionItemNames READ complexMissionItemNames NOTIFY complexMissionItemNamesChanged) @@ -107,7 +107,6 @@ public: // Property accessors - QGeoCoordinate plannedHomePosition (void); QmlObjectListModel* visualItems (void) { return _visualItems; } QmlObjectListModel* waypointLines (void) { return &_waypointLines; } QStringList complexMissionItemNames (void) const; @@ -121,7 +120,6 @@ public: double missionMaxTelemetry (void) const { return _missionFlightStatus.maxTelemetryDistance; } signals: - void plannedHomePositionChanged(QGeoCoordinate plannedHomePosition); void visualItemsChanged(void); void waypointLinesChanged(void); void newItemsFromVehicle(void); @@ -137,13 +135,11 @@ signals: private slots: void _newMissionItemsAvailableFromVehicle(bool removeAllRequested); void _itemCommandChanged(void); - void _activeVehicleHomePositionAvailableChanged(bool homePositionAvailable); void _activeVehicleHomePositionChanged(const QGeoCoordinate& homePosition); void _inProgressChanged(bool inProgress); void _currentMissionItemChanged(int sequenceNumber); void _recalcWaypointLines(void); void _recalcMissionFlightStatus(void); - void _homeCoordinateChanged(void); void _updateContainsItems(void); private: @@ -176,6 +172,7 @@ private: void _setMissionMaxTelemetry(double missionMaxTelemetry); static void _scanForAdditionalSettings(QmlObjectListModel* visualItems, Vehicle* vehicle); static bool _convertToMissionItems(QmlObjectListModel* visualMissionItems, QList& rgMissionItems, QObject* missionItemParent); + void _setPlannedHomePositionFromFirstCoordinate(void); // Overrides from PlanElementController void _activeVehicleBeingRemoved(void) final; @@ -183,6 +180,7 @@ private: private: QmlObjectListModel* _visualItems; + MissionSettingsItem* _settingsItem; QmlObjectListModel _waypointLines; CoordVectHashTable _linesTable; bool _firstItemsFromVehicle; diff --git a/src/MissionManager/MissionSettings.FactMetaData.json b/src/MissionManager/MissionSettings.FactMetaData.json index 37d71da65e0534ddc745bcd955172acd9782b872..52f47a47ca3a04607837418049a8fed405bfc1c4 100644 --- a/src/MissionManager/MissionSettings.FactMetaData.json +++ b/src/MissionManager/MissionSettings.FactMetaData.json @@ -1,18 +1,4 @@ [ -{ - "name": "PlannedHomePositionLatitude", - "shortDescription": "Planned home position latitude", - "type": "double", - "decimalPlaces": 7, - "defaultValue": 37.803784 -}, -{ - "name": "PlannedHomePositionLongitude", - "shortDescription": "Planned home position longitude", - "type": "double", - "decimalPlaces": 7, - "defaultValue": -122.462276 -}, { "name": "PlannedHomePositionAltitude", "shortDescription": "Planned home position altitude", diff --git a/src/MissionManager/MissionSettingsComplexItem.cc b/src/MissionManager/MissionSettingsItem.cc similarity index 73% rename from src/MissionManager/MissionSettingsComplexItem.cc rename to src/MissionManager/MissionSettingsItem.cc index 6a523e3e45fc7b27d5236aaf98c3d1c4afa8585a..56227449aa8d8158759ac75c1575de5ccec90897 100644 --- a/src/MissionManager/MissionSettingsComplexItem.cc +++ b/src/MissionManager/MissionSettingsItem.cc @@ -7,7 +7,7 @@ * ****************************************************************************/ -#include "MissionSettingsComplexItem.h" +#include "MissionSettingsItem.h" #include "JsonHelper.h" #include "MissionController.h" #include "QGCGeo.h" @@ -21,21 +21,17 @@ QGC_LOGGING_CATEGORY(MissionSettingsComplexItemLog, "MissionSettingsComplexItemLog") -const char* MissionSettingsComplexItem::jsonComplexItemTypeValue = "MissionSettings"; +const char* MissionSettingsItem::jsonComplexItemTypeValue = "MissionSettings"; -const char* MissionSettingsComplexItem::_plannedHomePositionLatitudeName = "PlannedHomePositionLatitude"; -const char* MissionSettingsComplexItem::_plannedHomePositionLongitudeName = "PlannedHomePositionLongitude"; -const char* MissionSettingsComplexItem::_plannedHomePositionAltitudeName = "PlannedHomePositionAltitude"; -const char* MissionSettingsComplexItem::_missionFlightSpeedName = "FlightSpeed"; -const char* MissionSettingsComplexItem::_missionEndActionName = "MissionEndAction"; +const char* MissionSettingsItem::_plannedHomePositionAltitudeName = "PlannedHomePositionAltitude"; +const char* MissionSettingsItem::_missionFlightSpeedName = "FlightSpeed"; +const char* MissionSettingsItem::_missionEndActionName = "MissionEndAction"; -QMap MissionSettingsComplexItem::_metaDataMap; +QMap MissionSettingsItem::_metaDataMap; -MissionSettingsComplexItem::MissionSettingsComplexItem(Vehicle* vehicle, QObject* parent) +MissionSettingsItem::MissionSettingsItem(Vehicle* vehicle, QObject* parent) : ComplexMissionItem(vehicle, parent) , _specifyMissionFlightSpeed(false) - , _plannedHomePositionLatitudeFact (0, _plannedHomePositionLatitudeName, FactMetaData::valueTypeDouble) - , _plannedHomePositionLongitudeFact (0, _plannedHomePositionLongitudeName, FactMetaData::valueTypeDouble) , _plannedHomePositionAltitudeFact (0, _plannedHomePositionAltitudeName, FactMetaData::valueTypeDouble) , _missionFlightSpeedFact (0, _missionFlightSpeedName, FactMetaData::valueTypeDouble) , _missionEndActionFact (0, _missionEndActionName, FactMetaData::valueTypeUint32) @@ -48,14 +44,10 @@ MissionSettingsComplexItem::MissionSettingsComplexItem(Vehicle* vehicle, QObject _metaDataMap = FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/MissionSettings.FactMetaData.json"), NULL /* metaDataParent */); } - _plannedHomePositionLatitudeFact.setMetaData (_metaDataMap[_plannedHomePositionLatitudeName]); - _plannedHomePositionLongitudeFact.setMetaData (_metaDataMap[_plannedHomePositionLongitudeName]); _plannedHomePositionAltitudeFact.setMetaData (_metaDataMap[_plannedHomePositionAltitudeName]); _missionFlightSpeedFact.setMetaData (_metaDataMap[_missionFlightSpeedName]); _missionEndActionFact.setMetaData (_metaDataMap[_missionEndActionName]); - _plannedHomePositionLatitudeFact.setRawValue (_plannedHomePositionLatitudeFact.rawDefaultValue()); - _plannedHomePositionLongitudeFact.setRawValue (_plannedHomePositionLongitudeFact.rawDefaultValue()); _plannedHomePositionAltitudeFact.setRawValue (_plannedHomePositionAltitudeFact.rawDefaultValue()); _missionEndActionFact.setRawValue (_missionEndActionFact.rawDefaultValue()); @@ -66,25 +58,24 @@ MissionSettingsComplexItem::MissionSettingsComplexItem(Vehicle* vehicle, QObject setHomePositionSpecialCase(true); - connect(this, &MissionSettingsComplexItem::specifyMissionFlightSpeedChanged, this, &MissionSettingsComplexItem::_setDirtyAndUpdateLastSequenceNumber); - connect(&_cameraSection, &CameraSection::missionItemCountChanged, this, &MissionSettingsComplexItem::_setDirtyAndUpdateLastSequenceNumber); + connect(this, &MissionSettingsItem::specifyMissionFlightSpeedChanged, this, &MissionSettingsItem::_setDirtyAndUpdateLastSequenceNumber); + connect(&_cameraSection, &CameraSection::missionItemCountChanged, this, &MissionSettingsItem::_setDirtyAndUpdateLastSequenceNumber); - connect(&_plannedHomePositionLatitudeFact, &Fact::valueChanged, this, &MissionSettingsComplexItem::_setDirtyAndUpdateCoordinate); - connect(&_plannedHomePositionLongitudeFact, &Fact::valueChanged, this, &MissionSettingsComplexItem::_setDirtyAndUpdateCoordinate); - connect(&_plannedHomePositionAltitudeFact, &Fact::valueChanged, this, &MissionSettingsComplexItem::_setDirtyAndUpdateCoordinate); + connect(&_plannedHomePositionAltitudeFact, &Fact::valueChanged, this, &MissionSettingsItem::_setDirty); + connect(&_plannedHomePositionAltitudeFact, &Fact::valueChanged, this, &MissionSettingsItem::_updateAltitudeInCoordinate); - connect(&_missionFlightSpeedFact, &Fact::valueChanged, this, &MissionSettingsComplexItem::_setDirty); - connect(&_missionEndActionFact, &Fact::valueChanged, this, &MissionSettingsComplexItem::_setDirty); + connect(&_missionFlightSpeedFact, &Fact::valueChanged, this, &MissionSettingsItem::_setDirty); + connect(&_missionEndActionFact, &Fact::valueChanged, this, &MissionSettingsItem::_setDirty); - connect(&_cameraSection, &CameraSection::dirtyChanged, this, &MissionSettingsComplexItem::_cameraSectionDirtyChanged); + connect(&_cameraSection, &CameraSection::dirtyChanged, this, &MissionSettingsItem::_cameraSectionDirtyChanged); - connect(&_missionFlightSpeedFact, &Fact::valueChanged, this, &MissionSettingsComplexItem::specifiedFlightSpeedChanged); - connect(&_cameraSection, &CameraSection::specifyGimbalChanged, this, &MissionSettingsComplexItem::specifiedGimbalYawChanged); - connect(&_cameraSection, &CameraSection::specifiedGimbalYawChanged, this, &MissionSettingsComplexItem::specifiedGimbalYawChanged); + connect(&_missionFlightSpeedFact, &Fact::valueChanged, this, &MissionSettingsItem::specifiedFlightSpeedChanged); + connect(&_cameraSection, &CameraSection::specifyGimbalChanged, this, &MissionSettingsItem::specifiedGimbalYawChanged); + connect(&_cameraSection, &CameraSection::specifiedGimbalYawChanged, this, &MissionSettingsItem::specifiedGimbalYawChanged); } -void MissionSettingsComplexItem::setSpecifyMissionFlightSpeed(bool specifyMissionFlightSpeed) +void MissionSettingsItem::setSpecifyMissionFlightSpeed(bool specifyMissionFlightSpeed) { if (specifyMissionFlightSpeed != _specifyMissionFlightSpeed) { _specifyMissionFlightSpeed = specifyMissionFlightSpeed; @@ -92,7 +83,7 @@ void MissionSettingsComplexItem::setSpecifyMissionFlightSpeed(bool specifyMissio } } -int MissionSettingsComplexItem::lastSequenceNumber(void) const +int MissionSettingsItem::lastSequenceNumber(void) const { int lastSequenceNumber = _sequenceNumber; @@ -104,7 +95,7 @@ int MissionSettingsComplexItem::lastSequenceNumber(void) const return lastSequenceNumber; } -void MissionSettingsComplexItem::setDirty(bool dirty) +void MissionSettingsItem::setDirty(bool dirty) { if (_dirty != dirty) { _dirty = dirty; @@ -112,14 +103,14 @@ void MissionSettingsComplexItem::setDirty(bool dirty) } } -void MissionSettingsComplexItem::save(QJsonArray& missionItems) +void MissionSettingsItem::save(QJsonArray& missionItems) { QList items; appendMissionItems(items, this); // First item show be planned home position, we are not reponsible for save/load - // Remained we just output as is + // Remaining items we just output as is for (int i=1; i& items, QObject* missionItemParent) +void MissionSettingsItem::appendMissionItems(QList& items, QObject* missionItemParent) { int seqNum = _sequenceNumber; - // IMPORTANT NOTE: If anything changes here you must also change MissionSettingsComplexItem::scanForMissionSettings + // IMPORTANT NOTE: If anything changes here you must also change MissionSettingsItem::scanForMissionSettings // Planned home position MissionItem* item = new MissionItem(seqNum++, @@ -172,8 +163,8 @@ void MissionSettingsComplexItem::appendMissionItems(QList& items, 0, // Acceptance radius 0, // Not sure? 0, // Yaw - _plannedHomePositionLatitudeFact.rawValue().toDouble(), - _plannedHomePositionLongitudeFact.rawValue().toDouble(), + coordinate().latitude(), + coordinate().longitude(), _plannedHomePositionAltitudeFact.rawValue().toDouble(), true, // autoContinue false, // isCurrentItem @@ -199,11 +190,11 @@ void MissionSettingsComplexItem::appendMissionItems(QList& items, _cameraSection.appendMissionItems(items, missionItemParent, seqNum); } -bool MissionSettingsComplexItem::addMissionEndAction(QList& items, int seqNum, QObject* missionItemParent) +bool MissionSettingsItem::addMissionEndAction(QList& items, int seqNum, QObject* missionItemParent) { MissionItem* item = NULL; - // IMPORTANT NOTE: If anything changes here you must also change MissionSettingsComplexItem::scanForMissionSettings + // IMPORTANT NOTE: If anything changes here you must also change MissionSettingsItem::scanForMissionSettings // Find last waypoint coordinate information so we have a lat/lon/alt to use QGeoCoordinate lastWaypointCoord; @@ -278,17 +269,17 @@ bool MissionSettingsComplexItem::addMissionEndAction(QList& items, } } -bool MissionSettingsComplexItem::scanForMissionSettings(QmlObjectListModel* visualItems, int scanIndex, Vehicle* vehicle) +bool MissionSettingsItem::scanForMissionSettings(QmlObjectListModel* visualItems, int scanIndex, Vehicle* vehicle) { bool foundSpeed = false; bool foundCameraSection = false; bool stopLooking = false; - qCDebug(MissionSettingsComplexItemLog) << "MissionSettingsComplexItem::scanForMissionSettings count:scanIndex" << visualItems->count() << scanIndex; + qCDebug(MissionSettingsComplexItemLog) << "MissionSettingsItem::scanForMissionSettings count:scanIndex" << visualItems->count() << scanIndex; - MissionSettingsComplexItem* settingsItem = visualItems->value(scanIndex); + MissionSettingsItem* settingsItem = visualItems->value(scanIndex); if (!settingsItem) { - qWarning() << "Item specified by scanIndex not MissionSettingsComplexItem"; + qWarning() << "Item specified by scanIndex not MissionSettingsItem"; return false; } @@ -305,7 +296,7 @@ bool MissionSettingsComplexItem::scanForMissionSettings(QmlObjectListModel* visu qCDebug(MissionSettingsComplexItemLog) << item->command() << missionItem.param1() << missionItem.param2() << missionItem.param3() << missionItem.param4() << missionItem.param5() << missionItem.param6() << missionItem.param7() ; - // See MissionSettingsComplexItem::getMissionItems for specs on what compomises a known mission setting + // See MissionSettingsItem::getMissionItems for specs on what compomises a known mission setting switch ((MAV_CMD)item->command()) { case MAV_CMD_DO_CHANGE_SPEED: @@ -384,56 +375,57 @@ bool MissionSettingsComplexItem::scanForMissionSettings(QmlObjectListModel* visu return foundSpeed || foundCameraSection; } -double MissionSettingsComplexItem::complexDistance(void) const +double MissionSettingsItem::complexDistance(void) const { return 0; } -void MissionSettingsComplexItem::_setDirty(void) +void MissionSettingsItem::_setDirty(void) { setDirty(true); } -void MissionSettingsComplexItem::setCoordinate(const QGeoCoordinate& coordinate) +void MissionSettingsItem::setCoordinate(const QGeoCoordinate& coordinate) { - if (this->coordinate() != coordinate) { - _plannedHomePositionLatitudeFact.setRawValue(coordinate.latitude()); - _plannedHomePositionLongitudeFact.setRawValue(coordinate.longitude()); + if (_plannedHomePositionCoordinate != coordinate) { + _plannedHomePositionCoordinate = coordinate; + emit coordinateChanged(coordinate); + emit exitCoordinateChanged(coordinate); _plannedHomePositionAltitudeFact.setRawValue(coordinate.altitude()); } } -void MissionSettingsComplexItem::_setDirtyAndUpdateLastSequenceNumber(void) +void MissionSettingsItem::_setDirtyAndUpdateLastSequenceNumber(void) { emit lastSequenceNumberChanged(lastSequenceNumber()); setDirty(true); } -void MissionSettingsComplexItem::_setDirtyAndUpdateCoordinate(void) -{ - emit coordinateChanged(coordinate()); - emit exitCoordinateChanged(coordinate()); - setDirty(true); -} - -QGeoCoordinate MissionSettingsComplexItem::coordinate(void) const -{ - return QGeoCoordinate(_plannedHomePositionLatitudeFact.rawValue().toDouble(), _plannedHomePositionLongitudeFact.rawValue().toDouble(), _plannedHomePositionAltitudeFact.rawValue().toDouble()); -} - -void MissionSettingsComplexItem::_cameraSectionDirtyChanged(bool dirty) +void MissionSettingsItem::_cameraSectionDirtyChanged(bool dirty) { if (dirty) { setDirty(true); } } -double MissionSettingsComplexItem::specifiedFlightSpeed(void) +double MissionSettingsItem::specifiedFlightSpeed(void) { return _specifyMissionFlightSpeed ? _missionFlightSpeedFact.rawValue().toDouble() : std::numeric_limits::quiet_NaN(); } -double MissionSettingsComplexItem::specifiedGimbalYaw(void) +double MissionSettingsItem::specifiedGimbalYaw(void) { return _cameraSection.specifyGimbal() ? _cameraSection.gimbalYaw()->rawValue().toDouble() : std::numeric_limits::quiet_NaN(); } + +void MissionSettingsItem::_updateAltitudeInCoordinate(QVariant value) +{ + double newAltitude = value.toDouble(); + + if (!qFuzzyCompare(_plannedHomePositionCoordinate.altitude(), newAltitude)) { + + _plannedHomePositionCoordinate.setAltitude(newAltitude); + emit coordinateChanged(_plannedHomePositionCoordinate); + emit exitCoordinateChanged(_plannedHomePositionCoordinate); + } +} diff --git a/src/MissionManager/MissionSettingsComplexItem.h b/src/MissionManager/MissionSettingsItem.h similarity index 85% rename from src/MissionManager/MissionSettingsComplexItem.h rename to src/MissionManager/MissionSettingsItem.h index 9684610a82c9865856e5cc0091a2197849a91fc2..976db7af33981df1f788f99acc4d57ab241fa47a 100644 --- a/src/MissionManager/MissionSettingsComplexItem.h +++ b/src/MissionManager/MissionSettingsItem.h @@ -18,12 +18,12 @@ Q_DECLARE_LOGGING_CATEGORY(MissionSettingsComplexItemLog) -class MissionSettingsComplexItem : public ComplexMissionItem +class MissionSettingsItem : public ComplexMissionItem { Q_OBJECT public: - MissionSettingsComplexItem(Vehicle* vehicle, QObject* parent = NULL); + MissionSettingsItem(Vehicle* vehicle, QObject* parent = NULL); enum MissionEndAction { MissionEndNoAction, @@ -36,14 +36,10 @@ public: 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* plannedHomePositionLatitude READ plannedHomePositionLatitude CONSTANT) - Q_PROPERTY(Fact* plannedHomePositionLongitude READ plannedHomePositionLongitude CONSTANT) Q_PROPERTY(Fact* plannedHomePositionAltitude READ plannedHomePositionAltitude CONSTANT) Q_PROPERTY(QObject* cameraSection READ cameraSection CONSTANT) bool specifyMissionFlightSpeed (void) const { return _specifyMissionFlightSpeed; } - Fact* plannedHomePositionLatitude (void) { return &_plannedHomePositionLatitudeFact; } - Fact* plannedHomePositionLongitude(void) { return &_plannedHomePositionLongitudeFact; } Fact* plannedHomePositionAltitude (void) { return &_plannedHomePositionAltitudeFact; } Fact* missionFlightSpeed (void) { return &_missionFlightSpeedFact; } Fact* missionEndAction (void) { return &_missionEndActionFact; } @@ -79,8 +75,8 @@ public: QString commandDescription (void) const final { return "Mission Settings"; } QString commandName (void) const final { return "Mission Settings"; } QString abbreviation (void) const final { return "H"; } - QGeoCoordinate coordinate (void) const final; - QGeoCoordinate exitCoordinate (void) const final { return coordinate(); } + QGeoCoordinate coordinate (void) const final { return _plannedHomePositionCoordinate; } + QGeoCoordinate exitCoordinate (void) const final { return _plannedHomePositionCoordinate; } int sequenceNumber (void) const final { return _sequenceNumber; } double specifiedFlightSpeed (void) final; double specifiedGimbalYaw (void) final; @@ -102,14 +98,13 @@ signals: private slots: void _setDirtyAndUpdateLastSequenceNumber (void); - void _setDirtyAndUpdateCoordinate (void); void _setDirty (void); void _cameraSectionDirtyChanged (bool dirty); + void _updateAltitudeInCoordinate (QVariant value); private: bool _specifyMissionFlightSpeed; - Fact _plannedHomePositionLatitudeFact; - Fact _plannedHomePositionLongitudeFact; + QGeoCoordinate _plannedHomePositionCoordinate; // Does not include altitde Fact _plannedHomePositionAltitudeFact; Fact _missionFlightSpeedFact; Fact _missionEndActionFact; @@ -120,8 +115,6 @@ private: static QMap _metaDataMap; - static const char* _plannedHomePositionLatitudeName; - static const char* _plannedHomePositionLongitudeName; static const char* _plannedHomePositionAltitudeName; static const char* _missionFlightSpeedName; static const char* _missionEndActionName; diff --git a/src/MissionManager/SimpleMissionItem.cc b/src/MissionManager/SimpleMissionItem.cc index e943d835ca52d751c24f8805397a41c1a59b2c1c..f59759e1f11f0b0c357fd298e27610aab1b09d22 100644 --- a/src/MissionManager/SimpleMissionItem.cc +++ b/src/MissionManager/SimpleMissionItem.cc @@ -144,7 +144,6 @@ const SimpleMissionItem& SimpleMissionItem::operator=(const SimpleMissionItem& o setRawEdit(other._rawEdit); setDirty(other._dirty); setHomePositionSpecialCase(other._homePositionSpecialCase); - setShowHomePosition(other._showHomePosition); _syncFrameToAltitudeRelativeToHome(); diff --git a/src/MissionManager/SimpleMissionItemTest.cc b/src/MissionManager/SimpleMissionItemTest.cc index 3339cedbcfcf2942abb50ad7d2d4c6e163a9c75b..cb93db84eafc7055161e7d591d84509eafa6e2bb 100644 --- a/src/MissionManager/SimpleMissionItemTest.cc +++ b/src/MissionManager/SimpleMissionItemTest.cc @@ -156,7 +156,6 @@ void SimpleMissionItemTest::_testSignals(void) headingDegreesChangedIndex, rawEditChangedIndex, uiModelChangedIndex, - showHomePositionChangedIndex, maxSignalIndex }; @@ -170,7 +169,6 @@ void SimpleMissionItemTest::_testSignals(void) headingDegreesChangedMask = 1 << headingDegreesChangedIndex, rawEditChangedMask = 1 << rawEditChangedIndex, uiModelChangedMask = 1 << uiModelChangedIndex, - showHomePositionChangedMask = 1 << showHomePositionChangedIndex, }; static const size_t cSimpleMissionItemSignals = maxSignalIndex; @@ -185,7 +183,6 @@ void SimpleMissionItemTest::_testSignals(void) rgSimpleMissionItemSignals[headingDegreesChangedIndex] = SIGNAL(headingDegreesChanged(double)); rgSimpleMissionItemSignals[rawEditChangedIndex] = SIGNAL(rawEditChanged(bool)); rgSimpleMissionItemSignals[uiModelChangedIndex] = SIGNAL(uiModelChanged()); - rgSimpleMissionItemSignals[showHomePositionChangedIndex] = SIGNAL(showHomePositionChanged(bool)); MissionItem missionItem(1, // sequence number MAV_CMD_NAV_WAYPOINT, diff --git a/src/MissionManager/VisualMissionItem.cc b/src/MissionManager/VisualMissionItem.cc index 1cfc391355f516f46e4ca81ca9b6f5f1d2f0b246..12f30c08751d2963d9841782881dc2c62fde7cea 100644 --- a/src/MissionManager/VisualMissionItem.cc +++ b/src/MissionManager/VisualMissionItem.cc @@ -26,7 +26,6 @@ VisualMissionItem::VisualMissionItem(Vehicle* vehicle, QObject* parent) , _isCurrentItem(false) , _dirty(false) , _homePositionSpecialCase(false) - , _showHomePosition(false) , _altDifference(0.0) , _altPercent(0.0) , _azimuth(0.0) @@ -43,7 +42,6 @@ VisualMissionItem::VisualMissionItem(const VisualMissionItem& other, QObject* pa , _isCurrentItem(false) , _dirty(false) , _homePositionSpecialCase(false) - , _showHomePosition(false) , _altDifference(0.0) , _altPercent(0.0) , _azimuth(0.0) @@ -59,7 +57,6 @@ const VisualMissionItem& VisualMissionItem::operator=(const VisualMissionItem& o setIsCurrentItem(other._isCurrentItem); setDirty(other._dirty); _homePositionSpecialCase = other._homePositionSpecialCase; - setShowHomePosition(other.showHomePosition()); setAltDifference(other._altDifference); setAltPercent(other._altPercent); setAzimuth(other._azimuth); @@ -112,14 +109,6 @@ void VisualMissionItem::setAzimuth(double azimuth) } } -void VisualMissionItem::setShowHomePosition(bool showHomePosition) -{ - if (showHomePosition != _showHomePosition) { - _showHomePosition = showHomePosition; - emit showHomePositionChanged(_showHomePosition); - } -} - void VisualMissionItem::setMissionFlightStatus(MissionController::MissionFlightStatus_t& missionFlightStatus) { _missionFlightStatus = missionFlightStatus; diff --git a/src/MissionManager/VisualMissionItem.h b/src/MissionManager/VisualMissionItem.h index bb459d912d377020cd478e41a1aef117dc348261..eac6ecc9a76c63b0b236c22a887acee1cf9fba94 100644 --- a/src/MissionManager/VisualMissionItem.h +++ b/src/MissionManager/VisualMissionItem.h @@ -44,7 +44,6 @@ public: const VisualMissionItem& operator=(const VisualMissionItem& other); Q_PROPERTY(bool homePosition READ homePosition CONSTANT) ///< true: This item is being used as a home position indicator - Q_PROPERTY(bool showHomePosition READ showHomePosition WRITE setShowHomePosition NOTIFY showHomePositionChanged) Q_PROPERTY(QGeoCoordinate coordinate READ coordinate WRITE setCoordinate NOTIFY coordinateChanged) ///< This is the entry point for a waypoint line into the item. For a simple item it is also the location of the item Q_PROPERTY(bool coordinateHasRelativeAltitude READ coordinateHasRelativeAltitude NOTIFY coordinateHasRelativeAltitudeChanged) ///< true: coordinate.latitude is relative to home altitude Q_PROPERTY(QGeoCoordinate exitCoordinate READ exitCoordinate NOTIFY exitCoordinateChanged) ///< This is the exit point for a waypoint line coming out of the item. @@ -80,9 +79,7 @@ public: // Property accesors bool homePosition (void) const { return _homePositionSpecialCase; } - bool showHomePosition (void) const { return _showHomePosition; } void setHomePositionSpecialCase (bool homePositionSpecialCase) { _homePositionSpecialCase = homePositionSpecialCase; } - void setShowHomePosition (bool showHomePosition); double altDifference (void) const { return _altDifference; } double altPercent (void) const { return _altPercent; } @@ -151,7 +148,6 @@ public: static const char* jsonTypeComplexItemValue; ///< Item type is Complex Item signals: - void showHomePositionChanged (bool showHomePosition); void altDifferenceChanged (double altDifference); void altPercentChanged (double altPercent); void azimuthChanged (double azimuth); @@ -183,7 +179,6 @@ protected: bool _isCurrentItem; bool _dirty; bool _homePositionSpecialCase; ///< true: This item is being used as a ui home position indicator - bool _showHomePosition; double _altDifference; ///< Difference in altitude from previous waypoint double _altPercent; ///< Percent of total altitude change in mission double _azimuth; ///< Azimuth to previous waypoint diff --git a/src/MissionEditor/CameraSection.qml b/src/PlanView/CameraSection.qml similarity index 100% rename from src/MissionEditor/CameraSection.qml rename to src/PlanView/CameraSection.qml diff --git a/src/MissionEditor/FWLandingPatternEditor.qml b/src/PlanView/FWLandingPatternEditor.qml similarity index 100% rename from src/MissionEditor/FWLandingPatternEditor.qml rename to src/PlanView/FWLandingPatternEditor.qml diff --git a/src/MissionEditor/FWLandingPatternMapVisual.qml b/src/PlanView/FWLandingPatternMapVisual.qml similarity index 100% rename from src/MissionEditor/FWLandingPatternMapVisual.qml rename to src/PlanView/FWLandingPatternMapVisual.qml diff --git a/src/MissionEditor/GeoFenceEditor.qml b/src/PlanView/GeoFenceEditor.qml similarity index 100% rename from src/MissionEditor/GeoFenceEditor.qml rename to src/PlanView/GeoFenceEditor.qml diff --git a/src/MissionEditor/GeoFenceMapVisuals.qml b/src/PlanView/GeoFenceMapVisuals.qml similarity index 100% rename from src/MissionEditor/GeoFenceMapVisuals.qml rename to src/PlanView/GeoFenceMapVisuals.qml diff --git a/src/MissionEditor/MissionItemEditor.qml b/src/PlanView/MissionItemEditor.qml similarity index 100% rename from src/MissionEditor/MissionItemEditor.qml rename to src/PlanView/MissionItemEditor.qml diff --git a/src/MissionEditor/MissionItemMapVisual.qml b/src/PlanView/MissionItemMapVisual.qml similarity index 100% rename from src/MissionEditor/MissionItemMapVisual.qml rename to src/PlanView/MissionItemMapVisual.qml diff --git a/src/MissionEditor/MissionItemStatus.qml b/src/PlanView/MissionItemStatus.qml similarity index 100% rename from src/MissionEditor/MissionItemStatus.qml rename to src/PlanView/MissionItemStatus.qml diff --git a/src/MissionEditor/MissionSettingsEditor.qml b/src/PlanView/MissionSettingsEditor.qml similarity index 93% rename from src/MissionEditor/MissionSettingsEditor.qml rename to src/PlanView/MissionSettingsEditor.qml index fdc26e8fa3af602487a990664d64f62ad52761ff..573ff44639a4376cbf00c1be5a8dde9523463d19 100644 --- a/src/MissionEditor/MissionSettingsEditor.qml +++ b/src/PlanView/MissionSettingsEditor.qml @@ -34,6 +34,7 @@ Rectangle { 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 @@ -58,13 +59,14 @@ Rectangle { id: plannedHomePositionSection text: qsTr("Planned Home Position") showSpacer: false + visible: !_vehicleHasHomePosition } Column { anchors.left: parent.left anchors.right: parent.right spacing: _margin - visible: plannedHomePositionSection.checked + visible: plannedHomePositionSection.checked && !_vehicleHasHomePosition GridLayout { anchors.left: parent.left @@ -73,22 +75,6 @@ Rectangle { rowSpacing: columnSpacing columns: 2 - QGCLabel { - text: qsTr("Latitude") - } - FactTextField { - fact: missionItem.plannedHomePositionLatitude - Layout.fillWidth: true - } - - QGCLabel { - text: qsTr("Longitude") - } - FactTextField { - fact: missionItem.plannedHomePositionLongitude - Layout.fillWidth: true - } - QGCLabel { text: qsTr("Altitude") } @@ -178,7 +164,7 @@ Rectangle { SectionHeader { id: missionDefaultsSectionHeader text: qsTr("Mission Defaults") - checked: false + checked: true } Column { diff --git a/src/MissionEditor/MissionSettingsMapVisual.qml b/src/PlanView/MissionSettingsMapVisual.qml similarity index 98% rename from src/MissionEditor/MissionSettingsMapVisual.qml rename to src/PlanView/MissionSettingsMapVisual.qml index f1a3386dd8fdb6e853385eab03a7404f119a49e1..d3a150bd87536d04c26e8bcb5f4fda71b70eb14f 100644 --- a/src/MissionEditor/MissionSettingsMapVisual.qml +++ b/src/PlanView/MissionSettingsMapVisual.qml @@ -103,7 +103,7 @@ Item { MissionItemIndicator { coordinate: _missionItem.coordinate - visible: _missionItem.showHomePosition + visible: coordinate.isValid z: QGroundControl.zOrderMapItems missionItem: _missionItem diff --git a/src/MissionEditor/PlanToolBar.qml b/src/PlanView/PlanToolBar.qml similarity index 100% rename from src/MissionEditor/PlanToolBar.qml rename to src/PlanView/PlanToolBar.qml diff --git a/src/MissionEditor/MissionEditor.qml b/src/PlanView/PlanView.qml similarity index 97% rename from src/MissionEditor/MissionEditor.qml rename to src/PlanView/PlanView.qml index 069895f2b11d5fccfd8936654652c44939a7ee45..4de22013ede66b8bab71229c1c9b2c049aa2bce1 100644 --- a/src/MissionEditor/MissionEditor.qml +++ b/src/PlanView/PlanView.qml @@ -45,8 +45,6 @@ QGCView { property var _visualItems: missionController.visualItems property var _currentMissionItem property int _currentMissionIndex: 0 - property bool _firstVehiclePosition: true - property var activeVehiclePosition: _activeVehicle ? _activeVehicle.coordinate : QtPositioning.coordinate() property bool _lightWidgetBorders: editorMap.isSatelliteMap property bool _addWaypointOnClick: false property bool _singleComplexItem: missionController.complexMissionItemNames.length === 1 @@ -64,25 +62,6 @@ QGCView { toolbar.currentMissionItem = Qt.binding(function () { return _currentMissionItem }) } - onActiveVehiclePositionChanged: updateMapToVehiclePosition() - - Connections { - target: QGroundControl.multiVehicleManager - - onActiveVehicleChanged: { - // When the active vehicle changes we need to allow the first vehicle position to move the map again - _firstVehiclePosition = true - updateMapToVehiclePosition() - } - } - - function updateMapToVehiclePosition() { - if (_activeVehicle && _activeVehicle.coordinateValid && _activeVehicle.coordinate.isValid && _firstVehiclePosition) { - _firstVehiclePosition = false - editorMap.center = _activeVehicle.coordinate - } - } - function addComplexItem(complexItemName) { var coordinate = editorMap.center coordinate.latitude = coordinate.latitude.toFixed(_decimalPlaces) diff --git a/src/MissionEditor/QGCMapPolygonControls.qml b/src/PlanView/QGCMapPolygonControls.qml similarity index 100% rename from src/MissionEditor/QGCMapPolygonControls.qml rename to src/PlanView/QGCMapPolygonControls.qml diff --git a/src/MissionEditor/RallyPointEditorHeader.qml b/src/PlanView/RallyPointEditorHeader.qml similarity index 100% rename from src/MissionEditor/RallyPointEditorHeader.qml rename to src/PlanView/RallyPointEditorHeader.qml diff --git a/src/MissionEditor/RallyPointItemEditor.qml b/src/PlanView/RallyPointItemEditor.qml similarity index 100% rename from src/MissionEditor/RallyPointItemEditor.qml rename to src/PlanView/RallyPointItemEditor.qml diff --git a/src/MissionEditor/SectionHeader.qml b/src/PlanView/SectionHeader.qml similarity index 100% rename from src/MissionEditor/SectionHeader.qml rename to src/PlanView/SectionHeader.qml diff --git a/src/MissionEditor/SimpleItemEditor.qml b/src/PlanView/SimpleItemEditor.qml similarity index 100% rename from src/MissionEditor/SimpleItemEditor.qml rename to src/PlanView/SimpleItemEditor.qml diff --git a/src/MissionEditor/SimpleItemMapVisual.qml b/src/PlanView/SimpleItemMapVisual.qml similarity index 100% rename from src/MissionEditor/SimpleItemMapVisual.qml rename to src/PlanView/SimpleItemMapVisual.qml diff --git a/src/MissionEditor/SurveyItemEditor.qml b/src/PlanView/SurveyItemEditor.qml similarity index 100% rename from src/MissionEditor/SurveyItemEditor.qml rename to src/PlanView/SurveyItemEditor.qml diff --git a/src/MissionEditor/SurveyMapVisual.qml b/src/PlanView/SurveyMapVisual.qml similarity index 100% rename from src/MissionEditor/SurveyMapVisual.qml rename to src/PlanView/SurveyMapVisual.qml diff --git a/src/QGCApplication.cc b/src/QGCApplication.cc index a387a1a6be75e1bd6845fc14835f4d35406efa1f..6e084001f4ec218b289b6007c08c11cbe6442381 100644 --- a/src/QGCApplication.cc +++ b/src/QGCApplication.cc @@ -116,9 +116,6 @@ const char* QGCApplication::telemetryFileExtension = "tlog"; const char* QGCApplication::_deleteAllSettingsKey = "DeleteAllSettingsNextBoot"; const char* QGCApplication::_settingsVersionKey = "SettingsVersion"; -const char* QGCApplication::_lastKnownHomePositionLatKey = "LastKnownHomePositionLat"; -const char* QGCApplication::_lastKnownHomePositionLonKey = "LastKnownHomePositionLon"; -const char* QGCApplication::_lastKnownHomePositionAltKey = "LastKnownHomePositionAlt"; const char* QGCApplication::_darkStyleFile = ":/res/styles/style-dark.css"; const char* QGCApplication::_lightStyleFile = ":/res/styles/style-light.css"; @@ -173,7 +170,6 @@ QGCApplication::QGCApplication(int &argc, char* argv[], bool unitTesting) #endif , _toolbox(NULL) , _bluetoothAvailable(false) - , _lastKnownHomePosition(37.803784, -122.462276, 0.0) { Q_ASSERT(_app == NULL); _app = this; @@ -308,10 +304,6 @@ QGCApplication::QGCApplication(int &argc, char* argv[], bool unitTesting) // Set up our logging filters QGCLoggingCategoryRegister::instance()->setFilterRulesFromSettings(loggingOptions); - _lastKnownHomePosition.setLatitude(settings.value(_lastKnownHomePositionLatKey, 37.803784).toDouble()); - _lastKnownHomePosition.setLongitude(settings.value(_lastKnownHomePositionLonKey, -122.462276).toDouble()); - _lastKnownHomePosition.setAltitude(settings.value(_lastKnownHomePositionAltKey, 0.0).toDouble()); - // Initialize Bluetooth #ifdef QGC_ENABLE_BLUETOOTH QBluetoothLocalDevice localDevice; @@ -673,14 +665,3 @@ void QGCApplication::qmlAttemptWindowClose(void) { QMetaObject::invokeMethod(_rootQmlObject(), "attemptWindowClose"); } - - -void QGCApplication::setLastKnownHomePosition(QGeoCoordinate& lastKnownHomePosition) -{ - QSettings settings; - - settings.setValue(_lastKnownHomePositionLatKey, lastKnownHomePosition.latitude()); - settings.setValue(_lastKnownHomePositionLonKey, lastKnownHomePosition.longitude()); - settings.setValue(_lastKnownHomePositionAltKey, lastKnownHomePosition.altitude()); - _lastKnownHomePosition = lastKnownHomePosition; -} diff --git a/src/QGCApplication.h b/src/QGCApplication.h index bdc71476ce3c9e58efb3a8b87769a30a68cd402e..8a30838a12c4f84490775c6daad394fb35ee075f 100644 --- a/src/QGCApplication.h +++ b/src/QGCApplication.h @@ -98,9 +98,6 @@ public: /// Do we have Bluetooth Support? bool isBluetoothAvailable() { return _bluetoothAvailable; } - QGeoCoordinate lastKnownHomePosition(void) { return _lastKnownHomePosition; } - void setLastKnownHomePosition(QGeoCoordinate& lastKnownHomePosition); - public slots: /// You can connect to this slot to show an information message box from a different thread. void informationMessageBoxOnMainThread(const QString& title, const QString& msg); @@ -183,13 +180,8 @@ private: bool _bluetoothAvailable; - QGeoCoordinate _lastKnownHomePosition; ///< Map position when all other sources fail - static const char* _settingsVersionKey; ///< Settings key which hold settings version static const char* _deleteAllSettingsKey; ///< If this settings key is set on boot, all settings will be deleted - static const char* _lastKnownHomePositionLatKey; - static const char* _lastKnownHomePositionLonKey; - static const char* _lastKnownHomePositionAltKey; /// Unit Test have access to creating and destroying singletons friend class UnitTest; diff --git a/src/QmlControls/QGroundControlQmlGlobal.cc b/src/QmlControls/QGroundControlQmlGlobal.cc index 7152dde642faf991b02e47fb91f3a93c35bb5591..ad15a3b7878ab21d5e89f84f784e6bf71f705077 100644 --- a/src/QmlControls/QGroundControlQmlGlobal.cc +++ b/src/QmlControls/QGroundControlQmlGlobal.cc @@ -19,6 +19,11 @@ static const char* kQmlGlobalKeyName = "QGCQml"; +const char* QGroundControlQmlGlobal::_flightMapPositionSettingsGroup = "FlightMapPosition"; +const char* QGroundControlQmlGlobal::_flightMapPositionLatitudeSettingsKey = "Latitude"; +const char* QGroundControlQmlGlobal::_flightMapPositionLongitudeSettingsKey = "Longitude"; +const char* QGroundControlQmlGlobal::_flightMapZoomSettingsKey = "FlightMapZoom"; + QGroundControlQmlGlobal::QGroundControlQmlGlobal(QGCApplication* app) : QGCTool(app) , _linkManager(NULL) @@ -180,3 +185,44 @@ void QGroundControlQmlGlobal::setSkipSetupPage(bool skip) emit skipSetupPageChanged(); } } + +QGeoCoordinate QGroundControlQmlGlobal::flightMapPosition(void) +{ + QSettings settings; + QGeoCoordinate coord; + + settings.beginGroup(_flightMapPositionSettingsGroup); + coord.setLatitude(settings.value(_flightMapPositionLatitudeSettingsKey, 37.803784).toDouble()); + coord.setLongitude(settings.value(_flightMapPositionLongitudeSettingsKey, -122.462276).toDouble()); + + return coord; +} + +double QGroundControlQmlGlobal::flightMapZoom(void) +{ + QSettings settings; + + return settings.value(_flightMapZoomSettingsKey, 18).toDouble(); +} + +void QGroundControlQmlGlobal::setFlightMapPosition(QGeoCoordinate& coordinate) +{ + if (coordinate != flightMapPosition()) { + QSettings settings; + + settings.beginGroup(_flightMapPositionSettingsGroup); + settings.setValue(_flightMapPositionLatitudeSettingsKey, coordinate.latitude()); + settings.setValue(_flightMapPositionLongitudeSettingsKey, coordinate.longitude()); + emit flightMapPositionChanged(coordinate); + } +} + +void QGroundControlQmlGlobal::setFlightMapZoom(double zoom) +{ + if (zoom != flightMapZoom()) { + QSettings settings; + + settings.setValue(_flightMapZoomSettingsKey, zoom); + emit flightMapZoomChanged(zoom); + } +} diff --git a/src/QmlControls/QGroundControlQmlGlobal.h b/src/QmlControls/QGroundControlQmlGlobal.h index 0914aaa69ad60da0e5bcf2824a3c5815bac16017..744a9cfd2395f5f5c6fd471bf20383925aa5c845 100644 --- a/src/QmlControls/QGroundControlQmlGlobal.h +++ b/src/QmlControls/QGroundControlQmlGlobal.h @@ -59,9 +59,8 @@ public: Q_PROPERTY(bool isVersionCheckEnabled READ isVersionCheckEnabled WRITE setIsVersionCheckEnabled NOTIFY isVersionCheckEnabledChanged) Q_PROPERTY(int mavlinkSystemID READ mavlinkSystemID WRITE setMavlinkSystemID NOTIFY mavlinkSystemIDChanged) - Q_PROPERTY(QGeoCoordinate lastKnownHomePosition READ lastKnownHomePosition CONSTANT) - Q_PROPERTY(QGeoCoordinate flightMapPosition MEMBER _flightMapPosition NOTIFY flightMapPositionChanged) - Q_PROPERTY(double flightMapZoom MEMBER _flightMapZoom NOTIFY flightMapZoomChanged) + Q_PROPERTY(QGeoCoordinate flightMapPosition READ flightMapPosition WRITE setFlightMapPosition NOTIFY flightMapPositionChanged) + Q_PROPERTY(double flightMapZoom READ flightMapZoom WRITE setFlightMapZoom NOTIFY flightMapZoomChanged) Q_PROPERTY(QString parameterFileExtension READ parameterFileExtension CONSTANT) Q_PROPERTY(QString missionFileExtension READ missionFileExtension CONSTANT) @@ -133,6 +132,8 @@ public: MAVLinkLogManager* mavlinkLogManager () { return _mavlinkLogManager; } QGCCorePlugin* corePlugin () { return _corePlugin; } SettingsManager* settingsManager () { return _settingsManager; } + static QGeoCoordinate flightMapPosition (); + static double flightMapZoom (); qreal zOrderTopMost () { return 1000; } qreal zOrderWidgets () { return 100; } @@ -141,14 +142,14 @@ public: bool isVersionCheckEnabled () { return _toolbox->mavlinkProtocol()->versionCheckEnabled(); } int mavlinkSystemID () { return _toolbox->mavlinkProtocol()->getSystemId(); } - QGeoCoordinate lastKnownHomePosition() { return qgcApp()->lastKnownHomePosition(); } - int supportedFirmwareCount (); bool skipSetupPage () { return _skipSetupPage; } void setSkipSetupPage (bool skip); void setIsVersionCheckEnabled (bool enable); void setMavlinkSystemID (int id); + void setFlightMapPosition (QGeoCoordinate& coordinate); + void setFlightMapZoom (double zoom); QString parameterFileExtension(void) const { return QGCApplication::parameterFileExtension; } QString missionFileExtension(void) const { return QGCApplication::missionFileExtension; } @@ -180,9 +181,12 @@ private: FirmwarePluginManager* _firmwarePluginManager; SettingsManager* _settingsManager; - QGeoCoordinate _flightMapPosition; - double _flightMapZoom; bool _skipSetupPage; + + static const char* _flightMapPositionSettingsGroup; + static const char* _flightMapPositionLatitudeSettingsKey; + static const char* _flightMapPositionLongitudeSettingsKey; + static const char* _flightMapZoomSettingsKey; }; #endif diff --git a/src/QtLocationPlugin/QMLControl/OfflineMap.qml b/src/QtLocationPlugin/QMLControl/OfflineMap.qml index 5bd45f92ffcf5cdf0b2afb231e18984a22e823f3..266aa2c75835cd91d009de38e2930b1cc0fd92ae 100644 --- a/src/QtLocationPlugin/QMLControl/OfflineMap.qml +++ b/src/QtLocationPlugin/QMLControl/OfflineMap.qml @@ -315,7 +315,7 @@ QGCView { Map { id: _map anchors.fill: parent - center: QGroundControl.lastKnownHomePosition + center: QGroundControl.flightMapPosition visible: false gesture.flickDeceleration: 3000 diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index af8f17a336a2ece2005ed2d427fe1cb00ac8f4a4..612fa5b1b7088e29a4c7819963ec7061eb085bf1 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -925,7 +925,6 @@ void Vehicle::_handleHomePosition(mavlink_message_t& message) if (emitHomePositionChanged) { qCDebug(VehicleLog) << "New home position" << newHomePosition; - qgcApp()->setLastKnownHomePosition(_homePosition); emit homePositionChanged(_homePosition); } if (emitHomePositionAvailableChanged) { diff --git a/src/comm/QGCFlightGearLink.cc b/src/comm/QGCFlightGearLink.cc index 3af960e5f2f0d8638b3963a11b61a1c102ce46d1..6d8600def0b323f37dcb2f0a05f0b86b3f3a135b 100644 --- a/src/comm/QGCFlightGearLink.cc +++ b/src/comm/QGCFlightGearLink.cc @@ -35,6 +35,7 @@ #include "QGCApplication.h" #include "Vehicle.h" #include "UAS.h" +#include "QGroundControlQmlGlobal.h" // FlightGear _fgProcess start and connection is quite fragile. Uncomment the define below to get higher level of debug output // for tracking down problems. @@ -938,7 +939,7 @@ bool QGCFlightGearLink::connectSimulation() } // We start out at our home position - QGeoCoordinate homePosition = qgcApp()->lastKnownHomePosition(); + QGeoCoordinate homePosition = QGroundControlQmlGlobal::flightMapPosition(); _fgArgList << QString("--lat=%1").arg(homePosition.latitude()); _fgArgList << QString("--lon=%1").arg(homePosition.longitude()); // The altitude is not set because an altitude not equal to the ground altitude leads to a non-zero default throttle in flightgear diff --git a/src/ui/MainWindowInner.qml b/src/ui/MainWindowInner.qml index 4aceab65d03b21fd02b1ccf41c83edf6fed59012..53f5827329f16630eef2b24c596c166e3ceda772 100644 --- a/src/ui/MainWindowInner.qml +++ b/src/ui/MainWindowInner.qml @@ -19,7 +19,6 @@ import QGroundControl.Controls 1.0 import QGroundControl.FlightDisplay 1.0 import QGroundControl.ScreenTools 1.0 import QGroundControl.MultiVehicleManager 1.0 -import QGroundControl.QGCPositionManager 1.0 /// Inner common QML for mainWindow Item { @@ -29,7 +28,6 @@ Item { QGCPalette { id: qgcPal; colorGroupEnabled: true } - property var gcsPosition: QtPositioning.coordinate() // Starts as invalid coordinate property var currentPopUp: null property real currentCenterX: 0 property var activeVehicle: QGroundControl.multiVehicleManager.activeVehicle @@ -39,7 +37,7 @@ Item { readonly property string _settingsViewSource: "AppSettings.qml" readonly property string _setupViewSource: "SetupView.qml" - readonly property string _planViewSource: "MissionEditor.qml" + readonly property string _planViewSource: "PlanView.qml" readonly property string _analyzeViewSource: "AnalyzeView.qml" onHeightChanged: { @@ -181,24 +179,6 @@ Item { } } - //-- Detect tablet position - Connections { - target: QGroundControl.qgcPositionManger - onLastPositionUpdated: { - if(valid) { - if(lastPosition.latitude) { - if(Math.abs(lastPosition.latitude) > 0.001) { - if(lastPosition.longitude) { - if(Math.abs(lastPosition.longitude) > 0.001) { - gcsPosition = QtPositioning.coordinate(lastPosition.latitude,lastPosition.longitude) - } - } - } - } - } - } - } - property var messageQueue: [] function showMessage(message) {