TransectStyleComplexItem.h.orig 23.2 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 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
/****************************************************************************
 *
 * (c) 2009-2020 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.
 *
 ****************************************************************************/

#pragma once

#include "CameraCalc.h"
#include "ComplexMissionItem.h"
#include "MissionItem.h"
#include "QGCLoggingCategory.h"
#include "QGCMapPolygon.h"
#include "QGCMapPolyline.h"
#include "SettingsFact.h"
#include "TerrainQuery.h"

Q_DECLARE_LOGGING_CATEGORY(TransectStyleComplexItemLog)

<<<<<<< HEAD
<<<<<<< HEAD
class TransectStyleComplexItem : public ComplexMissionItem {
  Q_OBJECT

public:
  TransectStyleComplexItem(Vehicle *vehicle, bool flyView,
                           QString settignsGroup, QObject *parent);

  Q_PROPERTY(QGCMapPolygon *surveyAreaPolygon READ surveyAreaPolygon CONSTANT)
  Q_PROPERTY(CameraCalc *cameraCalc READ cameraCalc CONSTANT)
  Q_PROPERTY(Fact *turnAroundDistance READ turnAroundDistance CONSTANT)
  Q_PROPERTY(
      Fact *cameraTriggerInTurnAround READ cameraTriggerInTurnAround CONSTANT)
  Q_PROPERTY(Fact *hoverAndCapture READ hoverAndCapture CONSTANT)
  Q_PROPERTY(Fact *refly90Degrees READ refly90Degrees CONSTANT)

  Q_PROPERTY(int cameraShots READ cameraShots NOTIFY cameraShotsChanged)
  Q_PROPERTY(double timeBetweenShots READ timeBetweenShots NOTIFY
                 timeBetweenShotsChanged)
  Q_PROPERTY(double coveredArea READ coveredArea NOTIFY coveredAreaChanged)
  Q_PROPERTY(bool hoverAndCaptureAllowed READ hoverAndCaptureAllowed CONSTANT)
  Q_PROPERTY(QVariantList visualTransectPoints READ visualTransectPoints NOTIFY
                 visualTransectPointsChanged)

  Q_PROPERTY(bool followTerrain READ followTerrain WRITE setFollowTerrain NOTIFY
                 followTerrainChanged)
  Q_PROPERTY(Fact *terrainAdjustTolerance READ terrainAdjustTolerance CONSTANT)
  Q_PROPERTY(Fact *terrainAdjustMaxDescentRate READ terrainAdjustMaxDescentRate
                 CONSTANT)
  Q_PROPERTY(
      Fact *terrainAdjustMaxClimbRate READ terrainAdjustMaxClimbRate CONSTANT)

  QGCMapPolygon *surveyAreaPolygon(void) { return &_surveyAreaPolygon; }
  CameraCalc *cameraCalc(void) { return &_cameraCalc; }
  QVariantList visualTransectPoints(void) { return _visualTransectPoints; }

  Fact *turnAroundDistance(void) { return &_turnAroundDistanceFact; }
  Fact *cameraTriggerInTurnAround(void) {
    return &_cameraTriggerInTurnAroundFact;
  }
  Fact *hoverAndCapture(void) { return &_hoverAndCaptureFact; }
  Fact *refly90Degrees(void) { return &_refly90DegreesFact; }
  Fact *terrainAdjustTolerance(void) { return &_terrainAdjustToleranceFact; }
  Fact *terrainAdjustMaxDescentRate(void) {
    return &_terrainAdjustMaxDescentRateFact;
  }
  Fact *terrainAdjustMaxClimbRate(void) {
    return &_terrainAdjustMaxClimbRateFact;
  }

  const Fact *hoverAndCapture(void) const { return &_hoverAndCaptureFact; }

  int cameraShots(void) const { return _cameraShots; }
  double coveredArea(void) const;
  bool hoverAndCaptureAllowed(void) const;
  bool followTerrain(void) const { return _followTerrain; }

  virtual double timeBetweenShots(void) {
    return 0;
  } // Most be overridden. Implementation here is needed for unit testing.

  void setFollowTerrain(bool followTerrain);

