UASWaypointManager.h 12.1 KB
Newer Older
pixhawk's avatar
pixhawk committed
1 2
/*=====================================================================

3
QGroundControl Open Source Ground Control Station
pixhawk's avatar
pixhawk committed
4

5
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
pixhawk's avatar
pixhawk committed
6

7
This file is part of the QGROUNDCONTROL project
pixhawk's avatar
pixhawk committed
8

9
    QGROUNDCONTROL is free software: you can redistribute it and/or modify
pixhawk's avatar
pixhawk committed
10 11 12 13
    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.

14
    QGROUNDCONTROL is distributed in the hope that it will be useful,
pixhawk's avatar
pixhawk committed
15 16 17 18 19
    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
20
    along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
pixhawk's avatar
pixhawk committed
21 22 23 24 25 26 27 28 29 30 31

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

/**
 * @file
 *   @brief Definition of the waypoint protocol handler
 *
 *   @author Petri Tanskanen <mavteam@student.ethz.ch>
 *
 */

32 33 34 35
#ifndef UASWAYPOINTMANAGER_H
#define UASWAYPOINTMANAGER_H

#include <QObject>
36
#include <QList>
pixhawk's avatar
pixhawk committed
37
#include <QTimer>
38
#include <QPointer>
39
#include "MissionItem.h"
pixhawk's avatar
pixhawk committed
40
#include "QGCMAVLink.h"
41

42
class UAS;
43
class UASInterface;
44
class Vehicle;
45

46 47 48 49
/**
 * @brief Implementation of the MAVLINK waypoint protocol
 *
 * This class handles the communication with a waypoint manager on the MAV.
50
 * All waypoints are stored in the QList waypoints, modifications can be done with the WaypointList widget.
51 52 53 54
 * Notice that currently the access to the internal waypoint storage is not guarded nor thread-safe. This works as long as no other widget alters the data.
 *
 * See http://qgroundcontrol.org/waypoint_protocol for more information about the protocol and the states.
 */
55 56
class UASWaypointManager : public QObject
{
57
    Q_OBJECT
58 59
private:
    enum WaypointState {
60 61 62
        WP_IDLE = 0,        ///< Waiting for commands
        WP_SENDLIST,        ///< Initial state for sending waypoints to the MAV
        WP_SENDLIST_SENDWPS,///< Sending waypoints
63
        WP_GETLIST,         ///< Initial state for retrieving waypoints from the MAV
64
        WP_GETLIST_GETWPS,  ///< Receiving waypoints
65 66
        WP_CLEARLIST,       ///< Clearing waypoint list on the MAV
        WP_SETCURRENT       ///< Setting new current waypoint on the MAV
67 68 69
    }; ///< The possible states for the waypoint protocol

public:
70
    UASWaypointManager(Vehicle* vehicle, UAS* uas);   ///< Standard constructor
LM's avatar
LM committed
71
    ~UASWaypointManager();
72
    bool guidedModeSupported();
73

74
    void goToWaypoint(MissionItem *wp);
pixhawk's avatar
pixhawk committed
75
    /** @name Received message handlers */
76 77
    /*@{*/
    void handleWaypointCount(quint8 systemId, quint8 compId, quint16 count);                            ///< Handles received waypoint count messages
lm's avatar
lm committed
78 79 80 81 82
    void handleWaypoint(quint8 systemId, quint8 compId, mavlink_mission_item_t *wp);                        ///< Handles received waypoint messages
    void handleWaypointAck(quint8 systemId, quint8 compId, mavlink_mission_ack_t *wpa);                ///< Handles received waypoint ack messages
    void handleWaypointRequest(quint8 systemId, quint8 compId, mavlink_mission_request_t *wpr);        ///< Handles received waypoint request messages
    void handleWaypointReached(quint8 systemId, quint8 compId, mavlink_mission_item_reached_t *wpr);        ///< Handles received waypoint reached messages
    void handleWaypointCurrent(quint8 systemId, quint8 compId, mavlink_mission_current_t *wpc);        ///< Handles received set current waypoint messages
83
    /*@}*/
84

85 86 87
    /** @name Remote operations */
    /*@{*/
    void clearWaypointList();                       ///< Sends the waypoint clear all message to the MAV
pixhawk's avatar
pixhawk committed
88 89

