Unverified Commit 75a58f73 authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #8963 from DonLakeFlyer/VTOLWork

Plan: Better support for VTOL takeoff and landing pattern
parents 9f396d68 109d6a59
...@@ -4,6 +4,8 @@ Note: This file only contains high level features or important fixes. ...@@ -4,6 +4,8 @@ Note: This file only contains high level features or important fixes.
## 4.1 - Daily build ## 4.1 - Daily build
* VTOL: General setting for transition distance which affects Plan takeoff, landing pattern creation
* VTOL: Much better VTOL support throughout QGC
* Maps: Support zoom up to level 23 even if map provider doesn't provide tiles that high * Maps: Support zoom up to level 23 even if map provider doesn't provide tiles that high
* Settings/Mavlink: Add ability to forward mavlink traffic out specified UDP port * Settings/Mavlink: Add ability to forward mavlink traffic out specified UDP port
* Support mavlink terrain protocol which queries gcs for terrain height information. Allows planning missions with TERRAIN\_FRAME. * Support mavlink terrain protocol which queries gcs for terrain height information. Allows planning missions with TERRAIN\_FRAME.
......
...@@ -321,9 +321,9 @@ bool FactMetaData::isInRawMinLimit(const QVariant& variantValue) const ...@@ -321,9 +321,9 @@ bool FactMetaData::isInRawMinLimit(const QVariant& variantValue) const
case valueTypeInt64: case valueTypeInt64:
return _rawMin.value<int64_t>() <= variantValue.value<int64_t>(); return _rawMin.value<int64_t>() <= variantValue.value<int64_t>();
case valueTypeFloat: case valueTypeFloat:
return _rawMin.value<float>() <= variantValue.value<float>(); return qIsNaN(variantValue.toFloat()) || _rawMin.value<float>() <= variantValue.value<float>();
case valueTypeDouble: case valueTypeDouble:
return _rawMin.value<double>() <= variantValue.value<double>(); return qIsNaN(variantValue.toDouble()) || _rawMin.value<double>() <= variantValue.value<double>();
default: default:
return true; return true;
} }
...@@ -351,9 +351,9 @@ bool FactMetaData::isInRawMaxLimit(const QVariant& variantValue) const ...@@ -351,9 +351,9 @@ bool FactMetaData::isInRawMaxLimit(const QVariant& variantValue) const
case valueTypeInt64: case valueTypeInt64:
return _rawMax.value<int64_t>() >= variantValue.value<int64_t>(); return _rawMax.value<int64_t>() >= variantValue.value<int64_t>();
case valueTypeFloat: case valueTypeFloat:
return _rawMax.value<float>() >= variantValue.value<float>(); return qIsNaN(variantValue.toFloat()) || _rawMax.value<float>() >= variantValue.value<float>();
case valueTypeDouble: case valueTypeDouble:
return _rawMax.value<double>() >= variantValue.value<double>(); return qIsNaN(variantValue.toDouble()) || _rawMax.value<double>() >= variantValue.value<double>();
default: default:
return true; return true;
} }
...@@ -1294,26 +1294,31 @@ FactMetaData* FactMetaData::createFromJsonObject(const QJsonObject& json, QMap<Q ...@@ -1294,26 +1294,31 @@ FactMetaData* FactMetaData::createFromJsonObject(const QJsonObject& json, QMap<Q
metaData->setRawUnits(json[_unitsJsonKey].toString()); metaData->setRawUnits(json[_unitsJsonKey].toString());
} }
QString defaultValueJsonKey; QString defaultValueJsonKey = _defaultValueJsonKey;
#ifdef __mobile__ #ifdef __mobile__
if (json.contains(_mobileDefaultValueJsonKey)) { if (json.contains(_mobileDefaultValueJsonKey)) {
defaultValueJsonKey = _mobileDefaultValueJsonKey; defaultValueJsonKey = _mobileDefaultValueJsonKey;
} }
#endif #endif
if (defaultValueJsonKey.isEmpty() && json.contains(_defaultValueJsonKey)) {
defaultValueJsonKey = _defaultValueJsonKey; if (json.contains(defaultValueJsonKey)) {
} const QJsonValue jsonValue = json[defaultValueJsonKey];
if (!defaultValueJsonKey.isEmpty()) {
QVariant typedValue; if (jsonValue.type() == QJsonValue::Null && (type == valueTypeFloat || type == valueTypeDouble)) {
QString errorString; metaData->setRawDefaultValue(type == valueTypeFloat ? std::numeric_limits<float>::quiet_NaN() : std::numeric_limits<double>::quiet_NaN());
QVariant initialValue = json[defaultValueJsonKey].toVariant();
if (metaData->convertAndValidateRaw(initialValue, true /* convertOnly */, typedValue, errorString)) {
metaData->setRawDefaultValue(typedValue);
} else { } else {
qWarning() << "Invalid default value, name:" << metaData->name() QVariant typedValue;
<< " type:" << metaData->type() QString errorString;
<< " value:" << initialValue QVariant initialValue = jsonValue.toVariant();
<< " error:" << errorString;
if (metaData->convertAndValidateRaw(initialValue, true /* convertOnly */, typedValue, errorString)) {
metaData->setRawDefaultValue(typedValue);
} else {
qWarning() << "Invalid default value, name:" << metaData->name()
<< " type:" << metaData->type()
<< " value:" << initialValue
<< " error:" << errorString;
}
} }
} }
......
...@@ -574,17 +574,11 @@ void FixedWingLandingComplexItem::_recalcFromHeadingAndDistanceChange(void) ...@@ -574,17 +574,11 @@ void FixedWingLandingComplexItem::_recalcFromHeadingAndDistanceChange(void)
double landToTangentDistance = _landingDistanceFact.rawValue().toDouble(); double landToTangentDistance = _landingDistanceFact.rawValue().toDouble();
double heading = _landingHeadingFact.rawValue().toDouble(); double heading = _landingHeadingFact.rawValue().toDouble();
// Calculate loiter tangent coordinate // Heading is from loiter to land, hence +180
_loiterTangentCoordinate = _landingCoordinate.atDistanceAndAzimuth(landToTangentDistance, heading + 180); _loiterTangentCoordinate = _landingCoordinate.atDistanceAndAzimuth(landToTangentDistance, heading + 180);
// Calculate the distance and angle to the loiter coordinate // Loiter coord is 90 degrees counter clockwise from tangent coord
QGeoCoordinate tangent = _landingCoordinate.atDistanceAndAzimuth(landToTangentDistance, 0); _loiterCoordinate = _loiterTangentCoordinate.atDistanceAndAzimuth(radius, heading - 180 - 90);
QGeoCoordinate loiter = tangent.atDistanceAndAzimuth(radius, 90);
double loiterDistance = _landingCoordinate.distanceTo(loiter);
double loiterAzimuth = _landingCoordinate.azimuthTo(loiter) * (_loiterClockwise ? -1 : 1);
// Use those values to get the new loiter point which takes heading into acount
_loiterCoordinate = _landingCoordinate.atDistanceAndAzimuth(loiterDistance, heading + 180 + loiterAzimuth);
_loiterCoordinate.setAltitude(_loiterAltitudeFact.rawValue().toDouble()); _loiterCoordinate.setAltitude(_loiterAltitudeFact.rawValue().toDouble());
_ignoreRecalcSignals = true; _ignoreRecalcSignals = true;
......
...@@ -399,7 +399,7 @@ QString SimpleMissionItem::abbreviation() const ...@@ -399,7 +399,7 @@ QString SimpleMissionItem::abbreviation() const
case MAV_CMD_NAV_LAND: case MAV_CMD_NAV_LAND:
return tr("Land"); return tr("Land");
case MAV_CMD_NAV_VTOL_TAKEOFF: case MAV_CMD_NAV_VTOL_TAKEOFF:
return tr("VTOL Takeoff"); return tr("Transition Direction");
case MAV_CMD_NAV_VTOL_LAND: case MAV_CMD_NAV_VTOL_LAND:
return tr("VTOL Land"); return tr("VTOL Land");
case MAV_CMD_DO_SET_ROI: case MAV_CMD_DO_SET_ROI:
......
...@@ -175,12 +175,12 @@ void TakeoffMissionItem::setLaunchCoordinate(const QGeoCoordinate& launchCoordin ...@@ -175,12 +175,12 @@ void TakeoffMissionItem::setLaunchCoordinate(const QGeoCoordinate& launchCoordin
if (_launchTakeoffAtSameLocation) { if (_launchTakeoffAtSameLocation) {
takeoffCoordinate = launchCoordinate; takeoffCoordinate = launchCoordinate;
} else { } else {
double distance = 30.0; // Default distance is VTOL transition to takeoff point distance double distance = qgcApp()->toolbox()->settingsManager()->planViewSettings()->vtolTransitionDistance()->rawValue().toDouble(); // Default distance is VTOL transition to takeoff point distance
if (_controllerVehicle->fixedWing()) { if (_controllerVehicle->fixedWing()) {
double altitude = this->altitude()->rawValue().toDouble(); double altitude = this->altitude()->rawValue().toDouble();
if (altitudeMode() == QGroundControlQmlGlobal::AltitudeModeRelative) { if (altitudeMode() == QGroundControlQmlGlobal::AltitudeModeRelative) {
// Offset for fixed wing climb out of 30 degrees // Offset for fixed wing climb out of 30 degrees to specified altitude
if (altitude != 0.0) { if (altitude != 0.0) {
distance = altitude / tan(qDegreesToRadians(30.0)); distance = altitude / tan(qDegreesToRadians(30.0));
} }
......
...@@ -14,6 +14,7 @@ ...@@ -14,6 +14,7 @@
#include "SimpleMissionItem.h" #include "SimpleMissionItem.h"
#include "PlanMasterController.h" #include "PlanMasterController.h"
#include "FlightPathSegment.h" #include "FlightPathSegment.h"
#include "QGC.h"
#include <QPolygonF> #include <QPolygonF>
...@@ -54,9 +55,13 @@ VTOLLandingComplexItem::VTOLLandingComplexItem(PlanMasterController* masterContr ...@@ -54,9 +55,13 @@ VTOLLandingComplexItem::VTOLLandingComplexItem(PlanMasterController* masterContr
_editorQml = "qrc:/qml/VTOLLandingPatternEditor.qml"; _editorQml = "qrc:/qml/VTOLLandingPatternEditor.qml";
_isIncomplete = false; _isIncomplete = false;
QGeoCoordinate homePositionCoordinate = masterController->missionController()->plannedHomePosition(); // We adjust landing distance meta data to Plan View settings unless there was a custom build override
if (homePositionCoordinate.isValid()) { if (QGC::fuzzyCompare(_landingDistanceFact.rawValue().toDouble(), _landingDistanceFact.rawDefaultValue().toDouble())) {
setLandingCoordinate(homePositionCoordinate); Fact* vtolTransitionDistanceFact = qgcApp()->toolbox()->settingsManager()->planViewSettings()->vtolTransitionDistance();
double vtolTransitionDistance = vtolTransitionDistanceFact->rawValue().toDouble();
_landingDistanceFact.metaData()->setRawDefaultValue(vtolTransitionDistance);
_landingDistanceFact.setRawValue(vtolTransitionDistance);
_landingDistanceFact.metaData()->setRawMin(vtolTransitionDistanceFact->metaData()->rawMin());
} }
connect(&_loiterAltitudeFact, &Fact::valueChanged, this, &VTOLLandingComplexItem::_updateLoiterCoodinateAltitudeFromFact); connect(&_loiterAltitudeFact, &Fact::valueChanged, this, &VTOLLandingComplexItem::_updateLoiterCoodinateAltitudeFromFact);
...@@ -535,21 +540,15 @@ void VTOLLandingComplexItem::_recalcFromHeadingAndDistanceChange(void) ...@@ -535,21 +540,15 @@ void VTOLLandingComplexItem::_recalcFromHeadingAndDistanceChange(void)
if (!_ignoreRecalcSignals && _landingCoordSet) { if (!_ignoreRecalcSignals && _landingCoordSet) {
// These are our known values // These are our known values
double radius = _loiterRadiusFact.rawValue().toDouble(); double radius = _loiterRadiusFact.rawValue().toDouble();
double landToTangentDistance = _landingDistanceFact.rawValue().toDouble(); double landToTangentDistance = _landingDistanceFact.rawValue().toDouble();
double heading = _landingHeadingFact.rawValue().toDouble(); double heading = _landingHeadingFact.rawValue().toDouble();
// Calculate loiter tangent coordinate // Heading is from loiter to land, hence +180
_loiterTangentCoordinate = _landingCoordinate.atDistanceAndAzimuth(landToTangentDistance, heading + 180); _loiterTangentCoordinate = _landingCoordinate.atDistanceAndAzimuth(landToTangentDistance, heading + 180);
// Calculate the distance and angle to the loiter coordinate // Loiter coord is 90 degrees counter clockwise from tangent coord
QGeoCoordinate tangent = _landingCoordinate.atDistanceAndAzimuth(landToTangentDistance, 0); _loiterCoordinate = _loiterTangentCoordinate.atDistanceAndAzimuth(radius, heading - 180 - 90);
QGeoCoordinate loiter = tangent.atDistanceAndAzimuth(radius, 90);
double loiterDistance = _landingCoordinate.distanceTo(loiter);
double loiterAzimuth = _landingCoordinate.azimuthTo(loiter) * (_loiterClockwise ? -1 : 1);
// Use those values to get the new loiter point which takes heading into acount
_loiterCoordinate = _landingCoordinate.atDistanceAndAzimuth(loiterDistance, heading + 180 + loiterAzimuth);
_loiterCoordinate.setAltitude(_loiterAltitudeFact.rawValue().toDouble()); _loiterCoordinate.setAltitude(_loiterAltitudeFact.rawValue().toDouble());
_ignoreRecalcSignals = true; _ignoreRecalcSignals = true;
......
...@@ -5,59 +5,59 @@ ...@@ -5,59 +5,59 @@
[ [
{ {
"name": "LandingDistance", "name": "LandingDistance",
"shortDesc": "Distance between landing and loiter points.", "shortDesc": "Distance between landing and loiter points.",
"type": "double", "type": "double",
"units": "m", "units": "m",
"min": 10, "min": 10,
"decimalPlaces": 1, "decimalPlaces": 1,
"default": 30.0 "default": 300.0
}, },
{ {
"name": "LandingHeading", "name": "LandingHeading",
"shortDesc": "Heading from loiter point to land point.", "shortDesc": "Heading from loiter point to land point.",
"type": "double", "type": "double",
"units": "deg", "units": "deg",
"min": 0.0, "min": 0.0,
"max": 360.0, "max": 360.0,
"decimalPlaces": 0, "decimalPlaces": 0,
"default": 270.0 "default": 270.0
}, },
{ {
"name": "LoiterAltitude", "name": "LoiterAltitude",
"shortDesc": "Aircraft will proceed to the loiter point and loiter downwards until it reaches this approach altitude. Once altitude is reached the aircraft will fly to land point at current altitude.", "shortDesc": "Aircraft will proceed to the loiter point and loiter downwards until it reaches this approach altitude. Once altitude is reached the aircraft will fly to land point at current altitude.",
"type": "double", "type": "double",
"units": "m", "units": "m",
"decimalPlaces": 1, "decimalPlaces": 1,
"default": 40.0 "default": 30.0
}, },
{ {
"name": "LoiterRadius", "name": "LoiterRadius",
"shortDesc": "Loiter radius.", "shortDesc": "Loiter radius.",
"type": "double", "type": "double",
"decimalPlaces": 1, "decimalPlaces": 1,
"min": 1, "min": 1,
"units": "m", "units": "m",
"default": 75.0 "default": 75.0
}, },
{ {
"name": "LandingAltitude", "name": "LandingAltitude",
"shortDesc": "Altitude for landing point on ground.", "shortDesc": "Altitude for landing point on ground.",
"type": "double", "type": "double",
"units": "m", "units": "m",
"decimalPlaces": 1, "decimalPlaces": 1,
"default": 0.0 "default": 0.0
}, },
{ {
"name": "StopTakingPhotos", "name": "StopTakingPhotos",
"shortDesc": "Stop taking photos", "shortDesc": "Stop taking photos",
"type": "bool", "type": "bool",
"default": true "default": true
}, },
{ {
"name": "StopTakingVideo", "name": "StopTakingVideo",
"shortDesc": "Stop taking video", "shortDesc": "Stop taking video",
"type": "bool", "type": "bool",
"default": true "default": true
} }
] ]
} }
...@@ -317,8 +317,6 @@ Rectangle { ...@@ -317,8 +317,6 @@ Rectangle {
onClicked: { onClicked: {
missionItem.wizardMode = false missionItem.wizardMode = false
missionItem.landingDragAngleOnly = false missionItem.landingDragAngleOnly = false
// Trial of no auto select next item
//editorRoot.selectNextNotReadyItem()
} }
} }
} }
......
...@@ -27,7 +27,9 @@ Item { ...@@ -27,7 +27,9 @@ Item {
property var _controllerDirty: _controllerValid ? _planMasterController.dirty : false property var _controllerDirty: _controllerValid ? _planMasterController.dirty : false
property var _controllerSyncInProgress: _controllerValid ? _planMasterController.syncInProgress : false property var _controllerSyncInProgress: _controllerValid ? _planMasterController.syncInProgress : false
property bool _statusValid: _currentMissionItem !== undefined && _currentMissionItem !== null property bool _currentMissionItemValid: _currentMissionItem && _currentMissionItem !== undefined && _currentMissionItem !== null
property bool _curreItemIsFlyThrough: _currentMissionItemValid && _currentMissionItem.specifiesCoordinate && !_currentMissionItem.isStandaloneCoordinate
property bool _currentItemIsVTOLTakeoff: _currentMissionItemValid && _currentMissionItem.command == 84
property bool _missionValid: missionItems !== undefined property bool _missionValid: missionItems !== undefined
property real _dataFontSize: ScreenTools.defaultFontPointSize property real _dataFontSize: ScreenTools.defaultFontPointSize
...@@ -36,11 +38,10 @@ Item { ...@@ -36,11 +38,10 @@ Item {
property real _smallValueWidth: ScreenTools.defaultFontPixelWidth * 3 property real _smallValueWidth: ScreenTools.defaultFontPixelWidth * 3
property real _labelToValueSpacing: ScreenTools.defaultFontPixelWidth property real _labelToValueSpacing: ScreenTools.defaultFontPixelWidth
property real _rowSpacing: ScreenTools.isMobile ? 1 : 0 property real _rowSpacing: ScreenTools.isMobile ? 1 : 0
property real _distance: _statusValid && _currentMissionItem ? _currentMissionItem.distance : NaN property real _distance: _currentMissionItemValid ? _currentMissionItem.distance : NaN
property real _altDifference: _statusValid && _currentMissionItem ? _currentMissionItem.altDifference : NaN property real _altDifference: _currentMissionItemValid ? _currentMissionItem.altDifference : NaN
property real _gradient: _statusValid && _currentMissionItem && _currentMissionItem.distance > 0 ? (Math.atan(_currentMissionItem.altDifference / _currentMissionItem.distance) * (180.0/Math.PI)) : NaN property real _azimuth: _currentMissionItemValid ? _currentMissionItem.azimuth : NaN
property real _azimuth: _statusValid && _currentMissionItem ? _currentMissionItem.azimuth : NaN property real _heading: _currentMissionItemValid ? _currentMissionItem.missionVehicleYaw : NaN
property real _heading: _statusValid && _currentMissionItem ? _currentMissionItem.missionVehicleYaw : NaN
property real _missionDistance: _missionValid ? missionDistance : NaN property real _missionDistance: _missionValid ? missionDistance : NaN
property real _missionMaxTelemetry: _missionValid ? missionMaxTelemetry : NaN property real _missionMaxTelemetry: _missionValid ? missionMaxTelemetry : NaN
property real _missionTime: _missionValid ? missionTime : NaN property real _missionTime: _missionValid ? missionTime : NaN
...@@ -49,6 +50,11 @@ Item { ...@@ -49,6 +50,11 @@ Item {
property bool _batteryInfoAvailable: _batteryChangePoint >= 0 || _batteriesRequired >= 0 property bool _batteryInfoAvailable: _batteryChangePoint >= 0 || _batteriesRequired >= 0
property real _controllerProgressPct: _controllerValid ? _planMasterController.missionController.progressPct : 0 property real _controllerProgressPct: _controllerValid ? _planMasterController.missionController.progressPct : 0
property bool _syncInProgress: _controllerValid ? _planMasterController.missionController.syncInProgress : false property bool _syncInProgress: _controllerValid ? _planMasterController.missionController.syncInProgress : false
property real _gradient: _currentMissionItemValid && _currentMissionItem.distance > 0 ?
(_currentItemIsVTOLTakeoff ?
0 :
(Math.atan(_currentMissionItem.altDifference / _currentMissionItem.distance) * (180.0/Math.PI)))
: NaN
property string _distanceText: isNaN(_distance) ? "-.-" : QGroundControl.unitsConversion.metersToAppSettingsHorizontalDistanceUnits(_distance).toFixed(1) + " " + QGroundControl.unitsConversion.appSettingsHorizontalDistanceUnitsString property string _distanceText: isNaN(_distance) ? "-.-" : QGroundControl.unitsConversion.metersToAppSettingsHorizontalDistanceUnits(_distance).toFixed(1) + " " + QGroundControl.unitsConversion.appSettingsHorizontalDistanceUnitsString
property string _altDifferenceText: isNaN(_altDifference) ? "-.-" : QGroundControl.unitsConversion.metersToAppSettingsHorizontalDistanceUnits(_altDifference).toFixed(1) + " " + QGroundControl.unitsConversion.appSettingsHorizontalDistanceUnitsString property string _altDifferenceText: isNaN(_altDifference) ? "-.-" : QGroundControl.unitsConversion.metersToAppSettingsHorizontalDistanceUnits(_altDifference).toFixed(1) + " " + QGroundControl.unitsConversion.appSettingsHorizontalDistanceUnitsString
......
...@@ -82,7 +82,11 @@ Rectangle { ...@@ -82,7 +82,11 @@ Rectangle {
visible: missionItem.isTakeoffItem && missionItem.wizardMode // Hack special case for takeoff item visible: missionItem.isTakeoffItem && missionItem.wizardMode // Hack special case for takeoff item
QGCLabel { QGCLabel {
text: qsTr("Move '%1' Takeoff to the %2 location.").arg(_controllerVehicle.vtol ? qsTr("V") : qsTr("T")).arg(_controllerVehicle.vtol ? qsTr("desired") : qsTr("climbout")) text: qsTr("Move '%1' %2 to the %3 location. %4")
.arg(_controllerVehicle.vtol ? qsTr("T") : qsTr("T"))
.arg(_controllerVehicle.vtol ? qsTr("Transition Direction") : qsTr("Takeoff"))
.arg(_controllerVehicle.vtol ? qsTr("desired") : qsTr("climbout"))
.arg(_controllerVehicle.vtol ? (qsTr("Ensure distance from launch to transition direction is far enough to complete transition.")) : "")
Layout.fillWidth: true Layout.fillWidth: true
wrapMode: Text.WordWrap wrapMode: Text.WordWrap
visible: !initialClickLabel.visible visible: !initialClickLabel.visible
...@@ -101,8 +105,6 @@ Rectangle { ...@@ -101,8 +105,6 @@ Rectangle {
visible: !initialClickLabel.visible visible: !initialClickLabel.visible
onClicked: { onClicked: {
missionItem.wizardMode = false missionItem.wizardMode = false
// Trial of no auto select next item
//editorRoot.selectNextNotReadyItem()
} }
} }
......
...@@ -149,7 +149,6 @@ Item { ...@@ -149,7 +149,6 @@ Item {
readonly property int _decimalPlaces: 8 readonly property int _decimalPlaces: 8
onClicked: { onClicked: {
console.log("mousearea click")
var coordinate = map.toCoordinate(Qt.point(mouse.x, mouse.y), false /* clipToViewPort */) var coordinate = map.toCoordinate(Qt.point(mouse.x, mouse.y), false /* clipToViewPort */)
coordinate.latitude = coordinate.latitude.toFixed(_decimalPlaces) coordinate.latitude = coordinate.latitude.toFixed(_decimalPlaces)
coordinate.longitude = coordinate.longitude.toFixed(_decimalPlaces) coordinate.longitude = coordinate.longitude.toFixed(_decimalPlaces)
......
...@@ -32,9 +32,9 @@ Rectangle { ...@@ -32,9 +32,9 @@ Rectangle {
//property real availableWidth ///< Width for control //property real availableWidth ///< Width for control
//property var missionItem ///< Mission Item for editor //property var missionItem ///< Mission Item for editor
property var _masterControler: masterController property var _masterControler: masterController
property var _missionController: _masterControler.missionController property var _missionController: _masterControler.missionController
property var _missionVehicle: _masterControler.controllerVehicle property var _missionVehicle: _masterControler.controllerVehicle
property real _margin: ScreenTools.defaultFontPixelWidth / 2 property real _margin: ScreenTools.defaultFontPixelWidth / 2
property real _spacer: ScreenTools.defaultFontPixelWidth / 2 property real _spacer: ScreenTools.defaultFontPixelWidth / 2
property string _setToVehicleHeadingStr: qsTr("Set to vehicle heading") property string _setToVehicleHeadingStr: qsTr("Set to vehicle heading")
...@@ -51,6 +51,14 @@ Rectangle { ...@@ -51,6 +51,14 @@ Rectangle {
spacing: _margin spacing: _margin
visible: !editorColumnNeedLandingPoint.visible visible: !editorColumnNeedLandingPoint.visible
QGCLabel {
anchors.left: parent.left
anchors.right: parent.right
wrapMode: Text.WordWrap
font.pointSize: ScreenTools.smallFontPointSize
text: qsTr("Loiter down to specified altitude. Fly to land point while transitioning. Hover straight down to land.")
}
SectionHeader { SectionHeader {
id: loiterPointSection id: loiterPointSection
anchors.left: parent.left anchors.left: parent.left
...@@ -216,6 +224,15 @@ Rectangle { ...@@ -216,6 +224,15 @@ Rectangle {
font.pointSize: ScreenTools.smallFontPointSize font.pointSize: ScreenTools.smallFontPointSize
text: qsTr("* Avoid tailwind from loiter to land.") text: qsTr("* Avoid tailwind from loiter to land.")
} }
QGCLabel {
anchors.left: parent.left
anchors.right: parent.right
wrapMode: Text.WordWrap
color: qgcPal.warningText
font.pointSize: ScreenTools.smallFontPointSize
text: qsTr("* Ensure landing distance is enough to complete transition.")
}
} }
} }
...@@ -287,8 +304,6 @@ Rectangle { ...@@ -287,8 +304,6 @@ Rectangle {
onClicked: { onClicked: {
missionItem.wizardMode = false missionItem.wizardMode = false
missionItem.landingDragAngleOnly = false missionItem.landingDragAngleOnly = false
// Trial of no auto select next item
//editorRoot.selectNextNotReadyItem()
} }
} }
} }
......
{ {
"version": 1, "version": 1,
"fileType": "FactMetaData", "fileType": "FactMetaData",
"QGC.MetaData.Facts": "QGC.MetaData.Facts":
[ [
{ {
"name": "displayPresetsTabFirst", "name": "displayPresetsTabFirst",
"shortDesc": "Display the presets tab at start", "shortDesc": "Display the presets tab at start",
"type": "bool", "type": "bool",
"default": false "default": false
}, },
{ {
"name": "showMissionItemStatus", "name": "showMissionItemStatus",
"shortDesc": "Show/Hide the mission item status display", "shortDesc": "Show/Hide the mission item status display",
"type": "bool", "type": "bool",
"default": true "default": true
}, },
{ {
"name": "takeoffItemNotRequired", "name": "takeoffItemNotRequired",
"shortDesc": "Allow missions to not require a takeoff item", "shortDesc": "Allow missions to not require a takeoff item",
"type": "bool", "type": "bool",
"default": false "default": false
}, },
{ {
"name": "useConditionGate", "name": "useConditionGate",
"shortDesc": "Use MAV_CMD_CONDITION_GATE for pattern generation", "shortDesc": "Use MAV_CMD_CONDITION_GATE for pattern generation",
"type": "bool", "type": "bool",
"default": false "default": false
}, },
{ {
"name": "showGimbalOnlyWhenSet", "name": "showGimbalOnlyWhenSet",
"shortDesc": "Show gimbal yaw visual only when set explicitly for the waypoint", "shortDesc": "Show gimbal yaw visual only when set explicitly for the waypoint",
"type": "bool", "type": "bool",
"default": false "default": false
},
{
"name": "vtolTransitionDistance",
"shortDesc": "Amount of distance required for vehicle to complete a transition",
"type": "double",
"default": 300.0,
"units": "m",
"min": 100.0
} }
] ]
} }
...@@ -22,3 +22,4 @@ DECLARE_SETTINGSFACT(PlanViewSettings, showMissionItemStatus) ...@@ -22,3 +22,4 @@ DECLARE_SETTINGSFACT(PlanViewSettings, showMissionItemStatus)
DECLARE_SETTINGSFACT(PlanViewSettings, useConditionGate) DECLARE_SETTINGSFACT(PlanViewSettings, useConditionGate)
DECLARE_SETTINGSFACT(PlanViewSettings, takeoffItemNotRequired) DECLARE_SETTINGSFACT(PlanViewSettings, takeoffItemNotRequired)
DECLARE_SETTINGSFACT(PlanViewSettings, showGimbalOnlyWhenSet) DECLARE_SETTINGSFACT(PlanViewSettings, showGimbalOnlyWhenSet)
DECLARE_SETTINGSFACT(PlanViewSettings, vtolTransitionDistance)
...@@ -25,4 +25,5 @@ public: ...@@ -25,4 +25,5 @@ public:
DEFINE_SETTINGFACT(useConditionGate) DEFINE_SETTINGFACT(useConditionGate)
DEFINE_SETTINGFACT(takeoffItemNotRequired) DEFINE_SETTINGFACT(takeoffItemNotRequired)
DEFINE_SETTINGFACT(showGimbalOnlyWhenSet) DEFINE_SETTINGFACT(showGimbalOnlyWhenSet)
DEFINE_SETTINGFACT(vtolTransitionDistance)
}; };
{ {
"version": 1, "version": 1,
"fileType": "FactMetaData", "fileType": "FactMetaData",
"QGC.MetaData.Facts": "QGC.MetaData.Facts":
[ [
{ {
"name": "goodAttitudeEsimate", "name": "goodAttitudeEsimate",
"shortDesc": "Good Attitude Esimate", "shortDesc": "Good Attitude Esimate",
"type": "bool", "type": "bool",
"default": false "default": false
}, },
{ {
"name": "goodHorizVelEstimate", "name": "goodHorizVelEstimate",
"shortDesc": "Good Horiz Vel Estimate", "shortDesc": "Good Horiz Vel Estimate",
"type": "bool", "type": "bool",
"default": false "default": false
}, },
{ {
"name": "goodVertVelEstimate", "name": "goodVertVelEstimate",
"shortDesc": "Good Vert Vel Estimate", "shortDesc": "Good Vert Vel Estimate",
"type": "bool", "type": "bool",
"default": false "default": false
}, },
{ {
"name": "goodHorizPosRelEstimate", "name": "goodHorizPosRelEstimate",
"shortDesc": "Good Horiz Pos Rel Estimate", "shortDesc": "Good Horiz Pos Rel Estimate",
"type": "bool", "type": "bool",
"default": false "default": false
}, },
{ {
"name": "goodHorizPosAbsEstimate", "name": "goodHorizPosAbsEstimate",
"shortDesc": "Good Horiz Pos Abs Estimate", "shortDesc": "Good Horiz Pos Abs Estimate",
"type": "bool", "type": "bool",
"default": false "default": false
}, },
{ {
"name": "goodVertPosAbsEstimate", "name": "goodVertPosAbsEstimate",
"shortDesc": "Good Vert Pos Abs Estimate", "shortDesc": "Good Vert Pos Abs Estimate",
"type": "bool", "type": "bool",
"default": false "default": false
}, },
{ {
"name": "goodVertPosAGLEstimate", "name": "goodVertPosAGLEstimate",
"shortDesc": "Good Vert Pos AGL Estimate", "shortDesc": "Good Vert Pos AGL Estimate",
"type": "bool", "type": "bool",
"default": false "default": false
}, },
{ {
"name": "goodConstPosModeEstimate", "name": "goodConstPosModeEstimate",
"shortDesc": "Good Const Pos Mode Estimate", "shortDesc": "Good Const Pos Mode Estimate",
"type": "bool", "type": "bool",
"default": false "default": false
}, },
{ {
"name": "goodPredHorizPosRelEstimate", "name": "goodPredHorizPosRelEstimate",
"shortDesc": "Good Pred Horiz Pos Rel Estimate", "shortDesc": "Good Pred Horiz Pos Rel Estimate",
"type": "bool", "type": "bool",
"default": false "default": false
}, },
{ {
"name": "goodPredHorizPosAbsEstimate", "name": "goodPredHorizPosAbsEstimate",
"shortDesc": "Good Pred Horiz Pos Abs Estimate", "shortDesc": "Good Pred Horiz Pos Abs Estimate",
"type": "bool", "type": "bool",
"default": false "default": false
}, },
{ {
"name": "gpsGlitch", "name": "gpsGlitch",
"shortDesc": "Gps Glitch", "shortDesc": "Gps Glitch",
"type": "bool", "type": "bool",
"default": false "default": false
}, },
{ {
"name": "accelError", "name": "accelError",
"shortDesc": "Accel Error", "shortDesc": "Accel Error",
"type": "bool", "type": "bool",
"default": false "default": false
}, },
{ {
"name": "velRatio", "name": "velRatio",
"shortDesc": "Vel Ratio", "shortDesc": "Vel Ratio",
"type": "float", "type": "float",
"decimalPlaces": 2, "decimalPlaces": 2,
"default": null "default": null
}, },
{ {
"name": "horizPosRatio", "name": "horizPosRatio",
"shortDesc": "Horiz Pos Ratio", "shortDesc": "Horiz Pos Ratio",
"type": "float", "type": "float",
"decimalPlaces": 2, "decimalPlaces": 2,
"default": null "default": null
}, },
{ {
"name": "vertPosRatio", "name": "vertPosRatio",
"shortDesc": "Vert Pos Ratio", "shortDesc": "Vert Pos Ratio",
"type": "float", "type": "float",
"decimalPlaces": 2, "decimalPlaces": 2,
"default": null "default": null
}, },
{ {
"name": "magRatio", "name": "magRatio",
"shortDesc": "Mag Ratio", "shortDesc": "Mag Ratio",
"type": "float", "type": "float",
"decimalPlaces": 2, "decimalPlaces": 2,
"default": null "default": null
}, },
{ {
"name": "haglRatio", "name": "haglRatio",
"shortDesc": "HAGL Ratio", "shortDesc": "HAGL Ratio",
"type": "float", "type": "float",
"decimalPlaces": 2, "decimalPlaces": 2,
"default": null "default": null
}, },
{ {
"name": "tasRatio", "name": "tasRatio",
"shortDesc": "TAS Ratio", "shortDesc": "TAS Ratio",
"type": "float", "type": "float",
"decimalPlaces": 2, "decimalPlaces": 2,
"default": null "default": null
}, },
{ {
"name": "horizPosAccuracy", "name": "horizPosAccuracy",
"shortDesc": "Horiz Pos Accuracy", "shortDesc": "Horiz Pos Accuracy",
"type": "float", "type": "float",
"decimalPlaces": 2, "decimalPlaces": 2,
"default": null "default": null
}, },
{ {
"name": "vertPosAccuracy", "name": "vertPosAccuracy",
"shortDesc": "Vert Pos Accuracy", "shortDesc": "Vert Pos Accuracy",
"type": "float", "type": "float",
"decimalPlaces": 2, "decimalPlaces": 2,
"default": null "default": null
} }
] ]
} }
...@@ -348,15 +348,22 @@ Rectangle { ...@@ -348,15 +348,22 @@ Rectangle {
anchors.horizontalCenter: parent.horizontalCenter anchors.horizontalCenter: parent.horizontalCenter
spacing: _margins spacing: _margins
RowLayout { GridLayout {
spacing: ScreenTools.defaultFontPixelWidth columns: 2
visible: QGroundControl.settingsManager.appSettings.defaultMissionItemAltitude.visible columnSpacing: ScreenTools.defaultFontPixelWidth
visible: QGroundControl.settingsManager.appSettings.defaultMissionItemAltitude.visible
QGCLabel { text: qsTr("Default Mission Altitude") } QGCLabel { text: qsTr("Default Mission Altitude") }
FactTextField { FactTextField {
Layout.preferredWidth: _valueFieldWidth Layout.preferredWidth: _valueFieldWidth
fact: QGroundControl.settingsManager.appSettings.defaultMissionItemAltitude fact: QGroundControl.settingsManager.appSettings.defaultMissionItemAltitude
} }
QGCLabel { text: qsTr("VTOL TransitionDistance") }
FactTextField {
Layout.preferredWidth: _valueFieldWidth
fact: QGroundControl.settingsManager.planViewSettings.vtolTransitionDistance
}
} }
FactCheckBox { FactCheckBox {
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment