SurveyComplexItem.cc 63 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
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";
30
const char* SurveyComplexItem::flyAlternateTransectsName =  "FlyAlternateTransects";
31 32

const char* SurveyComplexItem::_jsonGridAngleKey =          "angle";
DonLakeFlyer's avatar
DonLakeFlyer committed
33
const char* SurveyComplexItem::_jsonEntryPointKey =         "entryLocation";
34 35 36 37 38 39

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";
DonLakeFlyer's avatar
DonLakeFlyer committed
40
const char* SurveyComplexItem::_jsonV3EntryPointKey =                   "entryLocation";
41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59
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
const char* SurveyComplexItem::_jsonFlyAlternateTransectsKey =          "flyAlternateTransects";
61

62 63
SurveyComplexItem::SurveyComplexItem(Vehicle* vehicle, bool flyView, QObject* parent)
    : TransectStyleComplexItem  (vehicle, flyView, settingsGroup, parent)
64 65
    , _metaDataMap              (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/Survey.SettingsGroup.json"), this))
    , _gridAngleFact            (settingsGroup, _metaDataMap[gridAngleName])
66
    , _flyAlternateTransectsFact(settingsGroup, _metaDataMap[flyAlternateTransectsName])
DonLakeFlyer's avatar
DonLakeFlyer committed
67
    , _entryPoint               (EntryLocationTopLeft)
68
{
69 70
    _editorQml = "qrc:/qml/SurveyItemEditor.qml";

71
    // 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.
72
    // NULL check since object creation during unit testing passes NULL for vehicle
73
    if (_vehicle && _vehicle->multiRotor() && _turnAroundDistanceFact.rawValue().toDouble() == _turnAroundDistanceFact.rawDefaultValue().toDouble()) {
74
        // 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.
75
        _turnAroundDistanceFact.setRawValue(10);
76
    }
Don Gagne's avatar
Don Gagne committed
77

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

83
    connect(&_gridAngleFact,            &Fact::valueChanged,                        this, &SurveyComplexItem::_setDirty);
84
    connect(&_flyAlternateTransectsFact,&Fact::valueChanged,                        this, &SurveyComplexItem::_setDirty);
85
    connect(this,                       &SurveyComplexItem::refly90DegreesChanged,  this, &SurveyComplexItem::_setDirty);
86

87
    connect(&_gridAngleFact,            &Fact::valueChanged,                        this, &SurveyComplexItem::_rebuildTransects);
88
    connect(&_flyAlternateTransectsFact,&Fact::valueChanged,                        this, &SurveyComplexItem::_rebuildTransects);
89
    connect(this,                       &SurveyComplexItem::refly90DegreesChanged,  this, &SurveyComplexItem::_rebuildTransects);
90

91 92 93
    // 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);
94 95
}

96
void SurveyComplexItem::save(QJsonArray&  planItems)
97
{
98
    QJsonObject saveObject;
99

100
    _save(saveObject);
101

102 103 104 105
    saveObject[JsonHelper::jsonVersionKey] =                    4;
    saveObject[VisualMissionItem::jsonTypeKey] =                VisualMissionItem::jsonTypeComplexItemValue;
    saveObject[ComplexMissionItem::jsonComplexItemTypeKey] =    jsonComplexItemTypeValue;
    saveObject[_jsonGridAngleKey] =                             _gridAngleFact.rawValue().toDouble();
106
    saveObject[_jsonFlyAlternateTransectsKey] =                 _flyAlternateTransectsFact.rawValue().toBool();
DonLakeFlyer's avatar
DonLakeFlyer committed
107
    saveObject[_jsonEntryPointKey] =                            _entryPoint;
108

109 110
    // Polygon shape
    _surveyAreaPolygon.saveToJson(saveObject);
111

112
    planItems.append(saveObject);
113 114
}

115
bool SurveyComplexItem::load(const QJsonObject& complexObject, int sequenceNumber, QString& errorString)
116
{
117 118 119 120 121 122
    // 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;
123 124
    }

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

131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147
    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
148
    }
149

150
    _rebuildTransects();
151

152
    return true;
153 154
}

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

168 169 170 171
    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);
172 173
        return false;
    }
Don Gagne's avatar
Don Gagne committed
174

