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

#include "TransectStyleComplexItem.h"
#include "JsonHelper.h"
#include "MissionController.h"
#include "QGCGeo.h"
#include "QGCQGeoCoordinate.h"
#include "SettingsManager.h"
#include "AppSettings.h"
#include "QGCQGeoCoordinate.h"
18
#include "QGCApplication.h"
19 20
#include "PlanMasterController.h"
#include "FlightPathSegment.h"
21 22 23 24 25 26 27 28 29 30

#include <QPolygonF>

QGC_LOGGING_CATEGORY(TransectStyleComplexItemLog, "TransectStyleComplexItemLog")

const char* TransectStyleComplexItem::turnAroundDistanceName =              "TurnAroundDistance";
const char* TransectStyleComplexItem::turnAroundDistanceMultiRotorName =    "TurnAroundDistanceMultiRotor";
const char* TransectStyleComplexItem::cameraTriggerInTurnAroundName =       "CameraTriggerInTurnAround";
const char* TransectStyleComplexItem::hoverAndCaptureName =                 "HoverAndCapture";
const char* TransectStyleComplexItem::refly90DegreesName =                  "Refly90Degrees";
31 32 33
const char* TransectStyleComplexItem::terrainAdjustToleranceName =          "TerrainAdjustTolerance";
const char* TransectStyleComplexItem::terrainAdjustMaxClimbRateName =       "TerrainAdjustMaxClimbRate";
const char* TransectStyleComplexItem::terrainAdjustMaxDescentRateName =     "TerrainAdjustMaxDescentRate";
34

35 36
const char* TransectStyleComplexItem::_jsonTransectStyleComplexItemKey =    "TransectStyleComplexItem";
const char* TransectStyleComplexItem::_jsonCameraCalcKey =                  "CameraCalc";
DonLakeFlyer's avatar
DonLakeFlyer committed
37
const char* TransectStyleComplexItem::_jsonVisualTransectPointsKey =        "VisualTransectPoints";
38
const char* TransectStyleComplexItem::_jsonItemsKey =                       "Items";
39 40
const char* TransectStyleComplexItem::_jsonTerrainFollowKey =               "FollowTerrain";
const char* TransectStyleComplexItem::_jsonTerrainFlightSpeed =             "TerrainFlightSpeed";
41
const char* TransectStyleComplexItem::_jsonCameraShotsKey =                 "CameraShots";
42

43 44 45
TransectStyleComplexItem::TransectStyleComplexItem(PlanMasterController* masterController, bool flyView, QString settingsGroup, QObject* parent)
    : ComplexMissionItem                (masterController, flyView, parent)
    , _cameraCalc                       (masterController, settingsGroup)
