FixedWingLandingComplexItem.cc 36.9 KB
Newer Older
1 2
/****************************************************************************
 *
Gus Grubba's avatar
Gus Grubba committed
3
 * (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
4 5 6 7 8 9 10 11 12 13
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/

#include "FixedWingLandingComplexItem.h"
#include "JsonHelper.h"
#include "MissionController.h"
#include "QGCGeo.h"
14
#include "SimpleMissionItem.h"
15
#include "PlanMasterController.h"
16
#include "FlightPathSegment.h"
17 18 19 20 21

#include <QPolygonF>

QGC_LOGGING_CATEGORY(FixedWingLandingComplexItemLog, "FixedWingLandingComplexItemLog")

22 23
const QString FixedWingLandingComplexItem::name(tr("Fixed Wing Landing"));

24
const char* FixedWingLandingComplexItem::settingsGroup =            "FixedWingLanding";
25 26
const char* FixedWingLandingComplexItem::jsonComplexItemTypeValue = "fwLandingPattern";

27 28 29 30 31
const char* FixedWingLandingComplexItem::loiterToLandDistanceName = "LandingDistance";
const char* FixedWingLandingComplexItem::landingHeadingName =       "LandingHeading";
const char* FixedWingLandingComplexItem::loiterAltitudeName =       "LoiterAltitude";
const char* FixedWingLandingComplexItem::loiterRadiusName =         "LoiterRadius";
const char* FixedWingLandingComplexItem::landingAltitudeName =      "LandingAltitude";
32
const char* FixedWingLandingComplexItem::glideSlopeName =           "GlideSlope";
33 34
const char* FixedWingLandingComplexItem::stopTakingPhotosName =     "StopTakingPhotos";
const char* FixedWingLandingComplexItem::stopTakingVideoName =      "StopTakingVideo";
35
const char* FixedWingLandingComplexItem::valueSetIsDistanceName =   "ValueSetIsDistance";
36

37 38 39 40
const char* FixedWingLandingComplexItem::_jsonLoiterCoordinateKey =         "loiterCoordinate";
const char* FixedWingLandingComplexItem::_jsonLoiterRadiusKey =             "loiterRadius";
const char* FixedWingLandingComplexItem::_jsonLoiterClockwiseKey =          "loiterClockwise";
const char* FixedWingLandingComplexItem::_jsonLandingCoordinateKey =        "landCoordinate";
41 42
const char* FixedWingLandingComplexItem::_jsonValueSetIsDistanceKey =       "valueSetIsDistance";
const char* FixedWingLandingComplexItem::_jsonAltitudesAreRelativeKey =     "altitudesAreRelative";
43 44
const char* FixedWingLandingComplexItem::_jsonStopTakingPhotosKey =         "stopTakingPhotos";
const char* FixedWingLandingComplexItem::_jsonStopTakingVideoKey =          "stopVideoPhotos";
45 46

// Usage deprecated
47
const char* FixedWingLandingComplexItem::_jsonFallRateKey =                 "fallRate";
48 49
const char* FixedWingLandingComplexItem::_jsonLandingAltitudeRelativeKey =  "landAltitudeRelative";
const char* FixedWingLandingComplexItem::_jsonLoiterAltitudeRelativeKey =   "loiterAltitudeRelative";
50

51 52
FixedWingLandingComplexItem::FixedWingLandingComplexItem(PlanMasterController* masterController, bool flyView, QObject* parent)
    : ComplexMissionItem        (masterController, flyView, parent)
53
    , _metaDataMap              (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/FWLandingPattern.FactMetaData.json"), this))
54 55 56 57 58 59
    , _landingDistanceFact      (settingsGroup, _metaDataMap[loiterToLandDistanceName])
    , _loiterAltitudeFact       (settingsGroup, _metaDataMap[loiterAltitudeName])
    , _loiterRadiusFact         (settingsGroup, _metaDataMap[loiterRadiusName])
    , _landingHeadingFact       (settingsGroup, _metaDataMap[landingHeadingName])
    , _landingAltitudeFact      (settingsGroup, _metaDataMap[landingAltitudeName])
    , _glideSlopeFact           (settingsGroup, _metaDataMap[glideSlopeName])
60 61
    , _stopTakingPhotosFact     (settingsGroup, _metaDataMap[stopTakingPhotosName])
    , _stopTakingVideoFact      (settingsGroup, _metaDataMap[stopTakingVideoName])
62
    , _valueSetIsDistanceFact   (settingsGroup, _metaDataMap[valueSetIsDistanceName])
63 64
{
    _editorQml = "qrc:/qml/FWLandingPatternEditor.qml";
65
    _isIncomplete = false;
66

67
    connect(&_loiterAltitudeFact,       &Fact::valueChanged,                                    this, &FixedWingLandingComplexItem::_updateLoiterCoodinateAltitudeFromFact);
68 69 70 71 72 73 74 75 76 77
    connect(&_landingAltitudeFact,      &Fact::valueChanged,                                    this, &FixedWingLandingComplexItem::_updateLandingCoodinateAltitudeFromFact);

    connect(&_landingDistanceFact,      &Fact::valueChanged,                                    this, &FixedWingLandingComplexItem::_recalcFromHeadingAndDistanceChange);
    connect(&_landingHeadingFact,       &Fact::valueChanged,                                    this, &FixedWingLandingComplexItem::_recalcFromHeadingAndDistanceChange);

    connect(&_loiterRadiusFact,         &Fact::valueChanged,                                    this, &FixedWingLandingComplexItem::_recalcFromRadiusChange);
    connect(this,                       &FixedWingLandingComplexItem::loiterClockwiseChanged,   this, &FixedWingLandingComplexItem::_recalcFromRadiusChange);

    connect(this,                       &FixedWingLandingComplexItem::loiterCoordinateChanged,  this, &FixedWingLandingComplexItem::_recalcFromCoordinateChange);
    connect(this,                       &FixedWingLandingComplexItem::landingCoordinateChanged, this, &FixedWingLandingComplexItem::_recalcFromCoordinateChange);
78

79 80
    connect(&_glideSlopeFact,           &Fact::valueChanged,                                    this, &FixedWingLandingComplexItem::_glideSlopeChanged);

81 82 83
    connect(&_stopTakingPhotosFact,     &Fact::valueChanged,                                            this, &FixedWingLandingComplexItem::_signalLastSequenceNumberChanged);
    connect(&_stopTakingVideoFact,      &Fact::valueChanged,                                            this, &FixedWingLandingComplexItem::_signalLastSequenceNumberChanged);

84 85 86 87 88
    connect(&_loiterAltitudeFact,       &Fact::valueChanged,                                            this, &FixedWingLandingComplexItem::_setDirty);
    connect(&_landingAltitudeFact,      &Fact::valueChanged,                                            this, &FixedWingLandingComplexItem::_setDirty);
    connect(&_landingDistanceFact,      &Fact::valueChanged,                                            this, &FixedWingLandingComplexItem::_setDirty);
    connect(&_landingHeadingFact,       &Fact::valueChanged,                                            this, &FixedWingLandingComplexItem::_setDirty);
    connect(&_loiterRadiusFact,         &Fact::valueChanged,                                            this, &FixedWingLandingComplexItem::_setDirty);
89 90
    connect(&_stopTakingPhotosFact,     &Fact::valueChanged,                                            this, &FixedWingLandingComplexItem::_setDirty);
    connect(&_stopTakingVideoFact,      &Fact::valueChanged,                                            this, &FixedWingLandingComplexItem::_setDirty);
91
    connect(&_valueSetIsDistanceFact,   &Fact::valueChanged,                                            this, &FixedWingLandingComplexItem::_setDirty);
92 93 94
    connect(this,                       &FixedWingLandingComplexItem::loiterCoordinateChanged,          this, &FixedWingLandingComplexItem::_setDirty);
    connect(this,                       &FixedWingLandingComplexItem::landingCoordinateChanged,         this, &FixedWingLandingComplexItem::_setDirty);
    connect(this,                       &FixedWingLandingComplexItem::loiterClockwiseChanged,           this, &FixedWingLandingComplexItem::_setDirty);
95
    connect(this,                       &FixedWingLandingComplexItem::altitudesAreRelativeChanged,      this, &FixedWingLandingComplexItem::_setDirty);
96
    connect(this,                       &FixedWingLandingComplexItem::valueSetIsDistanceChanged,        this, &FixedWingLandingComplexItem::_setDirty);
97

98 99 100 101 102 103 104 105
    connect(this,                       &FixedWingLandingComplexItem::altitudesAreRelativeChanged,      this, &FixedWingLandingComplexItem::_amslEntryAltChanged);
    connect(this,                       &FixedWingLandingComplexItem::altitudesAreRelativeChanged,      this, &FixedWingLandingComplexItem::_amslExitAltChanged);
    connect(_missionController,         &MissionController::plannedHomePositionChanged,                 this, &FixedWingLandingComplexItem::_amslEntryAltChanged);
    connect(_missionController,         &MissionController::plannedHomePositionChanged,                 this, &FixedWingLandingComplexItem::_amslExitAltChanged);
    connect(&_loiterAltitudeFact,       &Fact::valueChanged,                                            this, &FixedWingLandingComplexItem::_amslEntryAltChanged);
    connect(&_landingAltitudeFact,      &Fact::valueChanged,                                            this, &FixedWingLandingComplexItem::_amslExitAltChanged);
    connect(this,                       &FixedWingLandingComplexItem::amslEntryAltChanged,              this, &FixedWingLandingComplexItem::maxAMSLAltitudeChanged);
    connect(this,                       &FixedWingLandingComplexItem::amslExitAltChanged,               this, &FixedWingLandingComplexItem::minAMSLAltitudeChanged);
106

DonLakeFlyer's avatar
DonLakeFlyer committed
107
    connect(this,                       &FixedWingLandingComplexItem::landingCoordSetChanged,           this, &FixedWingLandingComplexItem::readyForSaveStateChanged);
108 109
    connect(this,                       &FixedWingLandingComplexItem::wizardModeChanged,                this, &FixedWingLandingComplexItem::readyForSaveStateChanged);

110 111 112 113 114 115 116 117 118 119 120
    connect(this,                       &FixedWingLandingComplexItem::loiterTangentCoordinateChanged,   this, &FixedWingLandingComplexItem::_updateFlightPathSegmentsSignal);
    connect(this,                       &FixedWingLandingComplexItem::landingCoordinateChanged,         this, &FixedWingLandingComplexItem::_updateFlightPathSegmentsSignal);
    connect(&_loiterAltitudeFact,       &Fact::valueChanged,                                            this, &FixedWingLandingComplexItem::_updateFlightPathSegmentsSignal);
    connect(&_landingAltitudeFact,      &Fact::valueChanged,                                            this, &FixedWingLandingComplexItem::_updateFlightPathSegmentsSignal);
    connect(this,                       &FixedWingLandingComplexItem::altitudesAreRelativeChanged,      this, &FixedWingLandingComplexItem::_updateFlightPathSegmentsSignal);
    connect(_missionController,         &MissionController::plannedHomePositionChanged,                 this, &FixedWingLandingComplexItem::_updateFlightPathSegmentsSignal);

    // The follow is used to compress multiple recalc calls in a row to into a single call.
    connect(this, &FixedWingLandingComplexItem::_updateFlightPathSegmentsSignal, this, &FixedWingLandingComplexItem::_updateFlightPathSegmentsDontCallDirectly,   Qt::QueuedConnection);
    qgcApp()->addCompressedSignal(QMetaMethod::fromSignal(&FixedWingLandingComplexItem::_updateFlightPathSegmentsSignal));

121
    if (_masterController->controllerVehicle()->apmFirmware()) {
122 123 124 125 126
        // ArduPilot does not support camera commands
        _stopTakingVideoFact.setRawValue(false);
        _stopTakingPhotosFact.setRawValue(false);
    }

127 128 129 130 131 132
    if (_valueSetIsDistanceFact.rawValue().toBool()) {
        _recalcFromHeadingAndDistanceChange();
    } else {
        _glideSlopeChanged();
    }
    setDirty(false);
133 134 135 136
}

int FixedWingLandingComplexItem::lastSequenceNumber(void) const
{
137 138 139 140 141
    // Fixed items are:
    //  land start, loiter, land
    // Optional items are:
    //  stop photos/video
    return _sequenceNumber + 2 + (_stopTakingPhotosFact.rawValue().toBool() ? 2 : 0) + (_stopTakingVideoFact.rawValue().toBool() ? 1 : 0);
142 143 144 145 146 147 148 149 150 151
}

void FixedWingLandingComplexItem::setDirty(bool dirty)
{
    if (_dirty != dirty) {
        _dirty = dirty;
        emit dirtyChanged(_dirty);
    }
}

152
void FixedWingLandingComplexItem::save(QJsonArray&  missionItems)
153
{
154 155
    QJsonObject saveObject;

156
    saveObject[JsonHelper::jsonVersionKey] =                    2;
157 158 159
    saveObject[VisualMissionItem::jsonTypeKey] =                VisualMissionItem::jsonTypeComplexItemValue;
    saveObject[ComplexMissionItem::jsonComplexItemTypeKey] =    jsonComplexItemTypeValue;

160 161 162 163 164 165 166 167 168 169 170 171 172
    QGeoCoordinate coordinate;
    QJsonValue jsonCoordinate;

    coordinate = _loiterCoordinate;
    coordinate.setAltitude(_loiterAltitudeFact.rawValue().toDouble());
    JsonHelper::saveGeoCoordinate(coordinate, true /* writeAltitude */, jsonCoordinate);
    saveObject[_jsonLoiterCoordinateKey] = jsonCoordinate;

    coordinate = _landingCoordinate;
    coordinate.setAltitude(_landingAltitudeFact.rawValue().toDouble());
    JsonHelper::saveGeoCoordinate(coordinate, true /* writeAltitude */, jsonCoordinate);
    saveObject[_jsonLandingCoordinateKey] = jsonCoordinate;