175 176 177 178 179 180
    _ignoreRecalc = true;

    setSequenceNumber(sequenceNumber);

    if (!_surveyAreaPolygon.loadFromJson(complexObject, true /* required */, errorString)) {
        _surveyAreaPolygon.clear();
181 182
        return false;
    }
183 184 185 186

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

189 190 191
    _gridAngleFact.setRawValue              (complexObject[_jsonGridAngleKey].toDouble());
    _flyAlternateTransectsFact.setRawValue  (complexObject[_jsonFlyAlternateTransectsKey].toBool(false));

DonLakeFlyer's avatar
DonLakeFlyer committed
192
    _entryPoint = complexObject[_jsonEntryPointKey].toInt();
193 194 195 196 197 198 199 200

    _ignoreRecalc = false;

    return true;
}

bool SurveyComplexItem::_loadV3(const QJsonObject& complexObject, int sequenceNumber, QString& errorString)
{
Don Gagne's avatar
Don Gagne committed
201 202 203
    QList<JsonHelper::KeyValidateInfo> mainKeyInfoList = {
        { VisualMissionItem::jsonTypeKey,               QJsonValue::String, true },
        { ComplexMissionItem::jsonComplexItemTypeKey,   QJsonValue::String, true },
204
        { QGCMapPolygon::jsonPolygonKey,                QJsonValue::Array,  true },
205 206 207 208 209 210 211 212
        { _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
213
    };
214
    if (!JsonHelper::validateKeys(complexObject, mainKeyInfoList, errorString)) {
215 216
        return false;
    }
Don Gagne's avatar
Don Gagne committed
217

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

225 226
    _ignoreRecalc = true;

Don Gagne's avatar
Don Gagne committed
227
    setSequenceNumber(sequenceNumber);
228

229 230 231 232 233 234
    _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
235

236
    bool manualGrid = complexObject[_jsonV3ManualGridKey].toBool(true);
237

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

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

DonLakeFlyer's avatar
DonLakeFlyer committed
255 256
    if (gridObject.contains(_jsonEntryPointKey)) {
        _entryPoint = gridObject[_jsonEntryPointKey].toDouble();
DonLakeFlyer's avatar
DonLakeFlyer committed
257
    } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
258
        _entryPoint = EntryLocationTopRight;
DonLakeFlyer's avatar
DonLakeFlyer committed
259
    }
Don Gagne's avatar
Don Gagne committed
260

261 262 263 264 265
    _cameraCalc.distanceToSurface()->setRawValue        (gridObject[_jsonV3GridAltitudeKey].toDouble());
    _cameraCalc.adjustedFootprintSide()->setRawValue    (gridObject[_jsonV3GridSpacingKey].toDouble());
    _cameraCalc.adjustedFootprintFrontal()->setRawValue (complexObject[_jsonV3CameraTriggerDistanceKey].toDouble());

    if (manualGrid) {
266
        _cameraCalc.cameraName()->setRawValue(_cameraCalc.manualCameraName());
267 268
    } else {
        if (!complexObject.contains(_jsonV3CameraObjectKey)) {
Don Gagne's avatar
Don Gagne committed
269
            errorString = tr("%1 but %2 object is missing").arg("manualGrid = false").arg("camera");
270
            _ignoreRecalc = false;
Don Gagne's avatar
Don Gagne committed
271 272 273
            return false;
        }

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

276 277 278
        // Older code had typo on "imageSideOverlap" incorrectly being "imageSizeOverlap"
        QString incorrectImageSideOverlap = "imageSizeOverlap";
        if (cameraObject.contains(incorrectImageSideOverlap)) {
279
            cameraObject[_jsonV3SideOverlapKey] = cameraObject[incorrectImageSideOverlap];
280 281 282
            cameraObject.remove(incorrectImageSideOverlap);
        }

Don Gagne's avatar
Don Gagne committed
283
        QList<JsonHelper::KeyValidateInfo> cameraKeyInfoList = {
284 285 286 287 288 289 290 291 292 293 294
            { _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
295
        };
Don Gagne's avatar
Don Gagne committed
296
        if (!JsonHelper::validateKeys(cameraObject, cameraKeyInfoList, errorString)) {
297
            _ignoreRecalc = false;
Don Gagne's avatar
Don Gagne committed
298 299 300
            return false;
        }

301
        _cameraCalc.cameraName()->setRawValue           (cameraObject[_jsonV3CameraNameKey].toString());
302 303 304 305 306 307 308 309 310 311 312
        _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
313
    }
314 315

    // Polygon shape
316 317 318 319 320
    /// 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)
321 322 323
    if (!_surveyAreaPolygon.loadFromJson(complexObject, true /* required */, errorString)) {
        _surveyAreaPolygon.clear();
        _ignoreRecalc = false;
324 325
        return false;
    }
326

327 328
    _ignoreRecalc = false;

329 330 331
    return true;
}

DonLakeFlyer's avatar
DonLakeFlyer committed
332
/// Reverse the order of the transects. First transect becomes last and so forth.
333
void SurveyComplexItem::_reverseTransectOrder(QList<QList<QGeoCoordinate>>& transects)
DonLakeFlyer's avatar
DonLakeFlyer committed
334 335 336 337 338 339 340 341 342
{
    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.
343
void SurveyComplexItem::_reverseInternalTransectPoints(QList<QList<QGeoCoordinate>>& transects)
DonLakeFlyer's avatar
DonLakeFlyer committed
344 345 346 347 348 349 350 351 352 353 354
{
    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
355 356 357 358
/// 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
359
void SurveyComplexItem::_optimizeTransectsForShortestDistance(const QGeoCoordinate& distanceCoord, QList<QList<QGeoCoordinate>>& transects)
360
{
361
    double rgTransectDistance[4];
DonLakeFlyer's avatar
DonLakeFlyer committed
362 363 364 365
    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);
366 367 368 369 370 371 372 373 374

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

376 377
    if (shortestIndex > 1) {
        // We need to reverse the order of segments
DonLakeFlyer's avatar
DonLakeFlyer committed
378
        _reverseTransectOrder(transects);
379 380 381
    }
    if (shortestIndex & 1) {
        // We need to reverse the points within each segment
DonLakeFlyer's avatar
DonLakeFlyer committed
382
        _reverseInternalTransectPoints(transects);
383 384
    }
}
385

386
qreal SurveyComplexItem::_ccw(QPointF pt1, QPointF pt2, QPointF pt3)
387 388 389 390
{
    return (pt2.x()-pt1.x())*(pt3.y()-pt1.y()) - (pt2.y()-pt1.y())*(pt3.x()-pt1.x());
}

391
qreal SurveyComplexItem::_dp(QPointF pt1, QPointF pt2)
392 393 394 395
{
    return (pt2.x()-pt1.x())/qSqrt((pt2.x()-pt1.x())*(pt2.x()-pt1.x()) + (pt2.y()-pt1.y())*(pt2.y()-pt1.y()));
}

396
void SurveyComplexItem::_swapPoints(QList<QPointF>& points, int index1, int index2)
397 398 399 400 401 402
{
    QPointF temp = points[index1];
    points[index1] = points[index2];
    points[index2] = temp;
}

DonLakeFlyer's avatar
DonLakeFlyer committed
403
/// Returns true if the current grid angle generates north/south oriented transects
404
bool SurveyComplexItem::_gridAngleIsNorthSouthTransects()
DonLakeFlyer's avatar
DonLakeFlyer committed
405 406 407 408 409 410
{
    // 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);
}

411
void SurveyComplexItem::_adjustTransectsToEntryPointLocation(QList<QList<QGeoCoordinate>>& transects)
DonLakeFlyer's avatar
DonLakeFlyer committed
412 413 414 415 416
{
    if (transects.count() == 0) {
        return;
    }

DonLakeFlyer's avatar
DonLakeFlyer committed
417 418
    bool reversePoints = false;
    bool reverseTransects = false;
DonLakeFlyer's avatar
DonLakeFlyer committed
419

DonLakeFlyer's avatar
DonLakeFlyer committed
420
    if (_entryPoint == EntryLocationBottomLeft || _entryPoint == EntryLocationBottomRight) {
DonLakeFlyer's avatar
DonLakeFlyer committed
421
        reversePoints = true;
DonLakeFlyer's avatar
DonLakeFlyer committed
422
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
423
    if (_entryPoint == EntryLocationTopRight || _entryPoint == EntryLocationBottomRight) {
DonLakeFlyer's avatar
DonLakeFlyer committed
424
        reverseTransects = true;
DonLakeFlyer's avatar
DonLakeFlyer committed
425
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
426

DonLakeFlyer's avatar
DonLakeFlyer committed
427
    if (reversePoints) {
428
        qCDebug(SurveyComplexItemLog) << "_adjustTransectsToEntryPointLocation Reverse Points";
DonLakeFlyer's avatar
DonLakeFlyer committed
429 430 431
        _reverseInternalTransectPoints(transects);
    }
    if (reverseTransects) {
432
        qCDebug(SurveyComplexItemLog) << "_adjustTransectsToEntryPointLocation Reverse Transects";
DonLakeFlyer's avatar
DonLakeFlyer committed
433
        _reverseTransectOrder(transects);
DonLakeFlyer's avatar
DonLakeFlyer committed
434
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
435

DonLakeFlyer's avatar
DonLakeFlyer committed
436
    qCDebug(SurveyComplexItemLog) << "_adjustTransectsToEntryPointLocation Modified entry point:entryLocation" << transects.first().first() << _entryPoint;
DonLakeFlyer's avatar
DonLakeFlyer committed
437 438
}

439
#if 0
440
void SurveyComplexItem::_generateGrid(void)
441
{
442 443 444 445
    if (_ignoreRecalc) {
        return;
    }

446 447
    if (_mapPolygon.count() < 3 || _gridSpacingFact.rawValue().toDouble() <= 0) {
        _clearInternal();
448 449 450
        return;
    }

451
    _simpleGridPoints.clear();
DonLakeFlyer's avatar
DonLakeFlyer committed
452
    _transectSegments.clear();
453
    _reflyTransectSegments.clear();
454
    _additionalFlightDelaySeconds = 0;
455

456
    QList<QPointF>          polygonPoints;
DonLakeFlyer's avatar
DonLakeFlyer committed
457
    QList<QList<QPointF>>   transectSegments;
458

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

    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
486
    int cameraShots = 0;
487
    cameraShots += _gridGenerator(polygonPoints, transectSegments, false /* refly */);
488
    _convertTransectToGeo(transectSegments, tangentOrigin, _transectSegments);
DonLakeFlyer's avatar
DonLakeFlyer committed
489
    _adjustTransectsToEntryPointLocation(_transectSegments);
490
    _appendGridPointsFromTransects(_transectSegments);
491 492
    if (_refly90Degrees) {
        transectSegments.clear();
493
        cameraShots += _gridGenerator(polygonPoints, transectSegments, true /* refly */);
494
        _convertTransectToGeo(transectSegments, tangentOrigin, _reflyTransectSegments);
DonLakeFlyer's avatar
DonLakeFlyer committed
495
        _optimizeTransectsForShortestDistance(_transectSegments.last().last(), _reflyTransectSegments);
496
        _appendGridPointsFromTransects(_reflyTransectSegments);
497
    }
498

499
    // Calc survey distance
500
    double surveyDistance = 0.0;
501 502 503 504
    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);
505 506
    }
    _setSurveyDistance(surveyDistance);
507

508
    if (cameraShots == 0 && _triggerCamera()) {
509 510 511
        cameraShots = (int)floor(surveyDistance / _triggerDistance());
        // Take into account immediate camera trigger at waypoint entry
        cameraShots++;
512
    }
513
    _setCameraShots(cameraShots);
514

515 516 517
    if (_hoverAndCaptureEnabled()) {
        _additionalFlightDelaySeconds = cameraShots * _hoverAndCaptureDelaySeconds;
    }
518
    emit additionalTimeDelayChanged();
519

520
    emit gridPointsChanged();
DonLakeFlyer's avatar
DonLakeFlyer committed
521 522

    // Determine command count for lastSequenceNumber
523 524
    _missionCommandCount = _calcMissionCommandCount(_transectSegments);
    _missionCommandCount += _calcMissionCommandCount(_reflyTransectSegments);
525 526
    emit lastSequenceNumberChanged(lastSequenceNumber());

DonLakeFlyer's avatar
DonLakeFlyer committed
527
    // Set exit coordinate
528 529
    if (_simpleGridPoints.count()) {
        QGeoCoordinate coordinate = _simpleGridPoints.first().value<QGeoCoordinate>();
530 531
        coordinate.setAltitude(_gridAltitudeFact.rawValue().toDouble());
        setCoordinate(coordinate);
532
        QGeoCoordinate exitCoordinate = _simpleGridPoints.last().value<QGeoCoordinate>();
533 534
        exitCoordinate.setAltitude(_gridAltitudeFact.rawValue().toDouble());
        _setExitCoordinate(exitCoordinate);
535
    }
536 537

    setDirty(true);
538
}
539
#endif
540

541
QPointF SurveyComplexItem::_rotatePoint(const QPointF& point, const QPointF& origin, double angle)
542 543
{
    QPointF rotated;
DonLakeFlyer's avatar
DonLakeFlyer committed
544
    double radians = (M_PI / 180.0) * -angle;
545 546 547 548 549 550 551

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

552
void SurveyComplexItem::_intersectLinesWithRect(const QList<QLineF>& lineList, const QRectF& boundRect, QList<QLineF>& resultLines)
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 604 605 606 607 608
{
    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;
        }
    }
}

609
void SurveyComplexItem::_intersectLinesWithPolygon(const QList<QLineF>& lineList, const QPolygonF& polygon, QList<QLineF>& resultLines)
610
{
611
    resultLines.clear();
612

613 614
    for (int i=0; i<lineList.count(); i++) {
        const QLineF& line = lineList[i];
615
        QList<QPointF> intersections;
616

617
        // Intersect the line with all the polygon edges
618 619 620 621
        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) {
622 623 624
                if (!intersections.contains(intersectPoint)) {
                    intersections.append(intersectPoint);
                }
625 626 627
            }
        }

628 629 630 631 632 633 634 635 636 637
        // 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]);
638
                    \
639 640 641 642 643 644 645 646 647 648
                    double newMaxDistance = lineTest.length();
                    if (newMaxDistance > currentMaxDistance) {
                        firstPoint = intersections[i];
                        secondPoint = intersections[j];
                        currentMaxDistance = newMaxDistance;
                    }
                }
            }

            resultLines += QLineF(firstPoint, secondPoint);
