MissionItem.h 8.24 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:
Don Gagne's avatar
Don Gagne committed
42 43 44 45 46 47 48 49 50 51 52
    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);
53

54 55
    MissionItem(const MissionItem& other);
    ~MissionItem();
pixhawk's avatar
pixhawk committed
56

57 58
    const MissionItem& operator=(const MissionItem& other);
    
Don Gagne's avatar
Don Gagne committed
59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77
    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 yaw                    WRITE setYaw            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(MavlinkQmlSingleton::Qml_MAV_CMD command READ command            WRITE setCommand        NOTIFY commandChanged)
    
    // Property accesors
    
    int sequenceNumber(void) const { return _sequenceNumber; }
    void setSequenceNumber(int sequenceNumber);
    
    bool isCurrentItem(void) const { return _isCurrentItem; }
    void setIsCurrentItem(bool isCurrentItem);
78
    
Don Gagne's avatar
Don Gagne committed
79
    bool specifiesCoordinate(void) const;
80
    
Don Gagne's avatar
Don Gagne committed
81 82 83 84 85
    QGeoCoordinate coordinate(void) const { return _coordinate; }
    void setCoordinate(const QGeoCoordinate& coordinate);
    
    QStringList commandNames(void);
    QString commandName(void);
86

Don Gagne's avatar
Don Gagne committed
87 88 89 90 91 92 93 94 95 96
    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);
    
    // C++ only methods
97

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

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

167 168
    void save(QTextStream &saveStream);
    bool load(QTextStream &loadStream);
169
    
170
    
Don Gagne's avatar
Don Gagne committed
171 172 173 174 175 176 177 178 179
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);
180

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

211 212 213
    void setChanged() {
        emit changed(this);
    }
214

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

private:
    typedef struct {
        MAV_CMD     command;
        const char* name;
    } MavCmd2Name_t;
    
    int             _sequenceNumber;
    QGeoCoordinate  _coordinate;
    double          _yaw;
    int             _frame;
    int             _action;
    bool            _autocontinue;
    bool            _isCurrentItem;
    double          _orbit;
    double          _param1;
    double          _param2;
    int             _turns;
    quint64         _reachedTime;
    
    static const int            _cMavCmd2Name = 9;
    static const MavCmd2Name_t  _rgMavCmd2Name[_cMavCmd2Name];
pixhawk's avatar
pixhawk committed
239 240
};

241
#endif