SimpleMissionItem.h.orig 12.6 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
/****************************************************************************
 *
 * (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.
 *
 ****************************************************************************/


#ifndef SimpleMissionItem_H
#define SimpleMissionItem_H

#include "VisualMissionItem.h"
#include "MissionItem.h"
#include "MissionCommandTree.h"
#include "CameraSection.h"
#include "SpeedSection.h"
#include "QGroundControlQmlGlobal.h"

/// A SimpleMissionItem is used to represent a single MissionItem to the ui.
class SimpleMissionItem : public VisualMissionItem
{
    Q_OBJECT
    
public:
    SimpleMissionItem(PlanMasterController* masterController, bool flyView, bool forLoad, QObject* parent);
    SimpleMissionItem(PlanMasterController* masterController, bool flyView, const MissionItem& missionItem, QObject* parent);

    ~SimpleMissionItem();

    Q_PROPERTY(QString          category                READ category                                           NOTIFY commandChanged)
    Q_PROPERTY(bool             friendlyEditAllowed     READ friendlyEditAllowed                                NOTIFY friendlyEditAllowedChanged)
    Q_PROPERTY(bool             rawEdit                 READ rawEdit                WRITE setRawEdit            NOTIFY rawEditChanged)              ///< true: raw item editing with all params
    Q_PROPERTY(bool             specifiesAltitude       READ specifiesAltitude                                  NOTIFY commandChanged)
    Q_PROPERTY(Fact*            altitude                READ altitude                                           CONSTANT)                           ///< Altitude as specified by altitudeMode. Not necessarily true mission item altitude
    Q_PROPERTY(QGroundControlQmlGlobal::AltitudeMode altitudeMode READ altitudeMode WRITE setAltitudeMode       NOTIFY altitudeModeChanged)
    Q_PROPERTY(Fact*            amslAltAboveTerrain     READ amslAltAboveTerrain                                CONSTANT)                           ///< Actual AMSL altitude for item if altitudeMode == AltitudeAboveTerrain
    Q_PROPERTY(int              command                 READ command                WRITE setCommand            NOTIFY commandChanged)

    /// Optional sections
    Q_PROPERTY(QObject*         speedSection            READ speedSection                                       NOTIFY speedSectionChanged)
    Q_PROPERTY(QObject*         cameraSection           READ cameraSection                                      NOTIFY cameraSectionChanged)

    // These properties are used to display the editing ui
    Q_PROPERTY(QmlObjectListModel*  comboboxFacts   READ comboboxFacts  CONSTANT)
    Q_PROPERTY(QmlObjectListModel*  textFieldFacts  READ textFieldFacts CONSTANT)
    Q_PROPERTY(QmlObjectListModel*  nanFacts        READ nanFacts       CONSTANT)

    /// This should be called before changing the command. It is needed if the command changes
    /// from an item which does not include a coordinate to an item which requires a coordinate.
    /// It uses this value to set that new coordinate.
    Q_INVOKABLE void setMapCenterHintForCommandChange(QGeoCoordinate mapCenter) { _mapCenterHint = mapCenter; }

    /// Scans the loaded items for additional section settings
    ///     @param visualItems List of all visual items
    ///     @param scanIndex Index to start scanning from
    ///     @param vehicle Vehicle associated with this mission
    /// @return true: section found, scanIndex updated
    bool scanForSections(QmlObjectListModel* visualItems, int scanIndex, PlanMasterController* masterController);

    // Property accesors
    
    QString         category            (void) const;
    int             command             (void) const { return _missionItem._commandFact.cookedValue().toInt(); }
    MAV_CMD         mavCommand          (void) const { return static_cast<MAV_CMD>(command()); }
    bool            friendlyEditAllowed (void) const;
    bool            rawEdit             (void) const;
    bool            specifiesAltitude   (void) const;
    QGroundControlQmlGlobal::AltitudeMode altitudeMode(void) const { return _altitudeMode; }
    Fact*           altitude            (void) { return &_altitudeFact; }
    Fact*           amslAltAboveTerrain (void) { return &_amslAltAboveTerrainFact; }