173
    saveObject[_jsonLoiterRadiusKey] =          _loiterRadiusFact.rawValue().toDouble();
174 175
    saveObject[_jsonStopTakingPhotosKey] =      _stopTakingPhotosFact.rawValue().toBool();
    saveObject[_jsonStopTakingVideoKey] =       _stopTakingVideoFact.rawValue().toBool();
176 177
    saveObject[_jsonLoiterClockwiseKey] =       _loiterClockwise;
    saveObject[_jsonAltitudesAreRelativeKey] =  _altitudesAreRelative;
178
    saveObject[_jsonValueSetIsDistanceKey] =    _valueSetIsDistanceFact.rawValue().toBool();
179 180

    missionItems.append(saveObject);
181 182 183 184 185 186 187 188 189 190 191 192 193
}

void FixedWingLandingComplexItem::setSequenceNumber(int sequenceNumber)
{
    if (_sequenceNumber != sequenceNumber) {
        _sequenceNumber = sequenceNumber;
        emit sequenceNumberChanged(sequenceNumber);
        emit lastSequenceNumberChanged(lastSequenceNumber());
    }
}

bool FixedWingLandingComplexItem::load(const QJsonObject& complexObject, int sequenceNumber, QString& errorString)
{
194 195 196 197 198 199 200 201
    QList<JsonHelper::KeyValidateInfo> keyInfoList = {
        { JsonHelper::jsonVersionKey,                   QJsonValue::Double, true },
        { VisualMissionItem::jsonTypeKey,               QJsonValue::String, true },
        { ComplexMissionItem::jsonComplexItemTypeKey,   QJsonValue::String, true },
        { _jsonLoiterCoordinateKey,                     QJsonValue::Array,  true },
        { _jsonLoiterRadiusKey,                         QJsonValue::Double, true },
        { _jsonLoiterClockwiseKey,                      QJsonValue::Bool,   true },
        { _jsonLandingCoordinateKey,                    QJsonValue::Array,  true },
202 203
        { _jsonStopTakingPhotosKey,                     QJsonValue::Bool,   false },
        { _jsonStopTakingVideoKey,                      QJsonValue::Bool,   false },
204 205 206 207
    };
    if (!JsonHelper::validateKeys(complexObject, keyInfoList, errorString)) {
        return false;
    }
208

209 210 211
    QString itemType = complexObject[VisualMissionItem::jsonTypeKey].toString();
    QString complexType = complexObject[ComplexMissionItem::jsonComplexItemTypeKey].toString();
    if (itemType != VisualMissionItem::jsonTypeComplexItemValue || complexType != jsonComplexItemTypeValue) {
212
        errorString = tr("%1 does not support loading this complex mission item type: %2:%3").arg(qgcApp()->applicationName()).arg(itemType).arg(complexType);
213 214
        return false;
    }
215

216
    setSequenceNumber(sequenceNumber);
217

218 219
    _ignoreRecalcSignals = true;

220 221
    int version = complexObject[JsonHelper::jsonVersionKey].toInt();
    if (version == 1) {
DonLakeFlyer's avatar
DonLakeFlyer committed
222 223 224 225 226 227 228 229
        QList<JsonHelper::KeyValidateInfo> v1KeyInfoList = {
            { _jsonLoiterAltitudeRelativeKey,   QJsonValue::Bool,  true },
            { _jsonLandingAltitudeRelativeKey,  QJsonValue::Bool,  true },
        };
        if (!JsonHelper::validateKeys(complexObject, v1KeyInfoList, errorString)) {
            return false;
        }

230 231 232
        bool loiterAltitudeRelative = complexObject[_jsonLoiterAltitudeRelativeKey].toBool();
        bool landingAltitudeRelative = complexObject[_jsonLandingAltitudeRelativeKey].toBool();
        if (loiterAltitudeRelative != landingAltitudeRelative) {
233
            qgcApp()->showAppMessage(tr("Fixed Wing Landing Pattern: "
234 235
                                        "Setting the loiter and landing altitudes with different settings for altitude relative is no longer supported. "
                                        "Both have been set to altitude relative. Be sure to adjust/check your plan prior to flight."));
236 237 238 239
            _altitudesAreRelative = true;
        } else {
            _altitudesAreRelative = loiterAltitudeRelative;
        }
240
        _valueSetIsDistanceFact.setRawValue(true);
241 242 243
    } else if (version == 2) {
        QList<JsonHelper::KeyValidateInfo> v2KeyInfoList = {
            { _jsonAltitudesAreRelativeKey, QJsonValue::Bool,  true },
DonLakeFlyer's avatar
DonLakeFlyer committed
244
            { _jsonValueSetIsDistanceKey,   QJsonValue::Bool,  true },
245 246
        };
        if (!JsonHelper::validateKeys(complexObject, v2KeyInfoList, errorString)) {
DonLakeFlyer's avatar
DonLakeFlyer committed
247
            _ignoreRecalcSignals = false;
248 249
            return false;
        }
DonLakeFlyer's avatar
DonLakeFlyer committed
250 251

        _altitudesAreRelative = complexObject[_jsonAltitudesAreRelativeKey].toBool();
252
        _valueSetIsDistanceFact.setRawValue(complexObject[_jsonValueSetIsDistanceKey].toBool());
253 254 255 256 257 258
    } else {
        errorString = tr("%1 complex item version %2 not supported").arg(jsonComplexItemTypeValue).arg(version);
        _ignoreRecalcSignals = false;
        return false;
    }

259 260 261 262 263 264
    QGeoCoordinate coordinate;
    if (!JsonHelper::loadGeoCoordinate(complexObject[_jsonLoiterCoordinateKey], true /* altitudeRequired */, coordinate, errorString)) {
        return false;
    }
    _loiterCoordinate = coordinate;
    _loiterAltitudeFact.setRawValue(coordinate.altitude());
265

266 267
    if (!JsonHelper::loadGeoCoordinate(complexObject[_jsonLandingCoordinateKey], true /* altitudeRequired */, coordinate, errorString)) {
        return false;
268
    }
269 270 271 272
    _landingCoordinate = coordinate;
    _landingAltitudeFact.setRawValue(coordinate.altitude());

    _loiterRadiusFact.setRawValue(complexObject[_jsonLoiterRadiusKey].toDouble());
273
    _loiterClockwise = complexObject[_jsonLoiterClockwiseKey].toBool();
DonLakeFlyer's avatar
DonLakeFlyer committed
274

275 276 277 278 279 280 281 282 283 284 285
    if (complexObject.contains(_jsonStopTakingPhotosKey)) {
        _stopTakingPhotosFact.setRawValue(complexObject[_jsonStopTakingPhotosKey].toBool());
    } else {
        _stopTakingPhotosFact.setRawValue(false);
    }
    if (complexObject.contains(_jsonStopTakingVideoKey)) {
        _stopTakingVideoFact.setRawValue(complexObject[_jsonStopTakingVideoKey].toBool());
    } else {
        _stopTakingVideoFact.setRawValue(false);
    }

DonLakeFlyer's avatar
DonLakeFlyer committed
286
    _calcGlideSlope();
287

288
    _landingCoordSet = true;
289 290

    _ignoreRecalcSignals = false;
291

292
    _recalcFromCoordinateChange();
293
    emit coordinateChanged(this->coordinate());    // This will kick off terrain query
294 295 296 297 298 299 300

    return true;
}

