SurveyComplexItem.cc 61.9 KB
Newer Older
1 2 3 4 5 6 7 8 9 10
/****************************************************************************
 *
 *   (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/


11
#include "SurveyComplexItem.h"
12 13 14
#include "JsonHelper.h"
#include "MissionController.h"
#include "QGCGeo.h"
15
#include "QGroundControlQmlGlobal.h"
16
#include "QGCQGeoCoordinate.h"
17 18
#include "SettingsManager.h"
#include "AppSettings.h"
19 20 21

#include <QPolygonF>

22 23
QGC_LOGGING_CATEGORY(SurveyComplexItemLog, "SurveyComplexItemLog")

24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59
const char* SurveyComplexItem::jsonComplexItemTypeValue =   "survey";
const char* SurveyComplexItem::jsonV3ComplexItemTypeValue = "survey";

const char* SurveyComplexItem::settingsGroup =              "Survey";
const char* SurveyComplexItem::gridAngleName =              "GridAngle";
const char* SurveyComplexItem::gridEntryLocationName =      "GridEntryLocation";

const char* SurveyComplexItem::_jsonGridAngleKey =          "angle";
const char* SurveyComplexItem::_jsonGridEntryLocationKey =  "entryLocation";

const char* SurveyComplexItem::_jsonV3GridObjectKey =                   "grid";
const char* SurveyComplexItem::_jsonV3GridAltitudeKey =                 "altitude";
const char* SurveyComplexItem::_jsonV3GridAltitudeRelativeKey =         "relativeAltitude";
const char* SurveyComplexItem::_jsonV3GridAngleKey =                    "angle";
const char* SurveyComplexItem::_jsonV3GridSpacingKey =                  "spacing";
const char* SurveyComplexItem::_jsonV3GridEntryLocationKey =            "entryLocation";
const char* SurveyComplexItem::_jsonV3TurnaroundDistKey =               "turnAroundDistance";
const char* SurveyComplexItem::_jsonV3CameraTriggerDistanceKey =        "cameraTriggerDistance";
const char* SurveyComplexItem::_jsonV3CameraTriggerInTurnaroundKey =    "cameraTriggerInTurnaround";
const char* SurveyComplexItem::_jsonV3HoverAndCaptureKey =              "hoverAndCapture";
const char* SurveyComplexItem::_jsonV3GroundResolutionKey =             "groundResolution";
const char* SurveyComplexItem::_jsonV3FrontalOverlapKey =               "imageFrontalOverlap";
const char* SurveyComplexItem::_jsonV3SideOverlapKey =                  "imageSideOverlap";
const char* SurveyComplexItem::_jsonV3CameraSensorWidthKey =            "sensorWidth";
const char* SurveyComplexItem::_jsonV3CameraSensorHeightKey =           "sensorHeight";
const char* SurveyComplexItem::_jsonV3CameraResolutionWidthKey =        "resolutionWidth";
const char* SurveyComplexItem::_jsonV3CameraResolutionHeightKey =       "resolutionHeight";
const char* SurveyComplexItem::_jsonV3CameraFocalLengthKey =            "focalLength";
const char* SurveyComplexItem::_jsonV3CameraMinTriggerIntervalKey =     "minTriggerInterval";
const char* SurveyComplexItem::_jsonV3CameraObjectKey =                 "camera";
const char* SurveyComplexItem::_jsonV3CameraNameKey =                   "name";
const char* SurveyComplexItem::_jsonV3ManualGridKey =                   "manualGrid";
const char* SurveyComplexItem::_jsonV3CameraOrientationLandscapeKey =   "orientationLandscape";
const char* SurveyComplexItem::_jsonV3FixedValueIsAltitudeKey =         "fixedValueIsAltitude";
const char* SurveyComplexItem::_jsonV3Refly90DegreesKey =               "refly90Degrees";

60 61

SurveyComplexItem::SurveyComplexItem(Vehicle* vehicle, QObject* parent)
62 63 64 65
    : TransectStyleComplexItem  (vehicle, settingsGroup, parent)
    , _metaDataMap              (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/Survey.SettingsGroup.json"), this))
    , _gridAngleFact            (settingsGroup, _metaDataMap[gridAngleName])
    , _gridEntryLocationFact    (settingsGroup, _metaDataMap[gridEntryLocationName])
66
{
67 68
    _editorQml = "qrc:/qml/SurveyItemEditor.qml";

69
    // If the user hasn't changed turnaround from the default (which is a fixed wing default) and we are multi-rotor set the multi-rotor default.
70
    // NULL check since object creation during unit testing passes NULL for vehicle
71
    if (_vehicle && _vehicle->multiRotor() && _turnAroundDistanceFact.rawValue().toDouble() == _turnAroundDistanceFact.rawDefaultValue().toDouble()) {
72
        // Note this is set to 10 meters to work around a problem with PX4 Pro turnaround behavior. Don't change unless firmware gets better as well.
73
        _turnAroundDistanceFact.setRawValue(10);
74
    }
Don Gagne's avatar
Don Gagne committed
75

76 77 78
    // We override the altitude to the mission default
    if (_cameraCalc.isManualCamera() || !_cameraCalc.valueSetIsDistance()->rawValue().toBool()) {
        _cameraCalc.distanceToSurface()->setRawValue(qgcApp()->toolbox()->settingsManager()->appSettings()->defaultMissionItemAltitude()->rawValue());
79 80
    }

81 82 83
    connect(&_gridAngleFact,            &Fact::valueChanged,                        this, &SurveyComplexItem::_setDirty);
    connect(&_gridEntryLocationFact,    &Fact::valueChanged,                        this, &SurveyComplexItem::_setDirty);
    connect(this,                       &SurveyComplexItem::refly90DegreesChanged,  this, &SurveyComplexItem::_setDirty);
84

85 86 87
    connect(&_gridAngleFact,            &Fact::valueChanged,                        this, &SurveyComplexItem::_rebuildTransects);
    connect(&_gridEntryLocationFact,    &Fact::valueChanged,                        this, &SurveyComplexItem::_rebuildTransects);
    connect(this,                       &SurveyComplexItem::refly90DegreesChanged,  this, &SurveyComplexItem::_rebuildTransects);
88

89 90 91
    // FIXME: Shouldn't these be in TransectStyleComplexItem? They are also in CorridorScanComplexItem constructur
    connect(&_cameraCalc, &CameraCalc::distanceToSurfaceRelativeChanged, this, &SurveyComplexItem::coordinateHasRelativeAltitudeChanged);
    connect(&_cameraCalc, &CameraCalc::distanceToSurfaceRelativeChanged, this, &SurveyComplexItem::exitCoordinateHasRelativeAltitudeChanged);
92 93
}

94
void SurveyComplexItem::save(QJsonArray&  planItems)
95
{
96
    QJsonObject saveObject;
97

98
    _save(saveObject);
99

100 101 102 103 104
    saveObject[JsonHelper::jsonVersionKey] =                    4;
    saveObject[VisualMissionItem::jsonTypeKey] =                VisualMissionItem::jsonTypeComplexItemValue;
    saveObject[ComplexMissionItem::jsonComplexItemTypeKey] =    jsonComplexItemTypeValue;
    saveObject[_jsonGridAngleKey] =                             _gridAngleFact.rawValue().toDouble();
    saveObject[_jsonGridEntryLocationKey] =                     _gridEntryLocationFact.rawValue().toInt();
105

106 107
    // Polygon shape
    _surveyAreaPolygon.saveToJson(saveObject);
108

109
    planItems.append(saveObject);
110 111
}

112
bool SurveyComplexItem::load(const QJsonObject& complexObject, int sequenceNumber, QString& errorString)
113
{
114 115 116 117 118 119
    // We need to pull version first to determine what validation/conversion needs to be performed
    QList<JsonHelper::KeyValidateInfo> versionKeyInfoList = {
        { JsonHelper::jsonVersionKey, QJsonValue::Double, true },
    };
    if (!JsonHelper::validateKeys(complexObject, versionKeyInfoList, errorString)) {
        return false;
120 121
    }

122 123 124 125
    int version = complexObject[JsonHelper::jsonVersionKey].toInt();
    if (version < 2 || version > 4) {
        errorString = tr("Survey items do not support version %1").arg(version);
        return false;
126
    }
127

128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144
    if (version == 4) {
        if (!_loadV4(complexObject, sequenceNumber, errorString)) {
            return false;
        }
    } else {
        // Must be v2 or v3
        QJsonObject v3ComplexObject = complexObject;
        if (version == 2) {
            // Convert to v3
            if (v3ComplexObject.contains(VisualMissionItem::jsonTypeKey) && v3ComplexObject[VisualMissionItem::jsonTypeKey].toString() == QStringLiteral("survey")) {
                v3ComplexObject[VisualMissionItem::jsonTypeKey] = VisualMissionItem::jsonTypeComplexItemValue;
                v3ComplexObject[ComplexMissionItem::jsonComplexItemTypeKey] = jsonComplexItemTypeValue;
            }
        }
        if (!_loadV3(complexObject, sequenceNumber, errorString)) {
            return false;
        }
Don Gagne's avatar
Don Gagne committed
145
    }
146

147
    _rebuildTransects();
148

149
    return true;
150 151
}

152
bool SurveyComplexItem::_loadV4(const QJsonObject& complexObject, int sequenceNumber, QString& errorString)
153
{
154 155 156 157 158 159 160 161
    QList<JsonHelper::KeyValidateInfo> keyInfoList = {
        { VisualMissionItem::jsonTypeKey,               QJsonValue::String, true },
        { ComplexMissionItem::jsonComplexItemTypeKey,   QJsonValue::String, true },
        { _jsonGridEntryLocationKey,                    QJsonValue::Double, true },
        { _jsonGridAngleKey,                            QJsonValue::Double, true },
    };
    if (!JsonHelper::validateKeys(complexObject, keyInfoList, errorString)) {
        return false;
162
    }
Don Gagne's avatar
Don Gagne committed
163

164 165 166 167
    QString itemType = complexObject[VisualMissionItem::jsonTypeKey].toString();
    QString complexType = complexObject[ComplexMissionItem::jsonComplexItemTypeKey].toString();
    if (itemType != VisualMissionItem::jsonTypeComplexItemValue || complexType != jsonComplexItemTypeValue) {
        errorString = tr("%1 does not support loading this complex mission item type: %2:%3").arg(qgcApp()->applicationName()).arg(itemType).arg(complexType);
168 169
        return false;
    }
Don Gagne's avatar
Don Gagne committed
170

171 172 173 174 175 176
    _ignoreRecalc = true;

    setSequenceNumber(sequenceNumber);

    if (!_surveyAreaPolygon.loadFromJson(complexObject, true /* required */, errorString)) {
        _surveyAreaPolygon.clear();
177 178
        return false;
    }
