Waypoint.h 6.1 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 23 24 25 26 27 28
/*=====================================================================

PIXHAWK Micro Air Vehicle Flying Robotics Toolkit

(c) 2009 PIXHAWK PROJECT  <http://pixhawk.ethz.ch>

This file is part of the PIXHAWK project

    PIXHAWK 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.

    PIXHAWK 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 PIXHAWK. If not, see <http://www.gnu.org/licenses/>.

======================================================================*/

/**
 * @file
 *   @brief Waypoint class
 *
 *   @author Benjamin Knecht <mavteam@student.ethz.ch>
29
 *   @author Petri Tanskanen <mavteam@student.ethz.ch>
pixhawk's avatar
pixhawk committed
30 31 32 33 34 35 36 37
 *
 */

#ifndef WAYPOINT_H
#define WAYPOINT_H

#include <QObject>
#include <QString>
38
#include <QtQml>
39
#include <QTextStream>
lm's avatar
lm committed
40
#include "QGCMAVLink.h"
lm's avatar
lm committed
41
#include "QGC.h"
pixhawk's avatar
pixhawk committed
42 43 44 45 46

class Waypoint : public QObject
{
    Q_OBJECT
public:
47
    Waypoint(
Gus Grubba's avatar
Gus Grubba committed
48
        QObject *parent = 0,
49 50 51 52 53 54 55 56 57 58 59 60 61 62 63
        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(""));

    Waypoint(const Waypoint& other);
pixhawk's avatar
pixhawk committed
64 65
    ~Waypoint();

66 67 68 69 70 71 72 73 74 75 76 77
    const Waypoint& operator=(const Waypoint& other);

    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)

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

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

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

159 160 161
    /** @brief Get the time this waypoint was reached */
    quint64 getReachedTime() const { return _reachedTime; }

162 163 164 165
    void save(QTextStream &saveStream);
    bool load(QTextStream &loadStream);


166
protected:
167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191
    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
192
    /** @brief Yaw angle in COMPASS DEGREES: 0-360 */
193
    void setYaw         (int _yaw);
lm's avatar
lm committed
194
    /** @brief Yaw angle in COMPASS DEGREES: 0-360 */
195
    void setYaw         (double _yaw);
196
    /** @brief Set the waypoint action */
197 198
    void setAction      (int _action);
    void setFrame       (int _frame);
pixhawk's avatar
pixhawk committed
199
    void setAutocontinue(bool autoContinue);
200 201 202 203 204 205 206 207 208
    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);
209
    void setAcceptanceRadius(double radius);
210 211
    void setHoldTime    (int holdTime);
    void setHoldTime    (double holdTime);
212
    /** @brief Number of turns for loiter waypoints */
213
    void setTurns       (int _turns);
lm's avatar
lm committed
214
    /** @brief Set waypoint as reached */
215
    void setReached     () { _reachedTime = QGC::groundTimeMilliseconds(); }
lm's avatar
lm committed
216
    /** @brief Wether this waypoint has been reached yet */
217 218
    bool isReached      () { return (_reachedTime > 0); }

219 220 221
    void setChanged() {
        emit changed(this);
    }
222 223 224

signals:
    /** @brief Announces a change to the waypoint data */
225 226 227 228 229 230
    void changed(Waypoint* wp);

    void latitudeChanged    ();
    void longitudeChanged   ();
    void altitudeChanged    ();

pixhawk's avatar
pixhawk committed
231 232
};

233 234
QML_DECLARE_TYPE(Waypoint)

pixhawk's avatar
pixhawk committed
235
#endif // WAYPOINT_H