MissionItem.h 12.4 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"
Don Gagne's avatar
Don Gagne committed
38
#include "QGCLoggingCategory.h"
Don Gagne's avatar
Don Gagne committed
39
#include "QmlObjectListModel.h"
Don Gagne's avatar
Don Gagne committed
40 41

Q_DECLARE_LOGGING_CATEGORY(MissionItemLog)
pixhawk's avatar
pixhawk committed
42

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

Don Gagne's avatar
Don Gagne committed
60
    MissionItem(const MissionItem& other, QObject* parent = NULL);
61
    ~MissionItem();
pixhawk's avatar
pixhawk committed
62

63 64
    const MissionItem& operator=(const MissionItem& other);
    
Don Gagne's avatar
Don Gagne committed
65 66 67
    /// Returns true if the item has been modified since the last time dirty was false
    Q_PROPERTY(bool                 dirty               READ dirty                  WRITE setDirty          NOTIFY dirtyChanged)
    
Don Gagne's avatar
Don Gagne committed
68 69
    Q_PROPERTY(int                  sequenceNumber      READ sequenceNumber         WRITE setSequenceNumber NOTIFY sequenceNumberChanged)
    Q_PROPERTY(bool                 isCurrentItem       READ isCurrentItem          WRITE setIsCurrentItem  NOTIFY isCurrentItemChanged)
70

71
    Q_PROPERTY(bool                 specifiesCoordinate READ specifiesCoordinate                            NOTIFY commandChanged)
Don Gagne's avatar
Don Gagne committed
72
    Q_PROPERTY(QGeoCoordinate       coordinate          READ coordinate             WRITE setCoordinate     NOTIFY coordinateChanged)
73 74 75 76

    Q_PROPERTY(bool                 specifiesHeading    READ specifiesHeading                               NOTIFY commandChanged)
    Q_PROPERTY(double               heading             READ headingDegrees         WRITE setHeadingDegrees NOTIFY headingDegreesChanged)

Don Gagne's avatar
Don Gagne committed
77 78
    Q_PROPERTY(QStringList          commandNames        READ commandNames                                   CONSTANT)
    Q_PROPERTY(QString              commandName         READ commandName                                    NOTIFY commandChanged)
79
    Q_PROPERTY(QString              commandDescription  READ commandDescription                             NOTIFY commandChanged)
Don Gagne's avatar
Don Gagne committed
80 81 82
    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)
83 84
    Q_PROPERTY(QmlObjectListModel*  textFieldFacts      READ textFieldFacts                                 NOTIFY commandChanged)
    Q_PROPERTY(QmlObjectListModel*  checkboxFacts       READ checkboxFacts                                  NOTIFY commandChanged)
Don Gagne's avatar
Don Gagne committed
85
    Q_PROPERTY(MavlinkQmlSingleton::Qml_MAV_CMD command READ command                WRITE setCommand        NOTIFY commandChanged)
Don Gagne's avatar
Don Gagne committed
86
    Q_PROPERTY(QmlObjectListModel*  childItems          READ childItems                                     CONSTANT)
87 88

    /// true: this item is being used as a home position indicator
89
    Q_PROPERTY(bool                 homePosition        READ homePosition                                   CONSTANT)
Don Gagne's avatar
Don Gagne committed
90
    
91 92 93
    /// true: home position should be shown
    Q_PROPERTY(bool                 homePositionValid   READ homePositionValid      WRITE setHomePositionValid NOTIFY homePositionValidChanged)

94 95 96
    /// Distance to previous waypoint, set by UI controller
    Q_PROPERTY(double               distance            READ distance               WRITE setDistance       NOTIFY distanceChanged)

Don Gagne's avatar
Don Gagne committed
97 98 99 100 101 102 103
    // Property accesors
    
    int sequenceNumber(void) const { return _sequenceNumber; }
    void setSequenceNumber(int sequenceNumber);
    
    bool isCurrentItem(void) const { return _isCurrentItem; }
    void setIsCurrentItem(bool isCurrentItem);
104
    
Don Gagne's avatar
Don Gagne committed
105
    bool specifiesCoordinate(void) const;
106
    QGeoCoordinate coordinate(void) const;
Don Gagne's avatar
Don Gagne committed
107 108
    void setCoordinate(const QGeoCoordinate& coordinate);
    
109 110 111 112
    bool specifiesHeading(void) const;
    double headingDegrees(void) const;
    void setHeadingDegrees(double headingDegrees);

Don Gagne's avatar
Don Gagne committed
113 114 115
    // This is public for unit testing
    double _yawRadians(void) const;

Don Gagne's avatar
Don Gagne committed
116 117
    QStringList commandNames(void);
    QString commandName(void);
118
    QString commandDescription(void);
119

Don Gagne's avatar
Don Gagne committed
120 121 122
    int commandByIndex(void);
    void setCommandByIndex(int index);
    