649 650 651 652 653
        }
    }
}

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

661 662 663 664 665
        if (i == 0) {
            firstAngle = line.angle();
        }

        if (qAbs(line.angle() - firstAngle) > 1.0) {
666 667 668 669 670 671 672 673 674 675
            adjustedLine.setP1(line.p2());
            adjustedLine.setP2(line.p1());
        } else {
            adjustedLine = line;
        }

        resultLines += adjustedLine;
    }
}

676
double SurveyComplexItem::_clampGridAngle90(double gridAngle)
DonLakeFlyer's avatar
DonLakeFlyer committed
677 678 679 680 681 682 683 684 685 686
{
    // 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;
}

687
#if 0
688
int SurveyComplexItem::_gridGenerator(const QList<QPointF>& polygonPoints,  QList<QList<QPointF>>& transectSegments, bool refly)
689
{
690 691
    int cameraShots = 0;

DonLakeFlyer's avatar
DonLakeFlyer committed
692
    double gridAngle = _gridAngleFact.rawValue().toDouble();
Don Gagne's avatar
Don Gagne committed
693 694
    double gridSpacing = _gridSpacingFact.rawValue().toDouble();

DonLakeFlyer's avatar
DonLakeFlyer committed
695 696
    gridAngle = _clampGridAngle90(gridAngle);
    gridAngle += refly ? 90 : 0;
697
    qCDebug(SurveyComplexItemLog) << "Clamped grid angle" << gridAngle;
DonLakeFlyer's avatar
DonLakeFlyer committed
698

699
    qCDebug(SurveyComplexItemLog) << "SurveyComplexItem::_gridGenerator gridSpacing:gridAngle:refly" << gridSpacing << gridAngle << refly;
700

DonLakeFlyer's avatar
DonLakeFlyer committed
701
    transectSegments.clear();
702 703 704

    // Convert polygon to bounding rect

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

    // 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
718

719
    QList<QLineF> lineList;
DonLakeFlyer's avatar
DonLakeFlyer committed
720

721
    // 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
722
    // This way they will always be guaranteed to intersect with a polygon edge no matter what angle they are rotated to.
723
    // They are initially generated with the transects flowing from west to east and then points within the transect north to south.
724
    double maxWidth = qMax(boundingRect.width(), boundingRect.height()) + 2000.0;
725 726 727 728 729 730 731 732 733 734 735
    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;
    }

