MockLink.h 4.32 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27
/*=====================================================================
 
 QGroundControl Open Source Ground Control Station
 
 (c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 
 This file is part of the QGROUNDCONTROL project
 
 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.
 
 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.
 
 You should have received a copy of the GNU General Public License
 along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
 
 ======================================================================*/

#ifndef MOCKLINK_H
#define MOCKLINK_H

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

#include "MockLinkMissionItemHandler.h"
#include "LinkInterface.h"
32 33 34
#include "QGCMAVLink.h"

Q_DECLARE_LOGGING_CATEGORY(MockLinkLog)
35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56

/// @file
///     @brief Mock implementation of a Link.
///
///     @author Don Gagne <don@thegagnes.com>

class MockLink : public LinkInterface
{
    Q_OBJECT
    
public:
    MockLink(void);
    ~MockLink(void);
    
    // Virtuals from LinkInterface
    virtual int getId(void) const { return _linkId; }
    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; }
    
57 58 59 60
    // MockLink methods
    MAV_AUTOPILOT getAutopilotType(void) { return _autopilotType; }
    void setAutopilotType(MAV_AUTOPILOT autopilot) { _autopilotType = autopilot; }
    
61 62 63 64 65
    // 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);
    
66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82
signals:
    /// @brief Used internally to move data to the thread.
    void _incomingBytes(const QByteArray bytes);
    
public slots:
    virtual void writeBytes(const char *bytes, qint64 cBytes);
    
protected slots:
    // FIXME: This should not be part of LinkInterface. It is an internal link implementation detail.
    virtual void readBytes(void);
    
private slots:
    void _run1HzTasks(void);
    void _run10HzTasks(void);
    void _run50HzTasks(void);
    
private:
83 84 85 86
    // From LinkInterface
    virtual bool _connect(void);
    virtual bool _disconnect(void);
    
87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104
    // QThread override
    virtual void run(void);
    
    // 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 _emitMavlinkMessage(const mavlink_message_t& msg);
    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 _handleMissionRequestList(const mavlink_message_t& msg);
    void _handleMissionRequest(const mavlink_message_t& msg);
    void _handleMissionItem(const mavlink_message_t& msg);
105 106 107
    float _floatUnionForParam(const QString& paramName);
    void _setParamFloatUnionIntoMap(const QString& paramName, float paramFloat);

108 109 110 111 112 113 114 115 116 117 118 119
    MockLinkMissionItemHandler* _missionItemHandler;
    
    int     _linkId;
    QString _name;
    bool    _connected;
    
    uint8_t _vehicleSystemId;
    uint8_t _vehicleComponentId;
    
    bool    _inNSH;
    bool    _mavlinkStarted;
    
120 121
    QMap<QString, QVariant>         _mapParamName2Value;
    QMap<QString, MAV_PARAM_TYPE>   _mapParamName2MavParamType;
122 123 124 125
    
    typedef QMap<uint16_t, mavlink_mission_item_t>   MissionList_t;
    MissionList_t   _missionItems;
    
Don Gagne's avatar
Don Gagne committed
126 127
    uint8_t _mavBaseMode;
    uint8_t _mavCustomMode;
128
    uint8_t _mavState;
129 130
    
    MAV_AUTOPILOT _autopilotType;
131 132 133
};

#endif