  double triggerDistance(void) const {
    return _cameraCalc.adjustedFootprintFrontal()->rawValue().toDouble();
  }
  bool hoverAndCaptureEnabled(void) const {
    return hoverAndCapture()->rawValue().toBool();
  }
  bool triggerCamera(void) const { return triggerDistance() != 0; }

  // Overrides from ComplexMissionItem

  int lastSequenceNumber(void) const final;
  QString mapVisualQML(void) const override = 0;
  bool load(const QJsonObject &complexObject, int sequenceNumber,
            QString &errorString) override = 0;

  double complexDistance(void) const final { return _complexDistance; }
  double greatestDistanceTo(const QGeoCoordinate &other) const final;

  // Overrides from VisualMissionItem

  void save(QJsonArray &planItems) override = 0;
  bool specifiesCoordinate(void) const override = 0;
  void appendMissionItems(QList<MissionItem *> &items,
                          QObject *missionItemParent) override = 0;
  void applyNewAltitude(double newAltitude) override = 0;

  bool dirty(void) const final { return _dirty; }
  bool isSimpleItem(void) const final { return false; }
  bool isStandaloneCoordinate(void) const final { return false; }
  bool specifiesAltitudeOnly(void) const final { return false; }
  QGeoCoordinate coordinate(void) const final { return _coordinate; }
  QGeoCoordinate exitCoordinate(void) const final { return _exitCoordinate; }
  int sequenceNumber(void) const final { return _sequenceNumber; }
  double specifiedFlightSpeed(void) final {
    return std::numeric_limits<double>::quiet_NaN();
  }
  double specifiedGimbalYaw(void) final {
    return std::numeric_limits<double>::quiet_NaN();
  }
  double specifiedGimbalPitch(void) final {
    return std::numeric_limits<double>::quiet_NaN();
  }
  void setMissionFlightStatus(const MissionController::MissionFlightStatus_t
                                  &missionFlightStatus) final;
  bool readyForSave(void) const override;
  QString commandDescription(void) const override { return tr("Transect"); }
  QString commandName(void) const override { return tr("Transect"); }
  QString abbreviation(void) const override { return tr("T"); }

  bool coordinateHasRelativeAltitude(void) const final;
  bool exitCoordinateHasRelativeAltitude(void) const final;
  bool exitCoordinateSameAsEntry(void) const final { return false; }

  void setDirty(bool dirty) final;
  void setCoordinate(const QGeoCoordinate &coordinate) final {
    Q_UNUSED(coordinate);
  }
  void setSequenceNumber(int sequenceNumber) final;

  static const char *turnAroundDistanceName;
  static const char *turnAroundDistanceMultiRotorName;
  static const char *cameraTriggerInTurnAroundName;
  static const char *hoverAndCaptureName;
  static const char *refly90DegreesName;
  static const char *terrainAdjustToleranceName;
  static const char *terrainAdjustMaxClimbRateName;
  static const char *terrainAdjustMaxDescentRateName;

signals:
  void cameraShotsChanged(void);
  void timeBetweenShotsChanged(void);
  void visualTransectPointsChanged(void);
  void coveredAreaChanged(void);
  void followTerrainChanged(bool followTerrain);
  void missionItemReady(void);
=======
=======
>>>>>>> upstream_merge
class PlanMasterController;

class TransectStyleComplexItem : public ComplexMissionItem
{
    Q_OBJECT

public:
    TransectStyleComplexItem(PlanMasterController* masterController, bool flyView, QString settignsGroup, QObject* parent);

    Q_PROPERTY(QGCMapPolygon*   surveyAreaPolygon           READ surveyAreaPolygon                                  CONSTANT)
    Q_PROPERTY(CameraCalc*      cameraCalc                  READ cameraCalc                                         CONSTANT)
    Q_PROPERTY(Fact*            turnAroundDistance          READ turnAroundDistance                                 CONSTANT)
    Q_PROPERTY(Fact*            cameraTriggerInTurnAround   READ cameraTriggerInTurnAround                          CONSTANT)
    Q_PROPERTY(Fact*            hoverAndCapture             READ hoverAndCapture                                    CONSTANT)
    Q_PROPERTY(Fact*            refly90Degrees              READ refly90Degrees                                     CONSTANT)