179 180 181 182

    if (!_load(complexObject, errorString)) {
        _ignoreRecalc = false;
        return false;
Don Gagne's avatar
Don Gagne committed
183
    }
184

185 186 187 188 189 190 191 192 193 194
    _gridAngleFact.setRawValue(complexObject[_jsonGridAngleKey].toDouble());
    _gridEntryLocationFact.setRawValue(complexObject[_jsonGridEntryLocationKey].toInt());

    _ignoreRecalc = false;

    return true;
}

bool SurveyComplexItem::_loadV3(const QJsonObject& complexObject, int sequenceNumber, QString& errorString)
{
Don Gagne's avatar
Don Gagne committed
195 196 197
    QList<JsonHelper::KeyValidateInfo> mainKeyInfoList = {
        { VisualMissionItem::jsonTypeKey,               QJsonValue::String, true },
        { ComplexMissionItem::jsonComplexItemTypeKey,   QJsonValue::String, true },
198
        { QGCMapPolygon::jsonPolygonKey,                QJsonValue::Array,  true },
199 200 201 202 203 204 205 206
        { _jsonV3GridObjectKey,                         QJsonValue::Object, true },
        { _jsonV3CameraObjectKey,                       QJsonValue::Object, false },
        { _jsonV3CameraTriggerDistanceKey,              QJsonValue::Double, true },
        { _jsonV3ManualGridKey,                         QJsonValue::Bool,   true },
        { _jsonV3FixedValueIsAltitudeKey,               QJsonValue::Bool,   true },
        { _jsonV3HoverAndCaptureKey,                    QJsonValue::Bool,   false },
        { _jsonV3Refly90DegreesKey,                     QJsonValue::Bool,   false },
        { _jsonV3CameraTriggerInTurnaroundKey,          QJsonValue::Bool,   false },    // Should really be required, but it was missing from initial code due to bug
Don Gagne's avatar
Don Gagne committed
207
    };
208
    if (!JsonHelper::validateKeys(complexObject, mainKeyInfoList, errorString)) {
209 210
        return false;
    }
Don Gagne's avatar
Don Gagne committed
211

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

219 220
    _ignoreRecalc = true;

Don Gagne's avatar
Don Gagne committed
221
    setSequenceNumber(sequenceNumber);
222

223 224 225 226 227 228
    _hoverAndCaptureFact.setRawValue            (complexObject[_jsonV3HoverAndCaptureKey].toBool(false));
    _refly90DegreesFact.setRawValue             (complexObject[_jsonV3Refly90DegreesKey].toBool(false));
    _cameraTriggerInTurnAroundFact.setRawValue  (complexObject[_jsonV3CameraTriggerInTurnaroundKey].toBool(true));

    _cameraCalc.valueSetIsDistance()->setRawValue   (complexObject[_jsonV3FixedValueIsAltitudeKey].toBool(true));
    _cameraCalc.setDistanceToSurfaceRelative        (complexObject[_jsonV3GridAltitudeRelativeKey].toBool(true));
Don Gagne's avatar
Don Gagne committed
229

230
    bool manualGrid = complexObject[_jsonV3ManualGridKey].toBool(true);
231

Don Gagne's avatar
Don Gagne committed
232
    QList<JsonHelper::KeyValidateInfo> gridKeyInfoList = {
233 234 235 236 237 238
        { _jsonV3GridAltitudeKey,           QJsonValue::Double, true },
        { _jsonV3GridAltitudeRelativeKey,   QJsonValue::Bool,   true },
        { _jsonV3GridAngleKey,              QJsonValue::Double, true },
        { _jsonV3GridSpacingKey,            QJsonValue::Double, true },
        { _jsonV3GridEntryLocationKey,      QJsonValue::Double, false },
        { _jsonV3TurnaroundDistKey,         QJsonValue::Double, true },
Don Gagne's avatar
Don Gagne committed
239
    };
240
    QJsonObject gridObject = complexObject[_jsonV3GridObjectKey].toObject();
Don Gagne's avatar
Don Gagne committed
241
    if (!JsonHelper::validateKeys(gridObject, gridKeyInfoList, errorString)) {
242
        _ignoreRecalc = false;
Don Gagne's avatar
Don Gagne committed
243 244
        return false;
    }
245 246 247 248 249 250

    _gridAngleFact.setRawValue          (gridObject[_jsonV3GridAngleKey].toDouble());
    _turnAroundDistanceFact.setRawValue (gridObject[_jsonV3TurnaroundDistKey].toDouble());

    if (gridObject.contains(_jsonV3GridEntryLocationKey)) {
        _gridEntryLocationFact.setRawValue(gridObject[_jsonV3GridEntryLocationKey].toDouble());
DonLakeFlyer's avatar
DonLakeFlyer committed
251 252 253
    } else {
        _gridEntryLocationFact.setRawValue(_gridEntryLocationFact.rawDefaultValue());
    }
Don Gagne's avatar
Don Gagne committed
254

255 256 257 258 259 260 261 262
    _cameraCalc.distanceToSurface()->setRawValue        (gridObject[_jsonV3GridAltitudeKey].toDouble());
    _cameraCalc.adjustedFootprintSide()->setRawValue    (gridObject[_jsonV3GridSpacingKey].toDouble());
    _cameraCalc.adjustedFootprintFrontal()->setRawValue (complexObject[_jsonV3CameraTriggerDistanceKey].toDouble());

    if (manualGrid) {
        _cameraCalc.setCameraName(_cameraCalc.manualCameraName());
    } else {
        if (!complexObject.contains(_jsonV3CameraObjectKey)) {
Don Gagne's avatar
Don Gagne committed
263
            errorString = tr("%1 but %2 object is missing").arg("manualGrid = false").arg("camera");
264
            _ignoreRecalc = false;
Don Gagne's avatar
Don Gagne committed
265 266 267
            return false;
        }

268
        QJsonObject cameraObject = complexObject[_jsonV3CameraObjectKey].toObject();
Don Gagne's avatar
Don Gagne committed
269

270 271 272
        // Older code had typo on "imageSideOverlap" incorrectly being "imageSizeOverlap"
        QString incorrectImageSideOverlap = "imageSizeOverlap";
        if (cameraObject.contains(incorrectImageSideOverlap)) {
273
            cameraObject[_jsonV3SideOverlapKey] = cameraObject[incorrectImageSideOverlap];
274 275 276
            cameraObject.remove(incorrectImageSideOverlap);
        }

Don Gagne's avatar
Don Gagne committed
277
        QList<JsonHelper::KeyValidateInfo> cameraKeyInfoList = {
278 279 280 281 282 283 284 285 286 287 288
            { _jsonV3GroundResolutionKey,           QJsonValue::Double, true },
            { _jsonV3FrontalOverlapKey,             QJsonValue::Double, true },
            { _jsonV3SideOverlapKey,                QJsonValue::Double, true },
            { _jsonV3CameraSensorWidthKey,          QJsonValue::Double, true },
            { _jsonV3CameraSensorHeightKey,         QJsonValue::Double, true },
            { _jsonV3CameraResolutionWidthKey,      QJsonValue::Double, true },
            { _jsonV3CameraResolutionHeightKey,     QJsonValue::Double, true },
            { _jsonV3CameraFocalLengthKey,          QJsonValue::Double, true },
            { _jsonV3CameraNameKey,                 QJsonValue::String, true },
            { _jsonV3CameraOrientationLandscapeKey, QJsonValue::Bool,   true },
            { _jsonV3CameraMinTriggerIntervalKey,   QJsonValue::Double, false },
Don Gagne's avatar
Don Gagne committed
289
        };
Don Gagne's avatar
Don Gagne committed
290
        if (!JsonHelper::validateKeys(cameraObject, cameraKeyInfoList, errorString)) {
291
            _ignoreRecalc = false;
Don Gagne's avatar
Don Gagne committed
292 293 294
            return false;
        }

295 296 297 298 299 300 301 302 303 304 305 306
        _cameraCalc.setCameraName                       (cameraObject[_jsonV3CameraNameKey].toString());
        _cameraCalc.landscape()->setRawValue            (cameraObject[_jsonV3CameraOrientationLandscapeKey].toBool(true));
        _cameraCalc.frontalOverlap()->setRawValue       (cameraObject[_jsonV3FrontalOverlapKey].toInt());
        _cameraCalc.sideOverlap()->setRawValue          (cameraObject[_jsonV3SideOverlapKey].toInt());
        _cameraCalc.sensorWidth()->setRawValue          (cameraObject[_jsonV3CameraSensorWidthKey].toDouble());
        _cameraCalc.sensorHeight()->setRawValue         (cameraObject[_jsonV3CameraSensorHeightKey].toDouble());
        _cameraCalc.focalLength()->setRawValue          (cameraObject[_jsonV3CameraFocalLengthKey].toDouble());
        _cameraCalc.imageWidth()->setRawValue           (cameraObject[_jsonV3CameraResolutionWidthKey].toInt());
        _cameraCalc.imageHeight()->setRawValue          (cameraObject[_jsonV3CameraResolutionHeightKey].toInt());
        _cameraCalc.minTriggerInterval()->setRawValue   (cameraObject[_jsonV3CameraMinTriggerIntervalKey].toDouble(0));
        _cameraCalc.imageDensity()->setRawValue         (cameraObject[_jsonV3GroundResolutionKey].toDouble());
        _cameraCalc.fixedOrientation()->setRawValue     (false);
Don Gagne's avatar
Don Gagne committed
307
    }
308 309

    // Polygon shape
310 311 312 313 314
    /// Load a polygon from json
    ///     @param json Json object to load from
    ///     @param required true: no polygon in object will generate error
    ///     @param errorString Error string if return is false
    /// @return true: success, false: failure (errorString set)
315 316 317
    if (!_surveyAreaPolygon.loadFromJson(complexObject, true /* required */, errorString)) {
        _surveyAreaPolygon.clear();
        _ignoreRecalc = false;
318 319
        return false;
    }
320

321 322
    _ignoreRecalc = false;

323 324 325
    return true;
}

