VisualMissionItem.h 19.3 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
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/

10
#pragma once
11 12 13 14 15 16 17 18 19 20 21 22 23 24

#include <QObject>
#include <QString>
#include <QtQml>
#include <QTextStream>
#include <QJsonObject>
#include <QGeoCoordinate>

#include "QGCMAVLink.h"
#include "QGC.h"
#include "QmlObjectListModel.h"
#include "Fact.h"
#include "QGCLoggingCategory.h"
#include "QmlObjectListModel.h"
25
#include "Vehicle.h"
DonLakeFlyer's avatar
DonLakeFlyer committed
26
#include "MissionController.h"
27

28
class MissionItem;
29
class PlanMasterController;
30

31 32 33 34
// Abstract base class for all Simple and Complex visual mission objects.
class VisualMissionItem : public QObject
{
    Q_OBJECT
35

36
public:
37
    VisualMissionItem(PlanMasterController* masterController, bool flyView, QObject* parent);
38
    VisualMissionItem(const VisualMissionItem& other, bool flyView, QObject* parent);
39 40 41 42 43

    ~VisualMissionItem();

    const VisualMissionItem& operator=(const VisualMissionItem& other);

DonLakeFlyer's avatar
DonLakeFlyer committed
44 45 46 47 48 49 50
    enum ReadyForSaveState {
        ReadyForSave,
        NotReadyForSaveTerrain,
        NotReadyForSaveData,
    };
    Q_ENUM(ReadyForSaveState)

51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72
    Q_PROPERTY(bool             homePosition                        READ homePosition                                                       CONSTANT)                                           ///< true: This item is being used as a home position indicator
    Q_PROPERTY(QGeoCoordinate   coordinate                          READ coordinate                         WRITE setCoordinate             NOTIFY coordinateChanged)                           ///< This is the entry point for a waypoint line into the item. For a simple item it is also the location of the item
    Q_PROPERTY(double           terrainAltitude                     READ terrainAltitude                                                    NOTIFY terrainAltitudeChanged)                      ///< The altitude of terrain at the coordinate position, NaN if not known
    Q_PROPERTY(bool             coordinateHasRelativeAltitude       READ coordinateHasRelativeAltitude                                      NOTIFY coordinateHasRelativeAltitudeChanged)        ///< true: coordinate.latitude is relative to home altitude
    Q_PROPERTY(QGeoCoordinate   exitCoordinate                      READ exitCoordinate                                                     NOTIFY exitCoordinateChanged)                       ///< This is the exit point for a waypoint line coming out of the item.
    Q_PROPERTY(bool             exitCoordinateHasRelativeAltitude   READ exitCoordinateHasRelativeAltitude                                  NOTIFY exitCoordinateHasRelativeAltitudeChanged)    ///< true: coordinate.latitude is relative to home altitude
    Q_PROPERTY(bool             exitCoordinateSameAsEntry           READ exitCoordinateSameAsEntry                                          NOTIFY exitCoordinateSameAsEntryChanged)            ///< true: exitCoordinate and coordinate are the same value
    Q_PROPERTY(QString          commandDescription                  READ commandDescription                                                 NOTIFY commandDescriptionChanged)
    Q_PROPERTY(QString          commandName                         READ commandName                                                        NOTIFY commandNameChanged)
    Q_PROPERTY(QString          abbreviation                        READ abbreviation                                                       NOTIFY abbreviationChanged)
    Q_PROPERTY(bool             dirty                               READ dirty                              WRITE setDirty                  NOTIFY dirtyChanged)                                ///< Item is dirty and requires save/send
    Q_PROPERTY(bool             isCurrentItem                       READ isCurrentItem                      WRITE setIsCurrentItem          NOTIFY isCurrentItemChanged)
    Q_PROPERTY(bool             hasCurrentChildItem                 READ hasCurrentChildItem                WRITE setHasCurrentChildItem    NOTIFY hasCurrentChildItemChanged)                  ///< true: On of this items children is current
    Q_PROPERTY(int              sequenceNumber                      READ sequenceNumber                     WRITE setSequenceNumber         NOTIFY sequenceNumberChanged)
    Q_PROPERTY(int              lastSequenceNumber                  READ lastSequenceNumber                                                 NOTIFY lastSequenceNumberChanged)
    Q_PROPERTY(bool             specifiesCoordinate                 READ specifiesCoordinate                                                NOTIFY specifiesCoordinateChanged)                  ///< true: Item is associated with a coordinate position
    Q_PROPERTY(bool             isStandaloneCoordinate              READ isStandaloneCoordinate                                             NOTIFY isStandaloneCoordinateChanged)               ///< true: Waypoint line does not go through item
    Q_PROPERTY(bool             specifiesAltitudeOnly               READ specifiesAltitudeOnly                                              NOTIFY specifiesAltitudeOnlyChanged)                ///< true: Item has altitude only, no full coordinate
    Q_PROPERTY(bool             isSimpleItem                        READ isSimpleItem                                                       NOTIFY isSimpleItemChanged)                         ///< Simple or Complex MissionItem
    Q_PROPERTY(bool             isTakeoffItem                       READ isTakeoffItem                                                      NOTIFY isTakeoffItemChanged)                        ///< true: Takeoff item special case
    Q_PROPERTY(QString          editorQml                           MEMBER _editorQml                                                       CONSTANT)                                           ///< Qml code for editing this item
    Q_PROPERTY(QString          mapVisualQML                        READ mapVisualQML                                                       CONSTANT)                                           ///< QMl code for map visuals
73 74 75 76
    Q_PROPERTY(double           specifiedFlightSpeed                READ specifiedFlightSpeed                                               NOTIFY specifiedFlightSpeedChanged)                 ///< NaN for not specified
    Q_PROPERTY(double           specifiedGimbalYaw                  READ specifiedGimbalYaw                                                 NOTIFY specifiedGimbalYawChanged)                   ///< NaN for not specified
    Q_PROPERTY(double           specifiedGimbalPitch                READ specifiedGimbalPitch                                               NOTIFY specifiedGimbalPitchChanged)                 ///< NaN for not specified
    Q_PROPERTY(double           specifiedVehicleYaw                 READ specifiedVehicleYaw                                                NOTIFY specifiedVehicleYawChanged)                  ///< NaN for not specified
77 78 79 80 81
    Q_PROPERTY(double           missionGimbalYaw                    READ missionGimbalYaw                                                   NOTIFY missionGimbalYawChanged)                     ///< Current gimbal yaw state at this point in mission
    Q_PROPERTY(double           missionVehicleYaw                   READ missionVehicleYaw                                                  NOTIFY missionVehicleYawChanged)                    ///< Expected vehicle yaw at this point in mission
    Q_PROPERTY(bool             flyView                             READ flyView                                                            CONSTANT)
    Q_PROPERTY(bool             wizardMode                          READ wizardMode                        WRITE setWizardMode              NOTIFY wizardModeChanged)

82 83 84 85 86
    Q_PROPERTY(PlanMasterController*    masterController    READ masterController                                                   CONSTANT)
    Q_PROPERTY(ReadyForSaveState        readyForSaveState   READ readyForSaveState                                                  NOTIFY readyForSaveStateChanged)
    Q_PROPERTY(VisualMissionItem*       parentItem          READ parentItem                        WRITE setParentItem              NOTIFY parentItemChanged)
    Q_PROPERTY(QmlObjectListModel*      childItems          READ childItems                                                         CONSTANT)
    Q_PROPERTY(QGCGeoBoundingCube*      boundingCube        READ boundingCube                                                       NOTIFY boundingCubeChanged)
87

88
    // The following properties are calculated/set by the MissionController recalc methods
89

90 91
    Q_PROPERTY(double altDifference     READ altDifference      WRITE setAltDifference      NOTIFY altDifferenceChanged)        ///< Change in altitude from previous waypoint
    Q_PROPERTY(double altPercent        READ altPercent         WRITE setAltPercent         NOTIFY altPercentChanged)           ///< Percent of total altitude change in mission altitude
92
    Q_PROPERTY(double terrainPercent    READ terrainPercent     WRITE setTerrainPercent     NOTIFY terrainPercentChanged)       ///< Percent of terrain altitude in mission altitude
93
    Q_PROPERTY(bool   terrainCollision  READ terrainCollision   WRITE setTerrainCollision   NOTIFY terrainCollisionChanged)     ///< true: Item collides with terrain
94 95
    Q_PROPERTY(double azimuth           READ azimuth            WRITE setAzimuth            NOTIFY azimuthChanged)              ///< Azimuth to previous waypoint
    Q_PROPERTY(double distance          READ distance           WRITE setDistance           NOTIFY distanceChanged)             ///< Distance to previous waypoint
96 97