46
    , _metaDataMap                      (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/TransectStyle.SettingsGroup.json"), this))
47
    , _turnAroundDistanceFact           (settingsGroup, _metaDataMap[_controllerVehicle->multiRotor() ? turnAroundDistanceMultiRotorName : turnAroundDistanceName])
48 49 50 51 52 53
    , _cameraTriggerInTurnAroundFact    (settingsGroup, _metaDataMap[cameraTriggerInTurnAroundName])
    , _hoverAndCaptureFact              (settingsGroup, _metaDataMap[hoverAndCaptureName])
    , _refly90DegreesFact               (settingsGroup, _metaDataMap[refly90DegreesName])
    , _terrainAdjustToleranceFact       (settingsGroup, _metaDataMap[terrainAdjustToleranceName])
    , _terrainAdjustMaxClimbRateFact    (settingsGroup, _metaDataMap[terrainAdjustMaxClimbRateName])
    , _terrainAdjustMaxDescentRateFact  (settingsGroup, _metaDataMap[terrainAdjustMaxDescentRateName])
54
{
55
    _terrainQueryTimer.setInterval(qgcApp()->runningUnitTests() ? 10 : _terrainQueryTimeoutMsecs);
56 57 58
    _terrainQueryTimer.setSingleShot(true);
    connect(&_terrainQueryTimer, &QTimer::timeout, this, &TransectStyleComplexItem::_reallyQueryTransectsPathHeightInfo);

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

63 64 65
    connect(&_turnAroundDistanceFact,                   &Fact::valueChanged,            this, &TransectStyleComplexItem::_rebuildTransects);
    connect(&_hoverAndCaptureFact,                      &Fact::valueChanged,            this, &TransectStyleComplexItem::_rebuildTransects);
    connect(&_refly90DegreesFact,                       &Fact::valueChanged,            this, &TransectStyleComplexItem::_rebuildTransects);
66 67 68 69
    connect(this,                      &TransectStyleComplexItem::followTerrainChanged, this, &TransectStyleComplexItem::_rebuildTransects);
    connect(&_terrainAdjustMaxClimbRateFact,            &Fact::valueChanged,            this, &TransectStyleComplexItem::_rebuildTransects);
    connect(&_terrainAdjustMaxDescentRateFact,          &Fact::valueChanged,            this, &TransectStyleComplexItem::_rebuildTransects);
    connect(&_terrainAdjustToleranceFact,               &Fact::valueChanged,            this, &TransectStyleComplexItem::_rebuildTransects);
70 71 72 73
    connect(&_surveyAreaPolygon,                        &QGCMapPolygon::pathChanged,    this, &TransectStyleComplexItem::_rebuildTransects);
    connect(&_cameraTriggerInTurnAroundFact,            &Fact::valueChanged,            this, &TransectStyleComplexItem::_rebuildTransects);
    connect(_cameraCalc.adjustedFootprintSide(),        &Fact::valueChanged,            this, &TransectStyleComplexItem::_rebuildTransects);
    connect(_cameraCalc.adjustedFootprintFrontal(),     &Fact::valueChanged,            this, &TransectStyleComplexItem::_rebuildTransects);
74
    connect(_cameraCalc.distanceToSurface(),            &Fact::rawValueChanged,         this, &TransectStyleComplexItem::_rebuildTransects);
75

76 77 78 79
    connect(&_turnAroundDistanceFact,                   &Fact::valueChanged,            this, &TransectStyleComplexItem::complexDistanceChanged);
    connect(&_hoverAndCaptureFact,                      &Fact::valueChanged,            this, &TransectStyleComplexItem::complexDistanceChanged);
    connect(&_refly90DegreesFact,                       &Fact::valueChanged,            this, &TransectStyleComplexItem::complexDistanceChanged);
    connect(&_surveyAreaPolygon,                        &QGCMapPolygon::pathChanged,    this, &TransectStyleComplexItem::complexDistanceChanged);
80

81 82 83 84
    connect(&_turnAroundDistanceFact,                   &Fact::valueChanged,            this, &TransectStyleComplexItem::greatestDistanceToChanged);
    connect(&_hoverAndCaptureFact,                      &Fact::valueChanged,            this, &TransectStyleComplexItem::greatestDistanceToChanged);
    connect(&_refly90DegreesFact,                       &Fact::valueChanged,            this, &TransectStyleComplexItem::greatestDistanceToChanged);
    connect(&_surveyAreaPolygon,                        &QGCMapPolygon::pathChanged,    this, &TransectStyleComplexItem::greatestDistanceToChanged);
85

86 87 88 89
    connect(&_turnAroundDistanceFact,                   &Fact::valueChanged,            this, &TransectStyleComplexItem::_setDirty);
    connect(&_cameraTriggerInTurnAroundFact,            &Fact::valueChanged,            this, &TransectStyleComplexItem::_setDirty);
    connect(&_hoverAndCaptureFact,                      &Fact::valueChanged,            this, &TransectStyleComplexItem::_setDirty);
    connect(&_refly90DegreesFact,                       &Fact::valueChanged,            this, &TransectStyleComplexItem::_setDirty);
90 91 92 93
    connect(this,                      &TransectStyleComplexItem::followTerrainChanged, this, &TransectStyleComplexItem::_setDirty);
    connect(&_terrainAdjustMaxClimbRateFact,            &Fact::valueChanged,            this, &TransectStyleComplexItem::_setDirty);
    connect(&_terrainAdjustMaxDescentRateFact,          &Fact::valueChanged,            this, &TransectStyleComplexItem::_setDirty);
    connect(&_terrainAdjustToleranceFact,               &Fact::valueChanged,            this, &TransectStyleComplexItem::_setDirty);
94 95 96 97 98 99 100
    connect(&_surveyAreaPolygon,                        &QGCMapPolygon::pathChanged,    this, &TransectStyleComplexItem::_setDirty);

    connect(&_surveyAreaPolygon,                        &QGCMapPolygon::dirtyChanged,   this, &TransectStyleComplexItem::_setIfDirty);
    connect(&_cameraCalc,                               &CameraCalc::dirtyChanged,      this, &TransectStyleComplexItem::_setIfDirty);

    connect(&_surveyAreaPolygon,                        &QGCMapPolygon::pathChanged,    this, &TransectStyleComplexItem::coveredAreaChanged);

101 102 103 104 105 106 107
    connect(_cameraCalc.distanceToSurface(),            &Fact::rawValueChanged,                         this, &TransectStyleComplexItem::_amslEntryAltChanged);
    connect(_cameraCalc.distanceToSurface(),            &Fact::rawValueChanged,                         this, &TransectStyleComplexItem::_amslExitAltChanged);
    connect(&_cameraCalc,                               &CameraCalc::distanceToSurfaceRelativeChanged,  this, &TransectStyleComplexItem::_amslEntryAltChanged);
    connect(&_cameraCalc,                               &CameraCalc::distanceToSurfaceRelativeChanged,  this, &TransectStyleComplexItem::_amslExitAltChanged);
    connect(&_cameraCalc,                               &CameraCalc::distanceToSurfaceRelativeChanged,  this, &TransectStyleComplexItem::_updateFlightPathSegmentsSignal);

    connect(&_cameraCalc,                               &CameraCalc::distanceToSurfaceRelativeChanged,  _missionController, &MissionController::recalcTerrainProfile);
108

109 110
    connect(&_hoverAndCaptureFact,                      &Fact::rawValueChanged,         this, &TransectStyleComplexItem::_handleHoverAndCaptureEnabled);

111 112
    connect(this,                                       &TransectStyleComplexItem::visualTransectPointsChanged, this, &TransectStyleComplexItem::complexDistanceChanged);
    connect(this,                                       &TransectStyleComplexItem::visualTransectPointsChanged, this, &TransectStyleComplexItem::greatestDistanceToChanged);
113 114
    connect(this,                                       &TransectStyleComplexItem::followTerrainChanged,        this, &TransectStyleComplexItem::_followTerrainChanged);
    connect(this,                                       &TransectStyleComplexItem::wizardModeChanged,           this, &TransectStyleComplexItem::readyForSaveStateChanged);
115

116 117 118
    connect(_missionController,                         &MissionController::plannedHomePositionChanged,         this, &TransectStyleComplexItem::_amslEntryAltChanged);
    connect(_missionController,                         &MissionController::plannedHomePositionChanged,         this, &TransectStyleComplexItem::_amslExitAltChanged);

DonLakeFlyer's avatar
DonLakeFlyer committed
119 120
    connect(&_surveyAreaPolygon,                        &QGCMapPolygon::isValidChanged, this, &TransectStyleComplexItem::readyForSaveStateChanged);

121
    setDirty(false);
122 123 124 125 126 127 128 129 130 131 132 133
}

void TransectStyleComplexItem::_setCameraShots(int cameraShots)
{
    if (_cameraShots != cameraShots) {
        _cameraShots = cameraShots;
        emit cameraShotsChanged();
    }
}

void TransectStyleComplexItem::setDirty(bool dirty)
{
134 135 136 137
    if (!dirty) {
        _surveyAreaPolygon.setDirty(false);
        _cameraCalc.setDirty(false);
    }
138 139 140 141 142 143 144 145
    if (_dirty != dirty) {
        _dirty = dirty;
        emit dirtyChanged(_dirty);
    }
}

void TransectStyleComplexItem::_save(QJsonObject& complexObject)
{
146 147 148 149 150 151 152
    QJsonObject innerObject;

    innerObject[JsonHelper::jsonVersionKey] =       1;
    innerObject[turnAroundDistanceName] =           _turnAroundDistanceFact.rawValue().toDouble();
    innerObject[cameraTriggerInTurnAroundName] =    _cameraTriggerInTurnAroundFact.rawValue().toBool();
    innerObject[hoverAndCaptureName] =              _hoverAndCaptureFact.rawValue().toBool();
    innerObject[refly90DegreesName] =               _refly90DegreesFact.rawValue().toBool();
153
    innerObject[_jsonTerrainFollowKey] =            _followTerrain;
154
    innerObject[_jsonCameraShotsKey] =              _cameraShots;
155 156

    if (_followTerrain) {
157 158 159 160
        innerObject[terrainAdjustToleranceName]         = _terrainAdjustToleranceFact.rawValue().toDouble();
        innerObject[terrainAdjustMaxClimbRateName]      = _terrainAdjustMaxClimbRateFact.rawValue().toDouble();
        innerObject[terrainAdjustMaxDescentRateName]    = _terrainAdjustMaxDescentRateFact.rawValue().toDouble();
        innerObject[_jsonTerrainFlightSpeed]            = _vehicleSpeed;
161
    }
162 163 164

    QJsonObject cameraCalcObject;
    _cameraCalc.save(cameraCalcObject);
165 166 167 168 169
    innerObject[_jsonCameraCalcKey] = cameraCalcObject;

    QJsonValue  transectPointsJson;

    // Save transects polyline
170
    JsonHelper::saveGeoCoordinateArray(_visualTransectPoints, false /* writeAltitude */, transectPointsJson);
DonLakeFlyer's avatar
DonLakeFlyer committed
171
    innerObject[_jsonVisualTransectPointsKey] = transectPointsJson;
172 173 174 175 176 177

    // Save the interal mission items
    QJsonArray  missionItemsJsonArray;
    QObject* missionItemParent = new QObject();
    QList<MissionItem*> missionItems;
    appendMissionItems(missionItems, missionItemParent);
178
    for (const MissionItem* missionItem: missionItems) {
179 180 181 182 183 184 185 186
        QJsonObject missionItemJsonObject;
        missionItem->save(missionItemJsonObject);
        missionItemsJsonArray.append(missionItemJsonObject);
    }
    missionItemParent->deleteLater();
    innerObject[_jsonItemsKey] = missionItemsJsonArray;

    complexObject[_jsonTransectStyleComplexItemKey] = innerObject;
187 188 189 190 191 192 193 194 195 196 197
}

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

Don Gagne's avatar
Don Gagne committed
198
bool TransectStyleComplexItem::_load(const QJsonObject& complexObject, bool forPresets, QString& errorString)
199 200
{
    QList<JsonHelper::KeyValidateInfo> keyInfoList = {
201 202 203 204 205 206 207 208 209
        { _jsonTransectStyleComplexItemKey, QJsonValue::Object, true },
    };
    if (!JsonHelper::validateKeys(complexObject, keyInfoList, errorString)) {
        return false;
    }

    // The TransectStyleComplexItem is a sub-object of the main complex item object
    QJsonObject innerObject = complexObject[_jsonTransectStyleComplexItemKey].toObject();

210 211 212 213 214 215 216 217
    if (innerObject.contains(JsonHelper::jsonVersionKey)) {
        int version = innerObject[JsonHelper::jsonVersionKey].toInt();
        if (version != 1) {
            errorString = tr("TransectStyleComplexItem version %2 not supported").arg(version);
            return false;
        }
    }

218 219
    QList<JsonHelper::KeyValidateInfo> innerKeyInfoList = {
        { JsonHelper::jsonVersionKey,       QJsonValue::Double, true },
220 221 222 223 224
        { turnAroundDistanceName,           QJsonValue::Double, true },
        { cameraTriggerInTurnAroundName,    QJsonValue::Bool,   true },
        { hoverAndCaptureName,              QJsonValue::Bool,   true },
        { refly90DegreesName,               QJsonValue::Bool,   true },
        { _jsonCameraCalcKey,               QJsonValue::Object, true },
Don Gagne's avatar
Don Gagne committed
225 226
        { _jsonVisualTransectPointsKey,     QJsonValue::Array,  !forPresets },
        { _jsonItemsKey,                    QJsonValue::Array,  !forPresets },
227 228
        { _jsonTerrainFollowKey,            QJsonValue::Bool,   true },
        { _jsonCameraShotsKey,              QJsonValue::Double, false },        // Not required since it was missing from initial implementation
229
    };
230
    if (!JsonHelper::validateKeys(innerObject, innerKeyInfoList, errorString)) {
231 232 233
        return false;
    }

Don Gagne's avatar
Don Gagne committed
234 235 236
    if (!forPresets) {
        // Load visual transect points
        if (!JsonHelper::loadGeoCoordinateArray(innerObject[_jsonVisualTransectPointsKey], false /* altitudeRequired */, _visualTransectPoints, errorString)) {
237 238
            return false;
        }
Don Gagne's avatar
Don Gagne committed
239 240
        _coordinate = _visualTransectPoints.count() ? _visualTransectPoints.first().value<QGeoCoordinate>() : QGeoCoordinate();
        _exitCoordinate = _visualTransectPoints.count() ? _visualTransectPoints.last().value<QGeoCoordinate>() : QGeoCoordinate();
241
        _isIncomplete = false;
Don Gagne's avatar
Don Gagne committed
242 243 244 245 246 247 248 249 250 251 252 253 254

        // Load generated mission items
        _loadedMissionItemsParent = new QObject(this);
        QJsonArray missionItemsJsonArray = innerObject[_jsonItemsKey].toArray();
        for (const QJsonValue missionItemJson: missionItemsJsonArray) {
            MissionItem* missionItem = new MissionItem(_loadedMissionItemsParent);
            if (!missionItem->load(missionItemJson.toObject(), 0 /* sequenceNumber */, errorString)) {
                _loadedMissionItemsParent->deleteLater();
                _loadedMissionItemsParent = nullptr;
                return false;
            }
            _loadedMissionItems.append(missionItem);
        }
255 256 257
    }

    // Load CameraCalc data
Don Gagne's avatar
Don Gagne committed
258
    if (!_cameraCalc.load(innerObject[_jsonCameraCalcKey].toObject(), errorString)) {
259 260 261 262 263 264 265
        return false;
    }

    // Load TransectStyleComplexItem individual values
    _turnAroundDistanceFact.setRawValue         (innerObject[turnAroundDistanceName].toDouble());
    _cameraTriggerInTurnAroundFact.setRawValue  (innerObject[cameraTriggerInTurnAroundName].toBool());
    _hoverAndCaptureFact.setRawValue            (innerObject[hoverAndCaptureName].toBool());
266
    _refly90DegreesFact.setRawValue             (innerObject[refly90DegreesName].toBool());
267
    _followTerrain = innerObject[_jsonTerrainFollowKey].toBool();
268

269 270 271 272 273 274
    // These two keys where not included in initial implementation so they are optional. Without them the values will be
    // incorrect when loaded though.
    if (innerObject.contains(_jsonCameraShotsKey)) {
        _cameraShots = innerObject[_jsonCameraShotsKey].toInt();
    }

275 276 277 278 279
    if (_followTerrain) {
        QList<JsonHelper::KeyValidateInfo> followTerrainKeyInfoList = {
            { terrainAdjustToleranceName,       QJsonValue::Double, true },
            { terrainAdjustMaxClimbRateName,    QJsonValue::Double, true },
            { terrainAdjustMaxDescentRateName,  QJsonValue::Double, true },
280
            { _jsonTerrainFlightSpeed,          QJsonValue::Double, false },        // Not required since it was missing from initial implementation
281 282 283 284 285 286 287 288
        };
        if (!JsonHelper::validateKeys(innerObject, followTerrainKeyInfoList, errorString)) {
            return false;
        }

        _terrainAdjustToleranceFact.setRawValue         (innerObject[terrainAdjustToleranceName].toDouble());
        _terrainAdjustMaxClimbRateFact.setRawValue      (innerObject[terrainAdjustMaxClimbRateName].toDouble());
        _terrainAdjustMaxDescentRateFact.setRawValue    (innerObject[terrainAdjustMaxDescentRateName].toDouble());
289 290 291
        if (innerObject.contains(_jsonTerrainFlightSpeed)) {
            _vehicleSpeed = innerObject[_jsonTerrainFlightSpeed].toDouble();
        }
292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313

        if (!forPresets) {
            // We have to grovel through mission items to determine min/max alt
            _minAMSLAltitude = 0;
            _maxAMSLAltitude = 0;
            for (const MissionItem* missionItem: _loadedMissionItems) {
                if (missionItem->command() == MAV_CMD_NAV_WAYPOINT || missionItem->command() == MAV_CMD_CONDITION_GATE) {
                    _minAMSLAltitude = qMin(_minAMSLAltitude, missionItem->param7());
                    _maxAMSLAltitude = qMax(_maxAMSLAltitude, missionItem->param7());
                }
            }
        }
    } else if (!forPresets) {
        _minAMSLAltitude = _maxAMSLAltitude = _cameraCalc.distanceToSurface()->rawValue().toDouble() + (_cameraCalc.distanceToSurfaceRelative() ? _missionController->plannedHomePosition().altitude() : 0);
    }

    if (!forPresets) {
        emit minAMSLAltitudeChanged(_minAMSLAltitude);
        emit maxAMSLAltitudeChanged(_maxAMSLAltitude);
        _amslEntryAltChanged();
        _amslExitAltChanged();
        emit _updateFlightPathSegmentsSignal();
314
    }
315 316 317 318 319 320 321

    return true;
}

double TransectStyleComplexItem::greatestDistanceTo(const QGeoCoordinate &other) const
{
    double greatestDistance = 0.0;
322 323
    for (int i=0; i<_visualTransectPoints.count(); i++) {
        QGeoCoordinate vertex = _visualTransectPoints[i].value<QGeoCoordinate>();
324 325 326 327 328 329 330 331 332 333 334 335
        double distance = vertex.distanceTo(other);
        if (distance > greatestDistance) {
            greatestDistance = distance;
        }
    }

    return greatestDistance;
}

void TransectStyleComplexItem::setMissionFlightStatus(MissionController::MissionFlightStatus_t& missionFlightStatus)
{
    ComplexMissionItem::setMissionFlightStatus(missionFlightStatus);
336
    if (!QGC::fuzzyCompare(_vehicleSpeed, missionFlightStatus.vehicleSpeed)) {
337 338 339
        _vehicleSpeed = missionFlightStatus.vehicleSpeed;
        // Vehicle speed change affects max climb/descent rates calcs for terrain so we need to re-adjust
        _rebuildTransects();
340 341 342 343 344 345 346 347 348
        emit timeBetweenShotsChanged();
    }
}

void TransectStyleComplexItem::_setDirty(void)
{
    setDirty(true);
}

349 350 351 352 353 354 355
void TransectStyleComplexItem::_setIfDirty(bool dirty)
{
    if (dirty) {
        setDirty(true);
    }
}

356 357 358 359 360 361 362 363 364 365 366 367 368
void TransectStyleComplexItem::_updateCoordinateAltitudes(void)
{
    emit coordinateChanged(coordinate());
    emit exitCoordinateChanged(exitCoordinate());
}

double TransectStyleComplexItem::coveredArea(void) const
{
    return _surveyAreaPolygon.area();
}

bool TransectStyleComplexItem::_hasTurnaround(void) const
{
369
    return _turnAroundDistance() > 0;
370 371
}

372
double TransectStyleComplexItem::_turnAroundDistance(void) const
373 374 375 376 377 378
{
    return _turnAroundDistanceFact.rawValue().toDouble();
}

bool TransectStyleComplexItem::hoverAndCaptureAllowed(void) const
{
379
    return _controllerVehicle->multiRotor() || _controllerVehicle->vtol();
380 381
}

382 383
void TransectStyleComplexItem::_rebuildTransects(void)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
384 385 386 387
    if (_ignoreRecalc) {
        return;
    }

388
    _rebuildTransectsPhase1();
389

DonLakeFlyer's avatar
DonLakeFlyer committed
390 391 392
    if (_followTerrain) {
        // Query the terrain data. Once available terrain heights will be calculated
        _queryTransectsPathHeightInfo();
393 394
        // We won't know min/max till were done
        _minAMSLAltitude = _maxAMSLAltitude = qQNaN();
DonLakeFlyer's avatar
DonLakeFlyer committed
395 396 397 398 399 400 401 402 403 404 405 406 407
    } else {
        // Not following terrain, just add requested altitude to coords
        double requestedAltitude = _cameraCalc.distanceToSurface()->rawValue().toDouble();

        for (int i=0; i<_transects.count(); i++) {
            QList<CoordInfo_t>& transect = _transects[i];

            for (int j=0; j<transect.count(); j++) {
                QGeoCoordinate& coord = transect[j].coord;

                coord.setAltitude(requestedAltitude);
            }
        }
408 409

        _minAMSLAltitude = _maxAMSLAltitude = requestedAltitude + (_cameraCalc.distanceToSurfaceRelative() ? _missionController->plannedHomePosition().altitude() : 0);
DonLakeFlyer's avatar
DonLakeFlyer committed
410
    }
411

412 413 414 415 416 417 418
    // Calc bounding cube
    double north = 0.0;
    double south = 180.0;
    double east  = 0.0;
    double west  = 360.0;
    double bottom = 100000.;
    double top = 0.;
419 420
    // Generate the visuals transect representation
    _visualTransectPoints.clear();
421 422
    for (const QList<CoordInfo_t>& transect: _transects) {
        for (const CoordInfo_t& coordInfo: transect) {
423
            _visualTransectPoints.append(QVariant::fromValue(coordInfo.coord));
424 425 426 427 428 429 430 431
            double lat = coordInfo.coord.latitude()  + 90.0;
            double lon = coordInfo.coord.longitude() + 180.0;
            north   = fmax(north, lat);
            south   = fmin(south, lat);
            east    = fmax(east,  lon);
            west    = fmin(west,  lon);
            bottom  = fmin(bottom, coordInfo.coord.altitude());
            top     = fmax(top, coordInfo.coord.altitude());
432 433
        }
    }
434 435
    //-- Update bounding cube for airspace management control
    _setBoundingCube(QGCGeoBoundingCube(
436 437
                         QGeoCoordinate(north - 90.0, west - 180.0, bottom),
                         QGeoCoordinate(south - 90.0, east - 180.0, top)));
438 439
    emit visualTransectPointsChanged();

DonLakeFlyer's avatar
DonLakeFlyer committed
440 441 442 443 444
    _coordinate = _visualTransectPoints.count() ? _visualTransectPoints.first().value<QGeoCoordinate>() : QGeoCoordinate();
    _exitCoordinate = _visualTransectPoints.count() ? _visualTransectPoints.last().value<QGeoCoordinate>() : QGeoCoordinate();
    emit coordinateChanged(_coordinate);
    emit exitCoordinateChanged(_exitCoordinate);

445 446 447 448 449
    if (_isIncomplete) {
        _isIncomplete = false;
        emit isIncompleteChanged();
    }

450 451
    _recalcComplexDistance();
    _recalcCameraShots();
452 453

    emit lastSequenceNumberChanged(lastSequenceNumber());
454
    emit timeBetweenShotsChanged();
455
    emit additionalTimeDelayChanged();
456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546

    emit minAMSLAltitudeChanged(_minAMSLAltitude);
    emit maxAMSLAltitudeChanged(_maxAMSLAltitude);

    emit _updateFlightPathSegmentsSignal();
    _amslEntryAltChanged();
    _amslExitAltChanged();
}

