Waypoint.h 5.11 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 <QTextStream>
lm's avatar
lm committed
39
#include "QGCMAVLink.h"
lm's avatar
lm committed
40
#include "QGC.h"
pixhawk's avatar
pixhawk committed
41 42 43 44

class Waypoint : public QObject
{
    Q_OBJECT
45

pixhawk's avatar
pixhawk committed
46
public:
lm's avatar
lm committed
47
    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,
48
             bool autocontinue = true, bool current = false, MAV_FRAME frame=MAV_FRAME_GLOBAL, MAV_CMD action=MAV_CMD_NAV_WAYPOINT, const QString& description=QString(""));
pixhawk's avatar
pixhawk committed
49 50
    ~Waypoint();

51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122
    quint16 getId() const {
        return id;
    }
    double getX() const {
        return x;
    }
    double getY() const {
        return y;
    }
    double getZ() const {
        return z;
    }
    double getLatitude() const {
        return x;
    }
    double getLongitude() const {
        return y;
    }
    double getAltitude() const {
        return z;
    }
    double getYaw() const {
        return yaw;
    }
    bool getAutoContinue() const {
        return autocontinue;
    }
    bool getCurrent() const {
        return current;
    }
    double getLoiterOrbit() const {
        return orbit;
    }
    double getAcceptanceRadius() const {
        return param2;
    }
    double getHoldTime() const {
        return param1;
    }
    double getParam1() const {
        return param1;
    }
    double getParam2() const {
        return param2;
    }
    double getParam3() const {
        return orbit;
    }
    double getParam4() const {
        return yaw;
    }
    double getParam5() const {
        return x;
    }
    double getParam6() const {
        return y;
    }
    double getParam7() const {
        return z;
    }
    int getTurns() const {
        return param1;
    }
    MAV_FRAME getFrame() const {
        return frame;
    }
    MAV_CMD getAction() const {
        return action;
    }
    const QString& getName() const {
        return name;
    }
123 124 125
    const QString& getDescription() const {
        return description;
    }
126

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

130 131 132 133
    void save(QTextStream &saveStream);
    bool load(QTextStream &loadStream);


134
protected:
135
    quint16 id;
pixhawk's avatar
pixhawk committed
136 137 138 139
    double x;
    double y;
    double z;
    double yaw;
140
    MAV_FRAME frame;
141
    MAV_CMD action;
pixhawk's avatar
pixhawk committed
142 143
    bool autocontinue;
    bool current;
pixhawk's avatar
pixhawk committed
144
    double orbit;
145 146 147
    double param1;
    double param2;
    int turns;
148
    QString name;
149
    QString description;
lm's avatar
lm committed
150
    quint64 reachedTime;
pixhawk's avatar
pixhawk committed
151 152

public slots:
153
    void setId(quint16 id);
pixhawk's avatar
pixhawk committed
154 155 156
    void setX(double x);
    void setY(double y);
    void setZ(double z);
157 158 159
    void setLatitude(double lat);
    void setLongitude(double lon);
    void setAltitude(double alt);
lm's avatar
lm committed
160 161 162
    /** @brief Yaw angle in COMPASS DEGREES: 0-360 */
    void setYaw(int yaw);
    /** @brief Yaw angle in COMPASS DEGREES: 0-360 */
pixhawk's avatar
pixhawk committed
163
    void setYaw(double yaw);
164 165
    /** @brief Set the waypoint action */
    void setAction(int action);
166
    void setAction(MAV_CMD action);
167
    void setFrame(MAV_FRAME frame);
pixhawk's avatar
pixhawk committed
168 169
    void setAutocontinue(bool autoContinue);
    void setCurrent(bool current);
170 171 172 173 174
    void setLoiterOrbit(double orbit);
    void setParam1(double param1);
    void setParam2(double param2);
    void setParam3(double param3);
    void setParam4(double param4);
175 176
    void setParam5(double param5);
    void setParam6(double param6);
lm's avatar
lm committed
177
    void setParam7(double param7);
178
    void setAcceptanceRadius(double radius);
pixhawk's avatar
pixhawk committed
179
    void setHoldTime(int holdTime);
lm's avatar
lm committed
180
    void setHoldTime(double holdTime);
181 182
    /** @brief Number of turns for loiter waypoints */
    void setTurns(int turns);
lm's avatar
lm committed
183 184 185 186 187 188
    /** @brief Set waypoint as reached */
    void setReached() { reachedTime = QGC::groundTimeMilliseconds(); }
    /** @brief Wether this waypoint has been reached yet */
    bool isReached() { return (reachedTime > 0); }
    /** @brief Get the time this waypoint was reached */
    quint64 getReachedTime() { return reachedTime; }
189 190 191
    void setChanged() {
        emit changed(this);
    }
192 193 194

signals:
    /** @brief Announces a change to the waypoint data */
195
    void changed(Waypoint* wp);    
pixhawk's avatar
pixhawk committed
196 197 198
};

#endif // WAYPOINT_H