    // Property accesors
98 99 100 101 102 103 104 105 106 107 108 109 110
    bool    homePosition        (void) const { return _homePositionSpecialCase; }
    double  altDifference       (void) const { return _altDifference; }
    double  altPercent          (void) const { return _altPercent; }
    double  terrainPercent      (void) const { return _terrainPercent; }
    bool    terrainCollision    (void) const { return _terrainCollision; }
    double  azimuth             (void) const { return _azimuth; }
    double  distance            (void) const { return _distance; }
    bool    isCurrentItem       (void) const { return _isCurrentItem; }
    bool    hasCurrentChildItem (void) const { return _hasCurrentChildItem; }
    double  terrainAltitude     (void) const { return _terrainAltitude; }
    bool    flyView             (void) const { return _flyView; }
    bool    wizardMode          (void) const { return _wizardMode; }
    VisualMissionItem* parentItem(void) { return _parentItem; }
111 112 113

    QmlObjectListModel* childItems(void) { return &_childItems; }

114 115 116 117 118 119 120 121 122 123
    void setIsCurrentItem           (bool isCurrentItem);
    void setHasCurrentChildItem     (bool hasCurrentChildItem);
    void setAltDifference           (double altDifference);
    void setAltPercent              (double altPercent);
    void setTerrainPercent          (double terrainPercent);
    void setTerrainCollision        (bool terrainCollision);
    void setAzimuth                 (double azimuth);
    void setDistance                (double distance);
    void setWizardMode              (bool wizardMode);
    void setParentItem              (VisualMissionItem* parentItem);
124 125

