MissionItem.h 7.28 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"
pixhawk's avatar
pixhawk committed
36

37
class MissionItem : public QObject
pixhawk's avatar
pixhawk committed
38 39
{
    Q_OBJECT
40
    
pixhawk's avatar
pixhawk committed
41
public:
42
    MissionItem(
Gus Grubba's avatar
Gus Grubba committed
43
        QObject *parent = 0,
44 45 46 47 48 49 50 51 52 53 54 55 56 57
        quint16 id = 0,
        double  x = 0.0,
        double  y = 0.0,
        double  z = 0.0,
        double  param1 = 0.0,
        double  param2 = 0.0,
        double  param3 = 0.0,
        double  param4 = 0.0,
        bool    autocontinue = true,
        bool    current = false,
        int     frame = MAV_FRAME_GLOBAL,
        int     action = MAV_CMD_NAV_WAYPOINT,
        const QString& description=QString(""));

58 59
    MissionItem(const MissionItem& other);
    ~MissionItem();
pixhawk's avatar
pixhawk committed
60

61
    const MissionItem& operator=(const MissionItem& other);
62

63
    Q_PROPERTY(bool hasCoordinate READ hasCoordinate NOTIFY hasCoordinateChanged)
64
    Q_PROPERTY(QGeoCoordinate coordinate READ coordinate NOTIFY coordinateChanged)
65 66 67
    
    Q_PROPERTY(QString commandName READ commandName NOTIFY commandNameChanged)
    Q_PROPERTY(MavlinkQmlSingleton::Qml_MAV_CMD command READ command WRITE setCommand NOTIFY commandChanged)
68
    
69 70 71 72
    Q_PROPERTY(double  longitude READ longitude  NOTIFY longitudeChanged)
    Q_PROPERTY(double  latitude  READ latitude   NOTIFY latitudeChanged)
    Q_PROPERTY(double  altitude  READ altitude   NOTIFY altitudeChanged)
    Q_PROPERTY(quint16 id        READ id         CONSTANT)
73 74 75
    
    Q_PROPERTY(QStringList valueLabels READ valueLabels NOTIFY commandChanged)
    Q_PROPERTY(QStringList valueStrings READ valueStrings NOTIFY valueStringsChanged)
76 77 78 79 80 81

    double  latitude()  { return _x; }
    double  longitude() { return _y; }
    double  altitude()  { return _z; }
    quint16 id()        { return _id; }

82
    quint16 getId() const {
83
        return _id;
84 85
    }
    double getX() const {
86
        return _x;
87 88
    }
    double getY() const {
89
        return _y;
90 91
    }
    double getZ() const {
92
        return _z;
93 94
    }
    double getLatitude() const {
95
        return _x;
96 97
    }
    double getLongitude() const {
98
        return _y;
99 100
    }
    double getAltitude() const {
101
        return _z;
102 103
    }
    double getYaw() const {
104
        return _yaw;
105 106
    }
    bool getAutoContinue() const {
107
        return _autocontinue;
108 109
    }
    bool getCurrent() const {
110
        return _current;
111 112
    }
    double getLoiterOrbit() const {
113
        return _orbit;
114 115
    }
    double getAcceptanceRadius() const {
116
        return _param2;
117 118
    }
    double getHoldTime() const {
119
        return _param1;
120 121
    }
    double getParam1() const {
122
        return _param1;
123 124
    }
    double getParam2() const {
125
        return _param2;
126 127
    }
    double getParam3() const {
128
        return _orbit;
129 130
    }
    double getParam4() const {
131
        return _yaw;
132 133
    }
    double getParam5() const {
134
        return _x;
135 136
    }
    double getParam6() const {
137
        return _y;
138 139
    }
    double getParam7() const {
140
        return _z;
141 142
    }
    int getTurns() const {
143
        return _param1;
144
    }
145 146 147
    // MAV_FRAME
    int getFrame() const {
        return _frame;
148
    }
149 150 151
    // MAV_CMD
    int getAction() const {
        return _action;
152 153
    }
    const QString& getName() const {
154
        return _name;
155
    }
156
    const QString& getDescription() const {
157
        return _description;
158
    }
159

lm's avatar
lm committed
160 161
    /** @brief Returns true if x, y, z contain reasonable navigation data */
    bool isNavigationType();
162

163 164 165
    /** @brief Get the time this waypoint was reached */
    quint64 getReachedTime() const { return _reachedTime; }

166 167
    void save(QTextStream &saveStream);
    bool load(QTextStream &loadStream);
168
    
169
    bool hasCoordinate(void);
170
    QGeoCoordinate coordinate(void);
171 172
    
    QString commandName(void);
173

174 175 176 177 178 179
    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);
    
180
protected:
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
    quint16 _id;
    double  _x;
    double  _y;
    double  _z;
    double  _yaw;
    int     _frame;
    int     _action;
    bool    _autocontinue;
    bool    _current;
    double  _orbit;
    double  _param1;
    double  _param2;
    int     _turns;
    QString _name;
    QString _description;
    quint64 _reachedTime;

public:
    void setId          (quint16 _id);
    void setX           (double _x);
    void setY           (double _y);
    void setZ           (double _z);
    void setLatitude    (double lat);
    void setLongitude   (double lon);
    void setAltitude    (double alt);
lm's avatar
lm committed
206
    /** @brief Yaw angle in COMPASS DEGREES: 0-360 */
207
    void setYaw         (int _yaw);
lm's avatar
lm committed
208
    /** @brief Yaw angle in COMPASS DEGREES: 0-360 */
209
    void setYaw         (double _yaw);
210
    /** @brief Set the waypoint action */
211 212
    void setAction      (int _action);
    void setFrame       (int _frame);
pixhawk's avatar
pixhawk committed
213
    void setAutocontinue(bool autoContinue);
214 215 216 217 218 219 220 221 222
    void setCurrent     (bool _current);
    void setLoiterOrbit (double _orbit);
    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);
223
    void setAcceptanceRadius(double radius);
224 225
    void setHoldTime    (int holdTime);
    void setHoldTime    (double holdTime);
226
    /** @brief Number of turns for loiter waypoints */
227
    void setTurns       (int _turns);
lm's avatar
lm committed
228
    /** @brief Set waypoint as reached */
229
    void setReached     () { _reachedTime = QGC::groundTimeMilliseconds(); }
lm's avatar
lm committed
230
    /** @brief Wether this waypoint has been reached yet */
231 232
    bool isReached      () { return (_reachedTime > 0); }

233 234 235
    void setChanged() {
        emit changed(this);
    }
236 237 238

signals:
    /** @brief Announces a change to the waypoint data */
239
    void changed(MissionItem* wp);
240 241 242 243

    void latitudeChanged    ();
    void longitudeChanged   ();
    void altitudeChanged    ();
244
    void hasCoordinateChanged(bool hasCoordinate);
245
    void coordinateChanged(void);
246 247 248 249 250 251 252
    void commandNameChanged(QString type);
    void commandChanged(MavlinkQmlSingleton::Qml_MAV_CMD command);
    void valueLabelsChanged(QStringList valueLabels);
    void valueStringsChanged(QStringList valueStrings);
    
private:
    QString _oneDecimalString(double value);
pixhawk's avatar
pixhawk committed
253 254
};

255
#endif