MockLink.h 7.67 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
    MockConfiguration(const QString& name);
    MockConfiguration(MockConfiguration* source);

    MAV_AUTOPILOT firmwareType(void) { return _firmwareType; }
    void setFirmwareType(MAV_AUTOPILOT firmwareType) { _firmwareType = firmwareType; }

49 50 51
    MAV_TYPE vehicleType(void) { return _vehicleType; }
    void setVehicleType(MAV_TYPE vehicleType) { _vehicleType = vehicleType; }

52 53 54 55
    /// @param sendStatusText true: mavlink status text messages will be sent for each severity, as well as voice output info message
    void setSendStatusText(bool sendStatusText) { _sendStatusText = sendStatusText; }
    bool sendStatusText(void) { return _sendStatusText; }

56 57 58 59 60 61 62 63
    // Overrides from LinkConfiguration
    int  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);

private:
64
    MAV_AUTOPILOT   _firmwareType;
65
    MAV_TYPE        _vehicleType;
66
    bool            _sendStatusText;
67

68
    static const char* _firmwareTypeKey;
69
    static const char* _vehicleTypeKey;
70
    static const char* _sendStatusTextKey;
71 72
};

73 74 75
class MockLink : public LinkInterface
{
    Q_OBJECT
76

77
public:
78 79
    // LinkConfiguration is optional for MockLink
    MockLink(MockConfiguration* config = NULL);
80
    ~MockLink(void);
81

82
    // MockLink methods
Don Gagne's avatar
Don Gagne committed
83
    int vehicleId(void) { return _vehicleSystemId; }
Don Gagne's avatar
Don Gagne committed
84 85
    MAV_AUTOPILOT getFirmwareType(void) { return _firmwareType; }
    void setFirmwareType(MAV_AUTOPILOT autopilot) { _firmwareType = autopilot; }
86
    void setSendStatusText(bool sendStatusText) { _sendStatusText = sendStatusText; }
Don Gagne's avatar
Don Gagne committed
87 88 89 90 91 92 93

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

94
    void emitRemoteControlChannelRawChanged(int channel, uint16_t raw);
95 96 97 98 99
    
    /// Sends the specified mavlink message to QGC
    void respondWithMavlinkMessage(const mavlink_message_t& msg);
    
    MockLinkFileServer* getFileServer(void) { return _fileServer; }
100

Don Gagne's avatar
Don Gagne committed
101 102 103 104 105 106 107
    // 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; }

108 109 110 111
    // 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);
112 113

    LinkConfiguration* getLinkConfiguration() { return _config; }
114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130
    
    /// Sets a failure mode for unit testing
    ///     @param failureMode Type of failure to simulate
    ///     @param firstTimeOnly true: fail first call, success subsequent calls, false: fail all calls
    void setMissionItemFailureMode(MockLinkMissionItemHandler::FailureMode_t failureMode, bool firstTimeOnly);
    
    /// Called to send a MISSION_ACK message while the MissionManager is in idle state
    void sendUnexpectedMissionAck(MAV_MISSION_RESULT ackType) { _missionItemHandler.sendUnexpectedMissionAck(ackType); }
    
    /// Called to send a MISSION_ITEM message while the MissionManager is in idle state
    void sendUnexpectedMissionItem(void) { _missionItemHandler.sendUnexpectedMissionItem(); }
    
    /// Called to send a MISSION_REQUEST message while the MissionManager is in idle state
    void sendUnexpectedMissionRequest(void) { _missionItemHandler.sendUnexpectedMissionRequest(); }
    
    /// Reset the state of the MissionItemHandler to no items, no transactions in progress.
    void resetMissionItemHandler(void) { _missionItemHandler.reset(); }
131

132 133 134
signals:
    /// @brief Used internally to move data to the thread.
    void _incomingBytes(const QByteArray bytes);
135

136 137
public slots:
    virtual void writeBytes(const char *bytes, qint64 cBytes);
138

139 140 141
protected slots:
    // FIXME: This should not be part of LinkInterface. It is an internal link implementation detail.
    virtual void readBytes(void);
142

143 144 145 146
private slots:
    void _run1HzTasks(void);
    void _run10HzTasks(void);
    void _run50HzTasks(void);
147

148
private:
149 150
    // From LinkInterface
    virtual bool _connect(void);
Don Gagne's avatar
Don Gagne committed
151
    virtual void _disconnect(void);
152

153 154
    // QThread override
    virtual void run(void);
155

156 157 158 159 160 161 162 163 164 165 166
    // 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);
167
    void _handleFTP(const mavlink_message_t& msg);
168
    void _handleCommandLong(const mavlink_message_t& msg);
169 170
    float _floatUnionForParam(int componentId, const QString& paramName);
    void _setParamFloatUnionIntoMap(int componentId, const QString& paramName, float paramFloat);
171
    void _sendHomePosition(void);
Don Gagne's avatar
Don Gagne committed
172
    void _sendGpsRawInt(void);
173
    void _sendStatusTextMessages(void);
174

175
    MockLinkMissionItemHandler  _missionItemHandler;
176

177 178
    QString _name;
    bool    _connected;
179

180 181
    uint8_t _vehicleSystemId;
    uint8_t _vehicleComponentId;
182

183 184
    bool    _inNSH;
    bool    _mavlinkStarted;
185

186 187
    QMap<int, QMap<QString, QVariant> > _mapParamName2Value;
    QMap<QString, MAV_PARAM_TYPE>       _mapParamName2MavParamType;
188

189 190 191
    uint8_t     _mavBaseMode;
    uint32_t    _mavCustomMode;
    uint8_t     _mavState;
192

193 194 195
    MockConfiguration*  _config;
    MAV_AUTOPILOT       _firmwareType;
    MAV_TYPE            _vehicleType;
196 197
    
    MockLinkFileServer* _fileServer;
Don Gagne's avatar
Don Gagne committed
198

199
    bool _sendStatusText;
Don Gagne's avatar
Don Gagne committed
200
    bool _apmSendHomePositionOnEmptyList;
201

202 203
    int _sendHomePositionDelayCount;

Don Gagne's avatar
Don Gagne committed
204 205 206
    static float _vehicleLatitude;
    static float _vehicleLongitude;
    static float _vehicleAltitude;
207 208 209
};

#endif