MissionItem.h 9.15 KB
Newer Older
pixhawk's avatar
pixhawk committed
1
/*=====================================================================
2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22
 
 QGroundControl Open Source Ground Control Station
 
 (c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 
 This file is part of the QGROUNDCONTROL project
 
 QGROUNDCONTROL is free software: you can redistribute it and/or modify
 it under the terms of the GNU General Public License as published by
 the Free Software Foundation, either version 3 of the License, or
 (at your option) any later version.
 
 QGROUNDCONTROL is distributed in the hope that it will be useful,
 but WITHOUT ANY WARRANTY; without even the implied warranty of
 MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
 GNU General Public License for more details.
 
 You should have received a copy of the GNU General Public License
 along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
 
 ======================================================================*/
pixhawk's avatar
pixhawk committed
23

24 25
#ifndef MissionItem_H
#define MissionItem_H
pixhawk's avatar
pixhawk committed
26 27 28

#include <QObject>
#include <QString>
29
#include <QtQml>
30
#include <QTextStream>
31 32
#include <QGeoCoordinate>

lm's avatar
lm committed
33
#include "QGCMAVLink.h"
lm's avatar
lm committed
34
#include "QGC.h"
35
#include "MavlinkQmlSingleton.h"
Don Gagne's avatar
Don Gagne committed
36 37
#include "QmlObjectListModel.h"
#include "Fact.h"
pixhawk's avatar
pixhawk committed
38