    CameraSection*  cameraSection       (void) { return _cameraSection; }
    SpeedSection*   speedSection        (void) { return _speedSection; }

    QmlObjectListModel* textFieldFacts  (void) { return &_textFieldFacts; }
    QmlObjectListModel* nanFacts        (void) { return &_nanFacts; }
    QmlObjectListModel* comboboxFacts   (void) { return &_comboboxFacts; }

    void setRawEdit(bool rawEdit);
    void setAltitudeMode(QGroundControlQmlGlobal::AltitudeMode altitudeMode);
    
    void setCommandByIndex(int index);

    void setCommand(int command);

    void setAltDifference   (double altDifference);
    void setAltPercent      (double altPercent);
    void setAzimuth         (double azimuth);
    void setDistance        (double distance);

    virtual bool load(QTextStream &loadStream);
    virtual bool load(const QJsonObject& json, int sequenceNumber, QString& errorString);

    MissionItem& missionItem(void) { return _missionItem; }
    const MissionItem& missionItem(void) const { return _missionItem; }

    // Overrides from VisualMissionItem
<<<<<<< HEAD
<<<<<<< HEAD

    bool            dirty                   (void) const final { return _dirty; }
    bool            isSimpleItem            (void) const final { return true; }
    bool            isStandaloneCoordinate  (void) const final;
    bool            specifiesCoordinate     (void) const final;
    bool            specifiesAltitudeOnly   (void) const final;
    QString         commandDescription      (void) const final;
    QString         commandName             (void) const final;
    QString         abbreviation            (void) const final;
    QGeoCoordinate  coordinate              (void) const final { return _missionItem.coordinate(); }
    QGeoCoordinate  exitCoordinate          (void) const final { return coordinate(); }
    int             sequenceNumber          (void) const final { return _missionItem.sequenceNumber(); }
    double          specifiedFlightSpeed    (void) final;
    double          specifiedGimbalYaw      (void) final;
    double          specifiedGimbalPitch    (void) final;
    QString         mapVisualQML            (void) const final { return QStringLiteral("SimpleItemMapVisual.qml"); }
    void            appendMissionItems      (QList<MissionItem*>& items, QObject* missionItemParent) final;
    void            applyNewAltitude        (double newAltitude) final;
    void            setMissionFlightStatus  (const MissionController::MissionFlightStatus_t &missionFlightStatus) final;
    bool            readyForSave            (void) const final;
    double          additionalTimeDelay     (void) const final;

    bool coordinateHasRelativeAltitude      (void) const final { return _missionItem.relativeAltitude(); }
    bool exitCoordinateHasRelativeAltitude  (void) const final { return coordinateHasRelativeAltitude(); }
    bool exitCoordinateSameAsEntry          (void) const final { return true; }
=======
=======
>>>>>>> upstream_merge
    bool            dirty                       (void) const override { return _dirty; }
    bool            isSimpleItem                (void) const final { return true; }
    bool            isStandaloneCoordinate      (void) const final;
    bool            isLandCommand               (void) const final;
    bool            specifiesCoordinate         (void) const final;
    bool            specifiesAltitudeOnly       (void) const final;
    QString         commandDescription          (void) const final;
    QString         commandName                 (void) const final;
    QString         abbreviation                (void) const final;
    QGeoCoordinate  coordinate                  (void) const final;
    QGeoCoordinate  exitCoordinate              (void) const final { return coordinate(); }
    double          amslEntryAlt                (void) const final;
    double          amslExitAlt                 (void) const final { return amslEntryAlt(); }
    int             sequenceNumber              (void) const final { return _missionItem.sequenceNumber(); }
    double          specifiedFlightSpeed        (void) override;
    double          specifiedGimbalYaw          (void) override;
    double          specifiedGimbalPitch        (void) override;
    double          specifiedVehicleYaw         (void) override;
    QString         mapVisualQML                (void) const override { return QStringLiteral("SimpleItemMapVisual.qml"); }
    void            appendMissionItems          (QList<MissionItem*>& items, QObject* missionItemParent) final;
    void            applyNewAltitude            (double newAltitude) final;
    void            setMissionFlightStatus      (MissionController::MissionFlightStatus_t& missionFlightStatus) final;
    ReadyForSaveState readyForSaveState         (void) const final;
    double          additionalTimeDelay         (void) const final;
    bool            exitCoordinateSameAsEntry   (void) const final { return true; }
<<<<<<< HEAD
>>>>>>> upstream_merge
=======
>>>>>>> upstream_merge