double FixedWingLandingComplexItem::greatestDistanceTo(const QGeoCoordinate &other) const
{
    return qMax(_loiterCoordinate.distanceTo(other),_landingCoordinate.distanceTo(other));
301 302 303 304 305 306 307
}

bool FixedWingLandingComplexItem::specifiesCoordinate(void) const
{
    return true;
}

308
MissionItem* FixedWingLandingComplexItem::createDoLandStartItem(int seqNum, QObject* parent)
309
{
310 311 312 313 314 315 316 317
    return new MissionItem(seqNum,                              // sequence number
                           MAV_CMD_DO_LAND_START,               // MAV_CMD
                           MAV_FRAME_MISSION,                   // MAV_FRAME
                           0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,   // param 1-7
                           true,                                // autoContinue
                           false,                               // isCurrentItem
                           parent);
}
318

319 320 321
MissionItem* FixedWingLandingComplexItem::createLoiterToAltItem(int seqNum, bool altRel, double loiterRadius, double lat, double lon, double alt, QObject* parent)
{
    return new MissionItem(seqNum,
322
                           MAV_CMD_NAV_LOITER_TO_ALT,
323
                           altRel ? MAV_FRAME_GLOBAL_RELATIVE_ALT : MAV_FRAME_GLOBAL,
324 325 326
                           1.0,                             // Heading required = true
                           loiterRadius,                    // Loiter radius
                           0.0,                             // param 3 - unused
Don Gagne's avatar
Don Gagne committed
327
                           1.0,                             // Exit crosstrack - tangent of loiter to land point
328
                           lat, lon, alt,
329 330
                           true,                            // autoContinue
                           false,                           // isCurrentItem
331 332
                           parent);
}
333