void TransectStyleComplexItem::_segmentTerrainCollisionChanged(bool terrainCollision)
{
    ComplexMissionItem::_segmentTerrainCollisionChanged(terrainCollision);
    _surveyAreaPolygon.setShowAltColor(_cTerrainCollisionSegments != 0);
}

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

    _flightPathSegments.beginReset();
    _flightPathSegments.clearAndDeleteContents();

    QGeoCoordinate lastTransectExit = QGeoCoordinate();
    if (_followTerrain) {
        if (_loadedMissionItems.count()) {
            // We are working from loaded mission items from a plan. We have to grovel through the mission items
            // building up segments from waypoints.
            QGeoCoordinate prevCoord = QGeoCoordinate();
            double prevAlt = 0;
            for (const MissionItem* missionItem: _loadedMissionItems) {
                if (missionItem->command() == MAV_CMD_NAV_WAYPOINT || missionItem->command() == MAV_CMD_CONDITION_GATE) {
                    if (prevCoord.isValid()) {
                        _appendFlightPathSegment(prevCoord, prevAlt, missionItem->coordinate(), missionItem->param7());
                    }
                    prevCoord = missionItem->coordinate();
                    prevAlt = missionItem->param7();
                }
            }
        } else {
            // We are working for live transect data. We don't show flight path segments until terrain data is back and recalced
            if (_transectsPathHeightInfo.count()) {
                // The altitudes of the flight path segments for follow terrain can all occur at different altitudes. Because of that we
                // need to to add FlightPathSegment's for every section in order to get good terrain collision data and flight path profile.
                for (const QList<CoordInfo_t>& transect: _transects) {
                    // Turnaround segment
                    if (lastTransectExit.isValid()) {
                        const QGeoCoordinate& coord2 = transect.first().coord;
                        _appendFlightPathSegment(lastTransectExit, lastTransectExit.altitude(), coord2, coord2.altitude());
                    }

                    QGeoCoordinate prevCoordInTransect = QGeoCoordinate();
                    for (const CoordInfo_t& coordInfo: transect) {
                        if (prevCoordInTransect.isValid()) {
                            const QGeoCoordinate& coord2 = coordInfo.coord;
                            _appendFlightPathSegment(prevCoordInTransect, prevCoordInTransect.altitude(), coord2, coord2.altitude());
                        }
                        prevCoordInTransect = coordInfo.coord;
                    }

                    lastTransectExit = transect.last().coord;
                }
            }
        }
    } else {
        // Since we aren't following terrain all the transects are at the same height. We can use _visualTransectPoints to build the
        // flight path segments. The benefit of _visualTransectPoints is that it is also available when a Plan is loaded from a file
        // and we are working from  stored mission items. In that case we don't have _transects set up for use.
        QGeoCoordinate prevCoord;
        double surveyAlt = amslEntryAlt();
        for (const QVariant& varCoord: _visualTransectPoints) {
            QGeoCoordinate thisCoord = varCoord.value<QGeoCoordinate>();
            if (prevCoord.isValid()) {
                _appendFlightPathSegment(prevCoord,  surveyAlt, thisCoord,  surveyAlt);
            }
            prevCoord = thisCoord;
        }
    }

    _flightPathSegments.endReset();

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

    _masterController->missionController()->recalcTerrainProfile();