    Q_PROPERTY(int              cameraShots                 READ cameraShots                                        NOTIFY cameraShotsChanged)
    Q_PROPERTY(double           timeBetweenShots            READ timeBetweenShots                                   NOTIFY timeBetweenShotsChanged)
    Q_PROPERTY(double           coveredArea                 READ coveredArea                                        NOTIFY coveredAreaChanged)
    Q_PROPERTY(bool             hoverAndCaptureAllowed      READ hoverAndCaptureAllowed                             CONSTANT)
    Q_PROPERTY(QVariantList     visualTransectPoints        READ visualTransectPoints                               NOTIFY visualTransectPointsChanged)

    Q_PROPERTY(bool             followTerrain               READ followTerrain              WRITE setFollowTerrain  NOTIFY followTerrainChanged)
    Q_PROPERTY(Fact*            terrainAdjustTolerance      READ terrainAdjustTolerance                             CONSTANT)
    Q_PROPERTY(Fact*            terrainAdjustMaxDescentRate READ terrainAdjustMaxDescentRate                        CONSTANT)
    Q_PROPERTY(Fact*            terrainAdjustMaxClimbRate   READ terrainAdjustMaxClimbRate                          CONSTANT)

    QGCMapPolygon*  surveyAreaPolygon   (void) { return &_surveyAreaPolygon; }
    CameraCalc*     cameraCalc          (void) { return &_cameraCalc; }
    QVariantList    visualTransectPoints(void) { return _visualTransectPoints; }

    Fact* turnAroundDistance            (void) { return &_turnAroundDistanceFact; }
    Fact* cameraTriggerInTurnAround     (void) { return &_cameraTriggerInTurnAroundFact; }
    Fact* hoverAndCapture               (void) { return &_hoverAndCaptureFact; }
    Fact* refly90Degrees                (void) { return &_refly90DegreesFact; }
    Fact* terrainAdjustTolerance        (void) { return &_terrainAdjustToleranceFact; }
    Fact* terrainAdjustMaxDescentRate   (void) { return &_terrainAdjustMaxDescentRateFact; }
    Fact* terrainAdjustMaxClimbRate     (void) { return &_terrainAdjustMaxClimbRateFact; }

    const Fact* hoverAndCapture         (void) const { return &_hoverAndCaptureFact; }

    int             cameraShots             (void) const { return _cameraShots; }
    double          coveredArea             (void) const;
    bool            hoverAndCaptureAllowed  (void) const;
    bool            followTerrain           (void) const { return _followTerrain; }

    virtual double  timeBetweenShots        (void) { return 0; } // Most be overridden. Implementation here is needed for unit testing.

    void setFollowTerrain(bool followTerrain);

    double  triggerDistance         (void) const { return _cameraCalc.adjustedFootprintFrontal()->rawValue().toDouble(); }
    bool    hoverAndCaptureEnabled  (void) const { return hoverAndCapture()->rawValue().toBool(); }
    bool    triggerCamera           (void) const { return triggerDistance() != 0; }

    // Used internally only by unit tests
    int _transectCount(void) const { return _transects.count(); }

    // Overrides from ComplexMissionItem
    int     lastSequenceNumber  (void) const final;
    QString mapVisualQML        (void) const override = 0;
    bool    load                (const QJsonObject& complexObject, int sequenceNumber, QString& errorString) override = 0;
    void    addKMLVisuals       (KMLPlanDomDocument& domDocument) final;
    double  complexDistance     (void) const final { return _complexDistance; }
    double  greatestDistanceTo  (const QGeoCoordinate &other) const final;

