Commit 109d6a59 authored by DonLakeFlyer's avatar DonLakeFlyer

parent 6256bc21
...@@ -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.
......
...@@ -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);
...@@ -539,17 +544,11 @@ void VTOLLandingComplexItem::_recalcFromHeadingAndDistanceChange(void) ...@@ -539,17 +544,11 @@ void VTOLLandingComplexItem::_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;
......
...@@ -10,7 +10,7 @@ ...@@ -10,7 +10,7 @@
"units": "m", "units": "m",
"min": 10, "min": 10,
"decimalPlaces": 1, "decimalPlaces": 1,
"default": 30.0 "default": 300.0
}, },
{ {
"name": "LandingHeading", "name": "LandingHeading",
...@@ -28,7 +28,7 @@ ...@@ -28,7 +28,7 @@
"type": "double", "type": "double",
"units": "m", "units": "m",
"decimalPlaces": 1, "decimalPlaces": 1,
"default": 40.0 "default": 30.0
}, },
{ {
"name": "LoiterRadius", "name": "LoiterRadius",
......
...@@ -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)
......
...@@ -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()
} }
} }
} }
......
...@@ -32,6 +32,14 @@ ...@@ -32,6 +32,14 @@
"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)
}; };
...@@ -348,8 +348,9 @@ Rectangle { ...@@ -348,8 +348,9 @@ Rectangle {
anchors.horizontalCenter: parent.horizontalCenter anchors.horizontalCenter: parent.horizontalCenter
spacing: _margins spacing: _margins
RowLayout { GridLayout {
spacing: ScreenTools.defaultFontPixelWidth columns: 2
columnSpacing: ScreenTools.defaultFontPixelWidth
visible: QGroundControl.settingsManager.appSettings.defaultMissionItemAltitude.visible visible: QGroundControl.settingsManager.appSettings.defaultMissionItemAltitude.visible
QGCLabel { text: qsTr("Default Mission Altitude") } QGCLabel { text: qsTr("Default Mission Altitude") }
...@@ -357,6 +358,12 @@ Rectangle { ...@@ -357,6 +358,12 @@ Rectangle {
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