MockLink.h 10.8 KB
Newer Older
1 2 3 4 5 6 7 8
/****************************************************************************
 *
 *   (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/
9

10 11 12 13 14

#ifndef MOCKLINK_H
#define MOCKLINK_H

#include <QMap>
15
#include <QLoggingCategory>
16
#include <QGeoCoordinate>
17 18

#include "MockLinkMissionItemHandler.h"
19
#include "MockLinkFileServer.h"
20
#include "LinkManager.h"
21 22 23
#include "QGCMAVLink.h"

Q_DECLARE_LOGGING_CATEGORY(MockLinkLog)
Don Gagne's avatar
Don Gagne committed
24
Q_DECLARE_LOGGING_CATEGORY(MockLinkVerboseLog)
25

26 27
class MockConfiguration : public LinkConfiguration
{
Don Gagne's avatar
Don Gagne committed
28 29
    Q_OBJECT

30
public:
31 32 33 34 35 36 37 38 39 40 41

    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(); }

42 43 44 45
    MockConfiguration(const QString& name);
    MockConfiguration(MockConfiguration* source);

    MAV_AUTOPILOT firmwareType(void) { return _firmwareType; }
46
    void setFirmwareType(MAV_AUTOPILOT firmwareType) { _firmwareType = firmwareType; emit firmwareChanged(); }
47

48
    MAV_TYPE vehicleType(void) { return _vehicleType; }
49
    void setVehicleType(MAV_TYPE vehicleType) { _vehicleType = vehicleType; emit vehicleChanged(); }
50

51 52
    /// @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; }
53
    void setSendStatusText(bool sendStatusText) { _sendStatusText = sendStatusText; emit sendStatusChanged(); }
54

Don Gagne's avatar
Don Gagne committed
55 56 57 58 59 60 61 62 63
    typedef enum {
        FailNone,                           // No failures
        FailParamNoReponseToRequestList,    // Do no respond to PARAM_REQUEST_LIST
        FailMissingParamOnInitialReqest,    // Not all params are sent on initial request, should still succeed since QGC will re-query missing params
        FailMissingParamOnAllRequests,      // Not all params are sent on initial request, QGC retries will fail as well
    } FailureMode_t;
    FailureMode_t failureMode(void) { return _failureMode; }
    void setFailureMode(FailureMode_t failureMode) { _failureMode = failureMode; }

64
    // Overrides from LinkConfiguration
65 66 67 68 69 70 71 72 73 74 75
    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  ();
76 77

private:
78
    MAV_AUTOPILOT   _firmwareType;
79
    MAV_TYPE        _vehicleType;
80
    bool            _sendStatusText;
Don Gagne's avatar
Don Gagne committed
81
    FailureMode_t   _failureMode;
82

83
    static const char* _firmwareTypeKey;
84
    static const char* _vehicleTypeKey;
85
    static const char* _sendStatusTextKey;
Don Gagne's avatar
Don Gagne committed
86
    static const char* _failureModeKey;
87 88
};

89 90 91
class MockLink : public LinkInterface
{
    Q_OBJECT
92

93
public:
94
    MockLink(SharedLinkConfigurationPointer& config);
95
    ~MockLink(void);
96

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

    /// 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; }

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

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

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

Don Gagne's avatar
Don Gagne committed
117 118 119 120 121 122 123
    // 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; }

124 125 126 127
    // 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);
128

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

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

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

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

142 143
    /// Reset the state of the MissionItemHandler to no items, no transactions in progress.
    void resetMissionItemHandler(void) { _missionItemHandler.reset(); }
144

Patrick José Pereira's avatar
Patrick José Pereira committed
145
    /// Returns the filename for the simulated log file. Only available after a download is requested.
146 147
    QString logDownloadFile(void) { return _logDownloadFilename; }

Don Gagne's avatar
Don Gagne committed
148 149 150 151
    static MockLink* startPX4MockLink            (bool sendStatusText, MockConfiguration::FailureMode_t failureMode = MockConfiguration::FailNone);
    static MockLink* startGenericMockLink        (bool sendStatusText, MockConfiguration::FailureMode_t failureMode = MockConfiguration::FailNone);
    static MockLink* startAPMArduCopterMockLink  (bool sendStatusText, MockConfiguration::FailureMode_t failureMode = MockConfiguration::FailNone);
    static MockLink* startAPMArduPlaneMockLink   (bool sendStatusText, MockConfiguration::FailureMode_t failureMode = MockConfiguration::FailNone);
152
    static MockLink* startAPMArduSubMockLink     (bool sendStatusText, MockConfiguration::FailureMode_t failureMode = MockConfiguration::FailNone);
153

154
private slots:
155
    virtual void _writeBytes(const QByteArray bytes);
156

157 158 159
private slots:
    void _run1HzTasks(void);
    void _run10HzTasks(void);
Don Gagne's avatar
Don Gagne committed
160
    void _run500HzTasks(void);
161

162
private:
163 164
    // From LinkInterface
    virtual bool _connect(void);
Don Gagne's avatar
Don Gagne committed
165
    virtual void _disconnect(void);
166

167 168
    // QThread override
    virtual void run(void);
169

170 171 172 173 174 175 176 177 178 179
    // MockLink methods
    void _sendHeartBeat(void);
    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);
180
    void _handleFTP(const mavlink_message_t& msg);
181
    void _handleCommandLong(const mavlink_message_t& msg);
Don Gagne's avatar
Don Gagne committed
182
    void _handleManualControl(const mavlink_message_t& msg);
183
    void _handlePreFlightCalibration(const mavlink_command_long_t& request);
184 185
    void _handleLogRequestList(const mavlink_message_t& msg);
    void _handleLogRequestData(const mavlink_message_t& msg);
186 187
    float _floatUnionForParam(int componentId, const QString& paramName);
    void _setParamFloatUnionIntoMap(int componentId, const QString& paramName, float paramFloat);
188
    void _sendHomePosition(void);
Don Gagne's avatar
Don Gagne committed
189
    void _sendGpsRawInt(void);
Don Gagne's avatar
Don Gagne committed
190
    void _sendVibration(void);
191
    void _sendStatusTextMessages(void);
192
    void _respondWithAutopilotVersion(void);
Don Gagne's avatar
Don Gagne committed
193
    void _sendRCChannels(void);
Don Gagne's avatar
Don Gagne committed
194
    void _paramRequestListWorker(void);
195
    void _logDownloadWorker(void);
196
    void _sendADSBVehicles(void);
197
    void _moveADSBVehicle(void);
198

199 200
    static MockLink* _startMockLink(MockConfiguration* mockConfig);

201
    MockLinkMissionItemHandler  _missionItemHandler;
202

203 204
    QString _name;
    bool    _connected;
205
    int     _mavlinkChannel;
206

207 208
    uint8_t _vehicleSystemId;
    uint8_t _vehicleComponentId;
209

210 211
    bool    _inNSH;
    bool    _mavlinkStarted;
212

213 214
    QMap<int, QMap<QString, QVariant> > _mapParamName2Value;
    QMap<QString, MAV_PARAM_TYPE>       _mapParamName2MavParamType;
215

216 217 218
    uint8_t     _mavBaseMode;
    uint32_t    _mavCustomMode;
    uint8_t     _mavState;
219

220 221
    MAV_AUTOPILOT       _firmwareType;
    MAV_TYPE            _vehicleType;
222 223 224
    double              _vehicleLatitude;
    double              _vehicleLongitude;
    double              _vehicleAltitude;
225

226
    MockLinkFileServer* _fileServer;
Don Gagne's avatar
Don Gagne committed
227

228
    bool _sendStatusText;
Don Gagne's avatar
Don Gagne committed
229
    bool _apmSendHomePositionOnEmptyList;
Don Gagne's avatar
Don Gagne committed
230
    MockConfiguration::FailureMode_t _failureMode;
231

232
    int _sendHomePositionDelayCount;
233
    int _sendGPSPositionDelayCount;
234

Don Gagne's avatar
Don Gagne committed
235
    int _currentParamRequestListComponentIndex; // Current component index for param request list workflow, -1 for no request in progress
236 237 238 239 240 241 242 243
    int _currentParamRequestListParamIndex;     // Current parameter index for param request list workflow

    static const uint16_t _logDownloadLogId = 0;        ///< Id of siumulated log file
    static const uint32_t _logDownloadFileSize = 1000;  ///< Size of simulated log file

    QString _logDownloadFilename;           ///< Filename for log download which is in progress
    uint32_t    _logDownloadCurrentOffset;  ///< Current offset we are sending from
    uint32_t    _logDownloadBytesRemaining; ///< Number of bytes still to send, 0 = send inactive
Don Gagne's avatar
Don Gagne committed
244

245 246 247
    QGeoCoordinate  _adsbVehicleCoordinate;
    double          _adsbAngle;

248 249 250
    static double       _defaultVehicleLatitude;
    static double       _defaultVehicleLongitude;
    static double       _defaultVehicleAltitude;
Don Gagne's avatar
Don Gagne committed
251 252
    static int          _nextVehicleSystemId;
    static const char*  _failParam;
253 254 255
};

#endif