Unverified Commit c143db05 authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #8624 from mavlink/FWLandingLock

Plan FW Landing: Drag of land/loiter maintains land distance/heading as appropriate
parents 743d89de 3c2f1e88
......@@ -51,7 +51,6 @@ FixedWingLandingComplexItem::FixedWingLandingComplexItem(PlanMasterController* m
, _dirty (false)
, _landingCoordSet (false)
, _ignoreRecalcSignals (false)
, _loiterDragAngleOnly (false)
, _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/FWLandingPattern.FactMetaData.json"), this))
, _landingDistanceFact (settingsGroup, _metaDataMap[loiterToLandDistanceName])
, _loiterAltitudeFact (settingsGroup, _metaDataMap[loiterAltitudeName])
......@@ -719,10 +718,12 @@ FixedWingLandingComplexItem::ReadyForSaveState FixedWingLandingComplexItem::read
return _landingCoordSet && !_wizardMode ? ReadyForSave : NotReadyForSaveData;
}
void FixedWingLandingComplexItem::setLoiterDragAngleOnly(bool loiterDragAngleOnly)
void FixedWingLandingComplexItem::moveLandingPosition(const QGeoCoordinate& coordinate)
{
if (loiterDragAngleOnly != _loiterDragAngleOnly) {
_loiterDragAngleOnly = loiterDragAngleOnly;
emit loiterDragAngleOnlyChanged(_loiterDragAngleOnly);
}
double savedHeading = landingHeading()->rawValue().toDouble();
double savedDistance = landingDistance()->rawValue().toDouble();
setLandingCoordinate(coordinate);
landingHeading()->setRawValue(savedHeading);
landingDistance()->setRawValue(savedDistance);
}
......@@ -42,7 +42,8 @@ public:
Q_PROPERTY(QGeoCoordinate loiterTangentCoordinate READ loiterTangentCoordinate NOTIFY loiterTangentCoordinateChanged)
Q_PROPERTY(QGeoCoordinate landingCoordinate READ landingCoordinate WRITE setLandingCoordinate NOTIFY landingCoordinateChanged)
Q_PROPERTY(bool landingCoordSet MEMBER _landingCoordSet NOTIFY landingCoordSetChanged)
Q_PROPERTY(bool loiterDragAngleOnly READ loiterDragAngleOnly WRITE setLoiterDragAngleOnly NOTIFY loiterDragAngleOnlyChanged)
Q_INVOKABLE void moveLandingPosition(const QGeoCoordinate& coordinate); // Maintains the current landing distance and heading
Fact* loiterAltitude (void) { return &_loiterAltitudeFact; }
Fact* loiterRadius (void) { return &_loiterRadiusFact; }
......@@ -56,11 +57,9 @@ public:
QGeoCoordinate landingCoordinate (void) const { return _landingCoordinate; }
QGeoCoordinate loiterCoordinate (void) const { return _loiterCoordinate; }
QGeoCoordinate loiterTangentCoordinate (void) const { return _loiterTangentCoordinate; }
bool loiterDragAngleOnly (void) const { return _loiterDragAngleOnly; }
void setLandingCoordinate (const QGeoCoordinate& coordinate);
void setLoiterCoordinate (const QGeoCoordinate& coordinate);
void setLoiterDragAngleOnly (bool loiterDragAngleOnly);
/// Scans the loaded items for a landing pattern complex item
static bool scanForItem(QmlObjectListModel* visualItems, bool flyView, PlanMasterController* masterController);
......@@ -126,7 +125,6 @@ signals:
void loiterClockwiseChanged (bool loiterClockwise);
void altitudesAreRelativeChanged (bool altitudesAreRelative);
void valueSetIsDistanceChanged (bool valueSetIsDistance);
void loiterDragAngleOnlyChanged (bool loiterDragAngleOnly);
private slots:
void _recalcFromHeadingAndDistanceChange (void);
......@@ -151,7 +149,6 @@ private:
QGeoCoordinate _landingCoordinate;
bool _landingCoordSet;
bool _ignoreRecalcSignals;
bool _loiterDragAngleOnly;
QMap<QString, FactMetaData*> _metaDataMap;
......
......@@ -386,7 +386,6 @@ VisualMissionItem* MissionController::insertLandItem(QGeoCoordinate coordinate,
{
if (_managerVehicle->fixedWing()) {
FixedWingLandingComplexItem* fwLanding = qobject_cast<FixedWingLandingComplexItem*>(insertComplexMissionItem(MissionController::patternFWLandingName, coordinate, visualItemIndex, makeCurrentItem));
fwLanding->setLoiterDragAngleOnly(true);
return fwLanding;
} else {
return _insertSimpleMissionItemWorker(coordinate, _managerVehicle->vtol() ? MAV_CMD_NAV_VTOL_LAND : MAV_CMD_NAV_RETURN_TO_LAUNCH, visualItemIndex, makeCurrentItem);
......
......@@ -204,14 +204,12 @@ Item {
onItemCoordinateChanged: {
if (!_preventReentrancy) {
if (Drag.active && _missionItem.loiterDragAngleOnly) {
if (Drag.active) {
_preventReentrancy = true
var angle = _missionItem.landingCoordinate.azimuthTo(itemCoordinate)
var distance = _missionItem.landingCoordinate.distanceTo(_missionItem.loiterCoordinate)
_missionItem.loiterCoordinate = _missionItem.landingCoordinate.atDistanceAndAzimuth(distance, angle)
_preventReentrancy = false
} else {
_missionItem.loiterCoordinate = itemCoordinate
}
}
}
......@@ -227,7 +225,7 @@ Item {
itemIndicator: _landingPointObject
itemCoordinate: _missionItem.landingCoordinate
onItemCoordinateChanged: _missionItem.landingCoordinate = itemCoordinate
onItemCoordinateChanged: _missionItem.moveLandingPosition(itemCoordinate)
}
}
......
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