    void readWaypoints(bool read_to_edit=false);    ///< Requests the MAV's current waypoint list.
90
    void writeWaypoints();                          ///< Sends the waypoint list to the MAV
91 92
    int setCurrentWaypoint(quint16 seq);            ///< Sends the sequence number of the waypoint that should get the new target waypoint to the UAS
    int setCurrentEditable(quint16 seq);          ///< Changes the current waypoint in edit tab
93 94
    /*@}*/

95
    /** @name MissionItem list operations */
96
    /*@{*/
97
    const QList<MissionItem *> &getWaypointEditableList(void) {
pixhawk's avatar
pixhawk committed
98 99
        return waypointsEditable;    ///< Returns a const reference to the waypoint list.
    }
100
    const QList<MissionItem *> &getWaypointViewOnlyList(void) {
pixhawk's avatar
pixhawk committed
101
        return waypointsViewOnly;    ///< Returns a const reference to the waypoint list.
102
    }
103 104 105 106 107 108 109 110 111
    const QList<MissionItem *> getGlobalFrameWaypointList();  ///< Returns a global waypoint list
    const QList<MissionItem *> getGlobalFrameAndNavTypeWaypointList(); ///< Returns a global waypoint list containing only waypoints suitable for navigation. Actions and other mission items are filtered out.
    const QList<MissionItem *> getNavTypeWaypointList(); ///< Returns a waypoint list containing only waypoints suitable for navigation. Actions and other mission items are filtered out.
    int getIndexOf(MissionItem* wp);                   ///< Get the index of a waypoint in the list
    int getGlobalFrameIndexOf(MissionItem* wp);    ///< Get the index of a waypoint in the list, counting only global waypoints
    int getGlobalFrameAndNavTypeIndexOf(MissionItem* wp); ///< Get the index of a waypoint in the list, counting only global AND navigation mode waypoints
    int getNavTypeIndexOf(MissionItem* wp); ///< Get the index of a waypoint in the list, counting only navigation mode waypoints
    int getLocalFrameIndexOf(MissionItem* wp);     ///< Get the index of a waypoint in the list, counting only local waypoints
    int getMissionFrameIndexOf(MissionItem* wp);   ///< Get the index of a waypoint in the list, counting only mission waypoints
112
    int getGlobalFrameCount(); ///< Get the count of global waypoints in the list
lm's avatar
lm committed
113
    int getGlobalFrameAndNavTypeCount(); ///< Get the count of global waypoints in navigation mode in the list
LM's avatar
LM committed
114
    int getNavTypeCount(); ///< Get the count of global waypoints in navigation mode in the list
115
    int getLocalFrameCount();   ///< Get the count of local waypoints in the list
116
    /*@}*/
117

118 119 120 121 122
    UAS* getUAS();
    float getAltitudeRecommendation();
    int getFrameRecommendation();
    float getAcceptanceRadiusRecommendation();
    float getHomeAltitudeOffsetDefault();
123

124
private:
pixhawk's avatar
pixhawk committed
125 126
    /** @name Message send functions */
    /*@{*/
127 128 129 130
    void sendWaypointClearAll();
    void sendWaypointSetCurrent(quint16 seq);
    void sendWaypointCount();
    void sendWaypointRequestList();
131 132 133
    void sendWaypointRequest(quint16 seq);          ///< Requests a waypoint with sequence number seq
    void sendWaypoint(quint16 seq);                 ///< Sends a waypoint with sequence number seq
    void sendWaypointAck(quint8 type);              ///< Sends a waypoint ack
pixhawk's avatar
pixhawk committed
134
    /*@}*/
135 136

public slots:
137
    void timeout();                                 ///< Called by the timer if a response times out. Handles send retries.
138
    /** @name MissionItem list operations */
139
    /*@{*/
140 141 142
    void addWaypointEditable(MissionItem *wp, bool enforceFirstActive=true);                 ///< adds a new waypoint to the end of the editable list and changes its sequence number accordingly
    void addWaypointViewOnly(MissionItem *wp);                                               ///< adds a new waypoint to the end of the view-only list and changes its sequence number accordingly
    MissionItem* createWaypoint(bool enforceFirstActive=true);     ///< Creates a waypoint
143 144 145 146
    int removeWaypoint(quint16 seq);                       ///< locally remove the specified waypoint from the storage
    void moveWaypoint(quint16 cur_seq, quint16 new_seq);   ///< locally move a waypoint from its current position cur_seq to a new position new_seq
    void saveWaypoints(const QString &saveFile);           ///< saves the local waypoint list to saveFile
    void loadWaypoints(const QString &loadFile);           ///< loads a waypoint list from loadFile
147 148
    void notifyOfChangeEditable(MissionItem* wp);             ///< Notifies manager to changes to an editable waypoint
    void notifyOfChangeViewOnly(MissionItem* wp);             ///< Notifies manager to changes to a viewonly waypoint, e.g. some widget wants to change "current"
149
    /*@}*/
150
    void handleLocalPositionChanged(UASInterface* mav, double x, double y, double z, quint64 time);
151
    void handleGlobalPositionChanged(UASInterface* mav, double lat, double lon, double altAMSL, double altWGS84, quint64 time);
152

pixhawk's avatar
pixhawk committed
153
signals:
154 155
    void waypointEditableListChanged(void);                 ///< emits signal that the list of editable waypoints has been changed
    void waypointEditableListChanged(int uasid);            ///< emits signal that the list of editable waypoints has been changed
156
    void waypointEditableChanged(int uasid, MissionItem* wp);  ///< emits signal that a single editable waypoint has been changed
pixhawk's avatar
pixhawk committed
157 158
    void waypointViewOnlyListChanged(void);                 ///< emits signal that the list of editable waypoints has been changed
    void waypointViewOnlyListChanged(int uasid);            ///< emits signal that the list of editable waypoints has been changed
159
    void waypointViewOnlyChanged(int uasid, MissionItem* wp);  ///< emits signal that a single editable waypoint has been changed
160 161
    void currentWaypointChanged(quint16);           ///< emits the new current waypoint sequence number
    void updateStatusString(const QString &);       ///< emits the current status string
162
    void waypointDistanceChanged(double distance);   ///< Distance to next waypoint changed (in meters)
pixhawk's avatar
pixhawk committed
163

164 165
    void loadWPFile();                              ///< emits signal that a file wp has been load
    void readGlobalWPFromUAS(bool value);           ///< emits signal when finish to read Global WP from UAS
166 167 168 169 170 171 172
    