736 737 738 739 740 741 742 743 744
    // 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

745 746 747 748 749 750 751 752 753 754 755 756 757 758 759
    // 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);
    }

760 761 762 763 764
    // 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);

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

    // Turn into a path
775
    for (int i=0; i<resultLines.count(); i++) {
DonLakeFlyer's avatar
DonLakeFlyer committed
776 777 778
        QLineF          transectLine;
        QList<QPointF>  transectPoints;
        const QLineF&   line = resultLines[i];
779

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

782
        if (i & 1) {
DonLakeFlyer's avatar
DonLakeFlyer committed
783
            transectLine = QLineF(line.p2(), line.p1());
784
        } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
785 786 787 788 789 790 791 792 793 794 795 796 797 798 799 800
            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());
801
                qCDebug(SurveyComplexItemLog) << "innerPoints" << innerPoints;
DonLakeFlyer's avatar
DonLakeFlyer committed
802 803 804 805
                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
806
            }
807
        }
DonLakeFlyer's avatar
DonLakeFlyer committed
808 809 810 811 812 813 814 815 816

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

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

        transectSegments.append(transectPoints);
817
    }
818 819

    return cameraShots;
820
}
821
#endif
822

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

829
    qCDebug(SurveyComplexItemLog) << "_appendWaypointToMission seq:trigger" << seqNum << (cameraTrigger != CameraTriggerNone);