    void setDirty           (bool dirty) final;
    void setCoordinate      (const QGeoCoordinate& coordinate) override;
    void setSequenceNumber  (int sequenceNumber) final;
    int  lastSequenceNumber (void) const final;
    void save               (QJsonArray&  missionItems) final;

signals:
    void commandChanged             (int command);
    void friendlyEditAllowedChanged (bool friendlyEditAllowed);
    void headingDegreesChanged      (double heading);
    void rawEditChanged             (bool rawEdit);
    void cameraSectionChanged       (QObject* cameraSection);
    void speedSectionChanged        (QObject* cameraSection);
    void altitudeModeChanged        (void);

private slots:
    void _setDirty                              (void);
    void _sectionDirtyChanged                   (bool dirty);
    void _sendCommandChanged                    (void);
    void _sendCoordinateChanged                 (void);
    void _sendFriendlyEditAllowedChanged        (void);
    void _altitudeChanged                       (void);
    void _altitudeModeChanged                   (void);
    void _terrainAltChanged                     (void);
    void _updateLastSequenceNumber              (void);
    void _rebuildFacts                          (void);
    void _rebuildTextFieldFacts                 (void);
    void _possibleAdditionalTimeDelayChanged    (void);
    void _setDefaultsForCommand                 (void);
    void _possibleVehicleYawChanged             (void);
    void _signalIfVTOLTransitionCommand         (void);

private:
    void _connectSignals        (void);
    void _setupMetaData         (void);
    void _updateOptionalSections(void);
    void _rebuildNaNFacts       (void);
    void _rebuildComboBoxFacts  (void);

    MissionItem     _missionItem;
    bool            _rawEdit =                  false;
    bool            _dirty =                    false;
    bool            _ignoreDirtyChangeSignals = false;
    QGeoCoordinate  _mapCenterHint;
    SpeedSection*   _speedSection =             nullptr;
    CameraSection*  _cameraSection =             nullptr;

    MissionCommandTree* _commandTree = nullptr;
    bool _syncingHeadingDegreesAndParam4 = false;   ///< true: already in a sync signal, prevents signal loop

    Fact                _supportedCommandFact;

    QGroundControlQmlGlobal::AltitudeMode   _altitudeMode = QGroundControlQmlGlobal::AltitudeModeRelative;
    Fact                                    _altitudeFact;
    Fact                                    _amslAltAboveTerrainFact;

    QmlObjectListModel  _textFieldFacts;
    QmlObjectListModel  _nanFacts;
    QmlObjectListModel  _comboboxFacts;
    
    static FactMetaData*    _altitudeMetaData;
    static FactMetaData*    _commandMetaData;
    static FactMetaData*    _defaultParamMetaData;
    static FactMetaData*    _frameMetaData;
    static FactMetaData*    _latitudeMetaData;
    static FactMetaData*    _longitudeMetaData;

    FactMetaData    _param1MetaData;
    FactMetaData    _param2MetaData;
    FactMetaData    _param3MetaData;
    FactMetaData    _param4MetaData;
    FactMetaData    _param5MetaData;
    FactMetaData    _param6MetaData;
    FactMetaData    _param7MetaData;

    static const char* _jsonAltitudeModeKey;
    static const char* _jsonAltitudeKey;
    static const char* _jsonAMSLAltAboveTerrainKey;
};

#endif