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

10
#pragma once
11

12
#include <QElapsedTimer>
13
#include <QMap>
14
#include <QLoggingCategory>
15
#include <QGeoCoordinate>
16 17

#include "MockLinkMissionItemHandler.h"
18
#include "MockLinkFTP.h"
19 20 21
#include "QGCMAVLink.h"

Q_DECLARE_LOGGING_CATEGORY(MockLinkLog)
Don Gagne's avatar
Don Gagne committed
22
Q_DECLARE_LOGGING_CATEGORY(MockLinkVerboseLog)
23

24 25
class LinkManager;

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

30
public:
31 32 33
    MockConfiguration(const QString& name);
    MockConfiguration(MockConfiguration* source);

34 35 36 37 38 39 40 41 42 43 44
    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)
    Q_PROPERTY(bool     incrementVehicleId  READ incrementVehicleId WRITE setIncrementVehicleId NOTIFY incrementVehicleIdChanged)

    int     firmware                (void)                      { return (int)_firmwareType; }
    void    setFirmware             (int type)                  { _firmwareType = (MAV_AUTOPILOT)type; emit firmwareChanged(); }
    int     vehicle                 (void)                      { return (int)_vehicleType; }
    bool    incrementVehicleId      (void)                      { return _incrementVehicleId; }
    void    setVehicle              (int type)                  { _vehicleType = (MAV_TYPE)type; emit vehicleChanged(); }
    void    setIncrementVehicleId   (bool incrementVehicleId)   { _incrementVehicleId = incrementVehicleId; emit incrementVehicleIdChanged(); }
45

46

47 48 49 50 51 52 53
    MAV_AUTOPILOT   firmwareType        (void)                          { return _firmwareType; }
    MAV_TYPE        vehicleType         (void)                          { return _vehicleType; }
    bool            sendStatusText      (void)                          { return _sendStatusText; }

    void            setFirmwareType     (MAV_AUTOPILOT firmwareType)    { _firmwareType = firmwareType; emit firmwareChanged(); }
    void            setVehicleType      (MAV_TYPE vehicleType)          { _vehicleType = vehicleType; emit vehicleChanged(); }
    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
    LinkType    type            (void) override                                         { return LinkConfiguration::TypeMock; }
    void        copyFrom        (LinkConfiguration* source) override;
    void        loadSettings    (QSettings& settings, const QString& root) override;
    void        saveSettings    (QSettings& settings, const QString& root) override;
    QString     settingsURL     (void) override                                         { return "MockLinkSettings.qml"; }
    QString     settingsTitle   (void) override                                         { return tr("Mock Link Settings"); }
71 72

signals:
73 74 75 76
    void firmwareChanged            (void);
    void vehicleChanged             (void);
    void sendStatusChanged          (void);
    void incrementVehicleIdChanged  (void);
77 78

private:
79 80 81 82 83
    MAV_AUTOPILOT   _firmwareType       = MAV_AUTOPILOT_PX4;
    MAV_TYPE        _vehicleType        = MAV_TYPE_QUADROTOR;
    bool            _sendStatusText     = false;
    FailureMode_t   _failureMode        = FailNone;
    bool            _incrementVehicleId = true;
84

85
    static const char* _firmwareTypeKey;
86
    static const char* _vehicleTypeKey;
87
    static const char* _sendStatusTextKey;
88
    static const char* _incrementVehicleIdKey;
Don Gagne's avatar
Don Gagne committed
89
    static const char* _failureModeKey;
90 91
};