830 831 832 833

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

DonLakeFlyer's avatar
DonLakeFlyer committed
845 846 847 848 849 850 851
    switch (cameraTrigger) {
    case CameraTriggerOff:
    case CameraTriggerOn:
        item = new MissionItem(seqNum++,
                               MAV_CMD_DO_SET_CAM_TRIGG_DIST,
                               MAV_FRAME_MISSION,
                               cameraTrigger == CameraTriggerOn ? _triggerDistance() : 0,
852 853 854 855 856
                               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
857
                               missionItemParent);
858
        items.append(item);
DonLakeFlyer's avatar
DonLakeFlyer committed
859 860 861 862 863
        break;
    case CameraTriggerHoverAndCapture:
        item = new MissionItem(seqNum++,
                               MAV_CMD_IMAGE_START_CAPTURE,
                               MAV_FRAME_MISSION,
Gus Grubba's avatar
Gus Grubba committed
864
                               0,                           // Reserved (Set to 0)
865 866
                               0,                           // Interval (none)
                               1,                           // Take 1 photo
867
                               NAN, NAN, NAN, NAN,          // param 4-7 reserved
868 869
                               true,                        // autoContinue
                               false,                       // isCurrentItem
DonLakeFlyer's avatar
DonLakeFlyer committed
870 871
                               missionItemParent);
        items.append(item);
872 873
#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
874 875 876 877 878 879 880 881 882 883
        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);