39
class MissionItem : public QObject
pixhawk's avatar
pixhawk committed
40 41
{
    Q_OBJECT
42
    
pixhawk's avatar
pixhawk committed
43
public:
Don Gagne's avatar
Don Gagne committed
44 45 46 47 48 49 50 51 52 53 54
    MissionItem(QObject         *parent = 0,
                int             sequenceNumber = 0,
                QGeoCoordinate  coordiante = QGeoCoordinate(),
                double          param1 = 0.0,
                double          param2 = 0.0,
                double          param3 = 0.0,
                double          param4 = 0.0,
                bool            autocontinue = true,
                bool            isCurrentItem = false,
                int             frame = MAV_FRAME_GLOBAL,
                int             action = MAV_CMD_NAV_WAYPOINT);
55

Don Gagne's avatar
Don Gagne committed
56
    MissionItem(const MissionItem& other, QObject* parent = NULL);
57
    ~MissionItem();
pixhawk's avatar
pixhawk committed
58

59 60
    const MissionItem& operator=(const MissionItem& other);
    
Don Gagne's avatar
Don Gagne committed
61 62 63 64 65 66 67 68 69 70 71
    Q_PROPERTY(int                  sequenceNumber      READ sequenceNumber         WRITE setSequenceNumber NOTIFY sequenceNumberChanged)
    Q_PROPERTY(bool                 isCurrentItem       READ isCurrentItem          WRITE setIsCurrentItem  NOTIFY isCurrentItemChanged)
    Q_PROPERTY(bool                 specifiesCoordinate READ specifiesCoordinate                            NOTIFY specifiesCoordinateChanged)
    Q_PROPERTY(QGeoCoordinate       coordinate          READ coordinate             WRITE setCoordinate     NOTIFY coordinateChanged)
    Q_PROPERTY(double               yaw                 READ yawDegrees             WRITE setYawDegrees     NOTIFY yawChanged)
    Q_PROPERTY(QStringList          commandNames        READ commandNames                                   CONSTANT)
    Q_PROPERTY(QString              commandName         READ commandName                                    NOTIFY commandChanged)
    Q_PROPERTY(QStringList          valueLabels         READ valueLabels                                    NOTIFY commandChanged)
    Q_PROPERTY(QStringList          valueStrings        READ valueStrings                                   NOTIFY valueStringsChanged)
    Q_PROPERTY(int                  commandByIndex      READ commandByIndex         WRITE setCommandByIndex NOTIFY commandChanged)
    Q_PROPERTY(QmlObjectListModel*  facts               READ facts                                          NOTIFY commandChanged)
Don Gagne's avatar
Don Gagne committed
72
    Q_PROPERTY(int                  factCount           READ factCount                                      NOTIFY commandChanged)
Don Gagne's avatar
Don Gagne committed
73
    Q_PROPERTY(MavlinkQmlSingleton::Qml_MAV_CMD command READ command                WRITE setCommand        NOTIFY commandChanged)
Don Gagne's avatar
Don Gagne committed
74 75 76 77 78 79 80 81
    
    // Property accesors
    
    int sequenceNumber(void) const { return _sequenceNumber; }
    void setSequenceNumber(int sequenceNumber);
    
    bool isCurrentItem(void) const { return _isCurrentItem; }
    void setIsCurrentItem(bool isCurrentItem);
82
    
Don Gagne's avatar
Don Gagne committed
83
    bool specifiesCoordinate(void) const;
84
    
Don Gagne's avatar
Don Gagne committed
85 86 87 88 89
    QGeoCoordinate coordinate(void) const { return _coordinate; }
    void setCoordinate(const QGeoCoordinate& coordinate);
    
    QStringList commandNames(void);
    QString commandName(void);
90

Don Gagne's avatar
Don Gagne committed
91 92 93
    int commandByIndex(void);
    void setCommandByIndex(int index);
    
Don Gagne's avatar
Don Gagne committed
94
    MavlinkQmlSingleton::Qml_MAV_CMD command(void) { return (MavlinkQmlSingleton::Qml_MAV_CMD)_command; };
Don Gagne's avatar
Don Gagne committed
95 96 97 98 99
    void setCommand(MavlinkQmlSingleton::Qml_MAV_CMD command) { setAction(command); }
    
    QStringList valueLabels(void);
    QStringList valueStrings(void);
    
Don Gagne's avatar
Don Gagne committed
100
    QmlObjectListModel* facts(void);
Don Gagne's avatar
Don Gagne committed
101
    int factCount(void);
Don Gagne's avatar
Don Gagne committed
102 103 104 105
    
    double yawDegrees(void) const;
    void setYawDegrees(double yaw);
    
Don Gagne's avatar
Don Gagne committed
106
    // C++ only methods
107

Don Gagne's avatar
Don Gagne committed
108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123
    double latitude(void)  const { return _coordinate.latitude(); }
    double longitude(void) const { return _coordinate.longitude(); }
    double altitude(void)  const { return _coordinate.altitude(); }
    
    void setLatitude(double latitude);
    void setLongitude(double longitude);
    void setAltitude(double altitude);
    
    double x(void) const { return latitude(); }
    double y(void) const { return longitude(); }
    double z(void) const { return altitude(); }
    
    void setX(double x);
    void setY(double y);
    void setZ(double z);
    
Don Gagne's avatar
Don Gagne committed
124 125
    double yawRadians(void) const;
    void setYawRadians(double yaw);
Don Gagne's avatar
Don Gagne committed
126
    
Don Gagne's avatar
Don Gagne committed
127
    bool autoContinue() const {
128
        return _autocontinue;
129
    }
Don Gagne's avatar
Don Gagne committed
130 131
    double loiterOrbitRadius() const {
        return _loiterOrbitRadiusFact->value().toDouble();
132
    }
Don Gagne's avatar
Don Gagne committed
133 134
    double acceptanceRadius() const {
        return param2();
135
    }
Don Gagne's avatar
Don Gagne committed
136 137
    double holdTime() const {
        return param1();
138
    }
Don Gagne's avatar
Don Gagne committed
139
    double param1() const {
Don Gagne's avatar
Don Gagne committed
140
        return _param1Fact->value().toDouble();
141
    }
Don Gagne's avatar
Don Gagne committed
142
    double param2() const {
Don Gagne's avatar
Don Gagne committed
143
        return _param2Fact->value().toDouble();
144
    }
Don Gagne's avatar
Don Gagne committed
145
    double param3() const {
Don Gagne's avatar
Don Gagne committed
146
        return loiterOrbitRadius();
147
    }
Don Gagne's avatar
Don Gagne committed
148
    double param4() const {
Don Gagne's avatar
Don Gagne committed
149
        return yawRadians();
150
    }
Don Gagne's avatar
Don Gagne committed
151
    double param5() const {
Don Gagne's avatar
Don Gagne committed
152
        return latitude();
153
    }
Don Gagne's avatar
Don Gagne committed
154
    double param6() const {
Don Gagne's avatar
Don Gagne committed
155
        return longitude();
156
    }
Don Gagne's avatar
Don Gagne committed
157
    double param7() const {
Don Gagne's avatar
Don Gagne committed
158
        return altitude();
159
    }
160
    // MAV_FRAME
Don Gagne's avatar
Don Gagne committed
161
    int frame() const {
162
        return _frame;
163
    }
164
    // MAV_CMD
Don Gagne's avatar
Don Gagne committed
165 166
    int command() const {
        return _command;
167
    }
lm's avatar
lm committed
168 169
    /** @brief Returns true if x, y, z contain reasonable navigation data */
    bool isNavigationType();
170

171
    /** @brief Get the time this waypoint was reached */
Don Gagne's avatar
Don Gagne committed
172
    quint64 reachedTime() const { return _reachedTime; }
173

174 175
    void save(QTextStream &saveStream);
    bool load(QTextStream &loadStream);
176
    
Don Gagne's avatar
Don Gagne committed
177 178 179 180 181 182 183 184 185
signals:
    void sequenceNumberChanged(int sequenceNumber);
    void specifiesCoordinateChanged(bool specifiesCoordinate);
    void isCurrentItemChanged(bool isCurrentItem);
    void coordinateChanged(const QGeoCoordinate& coordinate);
    void yawChanged(double yaw);

    /** @brief Announces a change to the waypoint data */
    void changed(MissionItem* wp);
186

187
    
Don Gagne's avatar
Don Gagne committed
188 189 190 191
    void commandNameChanged(QString type);
    void commandChanged(MavlinkQmlSingleton::Qml_MAV_CMD command);
    void valueLabelsChanged(QStringList valueLabels);
    void valueStringsChanged(QStringList valueStrings);
192
    
193
public:
194
    /** @brief Set the waypoint action */
195 196
    void setAction      (int _action);
    void setFrame       (int _frame);
pixhawk's avatar
pixhawk committed
197
    void setAutocontinue(bool autoContinue);
198
    void setCurrent     (bool _current);
Don Gagne's avatar
Don Gagne committed
199
    void setLoiterOrbitRadius (double radius);
200 201 202 203 204 205 206
    void setParam1      (double _param1);
    void setParam2      (double _param2);
    void setParam3      (double param3);
    void setParam4      (double param4);
    void setParam5      (double param5);
    void setParam6      (double param6);
    void setParam7      (double param7);
207
    void setAcceptanceRadius(double radius);
208 209
    void setHoldTime    (int holdTime);
    void setHoldTime    (double holdTime);
lm's avatar
lm committed
210
    /** @brief Set waypoint as reached */
211
    void setReached     () { _reachedTime = QGC::groundTimeMilliseconds(); }
lm's avatar
lm committed
212
    /** @brief Wether this waypoint has been reached yet */
213 214
    bool isReached      () { return (_reachedTime > 0); }

215 216 217
    void setChanged() {
        emit changed(this);
    }
218

219 220
private:
    QString _oneDecimalString(double value);
Don Gagne's avatar
Don Gagne committed
221 222 223 224 225 226 227

private:
    typedef struct {
        MAV_CMD     command;
        const char* name;
    } MavCmd2Name_t;
    
Don Gagne's avatar
Don Gagne committed
228 229 230 231 232 233 234
    int                                 _sequenceNumber;
    QGeoCoordinate                      _coordinate;
    int                                 _frame;
    MavlinkQmlSingleton::Qml_MAV_CMD    _command;
    bool                                _autocontinue;
    bool                                _isCurrentItem;
    quint64                             _reachedTime;
Don Gagne's avatar
Don Gagne committed
235
    
Don Gagne's avatar
Don Gagne committed
236 237
    Fact*           _yawRadiansFact;
    Fact*           _loiterOrbitRadiusFact;
Don Gagne's avatar
Don Gagne committed
238 239 240 241 242 243 244 245 246 247 248 249
    Fact*           _param1Fact;
    Fact*           _param2Fact;
    
    FactMetaData*   _pitchMetaData;
    FactMetaData*   _acceptanceRadiusMetaData;
    FactMetaData*   _holdTimeMetaData;
    FactMetaData*   _loiterTurnsMetaData;
    FactMetaData*   _loiterSecondsMetaData;
    FactMetaData*   _delaySecondsMetaData;
    FactMetaData*   _jumpSequenceMetaData;
    FactMetaData*   _jumpRepeatMetaData;
    
Don Gagne's avatar
Don Gagne committed
250 251
    static const int            _cMavCmd2Name = 9;
    static const MavCmd2Name_t  _rgMavCmd2Name[_cMavCmd2Name];
pixhawk's avatar
pixhawk committed
252 253
};

254
#endif