DonLakeFlyer's avatar
DonLakeFlyer committed
326
/// Reverse the order of the transects. First transect becomes last and so forth.
327
void SurveyComplexItem::_reverseTransectOrder(QList<QList<QGeoCoordinate>>& transects)
DonLakeFlyer's avatar
DonLakeFlyer committed
328 329 330 331 332 333 334 335 336
{
    QList<QList<QGeoCoordinate>> rgReversedTransects;
    for (int i=transects.count() - 1; i>=0; i--) {
        rgReversedTransects.append(transects[i]);
    }
    transects = rgReversedTransects;
}

/// Reverse the order of all points withing each transect, First point becomes last and so forth.
337
void SurveyComplexItem::_reverseInternalTransectPoints(QList<QList<QGeoCoordinate>>& transects)
DonLakeFlyer's avatar
DonLakeFlyer committed
338 339 340 341 342 343 344 345 346 347 348
{
    for (int i=0; i<transects.count(); i++) {
        QList<QGeoCoordinate> rgReversedCoords;
        QList<QGeoCoordinate>& rgOriginalCoords = transects[i];
        for (int j=rgOriginalCoords.count()-1; j>=0; j--) {
            rgReversedCoords.append(rgOriginalCoords[j]);
        }
        transects[i] = rgReversedCoords;
    }
}

DonLakeFlyer's avatar
DonLakeFlyer committed
349 350 351 352
/// Reorders the transects such that the first transect is the shortest distance to the specified coordinate
/// and the first point within that transect is the shortest distance to the specified coordinate.
///     @param distanceCoord Coordinate to measure distance against
///     @param transects Transects to test and reorder
353
void SurveyComplexItem::_optimizeTransectsForShortestDistance(const QGeoCoordinate& distanceCoord, QList<QList<QGeoCoordinate>>& transects)
354
{
355
    double rgTransectDistance[4];
DonLakeFlyer's avatar
DonLakeFlyer committed
356 357 358 359
    rgTransectDistance[0] = transects.first().first().distanceTo(distanceCoord);
    rgTransectDistance[1] = transects.first().last().distanceTo(distanceCoord);
    rgTransectDistance[2] = transects.last().first().distanceTo(distanceCoord);
    rgTransectDistance[3] = transects.last().last().distanceTo(distanceCoord);
360 361 362 363 364 365 366 367 368

    int shortestIndex = 0;
    double shortestDistance = rgTransectDistance[0];
    for (int i=1; i<3; i++) {
        if (rgTransectDistance[i] < shortestDistance) {
            shortestIndex = i;
            shortestDistance = rgTransectDistance[i];
        }
    }
369

370 371
    if (shortestIndex > 1) {
        // We need to reverse the order of segments
DonLakeFlyer's avatar
DonLakeFlyer committed
372
        _reverseTransectOrder(transects);
373 374 375
    }
    if (shortestIndex & 1) {
        // We need to reverse the points within each segment
DonLakeFlyer's avatar
DonLakeFlyer committed
376
        _reverseInternalTransectPoints(transects);
377 378
    }
}
379

380
qreal SurveyComplexItem::_ccw(QPointF pt1, QPointF pt2, QPointF pt3)
381 382 383 384
{
    return (pt2.x()-pt1.x())*(pt3.y()-pt1.y()) - (pt2.y()-pt1.y())*(pt3.x()-pt1.x());
}

385
qreal SurveyComplexItem::_dp(QPointF pt1, QPointF pt2)
386 387 388 389
{
    return (pt2.x()-pt1.x())/qSqrt((pt2.x()-pt1.x())*(pt2.x()-pt1.x()) + (pt2.y()-pt1.y())*(pt2.y()-pt1.y()));
}

390
void SurveyComplexItem::_swapPoints(QList<QPointF>& points, int index1, int index2)
391 392 393 394 395 396
{
    QPointF temp = points[index1];
    points[index1] = points[index2];
    points[index2] = temp;
}

DonLakeFlyer's avatar
DonLakeFlyer committed
397
/// Returns true if the current grid angle generates north/south oriented transects
398
bool SurveyComplexItem::_gridAngleIsNorthSouthTransects()
DonLakeFlyer's avatar
DonLakeFlyer committed
399 400 401 402 403 404
{
    // Grid angle ranges from -360<->360
    double gridAngle = qAbs(_gridAngleFact.rawValue().toDouble());
    return gridAngle < 45.0 || (gridAngle > 360.0 - 45.0) || (gridAngle > 90.0 + 45.0 && gridAngle < 270.0 - 45.0);
}

