diff --git a/Vagrantfile b/Vagrantfile index e15e22d1f6351010a54d350356b5e8ec301323bd..a3df179e62ca9ac7c92c5ce68233df413e7794b9 100644 --- a/Vagrantfile +++ b/Vagrantfile @@ -15,7 +15,7 @@ Vagrant.configure(2) do |config| config.vm.provider "virtualbox" config.vm.provider "vmware_fusion" - config.vm.box = "boxcutter/ubuntu1604" + config.vm.box = "ubuntu/xenial64" config.vm.provider :docker do |docker, override| override.vm.box = "tknerr/baseimage-ubuntu-16.04" end diff --git a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml index 7bd0c188aa572e2491adc854a0714cd2e69977ca..27c08dac87e12760d2dbbecfcb760ec8e3b81e7a 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml +++ b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml @@ -3379,7 +3379,7 @@ by initializing the estimator to the LPE_LAT/LON parameters when global informat Integer bitmask controlling data fusion Set bits in the following positions to enable: 0 : Set to true to fuse GPS data if available, also requires GPS for altitude init 1 : Set to true to fuse optical flow data if available 2 : Set to true to fuse vision position 3 : Set to true to enable landing target 4 : Set to true to fuse land detector 5 : Set to true to publish AGL as local position down component 6 : Set to true to enable flow gyro compensation 7 : Set to true to enable baro fusion default (145 - GPS, baro, land detector) 0 - 4294967295 + 255 modules/local_position_estimator fuse GPS, requires GPS for alt. init @@ -5482,7 +5482,7 @@ the setpoint will be capped to MPC_XY_VEL_MAX Maximum number of search attempts Maximum number of times to seach for the landing target if it is lost during the precision landing. - 0.0 + 0 100 modules/navigator diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc index 8bb8ad3210d6a1ae3278053f2e253e5ed3e8c06b..af61115480e28554e384290cebba17c0b257417f 100644 --- a/src/MissionManager/MissionController.cc +++ b/src/MissionManager/MissionController.cc @@ -1216,8 +1216,6 @@ void MissionController::_recalcMissionFlightStatus() } } - qDebug() << "Gimbal calc"; - for (int i=0; i<_visualItems->count(); i++) { VisualMissionItem* item = qobject_cast(_visualItems->get(i)); SimpleMissionItem* simpleItem = qobject_cast(item); @@ -1247,7 +1245,6 @@ void MissionController::_recalcMissionFlightStatus() // Look for gimbal change double gimbalYaw = item->specifiedGimbalYaw(); if (!qIsNaN(gimbalYaw)) { - qDebug() << _editMode << gimbalYaw; _missionFlightStatus.gimbalYaw = gimbalYaw; } double gimbalPitch = item->specifiedGimbalPitch(); @@ -1353,7 +1350,6 @@ void MissionController::_recalcMissionFlightStatus() _addTimeDistance(vtolInHover, hoverTime, cruiseTime, extraTime, distance, item->sequenceNumber()); } - qDebug() << "setMissionFlightStatus" << item->sequenceNumber() << _missionFlightStatus.gimbalYaw << item->commandName(); item->setMissionFlightStatus(_missionFlightStatus); } diff --git a/src/MissionManager/MissionSettingsItem.cc b/src/MissionManager/MissionSettingsItem.cc index 808b4448d2351ada31d25bfa6a5c5ad8f3f987fd..24418695a8de74ff0a58c1b2560a339d3801a5b9 100644 --- a/src/MissionManager/MissionSettingsItem.cc +++ b/src/MissionManager/MissionSettingsItem.cc @@ -297,6 +297,11 @@ void MissionSettingsItem::setMissionEndRTL(bool missionEndRTL) void MissionSettingsItem::_setHomeAltFromTerrain(double terrainAltitude) { if (!_plannedHomePositionFromVehicle) { + // We need to stop this from signalling, Otherwise the dirty but get set on a delay + // which then marks the Plan view as incorrectly dirty + _plannedHomePositionAltitudeFact.setSendValueChangedSignals(false); _plannedHomePositionAltitudeFact.setRawValue(terrainAltitude); + _plannedHomePositionAltitudeFact.clearDeferredValueChangeSignal(); + _plannedHomePositionAltitudeFact.setSendValueChangedSignals(false); } } diff --git a/src/MissionManager/QGCMapPolygonVisuals.qml b/src/MissionManager/QGCMapPolygonVisuals.qml index daf0ad72e23f038b2fa0c5889fcf98ebee1b1a0c..d24ff4c64bf53df66bfe8a63b51bbac662c5dc02 100644 --- a/src/MissionManager/QGCMapPolygonVisuals.qml +++ b/src/MissionManager/QGCMapPolygonVisuals.qml @@ -453,6 +453,7 @@ Item { id: radiusField text: _circleRadius.toFixed(2) onEditingFinished: setRadiusFromDialog() + inputMethodHints: Qt.ImhFormattedNumbersOnly } } diff --git a/src/PlanView/MissionItemStatus.qml b/src/PlanView/MissionItemStatus.qml index 596d886b368d36dfc0f1f1803dab6a16ba9a6d8a..e5a2dd74599ea44fb0ed3024a0381fcbcdbd6b22 100644 --- a/src/PlanView/MissionItemStatus.qml +++ b/src/PlanView/MissionItemStatus.qml @@ -31,7 +31,7 @@ Rectangle { readonly property real _margins: ScreenTools.defaultFontPixelWidth onMaxWidthChanged: { - var calcLength = (statusListView.count + 1)*statusListView.contentItem.children[0].width + var calcLength = (statusListView.count + 1) * (statusListView.count ? statusListView.contentItem.children[0].width : 1) root.width = root.maxWidth > calcLength ? calcLength : root.maxWidth } @@ -63,7 +63,7 @@ Rectangle { currentIndex: _missionController.currentPlanViewIndex onCountChanged: { - var calcLength = (statusListView.count + 1)*statusListView.contentItem.children[0].width + var calcLength = (statusListView.count + 1) * (statusListView.count ? statusListView.contentItem.children[0].width : 1) root.width = root.maxWidth > calcLength ? calcLength : root.maxWidth } diff --git a/src/PlanView/MissionSettingsEditor.qml b/src/PlanView/MissionSettingsEditor.qml index 706fb4939b2e70f939edca4d6d0f731cac97d656..544fa893fa6c4013a19b8f1dcfa4407a19695859 100644 --- a/src/PlanView/MissionSettingsEditor.qml +++ b/src/PlanView/MissionSettingsEditor.qml @@ -15,7 +15,7 @@ import QGroundControl.Controllers 1.0 Rectangle { id: valuesRect width: availableWidth - height: deferedload.status == Loader.Ready ? (visible ? deferedload.item.height : 0) : 0 + height: valuesColumn.height + (_margin * 2) color: qgcPal.windowShadeDark visible: missionItem.isCurrentItem radius: _radius @@ -39,128 +39,166 @@ Rectangle { readonly property string _firmwareLabel: qsTr("Firmware") readonly property string _vehicleLabel: qsTr("Vehicle") + readonly property real _margin: ScreenTools.defaultFontPixelWidth / 2 QGCPalette { id: qgcPal } QGCFileDialogController { id: fileController } - Loader { - id: deferedload - active: valuesRect.visible - asynchronous: true - anchors.margins: _margin - anchors.left: valuesRect.left - anchors.right: valuesRect.right - anchors.top: valuesRect.top + Column { + id: valuesColumn + anchors.margins: _margin + anchors.left: parent.left + anchors.right: parent.right + anchors.top: parent.top + spacing: _margin - sourceComponent: Component { - Item { - id: valuesItem - height: valuesColumn.height + (_margin * 2) + Column { + anchors.left: parent.left + anchors.right: parent.right + spacing: _margin - Column { - id: valuesColumn - anchors.left: parent.left - anchors.right: parent.right - anchors.top: parent.top - spacing: _margin + GridLayout { + anchors.left: parent.left + anchors.right: parent.right + columnSpacing: ScreenTools.defaultFontPixelWidth + rowSpacing: columnSpacing + columns: 2 - Loader { - anchors.left: parent.left - anchors.right: parent.right - sourceComponent: missionSettings - } - } // Column - } // Item - } // Component - } // Loader + QGCLabel { + text: qsTr("Waypoint alt") + } + FactTextField { + fact: QGroundControl.settingsManager.appSettings.defaultMissionItemAltitude + Layout.fillWidth: true + } - Component { - id: missionSettings + QGCCheckBox { + id: flightSpeedCheckBox + text: qsTr("Flight speed") + visible: !_missionVehicle.vtol + checked: missionItem.speedSection.specifyFlightSpeed + onClicked: missionItem.speedSection.specifyFlightSpeed = checked + } + FactTextField { + Layout.fillWidth: true + fact: missionItem.speedSection.flightSpeed + visible: flightSpeedCheckBox.visible + enabled: flightSpeedCheckBox.checked + } + } // GridLayout + } + + CameraSection { + id: cameraSection + checked: missionItem.cameraSection.settingsSpecified + } + + QGCLabel { + anchors.left: parent.left + anchors.right: parent.right + text: qsTr("Above camera commands will take affect immediately upon mission start.") + wrapMode: Text.WordWrap + horizontalAlignment: Text.AlignHCenter + font.pointSize: ScreenTools.smallFontPointSize + visible: cameraSection.checked + } + + SectionHeader { + id: missionEndHeader + text: qsTr("Mission End") + checked: true + } Column { - id: valuesColumn - anchors.left: parent ? parent.left : undefined - anchors.right: parent ? parent.right : undefined - anchors.top: parent ? parent.top : undefined + anchors.left: parent.left + anchors.right: parent.right spacing: _margin + visible: missionEndHeader.checked - Column { - anchors.left: parent.left - anchors.right: parent.right - spacing: _margin + QGCCheckBox { + text: qsTr("Return To Launch") + checked: missionItem.missionEndRTL + onClicked: missionItem.missionEndRTL = checked + } + } - GridLayout { - anchors.left: parent.left - anchors.right: parent.right - columnSpacing: ScreenTools.defaultFontPixelWidth - rowSpacing: columnSpacing - columns: 2 - QGCLabel { - text: qsTr("Waypoint alt") - } - FactTextField { - fact: QGroundControl.settingsManager.appSettings.defaultMissionItemAltitude - Layout.fillWidth: true - } + SectionHeader { + id: vehicleInfoSectionHeader + text: qsTr("Vehicle Info") + visible: _offlineEditing && !_waypointsOnlyMode + checked: false + } - QGCCheckBox { - id: flightSpeedCheckBox - text: qsTr("Flight speed") - visible: !_missionVehicle.vtol - checked: missionItem.speedSection.specifyFlightSpeed - onClicked: missionItem.speedSection.specifyFlightSpeed = checked - } - FactTextField { - Layout.fillWidth: true - fact: missionItem.speedSection.flightSpeed - visible: flightSpeedCheckBox.visible - enabled: flightSpeedCheckBox.checked - } - } // GridLayout - } + GridLayout { + anchors.left: parent.left + anchors.right: parent.right + columnSpacing: ScreenTools.defaultFontPixelWidth + rowSpacing: columnSpacing + columns: 2 + visible: vehicleInfoSectionHeader.visible && vehicleInfoSectionHeader.checked - CameraSection { - id: cameraSection - checked: missionItem.cameraSection.settingsSpecified + QGCLabel { + text: _firmwareLabel + Layout.fillWidth: true + visible: _showOfflineVehicleCombos + } + FactComboBox { + fact: QGroundControl.settingsManager.appSettings.offlineEditingFirmwareType + indexModel: false + Layout.preferredWidth: _fieldWidth + visible: _showOfflineVehicleCombos + enabled: _enableOfflineVehicleCombos } QGCLabel { - anchors.left: parent.left - anchors.right: parent.right - text: qsTr("Above camera commands will take affect immediately upon mission start.") - wrapMode: Text.WordWrap - horizontalAlignment: Text.AlignHCenter - font.pointSize: ScreenTools.smallFontPointSize - visible: cameraSection.checked + text: _vehicleLabel + Layout.fillWidth: true + visible: _showOfflineVehicleCombos } - - SectionHeader { - id: missionEndHeader - text: qsTr("Mission End") - checked: true + FactComboBox { + fact: QGroundControl.settingsManager.appSettings.offlineEditingVehicleType + indexModel: false + Layout.preferredWidth: _fieldWidth + visible: _showOfflineVehicleCombos + enabled: _enableOfflineVehicleCombos } - Column { - anchors.left: parent.left - anchors.right: parent.right - spacing: _margin - visible: missionEndHeader.checked + QGCLabel { + text: qsTr("Cruise speed") + visible: _showCruiseSpeed + Layout.fillWidth: true + } + FactTextField { + fact: QGroundControl.settingsManager.appSettings.offlineEditingCruiseSpeed + visible: _showCruiseSpeed + Layout.preferredWidth: _fieldWidth + } - QGCCheckBox { - text: qsTr("Return To Launch") - checked: missionItem.missionEndRTL - onClicked: missionItem.missionEndRTL = checked - } + QGCLabel { + text: qsTr("Hover speed") + visible: _showHoverSpeed + Layout.fillWidth: true } + FactTextField { + fact: QGroundControl.settingsManager.appSettings.offlineEditingHoverSpeed + visible: _showHoverSpeed + Layout.preferredWidth: _fieldWidth + } + } // GridLayout + SectionHeader { + id: plannedHomePositionSection + text: qsTr("Planned Home Position") + visible: !_vehicleHasHomePosition + checked: false + } - SectionHeader { - id: vehicleInfoSectionHeader - text: qsTr("Vehicle Info") - visible: _offlineEditing && !_waypointsOnlyMode - checked: false - } + Column { + anchors.left: parent.left + anchors.right: parent.right + spacing: _margin + visible: plannedHomePositionSection.checked && !_vehicleHasHomePosition GridLayout { anchors.left: parent.left @@ -168,100 +206,29 @@ Rectangle { columnSpacing: ScreenTools.defaultFontPixelWidth rowSpacing: columnSpacing columns: 2 - visible: vehicleInfoSectionHeader.visible && vehicleInfoSectionHeader.checked - - QGCLabel { - text: _firmwareLabel - Layout.fillWidth: true - visible: _showOfflineVehicleCombos - } - FactComboBox { - fact: QGroundControl.settingsManager.appSettings.offlineEditingFirmwareType - indexModel: false - Layout.preferredWidth: _fieldWidth - visible: _showOfflineVehicleCombos - enabled: _enableOfflineVehicleCombos - } QGCLabel { - text: _vehicleLabel - Layout.fillWidth: true - visible: _showOfflineVehicleCombos - } - FactComboBox { - fact: QGroundControl.settingsManager.appSettings.offlineEditingVehicleType - indexModel: false - Layout.preferredWidth: _fieldWidth - visible: _showOfflineVehicleCombos - enabled: _enableOfflineVehicleCombos - } - - QGCLabel { - text: qsTr("Cruise speed") - visible: _showCruiseSpeed - Layout.fillWidth: true + text: qsTr("Altitude") } FactTextField { - fact: QGroundControl.settingsManager.appSettings.offlineEditingCruiseSpeed - visible: _showCruiseSpeed - Layout.preferredWidth: _fieldWidth - } - - QGCLabel { - text: qsTr("Hover speed") - visible: _showHoverSpeed + fact: missionItem.plannedHomePositionAltitude Layout.fillWidth: true } - FactTextField { - fact: QGroundControl.settingsManager.appSettings.offlineEditingHoverSpeed - visible: _showHoverSpeed - Layout.preferredWidth: _fieldWidth - } - } // GridLayout - - SectionHeader { - id: plannedHomePositionSection - text: qsTr("Planned Home Position") - visible: !_vehicleHasHomePosition - checked: false } - Column { - anchors.left: parent.left - anchors.right: parent.right - spacing: _margin - visible: plannedHomePositionSection.checked && !_vehicleHasHomePosition - - GridLayout { - anchors.left: parent.left - anchors.right: parent.right - columnSpacing: ScreenTools.defaultFontPixelWidth - rowSpacing: columnSpacing - columns: 2 - - QGCLabel { - text: qsTr("Altitude") - } - FactTextField { - fact: missionItem.plannedHomePositionAltitude - Layout.fillWidth: true - } - } - - QGCLabel { - width: parent.width - wrapMode: Text.WordWrap - font.pointSize: ScreenTools.smallFontPointSize - text: qsTr("Actual position set by vehicle at flight time.") - horizontalAlignment: Text.AlignHCenter - } + QGCLabel { + width: parent.width + wrapMode: Text.WordWrap + font.pointSize: ScreenTools.smallFontPointSize + text: qsTr("Actual position set by vehicle at flight time.") + horizontalAlignment: Text.AlignHCenter + } - QGCButton { - text: qsTr("Set Home To Map Center") - onClicked: missionItem.coordinate = map.center - anchors.horizontalCenter: parent.horizontalCenter - } + QGCButton { + text: qsTr("Set Home To Map Center") + onClicked: missionItem.coordinate = map.center + anchors.horizontalCenter: parent.horizontalCenter } - } // Column - } // Deferred loader + } + } // Column } // Rectangle