334 335 336
MissionItem* FixedWingLandingComplexItem::createLandItem(int seqNum, bool altRel, double lat, double lon, double alt, QObject* parent)
{
    return new MissionItem(seqNum,
337
                           MAV_CMD_NAV_LAND,
338 339 340
                           altRel ? MAV_FRAME_GLOBAL_RELATIVE_ALT : MAV_FRAME_GLOBAL,
                           0.0, 0.0, 0.0, 0.0,
                           lat, lon, alt,
341 342
                           true,                               // autoContinue
                           false,                              // isCurrentItem
343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376
                           parent);

}

void FixedWingLandingComplexItem::appendMissionItems(QList<MissionItem*>& items, QObject* missionItemParent)
{
    int seqNum = _sequenceNumber;

    // IMPORTANT NOTE: Any changes here must also be taken into account in scanForItem

    MissionItem* item = createDoLandStartItem(seqNum++, missionItemParent);
    items.append(item);


    if (_stopTakingPhotosFact.rawValue().toBool()) {
        CameraSection::appendStopTakingPhotos(items, seqNum, missionItemParent);
    }

    if (_stopTakingVideoFact.rawValue().toBool()) {
        CameraSection::appendStopTakingVideo(items, seqNum, missionItemParent);
    }

    double loiterRadius = _loiterRadiusFact.rawValue().toDouble() * (_loiterClockwise ? 1.0 : -1.0);
    item = createLoiterToAltItem(seqNum++,
                                 _altitudesAreRelative,
                                 loiterRadius,
                                 _loiterCoordinate.latitude(), _loiterCoordinate.longitude(), _loiterAltitudeFact.rawValue().toDouble(),
                                 missionItemParent);
    items.append(item);

    item = createLandItem(seqNum++,
                          _altitudesAreRelative,
                          _landingCoordinate.latitude(), _landingCoordinate.longitude(), _landingAltitudeFact.rawValue().toDouble(),
                          missionItemParent);
377
    items.append(item);
378 379
}