    // Overrides from VisualMissionItem
    void                save                        (QJsonArray&  planItems) override = 0;
    bool                specifiesCoordinate         (void) const override = 0;
    void                appendMissionItems          (QList<MissionItem*>& items, QObject* missionItemParent) final;
    void                applyNewAltitude            (double newAltitude) final;
    bool                dirty                       (void) const final { return _dirty; }
    bool                isSimpleItem                (void) const final { return false; }
    bool                isStandaloneCoordinate      (void) const final { return false; }
    bool                specifiesAltitudeOnly       (void) const final { return false; }
    QGeoCoordinate      coordinate                  (void) const final { return _coordinate; }
    QGeoCoordinate      exitCoordinate              (void) const final { return _exitCoordinate; }
    int                 sequenceNumber              (void) const final { return _sequenceNumber; }
    double              specifiedFlightSpeed        (void) final { return std::numeric_limits<double>::quiet_NaN(); }
    double              specifiedGimbalYaw          (void) final { return std::numeric_limits<double>::quiet_NaN(); }
    double              specifiedGimbalPitch        (void) final { return std::numeric_limits<double>::quiet_NaN(); }
    void                setMissionFlightStatus      (MissionController::MissionFlightStatus_t& missionFlightStatus) final;
    ReadyForSaveState   readyForSaveState         (void) const override;
    QString             commandDescription          (void) const override { return tr("Transect"); }
    QString             commandName                 (void) const override { return tr("Transect"); }
    QString             abbreviation                (void) const override { return tr("T"); }
    bool                exitCoordinateSameAsEntry   (void) const final { return false; }
    void                setDirty                    (bool dirty) final;
    void                setCoordinate               (const QGeoCoordinate& coordinate) final { Q_UNUSED(coordinate); }
    void                setSequenceNumber           (int sequenceNumber) final;
    double              amslEntryAlt                (void) const final;
    double              amslExitAlt                 (void) const final;
    double              minAMSLAltitude             (void) const final { return _minAMSLAltitude; }
    double              maxAMSLAltitude             (void) const final { return _maxAMSLAltitude; }

    static const char* turnAroundDistanceName;
    static const char* turnAroundDistanceMultiRotorName;
    static const char* cameraTriggerInTurnAroundName;
    static const char* hoverAndCaptureName;
    static const char* refly90DegreesName;
    static const char* terrainAdjustToleranceName;
    static const char* terrainAdjustMaxClimbRateName;
    static const char* terrainAdjustMaxDescentRateName;

signals:
    void cameraShotsChanged             (void);
    void timeBetweenShotsChanged        (void);
    void visualTransectPointsChanged    (void);
    void coveredAreaChanged             (void);
    void followTerrainChanged           (bool followTerrain);
    void _updateFlightPathSegmentsSignal(void);
<<<<<<< HEAD
>>>>>>> upstream_merge
=======
>>>>>>> upstream_merge

protected slots:
  void _setDirty(void);
  void _setIfDirty(bool dirty);
  void _updateCoordinateAltitudes(void);
  void _polyPathTerrainData(
      bool success,
      const QList<TerrainPathQuery::PathHeightInfo_t> &rgPathHeightInfo);
  void _rebuildTransects(void);
  void _updateTransectAltitude(void);
  void _clearLoadedMissionItems(void);

protected:
<<<<<<< HEAD
  virtual void
  _rebuildTransectsPhase1(void) = 0; ///< Rebuilds the _transects array
  virtual void _recalcComplexDistance(void) = 0;
  virtual void _recalcCameraShots(void) = 0;

  void _save(QJsonObject &saveObject);
  bool _load(const QJsonObject &complexObject, QString &errorString);
  void _setExitCoordinate(const QGeoCoordinate &coordinate);
  void _setCameraShots(int cameraShots);
  double _triggerDistance(void) const;
  bool _hasTurnaround(void) const;
  double _turnaroundDistance(void) const;

  int _sequenceNumber;
  QGeoCoordinate _coordinate;
  QGeoCoordinate _exitCoordinate;
  QGCMapPolygon _surveyAreaPolygon;

  enum CoordType {
    CoordTypeInterior,             ///< Interior waypoint for flight path only
    CoordTypeInteriorHoverTrigger, ///< Interior waypoint for hover and capture
                                   ///< trigger
    CoordTypeInteriorTerrainAdded, ///< Interior waypoint added for terrain
    CoordTypeSurveyEdge,           ///< Waypoint at edge of survey polygon
    CoordTypeTurnaround ///< Waypoint outside of survey polygon for turnaround
  };

  typedef struct {
    QGeoCoordinate coord;
    CoordType coordType;
  } CoordInfo_t;

