Waypoint.h 4.16 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"
pixhawk's avatar
pixhawk committed
40 41 42 43

class Waypoint : public QObject
{
    Q_OBJECT
44

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

50
    quint16 getId() const { return id; }
pixhawk's avatar
pixhawk committed
51 52 53
    double getX() const { return x; }
    double getY() const { return y; }
    double getZ() const { return z; }
54 55 56
    double getLatitude() const { return x; }
    double getLongitude() const { return y; }
    double getAltitude() const { return z; }
pixhawk's avatar
pixhawk committed
57
    double getYaw() const { return yaw; }
58 59
    bool getAutoContinue() const { return autocontinue; }
    bool getCurrent() const { return current; }
60
    double getLoiterOrbit() const { return orbit; }
61 62
    double getAcceptanceRadius() const { return param2; }
    double getHoldTime() const { return param1; }
63 64
    double getParam1() const { return param1; }
    double getParam2() const { return param2; }
65
    double getParam3() const { return orbit; }
lm's avatar
lm committed
66 67 68 69
    double getParam4() const { return yaw; }
    double getParam5() const { return x; }
    double getParam6() const { return y; }
    double getParam7() const { return z; }
70
    int getTurns() const { return param1; }
71
    MAV_FRAME getFrame() const { return frame; }
72
    MAV_CMD getAction() const { return action; }
73
    const QString& getName() const { return name; }
74

75 76 77 78
    void save(QTextStream &saveStream);
    bool load(QTextStream &loadStream);


79
protected:
80
    quint16 id;
pixhawk's avatar
pixhawk committed
81 82 83 84
    double x;
    double y;
    double z;
    double yaw;
85
    MAV_FRAME frame;
86
    MAV_CMD action;
pixhawk's avatar
pixhawk committed
87 88
    bool autocontinue;
    bool current;
pixhawk's avatar
pixhawk committed
89
    double orbit;
90 91 92
    double param1;
    double param2;
    int turns;
93
    QString name;
pixhawk's avatar
pixhawk committed
94 95

public slots:
96
    void setId(quint16 id);
pixhawk's avatar
pixhawk committed
97 98 99
    void setX(double x);
    void setY(double y);
    void setZ(double z);
100 101 102
    void setLatitude(double lat);
    void setLongitude(double lon);
    void setAltitude(double alt);
lm's avatar
lm committed
103 104 105
    /** @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
106
    void setYaw(double yaw);
107 108
    /** @brief Set the waypoint action */
    void setAction(int action);
109
    void setAction(MAV_CMD action);
110
    void setFrame(MAV_FRAME frame);
pixhawk's avatar
pixhawk committed
111 112
    void setAutocontinue(bool autoContinue);
    void setCurrent(bool current);
113 114 115 116 117
    void setLoiterOrbit(double orbit);
    void setParam1(double param1);
    void setParam2(double param2);
    void setParam3(double param3);
    void setParam4(double param4);
118 119
    void setParam5(double param5);
    void setParam6(double param6);
lm's avatar
lm committed
120
    void setParam7(double param7);
121
    void setAcceptanceRadius(double radius);
pixhawk's avatar
pixhawk committed
122
    void setHoldTime(int holdTime);
lm's avatar
lm committed
123
    void setHoldTime(double holdTime);
124 125
    /** @brief Number of turns for loiter waypoints */
    void setTurns(int turns);
126 127 128 129

signals:
    /** @brief Announces a change to the waypoint data */
    void changed(Waypoint* wp);
pixhawk's avatar
pixhawk committed
130 131 132
};

#endif // WAYPOINT_H