380
bool FixedWingLandingComplexItem::scanForItem(QmlObjectListModel* visualItems, bool flyView, PlanMasterController* masterController)
381 382 383
{
    qCDebug(FixedWingLandingComplexItemLog) << "FixedWingLandingComplexItem::scanForItem count" << visualItems->count();

384
    if (visualItems->count() < 3) {
385 386 387
        return false;
    }

388 389 390 391 392 393
    // A valid fixed wing landing pattern is comprised of the follow commands in this order at the end of the item list:
    //  MAV_CMD_DO_LAND_START - required
    //  Stop taking photos sequence - optional
    //  Stop taking video sequence - optional
    //  MAV_CMD_NAV_LOITER_TO_ALT - required
    //  MAV_CMD_NAV_LAND - required
394

395 396 397 398 399 400 401 402
    // Start looking for the commands in reverse order from the end of the list

    int scanIndex = visualItems->count() - 1;

    if (scanIndex < 0 || scanIndex > visualItems->count() - 1) {
        return false;
    }
    SimpleMissionItem* item = visualItems->value<SimpleMissionItem*>(scanIndex--);
403 404 405 406 407 408
    if (!item) {
        return false;
    }
    MissionItem& missionItemLand = item->missionItem();
    if (missionItemLand.command() != MAV_CMD_NAV_LAND ||
            !(missionItemLand.frame() == MAV_FRAME_GLOBAL_RELATIVE_ALT || missionItemLand.frame() == MAV_FRAME_GLOBAL) ||
Don Gagne's avatar
Don Gagne committed
409
            missionItemLand.param1() != 0 || missionItemLand.param2() != 0 || missionItemLand.param3() != 0 || missionItemLand.param4() != 0) {
410 411
        return false;
    }
412
    MAV_FRAME landPointFrame = missionItemLand.frame();
413

414 415 416 417
    if (scanIndex < 0 || scanIndex > visualItems->count() - 1) {
        return false;
    }
    item = visualItems->value<SimpleMissionItem*>(scanIndex);
418 419 420 421 422
    if (!item) {
        return false;
    }
    MissionItem& missionItemLoiter = item->missionItem();
    if (missionItemLoiter.command() != MAV_CMD_NAV_LOITER_TO_ALT ||
423
            missionItemLoiter.frame() != landPointFrame ||
424 425 426 427
            missionItemLoiter.param1() != 1.0 || missionItemLoiter.param3() != 0 || missionItemLoiter.param4() != 1.0) {
        return false;
    }

428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444
    scanIndex -= CameraSection::stopTakingVideoCommandCount();
    bool stopTakingVideo = CameraSection::scanStopTakingVideo(visualItems, scanIndex, false /* removeScannedItems */);
    if (!stopTakingVideo) {
        scanIndex += CameraSection::stopTakingVideoCommandCount();
    }

    scanIndex -= CameraSection::stopTakingPhotosCommandCount();
    bool stopTakingPhotos = CameraSection::scanStopTakingPhotos(visualItems, scanIndex, false /* removeScannedItems */);
    if (!stopTakingPhotos) {
        scanIndex += CameraSection::stopTakingPhotosCommandCount();
    }

    scanIndex--;
    if (scanIndex < 0 || scanIndex > visualItems->count() - 1) {
        return false;
    }
    item = visualItems->value<SimpleMissionItem*>(scanIndex);
445 446 447 448 449
    if (!item) {
        return false;
    }
    MissionItem& missionItemDoLandStart = item->missionItem();
    if (missionItemDoLandStart.command() != MAV_CMD_DO_LAND_START ||
Don Gagne's avatar
Don Gagne committed
450
            missionItemDoLandStart.frame() != MAV_FRAME_MISSION ||
451
            missionItemDoLandStart.param1() != 0 || missionItemDoLandStart.param2() != 0 || missionItemDoLandStart.param3() != 0 || missionItemDoLandStart.param4() != 0|| missionItemDoLandStart.param5() != 0|| missionItemDoLandStart.param6() != 0) {
452 453 454
        return false;
    }

455 456 457 458 459 460 461 462 463 464 465 466 467 468 469
    // We made it this far so we do have a Fixed Wing Landing Pattern item at the end of the mission.
    // Since we have scanned it we need to remove the items for it fromt the list
    int deleteCount = 3;
    if (stopTakingPhotos) {
        deleteCount += CameraSection::stopTakingPhotosCommandCount();
    }
    if (stopTakingVideo) {
        deleteCount += CameraSection::stopTakingVideoCommandCount();
    }
    int firstItem = visualItems->count() - deleteCount;
    while (deleteCount--) {
        visualItems->removeAt(firstItem)->deleteLater();
    }

    // Now stuff all the scanned information into the item
470

471
    FixedWingLandingComplexItem* complexItem = new FixedWingLandingComplexItem(masterController, flyView, visualItems);
472 473 474

    complexItem->_ignoreRecalcSignals = true;

475
    complexItem->_altitudesAreRelative = landPointFrame == MAV_FRAME_GLOBAL_RELATIVE_ALT;
476 477
    complexItem->_loiterRadiusFact.setRawValue(qAbs(missionItemLoiter.param2()));
    complexItem->_loiterClockwise = missionItemLoiter.param2() > 0;
478
    complexItem->setLoiterCoordinate(QGeoCoordinate(missionItemLoiter.param5(), missionItemLoiter.param6()));
479 480 481 482 483 484
    complexItem->_loiterAltitudeFact.setRawValue(missionItemLoiter.param7());

    complexItem->_landingCoordinate.setLatitude(missionItemLand.param5());
    complexItem->_landingCoordinate.setLongitude(missionItemLand.param6());
    complexItem->_landingAltitudeFact.setRawValue(missionItemLand.param7());

485 486 487
    complexItem->_stopTakingPhotosFact.setRawValue(stopTakingPhotos);
    complexItem->_stopTakingVideoFact.setRawValue(stopTakingVideo);

DonLakeFlyer's avatar
DonLakeFlyer committed
488 489
    complexItem->_calcGlideSlope();

490 491 492 493 494 495 496 497 498 499 500
    complexItem->_landingCoordSet = true;

    complexItem->_ignoreRecalcSignals = false;
    complexItem->_recalcFromCoordinateChange();
    complexItem->setDirty(false);

    visualItems->append(complexItem);

    return true;
}