405
void SurveyComplexItem::_adjustTransectsToEntryPointLocation(QList<QList<QGeoCoordinate>>& transects)
DonLakeFlyer's avatar
DonLakeFlyer committed
406 407 408 409 410
{
    if (transects.count() == 0) {
        return;
    }

DonLakeFlyer's avatar
DonLakeFlyer committed
411 412 413
    int entryLocation = _gridEntryLocationFact.rawValue().toInt();
    bool reversePoints = false;
    bool reverseTransects = false;
DonLakeFlyer's avatar
DonLakeFlyer committed
414

DonLakeFlyer's avatar
DonLakeFlyer committed
415 416
    if (entryLocation == EntryLocationBottomLeft || entryLocation == EntryLocationBottomRight) {
        reversePoints = true;
DonLakeFlyer's avatar
DonLakeFlyer committed
417
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
418 419
    if (entryLocation == EntryLocationTopRight || entryLocation == EntryLocationBottomRight) {
        reverseTransects = true;
DonLakeFlyer's avatar
DonLakeFlyer committed
420
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
421

DonLakeFlyer's avatar
DonLakeFlyer committed
422
    if (reversePoints) {
423
        qCDebug(SurveyComplexItemLog) << "_adjustTransectsToEntryPointLocation Reverse Points";
DonLakeFlyer's avatar
DonLakeFlyer committed
424 425 426
        _reverseInternalTransectPoints(transects);
    }
    if (reverseTransects) {
427
        qCDebug(SurveyComplexItemLog) << "_adjustTransectsToEntryPointLocation Reverse Transects";
DonLakeFlyer's avatar
DonLakeFlyer committed
428
        _reverseTransectOrder(transects);
DonLakeFlyer's avatar
DonLakeFlyer committed
429
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
430

431
    qCDebug(SurveyComplexItemLog) << "_adjustTransectsToEntryPointLocation Modified entry point:entryLocation" << transects.first().first() << entryLocation;
DonLakeFlyer's avatar
DonLakeFlyer committed
432 433
}

434
#if 0
435
void SurveyComplexItem::_generateGrid(void)
436
{
437 438 439 440
    if (_ignoreRecalc) {
        return;
    }

441 442
    if (_mapPolygon.count() < 3 || _gridSpacingFact.rawValue().toDouble() <= 0) {
        _clearInternal();
443 444 445
        return;
    }

446
    _simpleGridPoints.clear();
DonLakeFlyer's avatar
DonLakeFlyer committed
447
    _transectSegments.clear();
448
    _reflyTransectSegments.clear();
449
    _additionalFlightDelaySeconds = 0;
450

451
    QList<QPointF>          polygonPoints;
DonLakeFlyer's avatar
DonLakeFlyer committed
452
    QList<QList<QPointF>>   transectSegments;
453

454
    // Convert polygon to NED
DonLakeFlyer's avatar
DonLakeFlyer committed
455
    QGeoCoordinate tangentOrigin = _mapPolygon.pathModel().value<QGCQGeoCoordinate*>(0)->coordinate();
456
    qCDebug(SurveyComplexItemLog) << "Convert polygon to NED - tangentOrigin" << tangentOrigin;
457
    for (int i=0; i<_mapPolygon.count(); i++) {
458
        double y, x, down;
459
        QGeoCoordinate vertex = _mapPolygon.pathModel().value<QGCQGeoCoordinate*>(i)->coordinate();
DonLakeFlyer's avatar
DonLakeFlyer committed
460 461 462 463 464 465
        if (i == 0) {
            // This avoids a nan calculation that comes out of convertGeoToNed
            x = y = 0;
        } else {
            convertGeoToNed(vertex, tangentOrigin, &y, &x, &down);
        }
466
        polygonPoints += QPointF(x, y);
467
        qCDebug(SurveyComplexItemLog) << "vertex:x:y" << vertex << polygonPoints.last().x() << polygonPoints.last().y();
468 469 470 471 472 473 474 475 476 477 478 479 480
    }

    double coveredArea = 0.0;
    for (int i=0; i<polygonPoints.count(); i++) {
        if (i != 0) {
            coveredArea += polygonPoints[i - 1].x() * polygonPoints[i].y() - polygonPoints[i].x() * polygonPoints[i -1].y();
        } else {
            coveredArea += polygonPoints.last().x() * polygonPoints[i].y() - polygonPoints[i].x() * polygonPoints.last().y();
        }
    }
    _setCoveredArea(0.5 * fabs(coveredArea));

    // Generate grid
481
    int cameraShots = 0;
482
    cameraShots += _gridGenerator(polygonPoints, transectSegments, false /* refly */);
483
    _convertTransectToGeo(transectSegments, tangentOrigin, _transectSegments);
DonLakeFlyer's avatar
DonLakeFlyer committed
484
    _adjustTransectsToEntryPointLocation(_transectSegments);
485
    _appendGridPointsFromTransects(_transectSegments);
486 487
    if (_refly90Degrees) {
        transectSegments.clear();
488
        cameraShots += _gridGenerator(polygonPoints, transectSegments, true /* refly */);
489
        _convertTransectToGeo(transectSegments, tangentOrigin, _reflyTransectSegments);
DonLakeFlyer's avatar
DonLakeFlyer committed
490
        _optimizeTransectsForShortestDistance(_transectSegments.last().last(), _reflyTransectSegments);
491
        _appendGridPointsFromTransects(_reflyTransectSegments);
492
    }
493

494
    // Calc survey distance
495
    double surveyDistance = 0.0;
496 497 498 499
    for (int i=1; i<_simpleGridPoints.count(); i++) {
        QGeoCoordinate coord1 = _simpleGridPoints[i-1].value<QGeoCoordinate>();
        QGeoCoordinate coord2 = _simpleGridPoints[i].value<QGeoCoordinate>();
        surveyDistance += coord1.distanceTo(coord2);
500 501
    }
    _setSurveyDistance(surveyDistance);
502

503
    if (cameraShots == 0 && _triggerCamera()) {
504 505 506
        cameraShots = (int)floor(surveyDistance / _triggerDistance());
        // Take into account immediate camera trigger at waypoint entry
        cameraShots++;
507
    }
508
    _setCameraShots(cameraShots);
509

510 511 512
    if (_hoverAndCaptureEnabled()) {
        _additionalFlightDelaySeconds = cameraShots * _hoverAndCaptureDelaySeconds;
    }
513
    emit additionalTimeDelayChanged();
514

515
    emit gridPointsChanged();
DonLakeFlyer's avatar
DonLakeFlyer committed
516 517

    // Determine command count for lastSequenceNumber
518 519
    _missionCommandCount = _calcMissionCommandCount(_transectSegments);
    _missionCommandCount += _calcMissionCommandCount(_reflyTransectSegments);
520 521
    emit lastSequenceNumberChanged(lastSequenceNumber());

DonLakeFlyer's avatar
DonLakeFlyer committed
522
    // Set exit coordinate
523 524
    if (_simpleGridPoints.count()) {
        QGeoCoordinate coordinate = _simpleGridPoints.first().value<QGeoCoordinate>();
525 526
        coordinate.setAltitude(_gridAltitudeFact.rawValue().toDouble());
        setCoordinate(coordinate);
527
        QGeoCoordinate exitCoordinate = _simpleGridPoints.last().value<QGeoCoordinate>();
528 529
        exitCoordinate.setAltitude(_gridAltitudeFact.rawValue().toDouble());
        _setExitCoordinate(exitCoordinate);
530
    }
531 532

    setDirty(true);
533
}
534
#endif
535

536
QPointF SurveyComplexItem::_rotatePoint(const QPointF& point, const QPointF& origin, double angle)
537 538
{
    QPointF rotated;
DonLakeFlyer's avatar
DonLakeFlyer committed
539
    double radians = (M_PI / 180.0) * -angle;
540 541 542 543 544 545 546

    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;
}

547
void SurveyComplexItem::_intersectLinesWithRect(const QList<QLineF>& lineList, const QRectF& boundRect, QList<QLineF>& resultLines)
548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603
{
    QLineF topLine      (boundRect.topLeft(),       boundRect.topRight());
    QLineF bottomLine   (boundRect.bottomLeft(),    boundRect.bottomRight());
    QLineF leftLine     (boundRect.topLeft(),       boundRect.bottomLeft());
    QLineF rightLine    (boundRect.topRight(),      boundRect.bottomRight());

    for (int i=0; i<lineList.count(); i++) {
        QPointF intersectPoint;
        QLineF intersectLine;
        const QLineF& line = lineList[i];

        int foundCount = 0;
        if (line.intersect(topLine, &intersectPoint) == QLineF::BoundedIntersection) {
            intersectLine.setP1(intersectPoint);
            foundCount++;
        }
        if (line.intersect(rightLine, &intersectPoint) == QLineF::BoundedIntersection) {
            if (foundCount == 0) {
                intersectLine.setP1(intersectPoint);
            } else {
                if (foundCount != 1) {
                    qWarning() << "Found more than two intersecting points";
                }
                intersectLine.setP2(intersectPoint);
            }
            foundCount++;
        }
        if (line.intersect(bottomLine, &intersectPoint) == QLineF::BoundedIntersection) {
            if (foundCount == 0) {
                intersectLine.setP1(intersectPoint);
            } else {
                if (foundCount != 1) {
                    qWarning() << "Found more than two intersecting points";
                }
                intersectLine.setP2(intersectPoint);
            }
            foundCount++;
        }
        if (line.intersect(leftLine, &intersectPoint) == QLineF::BoundedIntersection) {
            if (foundCount == 0) {
                intersectLine.setP1(intersectPoint);
            } else {
                if (foundCount != 1) {
                    qWarning() << "Found more than two intersecting points";
                }
                intersectLine.setP2(intersectPoint);
            }
            foundCount++;
        }

        if (foundCount == 2) {
            resultLines += intersectLine;
        }
    }
}

604
void SurveyComplexItem::_intersectLinesWithPolygon(const QList<QLineF>& lineList, const QPolygonF& polygon, QList<QLineF>& resultLines)
605
{
606
    resultLines.clear();
607

608 609
    for (int i=0; i<lineList.count(); i++) {
        const QLineF& line = lineList[i];
610
        QList<QPointF> intersections;
611

612
        // Intersect the line with all the polygon edges
613 614 615 616
        for (int j=0; j<polygon.count()-1; j++) {
            QPointF intersectPoint;
            QLineF polygonLine = QLineF(polygon[j], polygon[j+1]);
            if (line.intersect(polygonLine, &intersectPoint) == QLineF::BoundedIntersection) {
617 618 619
                if (!intersections.contains(intersectPoint)) {
                    intersections.append(intersectPoint);
                }
620 621 622
            }
        }

623 624 625 626 627 628 629 630 631 632
        // We now have one or more intersection points all along the same line. Find the two
        // which are furthest away from each other to form the transect.
        if (intersections.count() > 1) {
            QPointF firstPoint;
            QPointF secondPoint;
            double currentMaxDistance = 0;

            for (int i=0; i<intersections.count(); i++) {
                for (int j=0; j<intersections.count(); j++) {
                    QLineF lineTest(intersections[i], intersections[j]);
633
                    \
634 635 636 637 638 639 640 641 642 643
                    double newMaxDistance = lineTest.length();
                    if (newMaxDistance > currentMaxDistance) {
                        firstPoint = intersections[i];
                        secondPoint = intersections[j];
                        currentMaxDistance = newMaxDistance;
                    }
                }
            }

            resultLines += QLineF(firstPoint, secondPoint);
644 645 646 647 648
        }
    }
}

/// Adjust the line segments such that they are all going the same direction with respect to going from P1->P2
649
void SurveyComplexItem::_adjustLineDirection(const QList<QLineF>& lineList, QList<QLineF>& resultLines)
650
{
651
    qreal firstAngle = 0;
652 653 654 655
    for (int i=0; i<lineList.count(); i++) {
        const QLineF& line = lineList[i];
        QLineF adjustedLine;

656 657 658 659 660
        if (i == 0) {
            firstAngle = line.angle();
        }

        if (qAbs(line.angle() - firstAngle) > 1.0) {
661 662 663 664 665 666 667 668 669 670
            adjustedLine.setP1(line.p2());
            adjustedLine.setP2(line.p1());
        } else {
            adjustedLine = line;
        }

        resultLines += adjustedLine;
    }
}

671
double SurveyComplexItem::_clampGridAngle90(double gridAngle)
DonLakeFlyer's avatar
DonLakeFlyer committed
672 673 674 675 676 677 678 679 680 681
{
    // Clamp grid angle to -90<->90. This prevents transects from being rotated to a reversed order.
    if (gridAngle > 90.0) {
        gridAngle -= 180.0;
    } else if (gridAngle < -90.0) {
        gridAngle += 180;
    }
    return gridAngle;
}

682
#if 0
683
int SurveyComplexItem::_gridGenerator(const QList<QPointF>& polygonPoints,  QList<QList<QPointF>>& transectSegments, bool refly)
684
{
685 686
    int cameraShots = 0;

DonLakeFlyer's avatar
DonLakeFlyer committed
687
    double gridAngle = _gridAngleFact.rawValue().toDouble();
Don Gagne's avatar
Don Gagne committed
688 689
    double gridSpacing = _gridSpacingFact.rawValue().toDouble();

DonLakeFlyer's avatar
DonLakeFlyer committed
690 691
    gridAngle = _clampGridAngle90(gridAngle);
    gridAngle += refly ? 90 : 0;
692
    qCDebug(SurveyComplexItemLog) << "Clamped grid angle" << gridAngle;
DonLakeFlyer's avatar
DonLakeFlyer committed
693

694
    qCDebug(SurveyComplexItemLog) << "SurveyComplexItem::_gridGenerator gridSpacing:gridAngle:refly" << gridSpacing << gridAngle << refly;
695

DonLakeFlyer's avatar
DonLakeFlyer committed
696
    transectSegments.clear();
697 698 699

    // Convert polygon to bounding rect

700
    qCDebug(SurveyComplexItemLog) << "Polygon";
701 702
    QPolygonF polygon;
    for (int i=0; i<polygonPoints.count(); i++) {
703
        qCDebug(SurveyComplexItemLog) << polygonPoints[i];
704 705 706
        polygon << polygonPoints[i];
    }
    polygon << polygonPoints[0];
707 708
    QRectF boundingRect = polygon.boundingRect();
    QPointF boundingCenter = boundingRect.center();
709
    qCDebug(SurveyComplexItemLog) << "Bounding rect" << boundingRect.topLeft().x() << boundingRect.topLeft().y() << boundingRect.bottomRight().x() << boundingRect.bottomRight().y();
710 711 712

    // Create set of rotated parallel lines within the expanded bounding rect. Make the lines larger than the
    // bounding box to guarantee intersection.
DonLakeFlyer's avatar
DonLakeFlyer committed
713

714
    QList<QLineF> lineList;
DonLakeFlyer's avatar
DonLakeFlyer committed
715

716
    // Transects are generated to be as long as the largest width/height of the bounding rect plus some fudge factor.
DonLakeFlyer's avatar
DonLakeFlyer committed
717
    // This way they will always be guaranteed to intersect with a polygon edge no matter what angle they are rotated to.
718
    // They are initially generated with the transects flowing from west to east and then points within the transect north to south.
719
    double maxWidth = qMax(boundingRect.width(), boundingRect.height()) + 2000.0;
720 721 722 723 724 725 726 727 728 729 730
    double halfWidth = maxWidth / 2.0;
    double transectX = boundingCenter.x() - halfWidth;
    double transectXMax = transectX + maxWidth;
    while (transectX < transectXMax) {
        double transectYTop = boundingCenter.y() - halfWidth;
        double transectYBottom = boundingCenter.y() + halfWidth;

        lineList += QLineF(_rotatePoint(QPointF(transectX, transectYTop), boundingCenter, gridAngle), _rotatePoint(QPointF(transectX, transectYBottom), boundingCenter, gridAngle));
        transectX += gridSpacing;
    }

731 732 733 734 735 736 737 738 739
    // Now intersect the lines with the polygon
    QList<QLineF> intersectLines;
#if 1
    _intersectLinesWithPolygon(lineList, polygon, intersectLines);
#else
    // This is handy for debugging grid problems, not for release
    intersectLines = lineList;
#endif

740 741 742 743 744 745 746 747 748 749 750 751 752 753 754
    // Less than two transects intersected with the polygon:
    //      Create a single transect which goes through the center of the polygon
    //      Intersect it with the polygon
    if (intersectLines.count() < 2) {
        _mapPolygon.center();
        QLineF firstLine = lineList.first();
        QPointF lineCenter = firstLine.pointAt(0.5);
        QPointF centerOffset = boundingCenter - lineCenter;
        firstLine.translate(centerOffset);
        lineList.clear();
        lineList.append(firstLine);
        intersectLines = lineList;
        _intersectLinesWithPolygon(lineList, polygon, intersectLines);
    }

755 756 757 758 759
    // Make sure all lines are going to same direction. Polygon intersection leads to line which
    // can be in varied directions depending on the order of the intesecting sides.
    QList<QLineF> resultLines;
    _adjustLineDirection(intersectLines, resultLines);

760
    // Calc camera shots here if there are no images in turnaround
DonLakeFlyer's avatar
DonLakeFlyer committed
761
    if (_triggerCamera() && !_imagesEverywhere()) {
762
        for (int i=0; i<resultLines.count(); i++) {
763 764 765
            cameraShots += (int)floor(resultLines[i].length() / _triggerDistance());
            // Take into account immediate camera trigger at waypoint entry
            cameraShots++;
766 767 768 769
        }
    }

    // Turn into a path
770
    for (int i=0; i<resultLines.count(); i++) {
DonLakeFlyer's avatar
DonLakeFlyer committed
771 772 773
        QLineF          transectLine;
        QList<QPointF>  transectPoints;
        const QLineF&   line = resultLines[i];
774

DonLakeFlyer's avatar
DonLakeFlyer committed
775
        float turnaroundPosition = _turnaroundDistance() / line.length();
Andreas Bircher's avatar
Andreas Bircher committed
776

777
        if (i & 1) {
DonLakeFlyer's avatar
DonLakeFlyer committed
778
            transectLine = QLineF(line.p2(), line.p1());
779
        } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
780 781 782 783 784 785 786 787 788 789 790 791 792 793 794 795
            transectLine = QLineF(line.p1(), line.p2());
        }

        // Build the points along the transect

        if (_hasTurnaround()) {
            transectPoints.append(transectLine.pointAt(-turnaroundPosition));
        }

        // Polygon entry point
        transectPoints.append(transectLine.p1());

        // For hover and capture we need points for each camera location
        if (_triggerCamera() && _hoverAndCaptureEnabled()) {
            if (_triggerDistance() < transectLine.length()) {
                int innerPoints = floor(transectLine.length() / _triggerDistance());
796
                qCDebug(SurveyComplexItemLog) << "innerPoints" << innerPoints;
DonLakeFlyer's avatar
DonLakeFlyer committed
797 798 799 800
                float transectPositionIncrement = _triggerDistance() / transectLine.length();
                for (int i=0; i<innerPoints; i++) {
                    transectPoints.append(transectLine.pointAt(transectPositionIncrement * (i + 1)));
                }
Andreas Bircher's avatar
Andreas Bircher committed
801
            }
802
        }
DonLakeFlyer's avatar
DonLakeFlyer committed
803 804 805 806 807 808 809 810 811

        // Polygon exit point
        transectPoints.append(transectLine.p2());

        if (_hasTurnaround()) {
            transectPoints.append(transectLine.pointAt(1 + turnaroundPosition));
        }

        transectSegments.append(transectPoints);
812
    }
813 814

    return cameraShots;
815
}
816
#endif
817

818
#if 0
819
int SurveyComplexItem::_appendWaypointToMission(QList<MissionItem*>& items, int seqNum, QGeoCoordinate& coord, CameraTriggerCode cameraTrigger, QObject* missionItemParent)
820
{
DonLakeFlyer's avatar
DonLakeFlyer committed
821 822 823
    double  altitude =          _gridAltitudeFact.rawValue().toDouble();
    bool    altitudeRelative =  _gridAltitudeRelativeFact.rawValue().toBool();

824
    qCDebug(SurveyComplexItemLog) << "_appendWaypointToMission seq:trigger" << seqNum << (cameraTrigger != CameraTriggerNone);
825 826 827 828

    MissionItem* item = new MissionItem(seqNum++,
                                        MAV_CMD_NAV_WAYPOINT,
                                        altitudeRelative ? MAV_FRAME_GLOBAL_RELATIVE_ALT : MAV_FRAME_GLOBAL,
829
                                        cameraTrigger == CameraTriggerHoverAndCapture ? _hoverAndCaptureDelaySeconds : 0,  // Hold time (delay for hover and capture to settle vehicle before image is taken)
830 831
                                        0.0, 0.0,
                                        std::numeric_limits<double>::quiet_NaN(),   // Yaw unchanged
832 833 834
                                        coord.latitude(),
                                        coord.longitude(),
                                        altitude,
835 836
                                        true,                                       // autoContinue
                                        false,                                      // isCurrentItem
837 838 839
                                        missionItemParent);
    items.append(item);

DonLakeFlyer's avatar
DonLakeFlyer committed
840 841 842 843 844 845 846
    switch (cameraTrigger) {
    case CameraTriggerOff:
    case CameraTriggerOn:
        item = new MissionItem(seqNum++,
                               MAV_CMD_DO_SET_CAM_TRIGG_DIST,
                               MAV_FRAME_MISSION,
                               cameraTrigger == CameraTriggerOn ? _triggerDistance() : 0,
847 848 849 850 851
                               0,                                           // shutter integration (ignore)
                               cameraTrigger == CameraTriggerOn ? 1 : 0,    // trigger immediately when starting
                               0, 0, 0, 0,                                  // param 4-7 unused
                               true,                                        // autoContinue
                               false,                                       // isCurrentItem
DonLakeFlyer's avatar
DonLakeFlyer committed
852
                               missionItemParent);
853
        items.append(item);
DonLakeFlyer's avatar
DonLakeFlyer committed
854 855 856 857 858
        break;
    case CameraTriggerHoverAndCapture:
        item = new MissionItem(seqNum++,
                               MAV_CMD_IMAGE_START_CAPTURE,
                               MAV_FRAME_MISSION,
Gus Grubba's avatar
Gus Grubba committed
859
                               0,                           // Reserved (Set to 0)
860 861
                               0,                           // Interval (none)
                               1,                           // Take 1 photo
862
                               NAN, NAN, NAN, NAN,          // param 4-7 reserved
863 864
                               true,                        // autoContinue
                               false,                       // isCurrentItem
DonLakeFlyer's avatar
DonLakeFlyer committed
865 866
                               missionItemParent);
        items.append(item);
867 868
#if 0
        // This generates too many commands. Pulling out for now, to see if image quality is still high enough.
DonLakeFlyer's avatar
DonLakeFlyer committed
869 870 871 872 873 874 875 876 877 878
        item = new MissionItem(seqNum++,
                               MAV_CMD_NAV_DELAY,
                               MAV_FRAME_MISSION,
                               0.5,                // Delay in seconds, give some time for image to be taken
                               -1, -1, -1,         // No time
                               0, 0, 0,            // Param 5-7 unused
                               true,               // autoContinue
                               false,              // isCurrentItem
                               missionItemParent);
        items.append(item);
879
#endif
DonLakeFlyer's avatar
DonLakeFlyer committed
880 881
    default:
        break;
882
    }
883 884

    return seqNum;
885
}
886
#endif
887

888
bool SurveyComplexItem::_nextTransectCoord(const QList<QGeoCoordinate>& transectPoints, int pointIndex, QGeoCoordinate& coord)
DonLakeFlyer's avatar
DonLakeFlyer committed
889 890 891 892 893 894 895 896 897 898
{
    if (pointIndex > transectPoints.count()) {
        qWarning() << "Bad grid generation";
        return false;
    }

    coord = transectPoints[pointIndex];
    return true;
}

899 900 901 902 903 904 905 906 907 908 909 910 911 912 913 914 915 916 917 918 919 920 921 922 923 924 925 926 927 928 929 930 931 932 933 934 935 936 937 938 939 940 941 942 943 944 945 946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963 964 965 966 967 968 969 970 971 972 973 974 975 976 977 978 979 980 981 982 983 984 985 986 987 988 989 990 991 992 993 994 995 996 997 998 999
void SurveyComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>& items, QObject* missionItemParent)
{
    qCDebug(SurveyComplexItemLog) << "_buildAndAppendMissionItems";

    // Now build the mission items from the transect points

    MissionItem* item;
    int seqNum =                    _sequenceNumber;
    bool imagesEverywhere =         _cameraTriggerInTurnAroundFact.rawValue().toBool();
    bool addTriggerAtBeginning =    imagesEverywhere;
    bool firstOverallPoint =        true;

    MAV_FRAME mavFrame = followTerrain() || !_cameraCalc.distanceToSurfaceRelative() ? MAV_FRAME_GLOBAL : MAV_FRAME_GLOBAL_RELATIVE_ALT;

    foreach (const QList<TransectStyleComplexItem::CoordInfo_t>& transect, _transects) {
        bool entryPoint = true;

        foreach (const CoordInfo_t& transectCoordInfo, transect) {
            item = new MissionItem(seqNum++,
                                   MAV_CMD_NAV_WAYPOINT,
                                   mavFrame,
                                   0,                                          // No hold time
                                   0.0,                                        // No acceptance radius specified
                                   0.0,                                        // Pass through waypoint
                                   std::numeric_limits<double>::quiet_NaN(),   // Yaw unchanged
                                   transectCoordInfo.coord.latitude(),
                                   transectCoordInfo.coord.longitude(),
                                   transectCoordInfo.coord.altitude(),
                                   true,                                       // autoContinue
                                   false,                                      // isCurrentItem
                                   missionItemParent);
            items.append(item);

            if (firstOverallPoint && addTriggerAtBeginning) {
                // Start triggering
                addTriggerAtBeginning = false;
                item = new MissionItem(seqNum++,
                                       MAV_CMD_DO_SET_CAM_TRIGG_DIST,
                                       MAV_FRAME_MISSION,
                                       _cameraCalc.adjustedFootprintFrontal()->rawValue().toDouble(),   // trigger distance
                                       0,                                                               // shutter integration (ignore)
                                       1,                                                               // trigger immediately when starting
                                       0, 0, 0, 0,                                                      // param 4-7 unused
                                       true,                                                            // autoContinue
                                       false,                                                           // isCurrentItem
                                       missionItemParent);
                items.append(item);
            }
            firstOverallPoint = false;

            if (transectCoordInfo.coordType == TransectStyleComplexItem::CoordTypeSurveyEdge && !imagesEverywhere) {
                if (entryPoint) {
                    // Start of transect, start triggering
                    item = new MissionItem(seqNum++,
                                           MAV_CMD_DO_SET_CAM_TRIGG_DIST,
                                           MAV_FRAME_MISSION,
                                           _cameraCalc.adjustedFootprintFrontal()->rawValue().toDouble(),   // trigger distance
                                           0,                                                               // shutter integration (ignore)
                                           1,                                                               // trigger immediately when starting
                                           0, 0, 0, 0,                                                      // param 4-7 unused
                                           true,                                                            // autoContinue
                                           false,                                                           // isCurrentItem
                                           missionItemParent);
                    items.append(item);
                } else {
                    // End of transect, stop triggering
                    item = new MissionItem(seqNum++,
                                           MAV_CMD_DO_SET_CAM_TRIGG_DIST,
                                           MAV_FRAME_MISSION,
                                           0,           // stop triggering
                                           0,           // shutter integration (ignore)
                                           0,           // trigger immediately when starting
                                           0, 0, 0, 0,  // param 4-7 unused
                                           true,        // autoContinue
                                           false,       // isCurrentItem
                                           missionItemParent);
                    items.append(item);
                }
                entryPoint = !entryPoint;
            }
        }
    }

    if (imagesEverywhere) {
        // Stop triggering
        MissionItem* item = new MissionItem(seqNum++,
                                            MAV_CMD_DO_SET_CAM_TRIGG_DIST,
                                            MAV_FRAME_MISSION,
                                            0,           // stop triggering
                                            0,           // shutter integration (ignore)
                                            0,           // trigger immediately when starting
                                            0, 0, 0, 0,  // param 4-7 unused
                                            true,        // autoContinue
                                            false,       // isCurrentItem
                                            missionItemParent);
        items.append(item);
    }
}

#if 0
bool SurveyComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>& items, QObject* missionItemParent)
1000
{
1001
    int seqNum = _sequenceNumber;
1002 1003
    bool firstWaypointTrigger = false;

1004 1005 1006 1007 1008 1009
#if 1
    // FIXME: Hack
    bool hasRefly = false;
    bool buildRefly = false;
#endif

1010
    qCDebug(SurveyComplexItemLog) << QStringLiteral("hasTurnaround(%1) triggerCamera(%2) hoverAndCapture(%3) imagesEverywhere(%4) hasRefly(%5) buildRefly(%6) ").arg(_hasTurnaround()).arg(_triggerCamera()).arg(_hoverAndCaptureEnabled()).arg(_imagesEverywhere()).arg(hasRefly).arg(buildRefly);
1011

1012
#if 0
1013
    QList<QList<QGeoCoordinate>>& transectSegments = buildRefly ? _reflyTransectSegments : _transectSegments;
1014
#endif
DonLakeFlyer's avatar
DonLakeFlyer committed
1015

1016
    if (!buildRefly && _imagesEverywhere()) {
1017
        firstWaypointTrigger = true;
DonLakeFlyer's avatar
DonLakeFlyer committed
1018 1019
    }

1020
    foreach (const QList<TransectStyleComplexItem::CoordInfo_t>& transect, _transects) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1021 1022
        int pointIndex = 0;
        QGeoCoordinate coord;
1023
        CameraTriggerCode cameraTrigger;
DonLakeFlyer's avatar
DonLakeFlyer committed
1024

1025
        qCDebug(SurveyComplexItemLog) << "transect.count" << transect.count();
DonLakeFlyer's avatar
DonLakeFlyer committed
1026 1027 1028

        if (_hasTurnaround()) {
            // Add entry turnaround point
1029 1030
            if (!_nextTransectCoord(segment, pointIndex++, coord)) {
                return false;
DonLakeFlyer's avatar
DonLakeFlyer committed
1031
            }
1032 1033
            seqNum = _appendWaypointToMission(items, seqNum, coord, firstWaypointTrigger ? CameraTriggerOn : CameraTriggerNone, missionItemParent);
            firstWaypointTrigger = false;
DonLakeFlyer's avatar
DonLakeFlyer committed
1034
        }
1035

DonLakeFlyer's avatar
DonLakeFlyer committed
1036
        // Add polygon entry point
1037 1038
        if (!_nextTransectCoord(segment, pointIndex++, coord)) {
            return false;
DonLakeFlyer's avatar
DonLakeFlyer committed
1039
        }
1040 1041 1042 1043 1044
        if (firstWaypointTrigger) {
            cameraTrigger = CameraTriggerOn;
        } else {
            cameraTrigger = _imagesEverywhere() || !_triggerCamera() ? CameraTriggerNone : (_hoverAndCaptureEnabled() ? CameraTriggerHoverAndCapture : CameraTriggerOn);
        }
1045
        seqNum = _appendWaypointToMission(items, seqNum, coord, cameraTrigger, missionItemParent);
1046
        firstWaypointTrigger = false;
1047

DonLakeFlyer's avatar
DonLakeFlyer committed
1048 1049
        // Add internal hover and capture points
        if (_hoverAndCaptureEnabled()) {
1050
            int lastHoverAndCaptureIndex = segment.count() - 1 - (_hasTurnaround() ? 1 : 0);
1051
            qCDebug(SurveyComplexItemLog) << "lastHoverAndCaptureIndex" << lastHoverAndCaptureIndex;
DonLakeFlyer's avatar
DonLakeFlyer committed
1052
            for (; pointIndex < lastHoverAndCaptureIndex; pointIndex++) {
1053 1054
                if (!_nextTransectCoord(segment, pointIndex, coord)) {
                    return false;
DonLakeFlyer's avatar
DonLakeFlyer committed
1055 1056
                }
                seqNum = _appendWaypointToMission(items, seqNum, coord, CameraTriggerHoverAndCapture, missionItemParent);
1057 1058
            }
        }
1059

DonLakeFlyer's avatar
DonLakeFlyer committed
1060
        // Add polygon exit point
1061 1062
        if (!_nextTransectCoord(segment, pointIndex++, coord)) {
            return false;
1063
        }
DonLakeFlyer's avatar
DonLakeFlyer committed
1064
        cameraTrigger = _imagesEverywhere() || !_triggerCamera() ? CameraTriggerNone : (_hoverAndCaptureEnabled() ? CameraTriggerNone : CameraTriggerOff);
1065 1066
        seqNum = _appendWaypointToMission(items, seqNum, coord, cameraTrigger, missionItemParent);

DonLakeFlyer's avatar
DonLakeFlyer committed
1067 1068
        if (_hasTurnaround()) {
            // Add exit turnaround point
1069 1070
            if (!_nextTransectCoord(segment, pointIndex++, coord)) {
                return false;
1071
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
1072
            seqNum = _appendWaypointToMission(items, seqNum, coord, CameraTriggerNone, missionItemParent);
1073
        }
1074

1075
        qCDebug(SurveyComplexItemLog) << "last PointIndex" << pointIndex;
1076 1077
    }

1078
    if (((hasRefly && buildRefly) || !hasRefly) && _imagesEverywhere()) {
1079 1080 1081 1082 1083 1084 1085 1086
        // Turn off camera at end of survey
        MissionItem* item = new MissionItem(seqNum++,
                                            MAV_CMD_DO_SET_CAM_TRIGG_DIST,
                                            MAV_FRAME_MISSION,
                                            0.0,                    // trigger distance (off)
                                            0, 0, 0, 0, 0, 0,       // param 2-7 unused
                                            true,                   // autoContinue
                                            false,                  // isCurrentItem
1087 1088
                                            missionItemParent);
        items.append(item);
1089
    }
1090 1091 1092

    return true;
}
1093
#endif
1094

