MissionItem.h 8.91 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 72
    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)
    Q_PROPERTY(MavlinkQmlSingleton::Qml_MAV_CMD command READ command                WRITE setCommand        NOTIFY commandChanged)
Don Gagne's avatar
Don Gagne committed
73 74 75 76 77 78 79 80
    
    // Property accesors
    
    int sequenceNumber(void) const { return _sequenceNumber; }
    void setSequenceNumber(int sequenceNumber);
    
    bool isCurrentItem(void) const { return _isCurrentItem; }
    void setIsCurrentItem(bool isCurrentItem);
81
    
Don Gagne's avatar
Don Gagne committed
82
    bool specifiesCoordinate(void) const;
83
    
Don Gagne's avatar
Don Gagne committed
84 85 86 87 88
    QGeoCoordinate coordinate(void) const { return _coordinate; }
    void setCoordinate(const QGeoCoordinate& coordinate);
    
    QStringList commandNames(void);
    QString commandName(void);
89

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

Don Gagne's avatar
Don Gagne committed
106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121
    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
122 123
    double yawRadians(void) const;
    void setYawRadians(double yaw);
Don Gagne's avatar
Don Gagne committed
124
    
125
    bool getAutoContinue() const {
126
        return _autocontinue;
127
    }
Don Gagne's avatar
Don Gagne committed
128 129
    double loiterOrbitRadius() const {
        return _loiterOrbitRadiusFact->value().toDouble();
130 131
    }
    double getAcceptanceRadius() const {
Don Gagne's avatar
Don Gagne committed
132
        return getParam2();
133 134
    }
    double getHoldTime() const {
Don Gagne's avatar
Don Gagne committed
135
        return getParam1();
136 137
    }
    double getParam1() const {
Don Gagne's avatar
Don Gagne committed
138
        return _param1Fact->value().toDouble();
139 140
    }
    double getParam2() const {
Don Gagne's avatar
Don Gagne committed
141
        return _param2Fact->value().toDouble();
142 143
    }
    double getParam3() const {
Don Gagne's avatar
Don Gagne committed
144
        return loiterOrbitRadius();
145 146
    }
    double getParam4() const {
Don Gagne's avatar
Don Gagne committed
147
        return yawRadians();
148 149
    }
    double getParam5() const {
Don Gagne's avatar
Don Gagne committed
150
        return latitude();
151 152
    }
    double getParam6() const {
Don Gagne's avatar
Don Gagne committed
153
        return longitude();
154 155
    }
    double getParam7() const {
Don Gagne's avatar
Don Gagne committed
156
        return altitude();
157
    }
158 159 160
    // MAV_FRAME
    int getFrame() const {
        return _frame;
161
    }
162 163 164
    // MAV_CMD
    int getAction() const {
        return _action;
165
    }
lm's avatar
lm committed
166 167
    /** @brief Returns true if x, y, z contain reasonable navigation data */
    bool isNavigationType();
168

169 170 171
    /** @brief Get the time this waypoint was reached */
    quint64 getReachedTime() const { return _reachedTime; }

172 173
    void save(QTextStream &saveStream);
    bool load(QTextStream &loadStream);
174
    
175
    
Don Gagne's avatar
Don Gagne committed
176 177 178 179 180 181 182 183 184
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);
185

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

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

218 219
private:
    QString _oneDecimalString(double value);
Don Gagne's avatar
Don Gagne committed
220 221 222 223 224 225 226 227 228 229 230 231 232 233 234

private:
    typedef struct {
        MAV_CMD     command;
        const char* name;
    } MavCmd2Name_t;
    
    int             _sequenceNumber;
    QGeoCoordinate  _coordinate;
    int             _frame;
    int             _action;
    bool            _autocontinue;
    bool            _isCurrentItem;
    quint64         _reachedTime;
    
Don Gagne's avatar
Don Gagne committed
235 236
    Fact*           _yawRadiansFact;
    Fact*           _loiterOrbitRadiusFact;
Don Gagne's avatar
Don Gagne committed
237 238 239 240 241 242 243 244 245 246 247 248
    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
249 250
    static const int            _cMavCmd2Name = 9;
    static const MavCmd2Name_t  _rgMavCmd2Name[_cMavCmd2Name];
pixhawk's avatar
pixhawk committed
251 252
};

253
#endif