    void setHomePositionSpecialCase (bool homePositionSpecialCase) { _homePositionSpecialCase = homePositionSpecialCase; }
126

127
    PlanMasterController* masterController(void) { return _masterController; }
128 129 130 131 132

    // Pure virtuals which must be provides by derived classes

    virtual bool            dirty                   (void) const = 0;
    virtual bool            isSimpleItem            (void) const = 0;
133
    virtual bool            isTakeoffItem           (void) const { return false; }
134 135
    virtual bool            isStandaloneCoordinate  (void) const = 0;
    virtual bool            specifiesCoordinate     (void) const = 0;
136
    virtual bool            specifiesAltitudeOnly   (void) const = 0;
137 138
    virtual QString         commandDescription      (void) const = 0;
    virtual QString         commandName             (void) const = 0;
139
    virtual QString         abbreviation            (void) const = 0;
140 141
    virtual QGeoCoordinate  coordinate              (void) const = 0;
    virtual QGeoCoordinate  exitCoordinate          (void) const = 0;
142
    virtual int             sequenceNumber          (void) const = 0;
DonLakeFlyer's avatar
DonLakeFlyer committed
143 144
    virtual double          specifiedFlightSpeed    (void) = 0;
    virtual double          specifiedGimbalYaw      (void) = 0;
145
    virtual double          specifiedGimbalPitch    (void) = 0;
146
    virtual double          specifiedVehicleYaw     (void) { return qQNaN(); }
DonLakeFlyer's avatar
DonLakeFlyer committed
147

148 149 150
    //-- Default implementation returns an invalid bounding cube
    virtual QGCGeoBoundingCube* boundingCube        (void) { return &_boundingCube; }

DonLakeFlyer's avatar
DonLakeFlyer committed
151 152 153
    /// Update item to mission flight status at point where this item appears in mission.
    /// IMPORTANT: Overrides must call base class implementation
    virtual void setMissionFlightStatus(MissionController::MissionFlightStatus_t& missionFlightStatus);
154 155 156 157 158 159 160

