MockLink.h 8.76 KB
Newer Older
1
/*=====================================================================
2

3
 QGroundControl Open Source Ground Control Station
4

5
 (c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
6

7
 This file is part of the QGROUNDCONTROL project
8

9 10 11 12
 QGROUNDCONTROL 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.
13

14 15 16 17
 QGROUNDCONTROL 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.
18

19 20
 You should have received a copy of the GNU General Public License
 along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
21

22 23 24 25 26 27
 ======================================================================*/

#ifndef MOCKLINK_H
#define MOCKLINK_H

#include <QMap>
28
#include <QLoggingCategory>
29 30

#include "MockLinkMissionItemHandler.h"
31
#include "MockLinkFileServer.h"
32
#include "LinkManager.h"
33 34 35
#include "QGCMAVLink.h"

Q_DECLARE_LOGGING_CATEGORY(MockLinkLog)
Don Gagne's avatar
Don Gagne committed
36
Q_DECLARE_LOGGING_CATEGORY(MockLinkVerboseLog)
37

38 39
class MockConfiguration : public LinkConfiguration
{
Don Gagne's avatar
Don Gagne committed
40 41
    Q_OBJECT

42
public:
43 44 45 46 47 48 49 50 51 52 53

    Q_PROPERTY(int      firmware    READ firmware           WRITE setFirmware       NOTIFY firmwareChanged)
    Q_PROPERTY(int      vehicle     READ vehicle            WRITE setVehicle        NOTIFY vehicleChanged)
    Q_PROPERTY(bool     sendStatus  READ sendStatusText     WRITE setSendStatusText NOTIFY sendStatusChanged)

    // QML Access
    int     firmware        () { return (int)_firmwareType; }
    void    setFirmware     (int type) { _firmwareType = (MAV_AUTOPILOT)type; emit firmwareChanged(); }
    int     vehicle         () { return (int)_vehicleType; }
    void    setVehicle      (int type) { _vehicleType = (MAV_TYPE)type; emit vehicleChanged(); }

54 55 56 57
    MockConfiguration(const QString& name);
    MockConfiguration(MockConfiguration* source);

    MAV_AUTOPILOT firmwareType(void) { return _firmwareType; }
58
    void setFirmwareType(MAV_AUTOPILOT firmwareType) { _firmwareType = firmwareType; emit firmwareChanged(); }
59

60
    MAV_TYPE vehicleType(void) { return _vehicleType; }
61
    void setVehicleType(MAV_TYPE vehicleType) { _vehicleType = vehicleType; emit vehicleChanged(); }
62

63 64
    /// @param sendStatusText true: mavlink status text messages will be sent for each severity, as well as voice output info message
    bool sendStatusText(void) { return _sendStatusText; }
65
    void setSendStatusText(bool sendStatusText) { _sendStatusText = sendStatusText; emit sendStatusChanged(); }
66

67
    // Overrides from LinkConfiguration
68 69 70 71 72 73 74 75 76 77 78
    LinkType    type            (void) { return LinkConfiguration::TypeMock; }
    void        copyFrom        (LinkConfiguration* source);
    void        loadSettings    (QSettings& settings, const QString& root);
    void        saveSettings    (QSettings& settings, const QString& root);
    void        updateSettings  (void);
    QString     settingsURL     () { return "MockLinkSettings.qml"; }

signals:
    void firmwareChanged    ();
    void vehicleChanged     ();
    void sendStatusChanged  ();
79 80

private:
81
    MAV_AUTOPILOT   _firmwareType;
82
    MAV_TYPE        _vehicleType;
83
    bool            _sendStatusText;
84

85
    static const char* _firmwareTypeKey;
86
    static const char* _vehicleTypeKey;
87
    static const char* _sendStatusTextKey;
88 89
};

90 91 92
class MockLink : public LinkInterface
{
    Q_OBJECT
93

94
public:
95 96
    // LinkConfiguration is optional for MockLink
    MockLink(MockConfiguration* config = NULL);
97
    ~MockLink(void);
98

99
    // MockLink methods
Don Gagne's avatar
Don Gagne committed
100
    int vehicleId(void) { return _vehicleSystemId; }
Don Gagne's avatar
Don Gagne committed
101 102
    MAV_AUTOPILOT getFirmwareType(void) { return _firmwareType; }
    void setFirmwareType(MAV_AUTOPILOT autopilot) { _firmwareType = autopilot; }
103
    void setSendStatusText(bool sendStatusText) { _sendStatusText = sendStatusText; }
Don Gagne's avatar
Don Gagne committed
104 105 106 107 108 109 110

    /// APM stack has strange handling of the first item of the mission list. If it has no
    /// onboard mission items, sometimes it sends back a home position in position 0 and
    /// sometimes it doesn't. Don't ask. This option allows you to configure that behavior
    /// for unit testing.
    void setAPMMissionResponseMode(bool sendHomePositionOnEmptyList) { _apmSendHomePositionOnEmptyList = sendHomePositionOnEmptyList; }

111
    void emitRemoteControlChannelRawChanged(int channel, uint16_t raw);
112

113 114
    /// Sends the specified mavlink message to QGC
    void respondWithMavlinkMessage(const mavlink_message_t& msg);
115

116
    MockLinkFileServer* getFileServer(void) { return _fileServer; }
117

Don Gagne's avatar
Don Gagne committed
118 119 120 121 122 123 124
    // Virtuals from LinkInterface
    virtual QString getName(void) const { return _name; }
    virtual void requestReset(void){ }
    virtual bool isConnected(void) const { return _connected; }
    virtual qint64 getConnectionSpeed(void) const { return 100000000; }
    virtual qint64 bytesAvailable(void) { return 0; }

125 126 127 128
    // These are left unimplemented in order to cause linker errors which indicate incorrect usage of
    // connect/disconnect on link directly. All connect/disconnect calls should be made through LinkManager.
    bool connect(void);
    bool disconnect(void);
129 130