547
}
548 549 550 551

void TransectStyleComplexItem::_queryTransectsPathHeightInfo(void)
{
    _transectsPathHeightInfo.clear();
DonLakeFlyer's avatar
DonLakeFlyer committed
552
    emit readyForSaveStateChanged();
553

554
    if (_transects.count()) {
555
        // We don't actually send the query until this timer times out. This way we only send
556
        // the latest request if we get a bunch in a row.
557 558 559 560 561 562
        _terrainQueryTimer.start();
    }
}

void TransectStyleComplexItem::_reallyQueryTransectsPathHeightInfo(void)
{
563
    // Clear any previous query
564 565 566 567
    if (_currentTerrainFollowQuery) {
        // We are already waiting on another query. We don't care about those results any more.
        disconnect(_currentTerrainFollowQuery, &TerrainPolyPathQuery::terrainDataReceived, this, &TransectStyleComplexItem::_polyPathTerrainData);
        _currentTerrainFollowQuery = nullptr;
568 569
    }

570 571
    // Append all transects into a single PolyPath query
    QList<QGeoCoordinate> transectPoints;
572 573
    for (const QList<CoordInfo_t>& transect: _transects) {
        for (const CoordInfo_t& coordInfo: transect) {
574 575 576 577 578
            transectPoints.append(coordInfo.coord);
        }
    }

    if (transectPoints.count() > 1) {
579 580 581
        _currentTerrainFollowQuery = new TerrainPolyPathQuery(true /* autoDelete */);
        connect(_currentTerrainFollowQuery, &TerrainPolyPathQuery::terrainDataReceived, this, &TransectStyleComplexItem::_polyPathTerrainData);
        _currentTerrainFollowQuery->requestData(transectPoints);
582 583 584 585 586
    }
}