Don Gagne's avatar
Don Gagne committed
123
    MavlinkQmlSingleton::Qml_MAV_CMD command(void) { return (MavlinkQmlSingleton::Qml_MAV_CMD)_command; };
Don Gagne's avatar
Don Gagne committed
124 125 126 127 128
    void setCommand(MavlinkQmlSingleton::Qml_MAV_CMD command) { setAction(command); }
    
    QStringList valueLabels(void);
    QStringList valueStrings(void);
    
129 130
    QmlObjectListModel* textFieldFacts(void);
    QmlObjectListModel* checkboxFacts(void);
Don Gagne's avatar
Don Gagne committed
131
    
Don Gagne's avatar
Don Gagne committed
132 133 134
    bool dirty(void) { return _dirty; }
    void setDirty(bool dirty);
    
Don Gagne's avatar
Don Gagne committed
135
    QmlObjectListModel* childItems(void) { return &_childItems; }
136

137
    bool homePosition(void) { return _homePositionSpecialCase; }
138 139
    bool homePositionValid(void) { return _homePositionValid; }
    void setHomePositionValid(bool homePositionValid);
140 141 142

    double distance(void) { return _distance; }
    void setDistance(double distance);
Don Gagne's avatar
Don Gagne committed
143
    
Don Gagne's avatar
Don Gagne committed
144
    // C++ only methods
Don Gagne's avatar
Don Gagne committed
145 146 147
    
    /// Returns true if this item can be edited in the ui
    bool canEdit(void);
148

149 150 151
    double latitude(void)  const { return _latitudeFact->value().toDouble(); }
    double longitude(void) const { return _longitudeFact->value().toDouble(); }
    double altitude(void)  const { return _altitudeFact->value().toDouble(); }
Don Gagne's avatar
Don Gagne committed
152 153 154 155 156 157 158 159 160 161 162 163 164
    
    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
165
    bool autoContinue() const {
166
        return _autocontinue;
167
    }
Don Gagne's avatar
Don Gagne committed
168 169
    double loiterOrbitRadius() const {
        return _loiterOrbitRadiusFact->value().toDouble();
170
    }
Don Gagne's avatar
Don Gagne committed
171 172
    double acceptanceRadius() const {
        return param2();
173
    }
Don Gagne's avatar
Don Gagne committed
174 175
    double holdTime() const {
        return param1();
176
    }
Don Gagne's avatar
Don Gagne committed
177
    double param1() const {
Don Gagne's avatar
Don Gagne committed
178
        return _param1Fact->value().toDouble();
179
    }
Don Gagne's avatar
Don Gagne committed
180
    double param2() const {
Don Gagne's avatar
Don Gagne committed
181
        return _param2Fact->value().toDouble();
182
    }
Don Gagne's avatar
Don Gagne committed
183
    double param3() const {
Don Gagne's avatar
Don Gagne committed
184
        return loiterOrbitRadius();
185
    }
Don Gagne's avatar
Don Gagne committed
186
    double param4() const {
187
        return _yawRadians();
188
    }
Don Gagne's avatar
Don Gagne committed
189
    double param5() const {
Don Gagne's avatar
Don Gagne committed
190
        return latitude();
191
    }
Don Gagne's avatar
Don Gagne committed
192
    double param6() const {
Don Gagne's avatar
Don Gagne committed
193
        return longitude();
194
    }
Don Gagne's avatar
Don Gagne committed
195
    double param7() const {
Don Gagne's avatar
Don Gagne committed
196
        return altitude();
197
    }
198
    // MAV_FRAME
199 200
    int frame() const;
    
201
    // MAV_CMD
Don Gagne's avatar
Don Gagne committed
202 203
    int command() const {
        return _command;
204
    }
lm's avatar
lm committed
205 206
    /** @brief Returns true if x, y, z contain reasonable navigation data */
    bool isNavigationType();
207

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

211 212
    void save(QTextStream &saveStream);
    bool load(QTextStream &loadStream);
213
    
Don Gagne's avatar
Don Gagne committed
214
    void setHomePositionSpecialCase(bool homePositionSpecialCase) { _homePositionSpecialCase = homePositionSpecialCase; }
215

Don Gagne's avatar
Don Gagne committed
216 217
    bool relativeAltitude(void) { return _frame == MAV_FRAME_GLOBAL_RELATIVE_ALT; }

218 219 220 221 222 223 224
    static const double defaultPitch;
    static const double defaultHeading;
    static const double defaultAltitude;
    static const double defaultAcceptanceRadius;
    static const double defaultLoiterOrbitRadius;
    static const double defaultLoiterTurns;

Don Gagne's avatar
Don Gagne committed
225 226 227 228
signals:
    void sequenceNumberChanged(int sequenceNumber);
    void isCurrentItemChanged(bool isCurrentItem);
    void coordinateChanged(const QGeoCoordinate& coordinate);