884
#endif
DonLakeFlyer's avatar
DonLakeFlyer committed
885 886
    default:
        break;
887
    }
888 889

    return seqNum;
890
}
891
#endif
892

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

    coord = transectPoints[pointIndex];
    return true;
}

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 1000 1001 1002 1003 1004
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)
1005
{
1006
    int seqNum = _sequenceNumber;
1007 1008
    bool firstWaypointTrigger = false;

1009 1010 1011 1012 1013 1014
#if 1
    // FIXME: Hack
    bool hasRefly = false;
    bool buildRefly = false;
#endif

1015
    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);
1016

1017
#if 0
1018
    QList<QList<QGeoCoordinate>>& transectSegments = buildRefly ? _reflyTransectSegments : _transectSegments;
1019
#endif
DonLakeFlyer's avatar
DonLakeFlyer committed
1020

1021
    if (!buildRefly && _imagesEverywhere()) {
1022
        firstWaypointTrigger = true;
DonLakeFlyer's avatar
DonLakeFlyer committed
1023 1024
    }

1025
    foreach (const QList<TransectStyleComplexItem::CoordInfo_t>& transect, _transects) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1026 1027
        int pointIndex = 0;
        QGeoCoordinate coord;
1028
        CameraTriggerCode cameraTrigger;
DonLakeFlyer's avatar
DonLakeFlyer committed
1029

1030
        qCDebug(SurveyComplexItemLog) << "transect.count" << transect.count();