1095
#if 0
1096
void SurveyComplexItem::appendMissionItems(QList<MissionItem*>& items, QObject* missionItemParent)
1097 1098
{
    int seqNum = _sequenceNumber;
1099
    bool refly = refly90Degrees()->rawValue().toBool();
1100

1101
    if (!_appendMissionItemsWorker(items, missionItemParent, seqNum, refly, false /* buildRefly */)) {
1102 1103 1104
        return;
    }

1105 1106
    if (refly) {
        _appendMissionItemsWorker(items, missionItemParent, seqNum, refly, true /* buildRefly */);
1107 1108
    }
}
1109
#endif
1110

1111
bool SurveyComplexItem::_hasTurnaround(void) const
1112
{
1113
    return _turnaroundDistance() > 0;
1114
}
DonLakeFlyer's avatar
DonLakeFlyer committed
1115

1116
double SurveyComplexItem::_turnaroundDistance(void) const
DonLakeFlyer's avatar
DonLakeFlyer committed
1117
{
1118
    return _turnAroundDistanceFact.rawValue().toDouble();
DonLakeFlyer's avatar
DonLakeFlyer committed
1119 1120
}

1121
#if 0
1122
bool SurveyComplexItem::_triggerCamera(void) const
DonLakeFlyer's avatar
DonLakeFlyer committed
1123
{
1124
    return _triggerDistance() > 0;
DonLakeFlyer's avatar
DonLakeFlyer committed
1125 1126
}