  QVariantList _visualTransectPoints;
  using Transects = QList<QList<CoordInfo_t>>;
  Transects _transects;
  QList<QList<TerrainPathQuery::PathHeightInfo_t>> _transectsPathHeightInfo;
  TerrainPolyPathQuery *_terrainPolyPathQuery;
  QTimer _terrainQueryTimer;

  bool _ignoreRecalc;
  double _complexDistance;
  int _cameraShots;
  double _timeBetweenShots;
  double _cruiseSpeed;
  CameraCalc _cameraCalc;
  bool _followTerrain;

  QObject
      *_loadedMissionItemsParent; ///< Parent for all items in
                                  ///< _loadedMissionItems for simpler delete
  QList<MissionItem *>
      _loadedMissionItems; ///< Mission items loaded from plan file

  QMap<QString, FactMetaData *> _metaDataMap;

  SettingsFact _turnAroundDistanceFact;
  SettingsFact _cameraTriggerInTurnAroundFact;
  SettingsFact _hoverAndCaptureFact;
  SettingsFact _refly90DegreesFact;
  SettingsFact _terrainAdjustToleranceFact;
  SettingsFact _terrainAdjustMaxClimbRateFact;
  SettingsFact _terrainAdjustMaxDescentRateFact;

  static const char *_jsonCameraCalcKey;
  static const char *_jsonTransectStyleComplexItemKey;
  static const char *_jsonVisualTransectPointsKey;
  static const char *_jsonItemsKey;
  static const char *_jsonFollowTerrainKey;
  static const char *_jsonCameraShotsKey;

  static const int _terrainQueryTimeoutMsecs;

private slots:
  void _reallyQueryTransectsPathHeightInfo(void);
  void _followTerrainChanged(bool followTerrain);

protected:
  bool _transectsDirty;

private:
  void _queryTransectsPathHeightInfo(void);
  void _adjustTransectsForTerrain(void);
  void _addInterstitialTerrainPoints(
      QList<CoordInfo_t> &transect,
      const QList<TerrainPathQuery::PathHeightInfo_t> &transectPathHeightInfo);
  void _adjustForMaxRates(QList<CoordInfo_t> &transect);
  void _adjustForTolerance(QList<CoordInfo_t> &transect);
  double _altitudeBetweenCoords(const QGeoCoordinate &fromCoord,
                                const QGeoCoordinate &toCoord,
                                double percentTowardsTo);
  int _maxPathHeight(const TerrainPathQuery::PathHeightInfo_t &pathHeightInfo,
                     int fromIndex, int toIndex, double &maxHeight);
=======
    virtual void _rebuildTransectsPhase1    (void) = 0; ///< Rebuilds the _transects array
    virtual void _recalcCameraShots         (void) = 0;

    void    _save                           (QJsonObject& saveObject);
    bool    _load                           (const QJsonObject& complexObject, bool forPresets, QString& errorString);
    void    _setExitCoordinate              (const QGeoCoordinate& coordinate);
    void    _setCameraShots                 (int cameraShots);
    double  _triggerDistance                (void) const;
    bool    _hasTurnaround                  (void) const;
    double  _turnAroundDistance             (void) const;
    void    _appendWaypoint                 (QList<MissionItem*>& items, QObject* missionItemParent, int& seqNum, MAV_FRAME mavFrame, float holdTime, const QGeoCoordinate& coordinate);
    void    _appendSinglePhotoCapture       (QList<MissionItem*>& items, QObject* missionItemParent, int& seqNum);
    void    _appendConditionGate            (QList<MissionItem*>& items, QObject* missionItemParent, int& seqNum, MAV_FRAME mavFrame, const QGeoCoordinate& coordinate);
    void    _appendCameraTriggerDistance    (QList<MissionItem*>& items, QObject* missionItemParent, int& seqNum, float triggerDistance);
    void    _appendCameraTriggerDistanceUpdatePoint(QList<MissionItem*>& items, QObject* missionItemParent, int& seqNum, MAV_FRAME mavFrame, const QGeoCoordinate& coordinate, bool useConditionGate, float triggerDistance);
    void    _buildAndAppendMissionItems     (QList<MissionItem*>& items, QObject* missionItemParent);
    void    _appendLoadedMissionItems       (QList<MissionItem*>& items, QObject* missionItemParent);
    void    _recalcComplexDistance          (void);