DonLakeFlyer's avatar
DonLakeFlyer committed
1031 1032 1033

        if (_hasTurnaround()) {
            // Add entry turnaround point
1034 1035
            if (!_nextTransectCoord(segment, pointIndex++, coord)) {
                return false;
DonLakeFlyer's avatar
DonLakeFlyer committed
1036
            }
1037 1038
            seqNum = _appendWaypointToMission(items, seqNum, coord, firstWaypointTrigger ? CameraTriggerOn : CameraTriggerNone, missionItemParent);
            firstWaypointTrigger = false;
DonLakeFlyer's avatar
DonLakeFlyer committed
1039
        }
1040

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

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

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

DonLakeFlyer's avatar
DonLakeFlyer committed
1072 1073
        if (_hasTurnaround()) {
            // Add exit turnaround point
1074 1075
            if (!_nextTransectCoord(segment, pointIndex++, coord)) {
                return false;
1076
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
1077
            seqNum = _appendWaypointToMission(items, seqNum, coord, CameraTriggerNone, missionItemParent);
1078
        }
1079

1080
        qCDebug(SurveyComplexItemLog) << "last PointIndex" << pointIndex;
1081 1082
    }

1083
    if (((hasRefly && buildRefly) || !hasRefly) && _imagesEverywhere()) {
1084 1085 1086 1087 1088 1089 1090 1091
        // 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
1092 1093
                                            missionItemParent);
        items.append(item);
1094
    }
1095 1096 1097

    return true;
}
1098
#endif
1099

1100
#if 0
1101
void SurveyComplexItem::appendMissionItems(QList<MissionItem*>& items, QObject* missionItemParent)
1102 1103
{
    int seqNum = _sequenceNumber;
1104
    bool refly = refly90Degrees()->rawValue().toBool();
1105

1106
    if (!_appendMissionItemsWorker(items, missionItemParent, seqNum, refly, false /* buildRefly */)) {
1107 1108 1109
        return;
    }

1110 1111
    if (refly) {
        _appendMissionItemsWorker(items, missionItemParent, seqNum, refly, true /* buildRefly */);
1112 1113
    }
}
1114
#endif
1115

1116
bool SurveyComplexItem::_hasTurnaround(void) const
1117
{
1118
    return _turnaroundDistance() > 0;
1119
}
DonLakeFlyer's avatar
DonLakeFlyer committed
1120

1121
double SurveyComplexItem::_turnaroundDistance(void) const
DonLakeFlyer's avatar
DonLakeFlyer committed
1122
{
1123
    return _turnAroundDistanceFact.rawValue().toDouble();
DonLakeFlyer's avatar
DonLakeFlyer committed
1124 1125
}

1126
#if 0
1127
bool SurveyComplexItem::_triggerCamera(void) const
DonLakeFlyer's avatar
DonLakeFlyer committed
1128
{
1129
    return _triggerDistance() > 0;
DonLakeFlyer's avatar
DonLakeFlyer committed
1130 1131
}

1132
bool SurveyComplexItem::_imagesEverywhere(void) const
DonLakeFlyer's avatar
DonLakeFlyer committed
1133 1134 1135 1136
{
    return _triggerCamera() && _cameraTriggerInTurnaroundFact.rawValue().toBool();
}

1137
bool SurveyComplexItem::_hoverAndCaptureEnabled(void) const
DonLakeFlyer's avatar
DonLakeFlyer committed
1138 1139 1140
{
    return hoverAndCaptureAllowed() && !_imagesEverywhere() && _triggerCamera() && _hoverAndCaptureFact.rawValue().toBool();
}
1141
#endif
DonLakeFlyer's avatar
DonLakeFlyer committed
1142

1143
void SurveyComplexItem::_rebuildTransectsPhase1(void)
1144 1145 1146 1147 1148 1149 1150 1151
{
    _rebuildTransectsPhase1Worker(false /* refly */);
    if (_refly90DegreesFact.rawValue().toBool()) {
        _rebuildTransectsPhase1Worker(true /* refly */);
    }
}

void SurveyComplexItem::_rebuildTransectsPhase1Worker(bool refly)
DonLakeFlyer's avatar
DonLakeFlyer committed
1152
{
1153 1154 1155 1156 1157 1158 1159 1160 1161 1162 1163
    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;
    }

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

    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);