501 502
double FixedWingLandingComplexItem::complexDistance(void) const
{
503
    return _loiterCoordinate.distanceTo(_landingCoordinate);
504 505
}

506
void FixedWingLandingComplexItem::setLandingCoordinate(const QGeoCoordinate& coordinate)
507
{
508 509 510 511 512 513 514 515 516 517 518
    if (coordinate != _landingCoordinate) {
        _landingCoordinate = coordinate;
        if (_landingCoordSet) {
            emit exitCoordinateChanged(coordinate);
            emit landingCoordinateChanged(coordinate);
        } else {
            _ignoreRecalcSignals = true;
            emit exitCoordinateChanged(coordinate);
            emit landingCoordinateChanged(coordinate);
            _ignoreRecalcSignals = false;
            _landingCoordSet = true;
519
            _recalcFromHeadingAndDistanceChange();
520 521 522 523
            emit landingCoordSetChanged(true);
        }
    }
}
524

525 526 527 528 529 530 531 532
void FixedWingLandingComplexItem::setLoiterCoordinate(const QGeoCoordinate& coordinate)
{
    if (coordinate != _loiterCoordinate) {
        _loiterCoordinate = coordinate;
        emit coordinateChanged(coordinate);
        emit loiterCoordinateChanged(coordinate);
    }
}
533

534
double FixedWingLandingComplexItem::_mathematicAngleToHeading(double angle)
535
{
536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565
    double heading = (angle - 90) * -1;
    if (heading < 0) {
        heading += 360;
    }

    return heading;
}

double FixedWingLandingComplexItem::_headingToMathematicAngle(double heading)
{
    return heading - 90 * -1;
}