    LinkConfiguration* getLinkConfiguration() { return _config; }
131

132 133
    /// Sets a failure mode for unit testing
    ///     @param failureMode Type of failure to simulate
134
    void setMissionItemFailureMode(MockLinkMissionItemHandler::FailureMode_t failureMode);
135

136 137
    /// Called to send a MISSION_ACK message while the MissionManager is in idle state
    void sendUnexpectedMissionAck(MAV_MISSION_RESULT ackType) { _missionItemHandler.sendUnexpectedMissionAck(ackType); }
138

139 140
    /// Called to send a MISSION_ITEM message while the MissionManager is in idle state
    void sendUnexpectedMissionItem(void) { _missionItemHandler.sendUnexpectedMissionItem(); }
141

142 143
    /// Called to send a MISSION_REQUEST message while the MissionManager is in idle state
    void sendUnexpectedMissionRequest(void) { _missionItemHandler.sendUnexpectedMissionRequest(); }
144

145 146
    /// Reset the state of the MissionItemHandler to no items, no transactions in progress.
    void resetMissionItemHandler(void) { _missionItemHandler.reset(); }
147

148 149 150 151 152
    static MockLink* startPX4MockLink            (bool sendStatusText);
    static MockLink* startGenericMockLink        (bool sendStatusText);
    static MockLink* startAPMArduCopterMockLink  (bool sendStatusText);
    static MockLink* startAPMArduPlaneMockLink   (bool sendStatusText);

153 154 155
signals:
    /// @brief Used internally to move data to the thread.
    void _incomingBytes(const QByteArray bytes);
156

157 158
public slots:
    virtual void writeBytes(const char *bytes, qint64 cBytes);
159

160 161 162 163
private slots:
    void _run1HzTasks(void);
    void _run10HzTasks(void);
    void _run50HzTasks(void);
164

165
private:
166 167
    // From LinkInterface
    virtual bool _connect(void);
Don Gagne's avatar
Don Gagne committed
168
    virtual void _disconnect(void);
169

170 171
    // QThread override
    virtual void run(void);
172

173 174 175 176 177 178 179 180 181 182 183
    // MockLink methods
    void _sendHeartBeat(void);
    void _handleIncomingBytes(const QByteArray bytes);
    void _handleIncomingNSHBytes(const char* bytes, int cBytes);
    void _handleIncomingMavlinkBytes(const uint8_t* bytes, int cBytes);
    void _loadParams(void);
    void _handleHeartBeat(const mavlink_message_t& msg);
    void _handleSetMode(const mavlink_message_t& msg);
    void _handleParamRequestList(const mavlink_message_t& msg);
    void _handleParamSet(const mavlink_message_t& msg);
    void _handleParamRequestRead(const mavlink_message_t& msg);
184
    void _handleFTP(const mavlink_message_t& msg);
185
    void _handleCommandLong(const mavlink_message_t& msg);
Don Gagne's avatar
Don Gagne committed
186
    void _handleManualControl(const mavlink_message_t& msg);
187 188
    float _floatUnionForParam(int componentId, const QString& paramName);
    void _setParamFloatUnionIntoMap(int componentId, const QString& paramName, float paramFloat);
189
    void _sendHomePosition(void);
Don Gagne's avatar
Don Gagne committed
190
    void _sendGpsRawInt(void);
Don Gagne's avatar
Don Gagne committed
191
    void _sendVibration(void);
192
    void _sendStatusTextMessages(void);
193

194 195
    static MockLink* _startMockLink(MockConfiguration* mockConfig);

196
    MockLinkMissionItemHandler  _missionItemHandler;
197

198 199
    QString _name;
    bool    _connected;
200

201 202
    uint8_t _vehicleSystemId;
    uint8_t _vehicleComponentId;
203

204 205
    bool    _inNSH;
    bool    _mavlinkStarted;
206

207 208
    QMap<int, QMap<QString, QVariant> > _mapParamName2Value;
    QMap<QString, MAV_PARAM_TYPE>       _mapParamName2MavParamType;
209

210 211 212
    uint8_t     _mavBaseMode;
    uint32_t    _mavCustomMode;
    uint8_t     _mavState;
213

214 215 216
    MockConfiguration*  _config;
    MAV_AUTOPILOT       _firmwareType;
    MAV_TYPE            _vehicleType;
217

218
    MockLinkFileServer* _fileServer;
Don Gagne's avatar
Don Gagne committed
219

220
    bool _sendStatusText;
Don Gagne's avatar
Don Gagne committed
221
    bool _apmSendHomePositionOnEmptyList;
222

223 224
    int _sendHomePositionDelayCount;

Don Gagne's avatar
Don Gagne committed
225 226 227
    static float _vehicleLatitude;
    static float _vehicleLongitude;
    static float _vehicleAltitude;
228 229 230
};

#endif