void TransectStyleComplexItem::_polyPathTerrainData(bool success, const QList<TerrainPathQuery::PathHeightInfo_t>& rgPathHeightInfo)
{
587
    _transectsPathHeightInfo.clear();
DonLakeFlyer's avatar
DonLakeFlyer committed
588
    emit readyForSaveStateChanged();
589

590
    if (success) {
591 592 593 594 595 596 597 598 599 600
        // Break out into individual transects
        int pathHeightIndex = 0;
        for (int i=0; i<_transects.count(); i++) {
            _transectsPathHeightInfo.append(QList<TerrainPathQuery::PathHeightInfo_t>());
            int cPathHeight = _transects[i].count() - 1;
            while (cPathHeight-- > 0) {
                _transectsPathHeightInfo[i].append(rgPathHeightInfo[pathHeightIndex++]);
            }
            pathHeightIndex++;  // There is an extra on between each transect
        }
DonLakeFlyer's avatar
DonLakeFlyer committed
601
        emit readyForSaveStateChanged();
602 603 604

        // Now that we have terrain data we can adjust
        _adjustTransectsForTerrain();
605
    }
606

607 608 609 610

    QObject* object = qobject_cast<QObject*>(sender());
    if (object) {
        object->deleteLater();
611
    }
612
    _currentTerrainFollowQuery = nullptr;
613 614
}