void FixedWingLandingComplexItem::_recalcFromRadiusChange(void)
{
    // Fixed:
    //      land
    //      loiter tangent
    //      distance
    //      radius
    //      heading
    // Adjusted:
    //      loiter

    if (!_ignoreRecalcSignals) {
        // These are our known values
        double radius  = _loiterRadiusFact.rawValue().toDouble();
        double landToTangentDistance = _landingDistanceFact.rawValue().toDouble();
        double heading = _landingHeadingFact.rawValue().toDouble();

566 567 568 569
        double landToLoiterDistance = _landingCoordinate.distanceTo(_loiterCoordinate);
        if (landToLoiterDistance < radius) {
            // Degnenerate case: Move tangent to loiter point
            _loiterTangentCoordinate = _loiterCoordinate;
570

571
            double heading = _landingCoordinate.azimuthTo(_loiterTangentCoordinate);
572

573 574 575 576 577 578 579 580 581
            _ignoreRecalcSignals = true;
            _landingHeadingFact.setRawValue(heading);
            emit loiterTangentCoordinateChanged(_loiterTangentCoordinate);
            _ignoreRecalcSignals = false;
        } else {
            double landToLoiterDistance = qSqrt(qPow(radius, 2) + qPow(landToTangentDistance, 2));
            double angleLoiterToTangent = qRadiansToDegrees(qAsin(radius/landToLoiterDistance)) * (_loiterClockwise ? -1 : 1);

            _loiterCoordinate = _landingCoordinate.atDistanceAndAzimuth(landToLoiterDistance, heading + 180 + angleLoiterToTangent);
582
            _loiterCoordinate.setAltitude(_loiterAltitudeFact.rawValue().toDouble());
583 584 585

            _ignoreRecalcSignals = true;
            emit loiterCoordinateChanged(_loiterCoordinate);
586
            emit coordinateChanged(_loiterCoordinate);
587 588
            _ignoreRecalcSignals = false;
        }
589 590
    }
}
591

592 593 594 595 596 597 598 599 600 601
void FixedWingLandingComplexItem::_recalcFromHeadingAndDistanceChange(void)
{
    // Fixed:
    //      land
    //      heading
    //      distance
    //      radius
    // Adjusted:
    //      loiter
    //      loiter tangent
602
    //      glide slope
603

604 605 606 607
    if (!_ignoreRecalcSignals && _landingCoordSet) {
        // These are our known values
        double radius = _loiterRadiusFact.rawValue().toDouble();
        double landToTangentDistance = _landingDistanceFact.rawValue().toDouble();
608 609
        double heading = _landingHeadingFact.rawValue().toDouble();

610 611 612 613 614 615 616 617
        // Calculate loiter tangent coordinate
        _loiterTangentCoordinate = _landingCoordinate.atDistanceAndAzimuth(landToTangentDistance, heading + 180);

        // Calculate the distance and angle to the loiter coordinate
        QGeoCoordinate tangent = _landingCoordinate.atDistanceAndAzimuth(landToTangentDistance, 0);
        QGeoCoordinate loiter = tangent.atDistanceAndAzimuth(radius, 90);
        double loiterDistance = _landingCoordinate.distanceTo(loiter);
        double loiterAzimuth = _landingCoordinate.azimuthTo(loiter) * (_loiterClockwise ? -1 : 1);
618

619 620
        // Use those values to get the new loiter point which takes heading into acount
        _loiterCoordinate = _landingCoordinate.atDistanceAndAzimuth(loiterDistance, heading + 180 + loiterAzimuth);
621
        _loiterCoordinate.setAltitude(_loiterAltitudeFact.rawValue().toDouble());
622 623

        _ignoreRecalcSignals = true;
624
        emit loiterTangentCoordinateChanged(_loiterTangentCoordinate);
625
        emit loiterCoordinateChanged(_loiterCoordinate);
626
        emit coordinateChanged(_loiterCoordinate);
627
        _calcGlideSlope();
628 629
        _ignoreRecalcSignals = false;
    }
630 631 632 633 634 635 636 637 638 639 640 641
}

QPointF FixedWingLandingComplexItem::_rotatePoint(const QPointF& point, const QPointF& origin, double angle)
{
    QPointF rotated;
    double radians = (M_PI / 180.0) * angle;

    rotated.setX(((point.x() - origin.x()) * cos(radians)) - ((point.y() - origin.y()) * sin(radians)) + origin.x());
    rotated.setY(((point.x() - origin.x()) * sin(radians)) + ((point.y() - origin.y()) * cos(radians)) + origin.y());

    return rotated;
}
642