    virtual bool coordinateHasRelativeAltitude      (void) const = 0;
    virtual bool exitCoordinateHasRelativeAltitude  (void) const = 0;
    virtual bool exitCoordinateSameAsEntry          (void) const = 0;

    virtual void setDirty           (bool dirty) = 0;
    virtual void setCoordinate      (const QGeoCoordinate& coordinate) = 0;
161
    virtual void setSequenceNumber  (int sequenceNumber) = 0;
162
    virtual int  lastSequenceNumber (void) const = 0;
163

DonLakeFlyer's avatar
DonLakeFlyer committed
164 165
    /// @return Returns whether the item is ready for save and if not, why
    virtual ReadyForSaveState readyForSaveState(void) const { return ReadyForSave; }
166

167
    /// Save the item(s) in Json format
168
    ///     @param missionItems Current set of mission items, new items should be appended to the end
169
    virtual void save(QJsonArray&  missionItems) = 0;
170

171 172 173
    /// @return The QML resource file which contains the control which visualizes the item on the map.
    virtual QString mapVisualQML(void) const = 0;

174 175 176 177 178
    /// Returns the mission items associated with the complex item. Caller is responsible for freeing.
    ///     @param items List to append to
    ///     @param missionItemParent Parent object for newly created MissionItems
    virtual void appendMissionItems(QList<MissionItem*>& items, QObject* missionItemParent) = 0;

DonLakeFlyer's avatar
DonLakeFlyer committed
179 180 181
    /// Adjust the altitude of the item if appropriate to the new altitude.
    virtual void applyNewAltitude(double newAltitude) = 0;

182 183 184
    /// @return Amount of additional time delay in seconds needed to fly this item
    virtual double additionalTimeDelay(void) const = 0;

DonLakeFlyer's avatar
DonLakeFlyer committed
185 186 187 188
    double  missionGimbalYaw    (void) const { return _missionGimbalYaw; }
    double  missionVehicleYaw   (void) const { return _missionVehicleYaw; }
    void    setMissionVehicleYaw(double vehicleYaw);

Don Gagne's avatar
Don Gagne committed
189 190 191 192
    static const char* jsonTypeKey;                 ///< Json file attribute which specifies the item type
    static const char* jsonTypeSimpleItemValue;     ///< Item type is MISSION_ITEM
    static const char* jsonTypeComplexItemValue;    ///< Item type is Complex Item

193 194 195
signals:
    void altDifferenceChanged           (double altDifference);
    void altPercentChanged              (double altPercent);
196
    void terrainPercentChanged          (double terrainPercent);
197
    void terrainCollisionChanged        (double terrainCollision);
198 199 200
    void azimuthChanged                 (double azimuth);
    void commandDescriptionChanged      (void);
    void commandNameChanged             (void);
201
    void abbreviationChanged            (void);
202 203 204 205 206
    void coordinateChanged              (const QGeoCoordinate& coordinate);
    void exitCoordinateChanged          (const QGeoCoordinate& exitCoordinate);
    void dirtyChanged                   (bool dirty);
    void distanceChanged                (double distance);
    void isCurrentItemChanged           (bool isCurrentItem);
207
    void hasCurrentChildItemChanged     (bool hasCurrentChildItem);
208 209
    void sequenceNumberChanged          (int sequenceNumber);
    void isSimpleItemChanged            (bool isSimpleItem);
210
    void isTakeoffItemChanged           (bool isTakeoffItem);
211 212
    void specifiesCoordinateChanged     (void);
    void isStandaloneCoordinateChanged  (void);
DonLakeFlyer's avatar
DonLakeFlyer committed
213 214 215
    void specifiesAltitudeOnlyChanged   (void);
    void specifiedFlightSpeedChanged    (void);
    void specifiedGimbalYawChanged      (void);
216
    void specifiedGimbalPitchChanged    (void);
217
    void specifiedVehicleYawChanged     (void);
218
    void lastSequenceNumberChanged      (int sequenceNumber);
DonLakeFlyer's avatar
DonLakeFlyer committed
219 220
    void missionGimbalYawChanged        (double missionGimbalYaw);
    void missionVehicleYawChanged       (double missionVehicleYaw);
221
    void terrainAltitudeChanged         (double terrainAltitude);
222
    void additionalTimeDelayChanged     (void);
223
    void boundingCubeChanged            (void);
DonLakeFlyer's avatar
DonLakeFlyer committed
224
    void readyForSaveStateChanged       (void);
225
    void wizardModeChanged              (bool wizardMode);
226
    void parentItemChanged              (VisualMissionItem* parentItem);
227 228 229