    int                 _sequenceNumber = 0;
    QGeoCoordinate      _coordinate;
    QGeoCoordinate      _exitCoordinate;
    QGCMapPolygon       _surveyAreaPolygon;

    enum CoordType {
        CoordTypeInterior,              ///< Interior waypoint for flight path only
        CoordTypeInteriorHoverTrigger,  ///< Interior waypoint for hover and capture trigger
        CoordTypeInteriorTerrainAdded,  ///< Interior waypoint added for terrain
        CoordTypeSurveyEntry,           ///< Waypoint at entry edge of survey polygon
        CoordTypeSurveyExit,            ///< Waypoint at exit edge of survey polygon
        CoordTypeTurnaround,            ///< First turnaround waypoint
    };

    typedef struct {
        QGeoCoordinate  coord;
        CoordType       coordType;
    } CoordInfo_t;

    QVariantList                                        _visualTransectPoints;
    QList<QList<CoordInfo_t>>                           _transects;
    QList<QList<TerrainPathQuery::PathHeightInfo_t>>    _transectsPathHeightInfo;

    bool            _ignoreRecalc =     false;
    double          _complexDistance =  qQNaN();
    int             _cameraShots =      0;
    double          _timeBetweenShots = 0;
    double          _vehicleSpeed =     5;
    CameraCalc      _cameraCalc;
    bool            _followTerrain =    false;
    double          _minAMSLAltitude =  qQNaN();
    double          _maxAMSLAltitude =  qQNaN();

    QObject*            _loadedMissionItemsParent = nullptr;	///< Parent for all items in _loadedMissionItems for simpler delete
    QList<MissionItem*> _loadedMissionItems;                    ///< Mission items loaded from plan file

    QMap<QString, FactMetaData*> _metaDataMap;

    SettingsFact _turnAroundDistanceFact;
    SettingsFact _cameraTriggerInTurnAroundFact;
    SettingsFact _hoverAndCaptureFact;
    SettingsFact _refly90DegreesFact;
    SettingsFact _terrainAdjustToleranceFact;
    SettingsFact _terrainAdjustMaxClimbRateFact;
    SettingsFact _terrainAdjustMaxDescentRateFact;

    static const char* _jsonCameraCalcKey;
    static const char* _jsonTransectStyleComplexItemKey;
    static const char* _jsonVisualTransectPointsKey;
    static const char* _jsonItemsKey;
    static const char* _jsonTerrainFollowKey;
    static const char* _jsonTerrainFlightSpeed;
    static const char* _jsonCameraShotsKey;

    static const int _terrainQueryTimeoutMsecs=     1000;
    static const int _hoverAndCaptureDelaySeconds = 4;

private slots:
    void _reallyQueryTransectsPathHeightInfo        (void);
    void _followTerrainChanged                      (bool followTerrain);
    void _handleHoverAndCaptureEnabled              (QVariant enabled);
    void _updateFlightPathSegmentsDontCallDirectly  (void);
    void _segmentTerrainCollisionChanged            (bool terrainCollision) final;

private:
    void    _queryTransectsPathHeightInfo   (void);
    void    _adjustTransectsForTerrain      (void);
    void    _addInterstitialTerrainPoints   (QList<CoordInfo_t>& transect, const QList<TerrainPathQuery::PathHeightInfo_t>& transectPathHeightInfo);
    void    _adjustForMaxRates              (QList<CoordInfo_t>& transect);
    void    _adjustForTolerance             (QList<CoordInfo_t>& transect);
    double  _altitudeBetweenCoords          (const QGeoCoordinate& fromCoord, const QGeoCoordinate& toCoord, double percentTowardsTo);
    int     _maxPathHeight                  (const TerrainPathQuery::PathHeightInfo_t& pathHeightInfo, int fromIndex, int toIndex, double& maxHeight);

    TerrainPolyPathQuery*       _currentTerrainFollowQuery =            nullptr;
    QTimer                      _terrainQueryTimer;
<<<<<<< HEAD
>>>>>>> upstream_merge
=======
>>>>>>> upstream_merge
};