643
void FixedWingLandingComplexItem::_recalcFromCoordinateChange(void)
644
{
645 646 647 648 649 650 651 652
    // Fixed:
    //      land
    //      loiter
    //      radius
    // Adjusted:
    //      loiter tangent
    //      heading
    //      distance
653
    //      glide slope
654

655 656 657 658 659
    if (!_ignoreRecalcSignals && _landingCoordSet) {
        // These are our known values
        double radius = _loiterRadiusFact.rawValue().toDouble();
        double landToLoiterDistance = _landingCoordinate.distanceTo(_loiterCoordinate);
        double landToLoiterHeading = _landingCoordinate.azimuthTo(_loiterCoordinate);
660

661 662 663 664 665 666 667 668
        double landToTangentDistance;
        if (landToLoiterDistance < radius) {
            // Degenerate case, set tangent to loiter coordinate
            _loiterTangentCoordinate = _loiterCoordinate;
            landToTangentDistance = _landingCoordinate.distanceTo(_loiterTangentCoordinate);
        } else {
            double loiterToTangentAngle = qRadiansToDegrees(qAsin(radius/landToLoiterDistance)) * (_loiterClockwise ? 1 : -1);
            landToTangentDistance = qSqrt(qPow(landToLoiterDistance, 2) - qPow(radius, 2));
669

670 671 672
            _loiterTangentCoordinate = _landingCoordinate.atDistanceAndAzimuth(landToTangentDistance, landToLoiterHeading + loiterToTangentAngle);

        }
673

674
        double heading = _loiterTangentCoordinate.azimuthTo(_landingCoordinate);
675

676 677 678 679
        _ignoreRecalcSignals = true;
        _landingHeadingFact.setRawValue(heading);
        _landingDistanceFact.setRawValue(landToTangentDistance);
        emit loiterTangentCoordinateChanged(_loiterTangentCoordinate);
680
        _calcGlideSlope();
681 682 683
        _ignoreRecalcSignals = false;
    }
}
684 685 686 687

void FixedWingLandingComplexItem::_updateLoiterCoodinateAltitudeFromFact(void)
{
    _loiterCoordinate.setAltitude(_loiterAltitudeFact.rawValue().toDouble());
688 689
    emit loiterCoordinateChanged(_loiterCoordinate);
    emit coordinateChanged(_loiterCoordinate);
690 691 692 693 694
}

void FixedWingLandingComplexItem::_updateLandingCoodinateAltitudeFromFact(void)
{
    _landingCoordinate.setAltitude(_landingAltitudeFact.rawValue().toDouble());
695
    emit landingCoordinateChanged(_landingCoordinate);
696
}
697 698 699 700 701

void FixedWingLandingComplexItem::_setDirty(void)
{
    setDirty(true);
}
702

DonLakeFlyer's avatar
DonLakeFlyer committed
703 704 705 706
void FixedWingLandingComplexItem::applyNewAltitude(double newAltitude)
{
    _loiterAltitudeFact.setRawValue(newAltitude);
}
707 708 709 710 711 712 713 714 715 716 717 718 719 720 721 722 723

void FixedWingLandingComplexItem::_glideSlopeChanged(void)
{
    if (!_ignoreRecalcSignals) {
        double landingAltDifference = _loiterAltitudeFact.rawValue().toDouble() - _landingAltitudeFact.rawValue().toDouble();
        double glideSlope = _glideSlopeFact.rawValue().toDouble();
        _landingDistanceFact.setRawValue(landingAltDifference / qTan(qDegreesToRadians(glideSlope)));
    }
}

void FixedWingLandingComplexItem::_calcGlideSlope(void)
{
    double landingAltDifference = _loiterAltitudeFact.rawValue().toDouble() - _landingAltitudeFact.rawValue().toDouble();
    double landingDistance = _landingDistanceFact.rawValue().toDouble();

    _glideSlopeFact.setRawValue(qRadiansToDegrees(qAtan(landingAltDifference / landingDistance)));
}
724 725 726 727 728

void FixedWingLandingComplexItem::_signalLastSequenceNumberChanged(void)
{
    emit lastSequenceNumberChanged(lastSequenceNumber());
}
DonLakeFlyer's avatar
DonLakeFlyer committed
729 730 731

FixedWingLandingComplexItem::ReadyForSaveState FixedWingLandingComplexItem::readyForSaveState(void) const
{
732 733 734
    return _landingCoordSet && !_wizardMode ? ReadyForSave : NotReadyForSaveData;
}

735
void FixedWingLandingComplexItem::moveLandingPosition(const QGeoCoordinate& coordinate)
736
{
737 738 739 740 741 742
    double savedHeading = landingHeading()->rawValue().toDouble();
    double savedDistance = landingDistance()->rawValue().toDouble();

    setLandingCoordinate(coordinate);
    landingHeading()->setRawValue(savedHeading);
    landingDistance()->setRawValue(savedDistance);
DonLakeFlyer's avatar
DonLakeFlyer committed
743
}
744 745 746 747 748 749 750 751 752 753 754 755 756 757 758 759 760 761 762 763 764 765 766 767 768 769 770 771 772 773 774 775

double FixedWingLandingComplexItem::amslEntryAlt(void) const
{
    return _loiterAltitudeFact.rawValue().toDouble() + (_altitudesAreRelative ? _missionController->plannedHomePosition().altitude() : 0);
}

double FixedWingLandingComplexItem::amslExitAlt(void) const
{
    return _landingAltitudeFact.rawValue().toDouble() + (_altitudesAreRelative ? _missionController->plannedHomePosition().altitude() : 0);

}

// Never call this method directly. If you want to update the flight segments you emit _updateFlightPathSegmentsSignal()
void FixedWingLandingComplexItem::_updateFlightPathSegmentsDontCallDirectly(void)
{
    if (_cTerrainCollisionSegments != 0) {
        _cTerrainCollisionSegments = 0;
        emit terrainCollisionChanged(false);
    }

    _flightPathSegments.beginReset();
    _flightPathSegments.clearAndDeleteContents();
    _appendFlightPathSegment(_loiterTangentCoordinate, amslEntryAlt(), _landingCoordinate, amslExitAlt());  // Loiter to land
    _appendFlightPathSegment(_landingCoordinate, amslEntryAlt(), _landingCoordinate, amslExitAlt());        // Land to ground
    _flightPathSegments.endReset();

    if (_cTerrainCollisionSegments != 0) {
        emit terrainCollisionChanged(true);
    }

    _masterController->missionController()->recalcTerrainProfile();
}