1127
bool SurveyComplexItem::_imagesEverywhere(void) const
DonLakeFlyer's avatar
DonLakeFlyer committed
1128 1129 1130 1131
{
    return _triggerCamera() && _cameraTriggerInTurnaroundFact.rawValue().toBool();
}

1132
bool SurveyComplexItem::_hoverAndCaptureEnabled(void) const
DonLakeFlyer's avatar
DonLakeFlyer committed
1133 1134 1135
{
    return hoverAndCaptureAllowed() && !_imagesEverywhere() && _triggerCamera() && _hoverAndCaptureFact.rawValue().toBool();
}
1136
#endif
DonLakeFlyer's avatar
DonLakeFlyer committed
1137

1138
void SurveyComplexItem::_rebuildTransectsPhase1(void)
1139 1140 1141 1142 1143 1144 1145 1146
{
    _rebuildTransectsPhase1Worker(false /* refly */);
    if (_refly90DegreesFact.rawValue().toBool()) {
        _rebuildTransectsPhase1Worker(true /* refly */);
    }
}

void SurveyComplexItem::_rebuildTransectsPhase1Worker(bool refly)
DonLakeFlyer's avatar
DonLakeFlyer committed
1147
{
1148 1149 1150 1151 1152 1153 1154 1155 1156 1157 1158
    if (_ignoreRecalc) {
        return;
    }

    // If the transects are getting rebuilt then any previously loaded mission items are now invalid
    if (_loadedMissionItemsParent) {
        _loadedMissionItems.clear();
        _loadedMissionItemsParent->deleteLater();
        _loadedMissionItemsParent = NULL;
    }

1159 1160 1161 1162 1163
    // First pass will clear old transect data, refly will append to existing data
    if (!refly) {
        _transects.clear();
        _transectsPathHeightInfo.clear();
    }
1164 1165 1166 1167 1168 1169 1170 1171 1172 1173 1174 1175 1176 1177 1178 1179 1180 1181 1182 1183 1184 1185 1186 1187 1188 1189 1190 1191 1192

    if (_surveyAreaPolygon.count() < 3) {
        return;
    }

    // Convert polygon to NED

    QList<QPointF> polygonPoints;
    QGeoCoordinate tangentOrigin = _surveyAreaPolygon.pathModel().value<QGCQGeoCoordinate*>(0)->coordinate();
    qCDebug(SurveyComplexItemLog) << "_rebuildTransectsPhase1 Convert polygon to NED - _surveyAreaPolygon.count():tangentOrigin" << _surveyAreaPolygon.count() << tangentOrigin;
    for (int i=0; i<_surveyAreaPolygon.count(); i++) {
        double y, x, down;
        QGeoCoordinate vertex = _surveyAreaPolygon.pathModel().value<QGCQGeoCoordinate*>(i)->coordinate();
        if (i == 0) {
            // This avoids a nan calculation that comes out of convertGeoToNed
            x = y = 0;
        } else {
            convertGeoToNed(vertex, tangentOrigin, &y, &x, &down);
        }
        polygonPoints += QPointF(x, y);
        qCDebug(SurveyComplexItemLog) << "_rebuildTransectsPhase1 vertex:x:y" << vertex << polygonPoints.last().x() << polygonPoints.last().y();
    }

    // Generate transects

    double gridAngle = _gridAngleFact.rawValue().toDouble();
    double gridSpacing = _cameraCalc.adjustedFootprintSide()->rawValue().toDouble();

    gridAngle = _clampGridAngle90(gridAngle);
1193
    gridAngle += refly ? 90 : 0;
1194 1195 1196 1197 1198 1199 1200 1201 1202 1203 1204 1205 1206 1207 1208 1209 1210 1211 1212 1213 1214 1215 1216 1217 1218 1219 1220 1221 1222 1223 1224 1225 1226 1227 1228 1229 1230 1231 1232 1233 1234 1235 1236 1237 1238 1239 1240 1241 1242 1243 1244 1245 1246 1247 1248 1249 1250 1251 1252 1253 1254 1255 1256 1257 1258 1259 1260 1261 1262 1263 1264 1265 1266 1267 1268 1269 1270 1271 1272 1273 1274 1275
    qCDebug(SurveyComplexItemLog) << "_rebuildTransectsPhase1 Clamped grid angle" << gridAngle;

    qCDebug(SurveyComplexItemLog) << "_rebuildTransectsPhase1 gridSpacing:gridAngle:refly" << gridSpacing << gridAngle << refly;

    // Convert polygon to bounding rect

    qCDebug(SurveyComplexItemLog) << "_rebuildTransectsPhase1 Polygon";
    QPolygonF polygon;
    for (int i=0; i<polygonPoints.count(); i++) {
        qCDebug(SurveyComplexItemLog) << "Vertex" << polygonPoints[i];
        polygon << polygonPoints[i];
    }
    polygon << polygonPoints[0];
    QRectF boundingRect = polygon.boundingRect();
    QPointF boundingCenter = boundingRect.center();
    qCDebug(SurveyComplexItemLog) << "Bounding rect" << boundingRect.topLeft().x() << boundingRect.topLeft().y() << boundingRect.bottomRight().x() << boundingRect.bottomRight().y();

    // Create set of rotated parallel lines within the expanded bounding rect. Make the lines larger than the
    // bounding box to guarantee intersection.

    QList<QLineF> lineList;

    // Transects are generated to be as long as the largest width/height of the bounding rect plus some fudge factor.
    // This way they will always be guaranteed to intersect with a polygon edge no matter what angle they are rotated to.
    // They are initially generated with the transects flowing from west to east and then points within the transect north to south.
    double maxWidth = qMax(boundingRect.width(), boundingRect.height()) + 2000.0;
    double halfWidth = maxWidth / 2.0;
    double transectX = boundingCenter.x() - halfWidth;
    double transectXMax = transectX + maxWidth;
    while (transectX < transectXMax) {
        double transectYTop = boundingCenter.y() - halfWidth;
        double transectYBottom = boundingCenter.y() + halfWidth;

        lineList += QLineF(_rotatePoint(QPointF(transectX, transectYTop), boundingCenter, gridAngle), _rotatePoint(QPointF(transectX, transectYBottom), boundingCenter, gridAngle));
        transectX += gridSpacing;
    }

    // Now intersect the lines with the polygon
    QList<QLineF> intersectLines;
#if 1
    _intersectLinesWithPolygon(lineList, polygon, intersectLines);
#else
    // This is handy for debugging grid problems, not for release
    intersectLines = lineList;
#endif

    // Less than two transects intersected with the polygon:
    //      Create a single transect which goes through the center of the polygon
    //      Intersect it with the polygon
    if (intersectLines.count() < 2) {
        _surveyAreaPolygon.center();
        QLineF firstLine = lineList.first();
        QPointF lineCenter = firstLine.pointAt(0.5);
        QPointF centerOffset = boundingCenter - lineCenter;
        firstLine.translate(centerOffset);
        lineList.clear();
        lineList.append(firstLine);
        intersectLines = lineList;
        _intersectLinesWithPolygon(lineList, polygon, intersectLines);
    }

    // Make sure all lines are going the same direction. Polygon intersection leads to lines which
    // can be in varied directions depending on the order of the intesecting sides.
    QList<QLineF> resultLines;
    _adjustLineDirection(intersectLines, resultLines);

    // Convert from NED to Geo
    QList<QList<QGeoCoordinate>> transects;
    foreach (const QLineF& line, resultLines) {
        QGeoCoordinate          coord;
        QList<QGeoCoordinate>   transect;

        convertNedToGeo(line.p1().y(), line.p1().x(), 0, tangentOrigin, &coord);
        transect.append(coord);
        convertNedToGeo(line.p2().y(), line.p2().x(), 0, tangentOrigin, &coord);
        transect.append(coord);

        transects.append(transect);
    }

    _adjustTransectsToEntryPointLocation(transects);

1276 1277 1278 1279 1280 1281 1282 1283 1284 1285 1286 1287 1288 1289 1290 1291 1292 1293 1294 1295 1296 1297 1298
    if (refly) {
        _optimizeTransectsForShortestDistance(_transects.last().last().coord, transects);
    }

    // Adjust to lawnmower pattern
    bool reverseVertices = false;
    for (int i=0; i<transects.count(); i++) {
        // We must reverse the vertices for every other transect in order to make a lawnmower pattern
        QList<QGeoCoordinate> transectVertices = transects[i];
        if (reverseVertices) {
            reverseVertices = false;
            QList<QGeoCoordinate> reversedVertices;
            for (int j=transectVertices.count()-1; j>=0; j--) {
                reversedVertices.append(transectVertices[j]);
            }
            transectVertices = reversedVertices;
        } else {
            reverseVertices = true;
        }
        transects[i] = transectVertices;
    }

    // Convert to CoordInfo transects and append to _transects
1299 1300 1301 1302 1303 1304 1305 1306 1307 1308 1309 1310 1311 1312 1313 1314 1315 1316 1317 1318 1319 1320 1321 1322 1323 1324 1325 1326 1327 1328 1329
    foreach (const QList<QGeoCoordinate>& transect, transects) {
        QGeoCoordinate                                  coord;
        QList<TransectStyleComplexItem::CoordInfo_t>    coordInfoTransect;
        TransectStyleComplexItem::CoordInfo_t           coordInfo;

        coordInfo = { transect[0], CoordTypeSurveyEdge };
        coordInfoTransect.append(coordInfo);
        coordInfo = { transect[1], CoordTypeSurveyEdge };
        coordInfoTransect.append(coordInfo);


        // Extend the transect ends for turnaround
        if (_hasTurnaround()) {
            QGeoCoordinate turnaroundCoord;
            double turnAroundDistance = _turnAroundDistanceFact.rawValue().toDouble();

            double azimuth = transect[0].azimuthTo(transect[1]);
            turnaroundCoord = transect[0].atDistanceAndAzimuth(-turnAroundDistance, azimuth);
            turnaroundCoord.setAltitude(qQNaN());
            TransectStyleComplexItem::CoordInfo_t coordInfo = { turnaroundCoord, CoordTypeTurnaround };
            coordInfoTransect.prepend(coordInfo);

            azimuth = transect.last().azimuthTo(transect[transect.count() - 2]);
            turnaroundCoord = transect.last().atDistanceAndAzimuth(-turnAroundDistance, azimuth);
            turnaroundCoord.setAltitude(qQNaN());
            coordInfo = { turnaroundCoord, CoordTypeTurnaround };
            coordInfoTransect.append(coordInfo);
        }

        _transects.append(coordInfoTransect);
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
1330 1331
}

1332
void SurveyComplexItem::_rebuildTransectsPhase2(void)
DonLakeFlyer's avatar
DonLakeFlyer committed
1333
{
1334 1335
    // Calculate distance flown for complex item
    _complexDistance = 0;
1336
    for (int i=0; i<_visualTransectPoints.count() - 1; i++) {
1337 1338 1339
        _complexDistance += _visualTransectPoints[i].value<QGeoCoordinate>().distanceTo(_visualTransectPoints[i+1].value<QGeoCoordinate>());
    }

1340
    double triggerDistance = _cameraCalc.adjustedFootprintFrontal()->rawValue().toDouble();
1341
    if (_cameraTriggerInTurnAroundFact.rawValue().toBool()) {
1342
        _cameraShots = qCeil(_complexDistance / triggerDistance);
1343
    } else {
1344 1345 1346 1347 1348 1349 1350 1351 1352 1353 1354 1355
        _cameraShots = 0;
        foreach (const QList<TransectStyleComplexItem::CoordInfo_t>& transect, _transects) {
            QGeoCoordinate firstCameraCoord, lastCameraCoord;
            if (_hasTurnaround()) {
                firstCameraCoord = transect[1].coord;
                lastCameraCoord = transect[transect.count() - 2].coord;
            } else {
                firstCameraCoord = transect.first().coord;
                lastCameraCoord = transect.last().coord;
            }
            _cameraShots += qCeil(firstCameraCoord.distanceTo(lastCameraCoord) / triggerDistance);
        }
1356 1357 1358 1359 1360 1361 1362 1363 1364
    }

    _coordinate = _visualTransectPoints.count() ? _visualTransectPoints.first().value<QGeoCoordinate>() : QGeoCoordinate();
    _exitCoordinate = _visualTransectPoints.count() ? _visualTransectPoints.last().value<QGeoCoordinate>() : QGeoCoordinate();

    emit cameraShotsChanged();
    emit complexDistanceChanged();
    emit coordinateChanged(_coordinate);
    emit exitCoordinateChanged(_exitCoordinate);
DonLakeFlyer's avatar
DonLakeFlyer committed
1365
}
DonLakeFlyer's avatar
DonLakeFlyer committed
1366

1367
// FIXME: This same exact code is in Corridor Scan. Move to TransectStyleComplex?
1368
void SurveyComplexItem::applyNewAltitude(double newAltitude)
DonLakeFlyer's avatar
DonLakeFlyer committed
1369
{
1370 1371 1372
    _cameraCalc.valueSetIsDistance()->setRawValue(true);
    _cameraCalc.distanceToSurface()->setRawValue(newAltitude);
    _cameraCalc.setDistanceToSurfaceRelative(true);
DonLakeFlyer's avatar
DonLakeFlyer committed
1373
}
1374

1375
bool SurveyComplexItem::readyForSave(void) const
1376
{
1377 1378 1379 1380 1381 1382 1383 1384 1385 1386 1387
    return TransectStyleComplexItem::readyForSave();
}

void SurveyComplexItem::appendMissionItems(QList<MissionItem*>& items, QObject* missionItemParent)
{
    if (_loadedMissionItems.count()) {
        // We have mission items from the loaded plan, use those
        _appendLoadedMissionItems(items, missionItemParent);
    } else {
        // Build the mission items on the fly
        _buildAndAppendMissionItems(items, missionItemParent);
1388 1389
    }
}
1390

1391
void SurveyComplexItem::_appendLoadedMissionItems(QList<MissionItem*>& items, QObject* missionItemParent)
1392
{
1393 1394 1395 1396 1397 1398 1399 1400
    qCDebug(SurveyComplexItemLog) << "_appendLoadedMissionItems";

    int seqNum = _sequenceNumber;

    foreach (const MissionItem* loadedMissionItem, _loadedMissionItems) {
        MissionItem* item = new MissionItem(*loadedMissionItem, missionItemParent);
        item->setSequenceNumber(seqNum++);
        items.append(item);
1401 1402
    }
}
1403 1404