    void coordinateHasRelativeAltitudeChanged       (bool coordinateHasRelativeAltitude);
    void exitCoordinateHasRelativeAltitudeChanged   (bool exitCoordinateHasRelativeAltitude);
230
    void exitCoordinateSameAsEntryChanged           (bool exitCoordinateSameAsEntry);
231 232

protected:
233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251
    bool     _flyView    =               false;
    bool    _isCurrentItem =            false;
    bool    _hasCurrentChildItem =      false;
    bool    _dirty =                    false;
    bool    _homePositionSpecialCase =  false;      ///< true: This item is being used as a ui home position indicator
    bool    _wizardMode =               false;      ///< true: Item editor is showing wizard completion panel
    double  _terrainAltitude =          qQNaN();    ///< Altitude of terrain at coordinate position, NaN for not known
    double  _altDifference =            0;          ///< Difference in altitude from previous waypoint
    double  _altPercent =               0;          ///< Percent of total altitude change in mission
    double  _terrainPercent =           qQNaN();    ///< Percent of terrain altitude for coordinate
    bool    _terrainCollision =         false;      ///< true: item collides with terrain
    double  _azimuth =                  0;          ///< Azimuth to previous waypoint
    double  _distance =                 0;          ///< Distance to previous waypoint
    QString _editorQml;                             ///< Qml resource for editing item
    double  _missionGimbalYaw =         qQNaN();
    double  _missionVehicleYaw =        qQNaN();

    PlanMasterController*   _masterController = nullptr;
    Vehicle*                _controllerVehicle = nullptr;
252 253 254

    VisualMissionItem*  _parentItem = nullptr;
    QGCGeoBoundingCube  _boundingCube;          ///< The bounding "cube" of this element.
255

DonLakeFlyer's avatar
DonLakeFlyer committed
256
    MissionController::MissionFlightStatus_t    _missionFlightStatus;
257 258 259

    /// This is used to reference any subsequent mission items which do not specify a coordinate.
    QmlObjectListModel  _childItems;
260

261 262 263
protected:
    void    _setBoundingCube                (QGCGeoBoundingCube bc);

264 265 266
private slots:
    void _updateTerrainAltitude (void);
    void _reallyUpdateTerrainAltitude (void);
267
    void _terrainDataReceived   (bool success, QList<double> heights);
268 269

private:
270 271
    void _commonInit(void);

272
    QTimer _updateTerrainTimer;
273 274
    double _lastLatTerrainQuery = 0;
    double _lastLonTerrainQuery = 0;
275
};