92 93 94
class MockLink : public LinkInterface
{
    Q_OBJECT
95

96
public:
97
    MockLink(SharedLinkConfigurationPtr& config);
98
    ~MockLink(void);
99

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

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

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

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

117
    MockLinkFTP* mockLinkFTP(void) { return _mockLinkFTP; }
Don Gagne's avatar
Don Gagne committed
118

119 120 121
    // Overrides from LinkInterface
    bool isConnected(void) const override { return _connected; }
    void disconnect (void) override;
122

123
    /// Sets a failure mode for unit testingqgcm
124
    ///     @param failureMode Type of failure to simulate
125 126
    ///     @param failureAckResult Error to send if one the ack error modes
    void setMissionItemFailureMode(MockLinkMissionItemHandler::FailureMode_t failureMode, MAV_MISSION_RESULT failureAckResult);
127

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

131 132
    /// Called to send a MISSION_ITEM message while the MissionManager is in idle state
    void sendUnexpectedMissionItem(void) { _missionItemHandler.sendUnexpectedMissionItem(); }
133

134 135
    /// Called to send a MISSION_REQUEST message while the MissionManager is in idle state
    void sendUnexpectedMissionRequest(void) { _missionItemHandler.sendUnexpectedMissionRequest(); }
136

137 138
    void sendUnexpectedCommandAck(MAV_CMD command, MAV_RESULT ackResult);

139 140
    /// Reset the state of the MissionItemHandler to no items, no transactions in progress.
    void resetMissionItemHandler(void) { _missionItemHandler.reset(); }
141

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

145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174
    Q_INVOKABLE void setCommLost                    (bool commLost)   { _commLost = commLost; }
    Q_INVOKABLE void simulateConnectionRemoved      (void);
    static MockLink* startPX4MockLink               (bool sendStatusText, MockConfiguration::FailureMode_t failureMode = MockConfiguration::FailNone);
    static MockLink* startGenericMockLink           (bool sendStatusText, MockConfiguration::FailureMode_t failureMode = MockConfiguration::FailNone);
    static MockLink* startNoInitialConnectMockLink  (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);
    static MockLink* startAPMArduSubMockLink        (bool sendStatusText, MockConfiguration::FailureMode_t failureMode = MockConfiguration::FailNone);
    static MockLink* startAPMArduRoverMockLink      (bool sendStatusText, MockConfiguration::FailureMode_t failureMode = MockConfiguration::FailNone);

    // Special commands for testing COMMAND_LONG handlers. By default all commands except for MAV_CMD_MOCKLINK_NO_RESPONSE_NO_RETRY should retry.
    static constexpr MAV_CMD MAV_CMD_MOCKLINK_ALWAYS_RESULT_ACCEPTED            = MAV_CMD_USER_1;
    static constexpr MAV_CMD MAV_CMD_MOCKLINK_ALWAYS_RESULT_FAILED              = MAV_CMD_USER_2;
    static constexpr MAV_CMD MAV_CMD_MOCKLINK_SECOND_ATTEMPT_RESULT_ACCEPTED    = MAV_CMD_USER_3;
    static constexpr MAV_CMD MAV_CMD_MOCKLINK_SECOND_ATTEMPT_RESULT_FAILED      = MAV_CMD_USER_4;
    static constexpr MAV_CMD MAV_CMD_MOCKLINK_NO_RESPONSE                       = MAV_CMD_USER_5;
    static constexpr MAV_CMD MAV_CMD_MOCKLINK_NO_RESPONSE_NO_RETRY              = static_cast<MAV_CMD>(MAV_CMD_USER_5 + 1);

    void clearSendMavCommandCounts(void) { _sendMavCommandCountMap.clear(); }
    int sendMavCommandCount(MAV_CMD command) { return _sendMavCommandCountMap[command]; }

    // Special message ids for testing requestMessage support
    typedef enum {
        FailRequestMessageNone,
        FailRequestMessageCommandAcceptedMsgNotSent,
        FailRequestMessageCommandUnsupported,
        FailRequestMessageCommandNoResponse,
        FailRequestMessageCommandAcceptedSecondAttempMsgSent,
    } RequestMessageFailureMode_t;
    void setRequestMessageFailureMode(RequestMessageFailureMode_t failureMode) { _requestMessageFailureMode = failureMode; }
175

176 177 178
signals:
    void writeBytesQueuedSignal                 (const QByteArray bytes);
    void highLatencyTransmissionEnabledChanged  (bool highLatencyTransmissionEnabled);
179

180
private slots:
181 182 183 184
    // LinkInterface overrides
    void _writeBytes(const QByteArray bytes) final;