    void _startProtocolTimer(void);                 ///< emits signal to start protocol timer
    void _stopProtocolTimer(void);                 ///< emits signal to stop protocol timer
    
private slots:
    void _startProtocolTimerOnThisThread(void);                 ///< Starts the protocol timer
    void _stopProtocolTimerOnThisThread(void);                 ///< Starts the protocol timer
173
    void _updateWPonTimer(void);                               ///< Starts requesting WP on timer timeout
174

175
private:
176
    Vehicle* _vehicle;
177
    quint32 current_retries;                        ///< The current number of retries left
178 179 180 181 182
    quint16 current_wp_id;                          ///< The last used waypoint ID in the current protocol transaction
    quint16 current_count;                          ///< The number of waypoints in the current protocol transaction
    WaypointState current_state;                    ///< The current protocol state
    quint8 current_partner_systemid;                ///< The current protocol communication target system
    quint8 current_partner_compid;                  ///< The current protocol communication target component
pixhawk's avatar
pixhawk committed
183
    bool read_to_edit;                              ///< If true, after readWaypoints() incoming waypoints will be copied both to "edit"-tab and "view"-tab. Otherwise, only to "view"-tab.
184

185 186 187
    QList<MissionItem *> waypointsViewOnly;                  ///< local copy of current waypoint list on MAV
    QList<MissionItem *> waypointsEditable;                  ///< local editable waypoint list
    QPointer<MissionItem> currentWaypointEditable;                      ///< The currently used waypoint
188
    QList<mavlink_mission_item_t *> waypoint_buffer;  ///< buffer for waypoints during communication
pixhawk's avatar
pixhawk committed
189
    QTimer protocol_timer;                          ///< Timer to catch timeouts
190
    QTimer _updateWPlist_timer;                     ///< update WP list if modified by another instance onboard
191
    bool standalone;                                ///< If standalone is set, do not write to UAS
192
    int uasid;                                   ///< The ID of the current UAS. Retrieved via `uas->getUASID();`, stored as an `int` to match its return type.
193 194

    // XXX export to settings
195
    static const float defaultAltitudeHomeOffset;    ///< Altitude offset in meters from home for new waypoints
196 197
    
    QString _offlineEditingModeMessage;
198 199 200
};

#endif // UASWAYPOINTMANAGER_H