DonLakeFlyer's avatar
DonLakeFlyer committed
615
TransectStyleComplexItem::ReadyForSaveState TransectStyleComplexItem::readyForSaveState(void) const
616
{
617 618 619 620 621 622 623 624 625 626 627 628 629
    bool terrainReady = false;
    if (_followTerrain) {
        if (_loadedMissionItems.count()) {
            // We have loaded mission items. Everything is ready to go.
            terrainReady = true;
        } else {
            // Survey is currently being designed. We aren't ready if we don't have terrain heights yet.
            terrainReady = _transectsPathHeightInfo.count();
        }
    } else {
        // Now following terrain so always ready on terrain
        terrainReady = true;
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
630
    bool polygonNotReady = !_surveyAreaPolygon.isValid();
Don Gagne's avatar
Don Gagne committed
631
    //qDebug() << polygonNotReady << _wizardMode << terrainReady;
632
    return (polygonNotReady || _wizardMode) ?
DonLakeFlyer's avatar
DonLakeFlyer committed
633 634
                NotReadyForSaveData :
                (terrainReady ? ReadyForSave : NotReadyForSaveTerrain);
635 636
}

637
void TransectStyleComplexItem::_adjustTransectsForTerrain(void)
638
{
639
    if (_followTerrain) {
DonLakeFlyer's avatar
DonLakeFlyer committed
640
        if (readyForSaveState() != ReadyForSave) {
641
            qCWarning(TransectStyleComplexItemLog) << "_adjustTransectPointsForTerrain called when terrain data not ready";
642
            qgcApp()->showAppMessage(tr("INTERNAL ERROR: TransectStyleComplexItem::_adjustTransectPointsForTerrain called when terrain data not ready. Plan will be incorrect."));
643 644
            return;
        }
645

646 647 648
        // First step is add all interstitial points at max resolution
        for (int i=0; i<_transects.count(); i++) {
            _addInterstitialTerrainPoints(_transects[i], _transectsPathHeightInfo[i]);
649
        }
650 651 652

        for (int i=0; i<_transects.count(); i++) {
            _adjustForMaxRates(_transects[i]);
653 654
        }

655 656 657
        for (int i=0; i<_transects.count(); i++) {
            _adjustForTolerance(_transects[i]);
        }
658

659
        emit lastSequenceNumberChanged(lastSequenceNumber());
660
        emit _updateFlightPathSegmentsSignal();
661

662 663 664
        _amslEntryAltChanged();
        _amslExitAltChanged();

DonLakeFlyer's avatar
DonLakeFlyer committed
665 666
        _minAMSLAltitude = qQNaN();
        _maxAMSLAltitude = qQNaN();
667 668
        for (const QList<CoordInfo_t>& transect: _transects) {
            for (const CoordInfo_t& coordInfo: transect) {
DonLakeFlyer's avatar
DonLakeFlyer committed
669 670
                _minAMSLAltitude = std::fmin(_minAMSLAltitude, coordInfo.coord.altitude());
                _maxAMSLAltitude = std::fmax(_maxAMSLAltitude, coordInfo.coord.altitude());
671 672
            }
        }
673 674
        emit minAMSLAltitudeChanged(_minAMSLAltitude);
        emit maxAMSLAltitudeChanged(_maxAMSLAltitude);
675
    }
676 677 678 679 680 681
}

/// Returns the altitude in between the two points on a line.
///     @param precentTowardsTo Example: .25 = twenty five percent along the distance of from to to
double TransectStyleComplexItem::_altitudeBetweenCoords(const QGeoCoordinate& fromCoord, const QGeoCoordinate& toCoord, double percentTowardsTo)
{
682 683
    double fromAlt = fromCoord.altitude();
    double toAlt = toCoord.altitude();
684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702 703 704 705 706 707 708 709 710 711 712 713 714 715 716
    double altDiff = toAlt - fromAlt;
    return fromAlt + (altDiff * percentTowardsTo);
}

/// Determine the maximum height within the PathHeightInfo
///     @param fromIndex First height index to consider
///     @param fromIndex Last height index to consider
///     @param[out] maxHeight Maximum height
/// @return index within PathHeightInfo_t.heights which contains maximum height, -1 no height data in between from and to indices
int TransectStyleComplexItem::_maxPathHeight(const TerrainPathQuery::PathHeightInfo_t& pathHeightInfo, int fromIndex, int toIndex, double& maxHeight)
{
    maxHeight = qQNaN();

    if (toIndex - fromIndex < 2) {
        return -1;
    }

    fromIndex++;
    toIndex--;

    int maxIndex = fromIndex;
    maxHeight = pathHeightInfo.heights[fromIndex];

    for (int i=fromIndex; i<=toIndex; i++) {
        if (pathHeightInfo.heights[i] > maxHeight) {
            maxIndex = i;
            maxHeight = pathHeightInfo.heights[i];
        }
    }

    return maxIndex;
}

717
void TransectStyleComplexItem::_adjustForMaxRates(QList<CoordInfo_t>& transect)
718
{
719 720 721
    double maxClimbRate     = _terrainAdjustMaxClimbRateFact.rawValue().toDouble();
    double maxDescentRate   = _terrainAdjustMaxDescentRateFact.rawValue().toDouble();
    double flightSpeed      = _vehicleSpeed;
722 723 724 725 726

    if (qIsNaN(flightSpeed) || (maxClimbRate == 0 && maxDescentRate == 0)) {
        if (qIsNaN(flightSpeed)) {
            qWarning() << "TransectStyleComplexItem::_adjustForMaxRates called with flightSpeed = NaN";
        }
727 728 729
        return;
    }

730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745 746 747 748 749 750 751 752
    if (maxClimbRate > 0) {
        // Adjust climb rates
        bool climbRateAdjusted;
        do {
            //qDebug() << "climbrate pass";
            climbRateAdjusted = false;
            for (int i=0; i<transect.count() - 1; i++) {
                QGeoCoordinate& fromCoord = transect[i].coord;
                QGeoCoordinate& toCoord = transect[i+1].coord;

                double altDifference = toCoord.altitude() - fromCoord.altitude();
                double distance = fromCoord.distanceTo(toCoord);
                double seconds = distance / flightSpeed;
                double climbRate = altDifference / seconds;

                //qDebug() << QString("Index:%1 altDifference:%2 distance:%3 seconds:%4 climbRate:%5").arg(i).arg(altDifference).arg(distance).arg(seconds).arg(climbRate);

                if (climbRate > 0 && climbRate - maxClimbRate > 0.1) {
                    double maxAltitudeDelta = maxClimbRate * seconds;
                    fromCoord.setAltitude(toCoord.altitude() - maxAltitudeDelta);
                    //qDebug() << "Adjusting";
                    climbRateAdjusted = true;
                }
753
            }
754 755 756 757 758 759 760 761 762 763 764 765 766 767 768 769 770 771 772 773 774 775 776 777 778 779 780
        } while (climbRateAdjusted);
    }

    if (maxDescentRate > 0) {
        // Adjust descent rates
        bool descentRateAdjusted;
        maxDescentRate = -maxDescentRate;
        do {
            //qDebug() << "descent rate pass";
            descentRateAdjusted = false;
            for (int i=1; i<transect.count(); i++) {
                QGeoCoordinate& fromCoord = transect[i-1].coord;
                QGeoCoordinate& toCoord = transect[i].coord;

                double altDifference = toCoord.altitude() - fromCoord.altitude();
                double distance = fromCoord.distanceTo(toCoord);
                double seconds = distance / flightSpeed;
                double descentRate = altDifference / seconds;

                //qDebug() << QString("Index:%1 altDifference:%2 distance:%3 seconds:%4 descentRate:%5").arg(i).arg(altDifference).arg(distance).arg(seconds).arg(descentRate);

                if (descentRate < 0 && descentRate - maxDescentRate < -0.1) {
                    double maxAltitudeDelta = maxDescentRate * seconds;
                    toCoord.setAltitude(fromCoord.altitude() + maxAltitudeDelta);
                    //qDebug() << "Adjusting";
                    descentRateAdjusted = true;
                }
781
            }
782 783
        } while (descentRateAdjusted);
    }
784 785 786 787 788 789
}

void TransectStyleComplexItem::_adjustForTolerance(QList<CoordInfo_t>& transect)
{
    QList<CoordInfo_t> adjustedPoints;

790 791 792
    if (transect.count()) {
        double          tolerance =     _terrainAdjustToleranceFact.rawValue().toDouble();
        CoordInfo_t&    lastCoordInfo = transect.first();
793

794
        adjustedPoints.append(lastCoordInfo);
795

796 797 798 799 800 801 802 803
        int coordIndex = 1;
        while (coordIndex < transect.count()) {
            // Walk forward until we fall out of tolerence. When we fall out of tolerance add that point.
            // We always add non-interstitial points no matter what.
            const CoordInfo_t& nextCoordInfo = transect[coordIndex];
            if (nextCoordInfo.coordType != CoordTypeInteriorTerrainAdded || qAbs(lastCoordInfo.coord.altitude() - nextCoordInfo.coord.altitude()) > tolerance) {
                adjustedPoints.append(nextCoordInfo);
                lastCoordInfo = nextCoordInfo;
804
            }
805
            coordIndex++;
806 807 808 809 810 811 812 813 814 815
        }
    }

    transect = adjustedPoints;
}

void TransectStyleComplexItem::_addInterstitialTerrainPoints(QList<CoordInfo_t>& transect, const QList<TerrainPathQuery::PathHeightInfo_t>& transectPathHeightInfo)
{
    QList<CoordInfo_t> adjustedTransect;

816
    double distanceToSurface = _cameraCalc.distanceToSurface()->rawValue().toDouble();
817 818 819 820

    for (int i=0; i<transect.count() - 1; i++) {
        CoordInfo_t fromCoordInfo = transect[i];
        CoordInfo_t toCoordInfo = transect[i+1];
821

822 823 824 825 826
        double azimuth = fromCoordInfo.coord.azimuthTo(toCoordInfo.coord);
        double distance = fromCoordInfo.coord.distanceTo(toCoordInfo.coord);

        const TerrainPathQuery::PathHeightInfo_t& pathHeightInfo = transectPathHeightInfo[i];

827 828
        fromCoordInfo.coord.setAltitude(pathHeightInfo.heights.first() + distanceToSurface);
        toCoordInfo.coord.setAltitude(pathHeightInfo.heights.last() + distanceToSurface);
829

830 831 832 833
        if (i == 0) {
            adjustedTransect.append(fromCoordInfo);
        }

834 835
        int cHeights = pathHeightInfo.heights.count();
        for (int pathHeightIndex=1; pathHeightIndex<cHeights - 1; pathHeightIndex++) {
836
            double interstitialTerrainHeight = pathHeightInfo.heights[pathHeightIndex];
837 838 839 840 841
            double percentTowardsTo = (1.0 / (cHeights - 1)) * pathHeightIndex;

            CoordInfo_t interstitialCoordInfo;
            interstitialCoordInfo.coordType = CoordTypeInteriorTerrainAdded;
            interstitialCoordInfo.coord = fromCoordInfo.coord.atDistanceAndAzimuth(distance * percentTowardsTo, azimuth);
842
            interstitialCoordInfo.coord.setAltitude(interstitialTerrainHeight + distanceToSurface);
843 844

            adjustedTransect.append(interstitialCoordInfo);
845
        }
846 847 848 849

        adjustedTransect.append(toCoordInfo);
    }

850 851
    CoordInfo_t lastCoordInfo = transect.last();
    const TerrainPathQuery::PathHeightInfo_t& pathHeightInfo = transectPathHeightInfo.last();
852
    lastCoordInfo.coord.setAltitude(pathHeightInfo.heights.last() + distanceToSurface);
853 854
    adjustedTransect.append(lastCoordInfo);

855 856
#if 0
    qDebug() << "_addInterstitialTerrainPoints";
857
    for (const TransectStyleComplexItem::CoordInfo_t& coordInfo: adjustedTransect) {
858
        qDebug() << coordInfo.coordType;
859
    }
860
#endif
861

862
    transect = adjustedTransect;
863 864 865 866 867 868 869 870 871
}

void TransectStyleComplexItem::setFollowTerrain(bool followTerrain)
{
    if (followTerrain != _followTerrain) {
        _followTerrain = followTerrain;
        emit followTerrainChanged(followTerrain);
    }
}
872 873 874

int TransectStyleComplexItem::lastSequenceNumber(void) const
{
DonLakeFlyer's avatar
DonLakeFlyer committed
875 876 877
    if (_loadedMissionItems.count()) {
        // We have stored mission items, just use those
        return _sequenceNumber + _loadedMissionItems.count() - 1;
878 879 880
    } else if (_transects.count() == 0) {
        // Polygon has not yet been set so we just return back a one item complex item for now
        return _sequenceNumber;
DonLakeFlyer's avatar
DonLakeFlyer committed
881 882 883
    } else {
        // We have to determine from transects
        int itemCount = 0;
884

885
        for (const QList<CoordInfo_t>& rgCoordInfo: _transects) {
886 887 888 889 890 891 892 893 894
            int commandsPerCoord = 1; // Waypoint command
            if (hoverAndCaptureEnabled()) {
                commandsPerCoord++; // Camera trigger
            }
            itemCount += rgCoordInfo.count() * commandsPerCoord;
            if (hoverAndCaptureEnabled() && _turnAroundDistance() != 0) {
                // The turnaround points do not have camera triggers on them
                itemCount -= 2;
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
895
        }
896

DonLakeFlyer's avatar
DonLakeFlyer committed
897

898
        if (!hoverAndCaptureEnabled() && triggerCamera()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
899
            if (_cameraTriggerInTurnAroundFact.rawValue().toBool()) {
900 901 902 903 904 905
                itemCount += _transects.count();    // One camera start for each transect entry
                itemCount++;                        // Single camera stop and the very end
                if (_turnAroundDistance() != 0) {
                    // If there are turnarounds then there is an additional camera start on the first turnaround
                    itemCount++;
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
906 907 908 909
            } else {
                // Each transect will have a camera start and stop in it
                itemCount += _transects.count() * 2;
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
910
        }
911

DonLakeFlyer's avatar
DonLakeFlyer committed
912 913
        return _sequenceNumber + itemCount - 1;
    }
914 915
}

916 917
void TransectStyleComplexItem::_followTerrainChanged(bool followTerrain)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
918
    _cameraCalc.setDistanceToSurfaceRelative(!followTerrain);
919 920 921 922 923
    if (followTerrain) {
        _refly90DegreesFact.setRawValue(false);
        _hoverAndCaptureFact.setRawValue(false);
    }
}
924 925 926 927 928 929 930

void TransectStyleComplexItem::_handleHoverAndCaptureEnabled(QVariant enabled)
{
    if (enabled.toBool() && _cameraTriggerInTurnAroundFact.rawValue().toBool()) {
        _cameraTriggerInTurnAroundFact.setRawValue(false);
    }
}
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 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027

void TransectStyleComplexItem::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);
    }
}