    void _writeBytesQueued(const QByteArray bytes);
185 186
    void _run1HzTasks(void);
    void _run10HzTasks(void);
Don Gagne's avatar
Don Gagne committed
187
    void _run500HzTasks(void);
188

189
private:
190 191
    // LinkInterface overrides
    bool _connect(void) override;
192

193
    // QThread override
194
    void run(void) final;
195

196
    // MockLink methods
197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233
    void _sendHeartBeat                 (void);
    void _sendHighLatency2              (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);
    void _handleFTP                     (const mavlink_message_t& msg);
    void _handleCommandLong             (const mavlink_message_t& msg);
    void _handleManualControl           (const mavlink_message_t& msg);
    void _handlePreFlightCalibration    (const mavlink_command_long_t& request);
    void _handleLogRequestList          (const mavlink_message_t& msg);
    void _handleLogRequestData          (const mavlink_message_t& msg);
    void _handleParamMapRC              (const mavlink_message_t& msg);
    bool _handleRequestMessage          (const mavlink_command_long_t& request, bool& noAck);
    float _floatUnionForParam           (int componentId, const QString& paramName);
    void _setParamFloatUnionIntoMap     (int componentId, const QString& paramName, float paramFloat);
    void _sendHomePosition              (void);
    void _sendGpsRawInt                 (void);
    void _sendVibration                 (void);
    void _sendSysStatus                 (void);
    void _sendBatteryStatus             (void);
    void _sendStatusTextMessages        (void);
    void _sendChunkedStatusText         (uint16_t chunkId, bool missingChunks);
    void _respondWithAutopilotVersion   (void);
    void _sendRCChannels                (void);
    void _paramRequestListWorker        (void);
    void _logDownloadWorker             (void);
    void _sendADSBVehicles              (void);
    void _moveADSBVehicle               (void);
    void _sendVersionMetaData           (void);
    void _sendParameterMetaData         (void);

    static MockLink* _startMockLinkWorker(QString configName, MAV_AUTOPILOT firmwareType, MAV_TYPE vehicleType, bool sendStatusText, MockConfiguration::FailureMode_t failureMode);
234 235
    static MockLink* _startMockLink(MockConfiguration* mockConfig);

236
    MockLinkMissionItemHandler  _missionItemHandler;
237

238 239 240
    QString                     _name;
    bool                        _connected;
    int                         _mavlinkChannel;
241

242 243
    uint8_t                     _vehicleSystemId;
    uint8_t                     _vehicleComponentId             = MAV_COMP_ID_AUTOPILOT1;
244

245 246
    bool                        _inNSH;
    bool                        _mavlinkStarted;
247

248 249 250
    uint8_t                     _mavBaseMode;
    uint32_t                    _mavCustomMode;
    uint8_t                     _mavState;
251

252 253 254 255 256 257 258 259
    QElapsedTimer               _runningTime;
    static const int32_t        _batteryMaxTimeRemaining        = 15 * 60;
    int8_t                      _battery1PctRemaining           = 100;
    int32_t                     _battery1TimeRemaining          = _batteryMaxTimeRemaining;
    MAV_BATTERY_CHARGE_STATE    _battery1ChargeState            = MAV_BATTERY_CHARGE_STATE_OK;
    int8_t                      _battery2PctRemaining           = 100;
    int32_t                     _battery2TimeRemaining          = _batteryMaxTimeRemaining;
    MAV_BATTERY_CHARGE_STATE    _battery2ChargeState            = MAV_BATTERY_CHARGE_STATE_OK;
260

261 262 263 264 265 266 267
    MAV_AUTOPILOT               _firmwareType;
    MAV_TYPE                    _vehicleType;
    double                      _vehicleLatitude;
    double                      _vehicleLongitude;
    double                      _vehicleAltitude;
    bool                        _commLost                       = false;
    bool                        _highLatencyTransmissionEnabled = true;
268

269
    MockLinkFTP* _mockLinkFTP = nullptr;
Don Gagne's avatar
Don Gagne committed
270

271
    bool _sendStatusText;
Don Gagne's avatar
Don Gagne committed
272
    bool _apmSendHomePositionOnEmptyList;
Don Gagne's avatar
Don Gagne committed
273
    MockConfiguration::FailureMode_t _failureMode;
274

275
    int _sendHomePositionDelayCount;
276
    int _sendGPSPositionDelayCount;
277

Don Gagne's avatar
Don Gagne committed
278
    int _currentParamRequestListComponentIndex; // Current component index for param request list workflow, -1 for no request in progress
279 280 281 282 283
    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

284
    QString     _logDownloadFilename;       ///< Filename for log download which is in progress
285 286
    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
287

288 289 290
    QGeoCoordinate  _adsbVehicleCoordinate;
    double          _adsbAngle;

291 292 293 294 295 296
    RequestMessageFailureMode_t _requestMessageFailureMode = FailRequestMessageNone;

    QMap<MAV_CMD, int>  _sendMavCommandCountMap;
    QMap<int, QMap<QString, QVariant>>          _mapParamName2Value;
    QMap<int, QMap<QString, MAV_PARAM_TYPE>>    _mapParamName2MavParamType;

297 298 299
    static double       _defaultVehicleLatitude;
    static double       _defaultVehicleLongitude;
    static double       _defaultVehicleAltitude;
Don Gagne's avatar
Don Gagne committed
300 301
    static int          _nextVehicleSystemId;
    static const char*  _failParam;
302 303
};