1198
    gridAngle += refly ? 90 : 0;
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 1276 1277 1278 1279 1280
    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);

1281 1282 1283 1284
    if (refly) {
        _optimizeTransectsForShortestDistance(_transects.last().last().coord, transects);
    }

1285 1286 1287 1288 1289 1290 1291 1292 1293 1294 1295 1296 1297 1298 1299
    if (_flyAlternateTransectsFact.rawValue().toBool()) {
        QList<QList<QGeoCoordinate>> alternatingTransects;
        for (int i=0; i<transects.count(); i++) {
            if (!(i & 1)) {
                alternatingTransects.append(transects[i]);
            }
        }
        for (int i=transects.count()-1; i>0; i--) {
            if (i & 1) {
                alternatingTransects.append(transects[i]);
            }
        }
        transects = alternatingTransects;
    }

1300 1301 1302 1303 1304 1305 1306 1307 1308 1309 1310 1311 1312 1313 1314 1315 1316 1317 1318
    // 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
1319 1320 1321 1322 1323 1324 1325 1326 1327 1328 1329 1330 1331 1332 1333 1334 1335 1336 1337 1338 1339 1340 1341 1342 1343 1344 1345 1346 1347 1348 1349
    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
1350 1351
}

1352
void SurveyComplexItem::_rebuildTransectsPhase2(void)
DonLakeFlyer's avatar
DonLakeFlyer committed
1353
{
1354 1355
    // Calculate distance flown for complex item
    _complexDistance = 0;
1356
    for (int i=0; i<_visualTransectPoints.count() - 1; i++) {
1357 1358 1359
        _complexDistance += _visualTransectPoints[i].value<QGeoCoordinate>().distanceTo(_visualTransectPoints[i+1].value<QGeoCoordinate>());
    }

1360
    double triggerDistance = _cameraCalc.adjustedFootprintFrontal()->rawValue().toDouble();
1361
    if (_cameraTriggerInTurnAroundFact.rawValue().toBool()) {
1362
        _cameraShots = qCeil(_complexDistance / triggerDistance);
1363
    } else {
1364 1365 1366 1367 1368 1369 1370 1371 1372 1373 1374 1375
        _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);
        }
1376 1377 1378 1379 1380 1381 1382 1383 1384
    }

    _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
1385
}
DonLakeFlyer's avatar
DonLakeFlyer committed
1386

1387
// FIXME: This same exact code is in Corridor Scan. Move to TransectStyleComplex?
1388
void SurveyComplexItem::applyNewAltitude(double newAltitude)
DonLakeFlyer's avatar
DonLakeFlyer committed
1389
{
1390 1391 1392
    _cameraCalc.valueSetIsDistance()->setRawValue(true);
    _cameraCalc.distanceToSurface()->setRawValue(newAltitude);
    _cameraCalc.setDistanceToSurfaceRelative(true);
DonLakeFlyer's avatar
DonLakeFlyer committed
1393
}
1394

1395
bool SurveyComplexItem::readyForSave(void) const
1396
{
1397 1398 1399 1400 1401 1402 1403 1404 1405 1406 1407
    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);
1408 1409
    }
}
1410

1411
void SurveyComplexItem::_appendLoadedMissionItems(QList<MissionItem*>& items, QObject* missionItemParent)
1412
{
1413 1414 1415 1416 1417 1418 1419 1420
    qCDebug(SurveyComplexItemLog) << "_appendLoadedMissionItems";

    int seqNum = _sequenceNumber;

    foreach (const MissionItem* loadedMissionItem, _loadedMissionItems) {
        MissionItem* item = new MissionItem(*loadedMissionItem, missionItemParent);
        item->setSequenceNumber(seqNum++);
        items.append(item);
1421 1422
    }
}
1423

DonLakeFlyer's avatar
DonLakeFlyer committed
1424 1425 1426 1427 1428 1429 1430
void SurveyComplexItem::rotateEntryPoint(void)
{
    if (_entryPoint == EntryLocationLast) {
        _entryPoint = EntryLocationFirst;
    } else {
        _entryPoint++;
    }
1431

DonLakeFlyer's avatar
DonLakeFlyer committed
1432 1433 1434 1435
    _rebuildTransects();

    setDirty(true);
}