Waypoint.h 6.08 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 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62
    Waypoint(
        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
63 64
    ~Waypoint();

65 66 67 68 69 70 71 72 73 74 75 76
    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; }

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

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

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

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


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

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

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

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

pixhawk's avatar
pixhawk committed
230 231
};

232 233
QML_DECLARE_TYPE(Waypoint)

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