229
    void headingDegreesChanged(double heading);
Don Gagne's avatar
Don Gagne committed
230
    void dirtyChanged(bool dirty);
231
    void homePositionValidChanged(bool homePostionValid);
232
    void distanceChanged(float distance);
Don Gagne's avatar
Don Gagne committed
233
    void frameChanged(int frame);
Don Gagne's avatar
Don Gagne committed
234 235 236 237
    void commandNameChanged(QString type);
    void commandChanged(MavlinkQmlSingleton::Qml_MAV_CMD command);
    void valueLabelsChanged(QStringList valueLabels);
    void valueStringsChanged(QStringList valueStrings);
Don Gagne's avatar
Don Gagne committed
238
    bool autoContinueChanged(bool autoContinue);
239
    
240
public:
241
    /** @brief Set the waypoint action */
242 243
    void setAction      (int _action);
    void setFrame       (int _frame);
pixhawk's avatar
pixhawk committed
244
    void setAutocontinue(bool autoContinue);
245
    void setCurrent     (bool _current);
Don Gagne's avatar
Don Gagne committed
246
    void setLoiterOrbitRadius (double radius);
247 248 249 250 251 252 253
    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);
254
    void setAcceptanceRadius(double radius);
255 256
    void setHoldTime    (int holdTime);
    void setHoldTime    (double holdTime);
lm's avatar
lm committed
257
    /** @brief Set waypoint as reached */
258
    void setReached     () { _reachedTime = QGC::groundTimeMilliseconds(); }
lm's avatar
lm committed
259
    /** @brief Wether this waypoint has been reached yet */
260 261
    bool isReached      () { return (_reachedTime > 0); }

Don Gagne's avatar
Don Gagne committed
262 263
private slots:
    void _factValueChanged(QVariant value);
264
    void _coordinateFactChanged(QVariant value);
265
    void _headingDegreesFactChanged(QVariant value);
Don Gagne's avatar
Don Gagne committed
266
    void _altitudeRelativeToHomeFactChanged(QVariant value);
267

268 269
private:
    QString _oneDecimalString(double value);
270 271
    void _connectSignals(void);
    void _setYawRadians(double yawRadians);
Don Gagne's avatar
Don Gagne committed
272 273 274 275 276 277 278

private:
    typedef struct {
        MAV_CMD     command;
        const char* name;
    } MavCmd2Name_t;
    
Don Gagne's avatar
Don Gagne committed
279 280 281 282 283 284
    int                                 _sequenceNumber;
    int                                 _frame;
    MavlinkQmlSingleton::Qml_MAV_CMD    _command;
    bool                                _autocontinue;
    bool                                _isCurrentItem;
    quint64                             _reachedTime;
285
    double                              _distance;
Don Gagne's avatar
Don Gagne committed
286
    
287 288 289
    Fact*           _latitudeFact;
    Fact*           _longitudeFact;
    Fact*           _altitudeFact;
290
    Fact*           _headingDegreesFact;
Don Gagne's avatar
Don Gagne committed
291
    Fact*           _loiterOrbitRadiusFact;
Don Gagne's avatar
Don Gagne committed
292 293
    Fact*           _param1Fact;
    Fact*           _param2Fact;
294
    Fact*           _altitudeRelativeToHomeFact;
Don Gagne's avatar
Don Gagne committed
295 296 297 298 299 300 301 302 303 304
    
    FactMetaData*   _pitchMetaData;
    FactMetaData*   _acceptanceRadiusMetaData;
    FactMetaData*   _holdTimeMetaData;
    FactMetaData*   _loiterTurnsMetaData;
    FactMetaData*   _loiterSecondsMetaData;
    FactMetaData*   _delaySecondsMetaData;
    FactMetaData*   _jumpSequenceMetaData;
    FactMetaData*   _jumpRepeatMetaData;
    
Don Gagne's avatar
Don Gagne committed
305 306
    bool _dirty;
    
Don Gagne's avatar
Don Gagne committed
307
    bool _homePositionSpecialCase;  ///< true: this item is being used as a ui home position indicator
308
    bool _homePositionValid;        ///< true: home psition should be displayed
Don Gagne's avatar
Don Gagne committed
309 310 311 312
    
    /// This is used to reference any subsequent mission items which do not specify a coordinate.
    QmlObjectListModel  _childItems;
    
Don Gagne's avatar
Don Gagne committed
313 314
    static const int            _cMavCmd2Name = 9;
    static const MavCmd2Name_t  _rgMavCmd2Name[_cMavCmd2Name];
pixhawk's avatar
pixhawk committed
315 316
};

317 318 319
QDebug operator<<(QDebug dbg, const MissionItem& missionItem);
QDebug operator<<(QDebug dbg, const MissionItem* missionItem);

320
#endif