void TransectStyleComplexItem::_appendWaypoint(QList<MissionItem*>& items, QObject* missionItemParent, int& seqNum, MAV_FRAME mavFrame, float holdTime, const QGeoCoordinate& coordinate)
{
    MissionItem* item = new MissionItem(seqNum++,
                                        MAV_CMD_NAV_WAYPOINT,
                                        mavFrame,
                                        holdTime,
                                        0.0,                                         // No acceptance radius specified
                                        0.0,                                         // Pass through waypoint
                                        std::numeric_limits<double>::quiet_NaN(),    // Yaw unchanged
                                        coordinate.latitude(),
                                        coordinate.longitude(),
                                        coordinate.altitude(),
                                        true,                                        // autoContinue
                                        false,                                       // isCurrentItem
                                        missionItemParent);
    items.append(item);
}

void TransectStyleComplexItem::_appendSinglePhotoCapture(QList<MissionItem*>& items, QObject* missionItemParent, int& seqNum)
{
    MissionItem* item = new MissionItem(seqNum++,
                                        MAV_CMD_IMAGE_START_CAPTURE,
                                        MAV_FRAME_MISSION,
                                        0,                                   // Reserved (Set to 0)
                                        0,                                   // Interval (none)
                                        1,                                   // Take 1 photo
                                        qQNaN(), qQNaN(), qQNaN(), qQNaN(),  // param 4-7 reserved
                                        true,                                // autoContinue
                                        false,                               // isCurrentItem
                                        missionItemParent);
    items.append(item);
}

void TransectStyleComplexItem::_appendConditionGate(QList<MissionItem*>& items, QObject* missionItemParent, int& seqNum, MAV_FRAME mavFrame, const QGeoCoordinate& coordinate)
{
    MissionItem* item = new MissionItem(seqNum++,
                                        MAV_CMD_CONDITION_GATE,
                                        mavFrame,
                                        0,                                           // Gate is orthogonal to path
                                        0,                                           // Ignore altitude
                                        0, 0,                                        // Param 3-4 ignored
                                        coordinate.latitude(),
                                        coordinate.longitude(),
                                        0,                                           // No altitude
                                        true,                                        // autoContinue
                                        false,                                       // isCurrentItem
                                        missionItemParent);
    items.append(item);
}

void TransectStyleComplexItem::_appendCameraTriggerDistance(QList<MissionItem*>& items, QObject* missionItemParent, int& seqNum, float triggerDistance)
{
    MissionItem* item = new MissionItem(seqNum++,
                                        MAV_CMD_DO_SET_CAM_TRIGG_DIST,
                                        MAV_FRAME_MISSION,
                                        triggerDistance,
                                        0,                              // shutter integration (ignore)
                                        1,                              // 1 - trigger one image immediately, both and entry and exit to get full coverage
                                        0, 0, 0, 0,                     // param 4-7 unused
                                        true,                           // autoContinue
                                        false,                          // isCurrentItem
                                        missionItemParent);
    items.append(item);
}

void TransectStyleComplexItem::_appendCameraTriggerDistanceUpdatePoint(QList<MissionItem*>& items, QObject* missionItemParent, int& seqNum, MAV_FRAME mavFrame, const QGeoCoordinate& coordinate, bool useConditionGate, float triggerDistance)
{
    if (useConditionGate) {
        _appendConditionGate(items, missionItemParent, seqNum, mavFrame, coordinate);
    } else {
        _appendWaypoint(items, missionItemParent, seqNum, mavFrame, 0 /* holdTime */, coordinate);
    }
    _appendCameraTriggerDistance(items, missionItemParent, seqNum, triggerDistance);
}

void TransectStyleComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>& items, QObject* missionItemParent)
{
    qCDebug(TransectStyleComplexItemLog) << "_buildAndAppendMissionItems";

    // Now build the mission items from the transect points

    int seqNum =                    _sequenceNumber;
    bool imagesInTurnaround =       _cameraTriggerInTurnAroundFact.rawValue().toBool();
    bool hasTurnarounds =           _turnAroundDistance() != 0;
    bool addTriggerAtBeginningEnd = !hoverAndCaptureEnabled() && imagesInTurnaround && triggerCamera();
1028
    bool useConditionGate =         _controllerVehicle->firmwarePlugin()->supportedMissionCommands(QGCMAVLink::VehicleClassGeneric).contains(MAV_CMD_CONDITION_GATE) &&
1029 1030
            triggerCamera() &&
            !hoverAndCaptureEnabled();
1031 1032 1033 1034 1035 1036 1037 1038 1039 1040 1041 1042 1043 1044 1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066 1067 1068 1069 1070 1071 1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082 1083 1084 1085 1086 1087 1088 1089 1090 1091 1092 1093 1094 1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108

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

    // Note: The code below is written to be understable as oppose to being compact and/or remove duplicate code
    int transectIndex = 0;
    for (const QList<TransectStyleComplexItem::CoordInfo_t>& transect: _transects) {
        bool entryTurnaround = true;
        for (const CoordInfo_t& transectCoordInfo: transect) {
            switch (transectCoordInfo.coordType) {
            case CoordTypeTurnaround:
            {
                bool firstEntryTurnaround = transectIndex == 0 && entryTurnaround;
                bool lastExitTurnaround = transectIndex == _transects.count() - 1 && !entryTurnaround;
                if (addTriggerAtBeginningEnd && (firstEntryTurnaround || lastExitTurnaround)) {
                    _appendCameraTriggerDistanceUpdatePoint(items, missionItemParent, seqNum, mavFrame, transectCoordInfo.coord, useConditionGate, firstEntryTurnaround ? triggerDistance() : 0);
                } else {
                    _appendWaypoint(items, missionItemParent, seqNum, mavFrame, 0 /* holdTime */, transectCoordInfo.coord);
                }
                entryTurnaround = false;
            }
                break;
            case CoordTypeInterior:
            case CoordTypeInteriorTerrainAdded:
                _appendWaypoint(items, missionItemParent, seqNum, mavFrame, 0 /* holdTime */, transectCoordInfo.coord);
                break;
            case CoordTypeInteriorHoverTrigger:
                _appendWaypoint(items, missionItemParent, seqNum, mavFrame, _hoverAndCaptureDelaySeconds, transectCoordInfo.coord);
                _appendSinglePhotoCapture(items, missionItemParent, seqNum);
                break;
            case CoordTypeSurveyEntry:
                if (triggerCamera()) {
                    if (hoverAndCaptureEnabled()) {
                        _appendWaypoint(items, missionItemParent, seqNum, mavFrame, _hoverAndCaptureDelaySeconds, transectCoordInfo.coord);
                        _appendSinglePhotoCapture(items, missionItemParent, seqNum);
                    } else {
                        // We always add a trigger start to survey entry. Even for imagesInTurnaround = true. This allows you to resume a mission and refly a transect
                        _appendCameraTriggerDistanceUpdatePoint(items, missionItemParent, seqNum, mavFrame, transectCoordInfo.coord, useConditionGate, triggerDistance());
                    }
                } else {
                    _appendWaypoint(items, missionItemParent, seqNum, mavFrame, 0 /* holdTime */, transectCoordInfo.coord);
                }
                break;
            case CoordTypeSurveyExit:
                bool lastSurveyExit = transectIndex == _transects.count() - 1;
                if (triggerCamera()) {
                    if (hoverAndCaptureEnabled()) {
                        _appendWaypoint(items, missionItemParent, seqNum, mavFrame, _hoverAndCaptureDelaySeconds, transectCoordInfo.coord);
                        _appendSinglePhotoCapture(items, missionItemParent, seqNum);
                    } else if (addTriggerAtBeginningEnd && !hasTurnarounds && lastSurveyExit) {
                        _appendCameraTriggerDistanceUpdatePoint(items, missionItemParent, seqNum, mavFrame, transectCoordInfo.coord, useConditionGate, 0 /* triggerDistance */);
                    } else if (imagesInTurnaround) {
                        _appendWaypoint(items, missionItemParent, seqNum, mavFrame, 0 /* holdTime */, transectCoordInfo.coord);
                    } else {
                        // If we get this far it means the camera is triggering start/stop for each transect
                        _appendCameraTriggerDistanceUpdatePoint(items, missionItemParent, seqNum, mavFrame, transectCoordInfo.coord, useConditionGate, 0 /* triggerDistance */);
                    }
                } else {
                    _appendWaypoint(items, missionItemParent, seqNum, mavFrame, 0 /* holdTime */, transectCoordInfo.coord);
                }
                break;
            }
        }
        transectIndex++;
    }
}

void TransectStyleComplexItem::_appendLoadedMissionItems(QList<MissionItem*>& items, QObject* missionItemParent)
{
    qCDebug(TransectStyleComplexItemLog) << "_appendLoadedMissionItems";

    int seqNum = _sequenceNumber;

    for (const MissionItem* loadedMissionItem: _loadedMissionItems) {
        MissionItem* item = new MissionItem(*loadedMissionItem, missionItemParent);
        item->setSequenceNumber(seqNum++);
        items.append(item);
    }
}
1109 1110 1111 1112 1113 1114 1115 1116 1117 1118 1119 1120

void TransectStyleComplexItem::addKMLVisuals(KMLPlanDomDocument& domDocument)
{
    // We add the survey area polygon as a Placemark

    QDomElement placemarkElement = domDocument.addPlacemark(QStringLiteral("Survey Area"), true);
    QDomElement polygonElement = _surveyAreaPolygon.kmlPolygonElement(domDocument);

    placemarkElement.appendChild(polygonElement);
    domDocument.addTextElement(placemarkElement, "styleUrl", QStringLiteral("#%1").arg(domDocument.surveyPolygonStyleName));
    domDocument.appendChildToRoot(placemarkElement);
}
1121 1122 1123 1124 1125 1126 1127 1128 1129 1130 1131 1132 1133 1134 1135 1136 1137 1138 1139 1140 1141 1142 1143 1144 1145 1146 1147 1148 1149 1150 1151 1152 1153 1154 1155 1156 1157 1158 1159 1160 1161 1162 1163 1164 1165 1166 1167 1168 1169 1170 1171 1172 1173 1174

void TransectStyleComplexItem::_recalcComplexDistance(void)
{
    _complexDistance = 0;
    for (int i=0; i<_visualTransectPoints.count() - 1; i++) {
        _complexDistance += _visualTransectPoints[i].value<QGeoCoordinate>().distanceTo(_visualTransectPoints[i+1].value<QGeoCoordinate>());
    }
    emit complexDistanceChanged();
}

double TransectStyleComplexItem::amslEntryAlt(void) const
{
    if (_followTerrain) {
        if (_loadedMissionItems.count()) {
            return _loadedMissionItems.first()->param7();
        } else {
            if (_transectCount() == 0) {
                return qQNaN();
            } else {
                bool addHomeAlt = !followTerrain() && _cameraCalc.distanceToSurfaceRelative();

                return _transects.first().first().coord.altitude() + (addHomeAlt ?  _missionController->plannedHomePosition().altitude() : 0);
            }
        }
    } else {
        return _cameraCalc.distanceToSurface()->rawValue().toDouble() + (_cameraCalc.distanceToSurfaceRelative() ? _missionController->plannedHomePosition().altitude() : 0) ;
    }
}

double TransectStyleComplexItem::amslExitAlt(void) const
{
    if (_followTerrain) {
        if (_loadedMissionItems.count()) {
            return _loadedMissionItems.last()->param7();
        } else {
            if (_transectCount() == 0) {
                return qQNaN();
            } else {
                bool addHomeAlt = !followTerrain() && _cameraCalc.distanceToSurfaceRelative();

                return _transects.last().last().coord.altitude() + (addHomeAlt ?  _missionController->plannedHomePosition().altitude() : 0);
            }
        }
    } else {
        return _cameraCalc.distanceToSurface()->rawValue().toDouble() + (_cameraCalc.distanceToSurfaceRelative() ? _missionController->plannedHomePosition().altitude() : 0) ;
    }
}

void TransectStyleComplexItem::applyNewAltitude(double newAltitude)
{
    _cameraCalc.valueSetIsDistance()->setRawValue(true);
    _cameraCalc.distanceToSurface()->setRawValue(newAltitude);
    _cameraCalc.setDistanceToSurfaceRelative(true);
}