LinkInterface.h 10.6 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

pixhawk's avatar
pixhawk committed
10 11 12 13
#ifndef _LINKINTERFACE_H_
#define _LINKINTERFACE_H_

#include <QThread>
14 15 16
#include <QDateTime>
#include <QMutex>
#include <QMutexLocker>
Lorenz Meier's avatar
Lorenz Meier committed
17
#include <QMetaType>
18
#include <QSharedPointer>
19
#include <QDebug>
pixhawk's avatar
pixhawk committed
20

Don Gagne's avatar
Don Gagne committed
21
#include "QGCMAVLink.h"
22
#include "LinkConfiguration.h"
Don Gagne's avatar
Don Gagne committed
23

24 25
class LinkManager;

pixhawk's avatar
pixhawk committed
26
/**
27 28 29 30
* The link interface defines the interface for all links used to communicate
* with the groundstation application.
*
**/
31 32
class LinkInterface : public QThread
{
33
    Q_OBJECT
34

35
    // Only LinkManager is allowed to create/delete or _connect/_disconnect a link
36
    friend class LinkManager;
37

38 39 40
public:    
    ~LinkInterface() { _config->setLink(NULL); }

Don Gagne's avatar
Don Gagne committed
41 42 43
    Q_PROPERTY(bool active      READ active         WRITE setActive         NOTIFY activeChanged)

    // Property accessors
44 45
    bool active(void)           { return _active; }
    void setActive(bool active) { _active = active; emit activeChanged(active); }
Don Gagne's avatar
Don Gagne committed
46

47
    LinkConfiguration* getLinkConfiguration(void) { return _config.data(); }
48

49 50 51 52 53
    /* Connection management */

    /**
     * @brief Get the human readable name of this link
     */
54
    virtual QString getName() const = 0;
55

56 57
    virtual void requestReset() = 0;

58 59 60 61 62
    /**
     * @brief Determine the connection status
     *
     * @return True if the connection is established, false otherwise
     **/
63
    virtual bool isConnected() const = 0;
64 65 66 67

    /* Connection characteristics */

    /**
68
     * @Brief Get the maximum connection speed for this interface.
69 70 71 72 73 74 75
     *
     * The nominal data rate is the theoretical maximum data rate of the
     * interface. For 100Base-T Ethernet this would be 100 Mbit/s (100'000'000
     * Bit/s, NOT 104'857'600 Bit/s).
     *
     * @return The nominal data rate of the interface in bit per second, 0 if unknown
     **/
76
    virtual qint64 getConnectionSpeed() const = 0;
Don Gagne's avatar
Don Gagne committed
77 78 79
    
    /// @return true: This link is replaying a log file, false: Normal two-way communication link
    virtual bool isLogReplay(void) { return false; }
80

dogmaphobic's avatar
dogmaphobic committed
81 82 83 84 85 86 87 88
    /**
     * @Enable/Disable data rate collection
     **/
    void enableDataRate(bool enable)
    {
        _enableRateCollection = enable;
    }

89 90 91 92 93 94 95 96
    /**
     * @Brief Get the current incoming data rate.
     *
     * This should be over a short timespan, something like 100ms. A precise value isn't necessary,
     * and this can be filtered, but should be a reasonable estimate of current data rate.
     *
     * @return The data rate of the interface in bits per second, 0 if unknown
     **/
97
    qint64 getCurrentInputDataRate() const
98
    {
99
        return _getCurrentDataRate(_inDataIndex, _inDataWriteTimes, _inDataWriteAmounts);
100
    }
101 102 103 104 105 106 107 108 109

    /**
     * @Brief Get the current outgoing data rate.
     *
     * This should be over a short timespan, something like 100ms. A precise value isn't necessary,
     * and this can be filtered, but should be a reasonable estimate of current data rate.
     *
     * @return The data rate of the interface in bits per second, 0 if unknown
     **/
110
    qint64 getCurrentOutputDataRate() const
111
    {
112
        return _getCurrentDataRate(_outDataIndex, _outDataWriteTimes, _outDataWriteAmounts);
113
    }
114 115 116
    
    /// mavlink channel to use for this link, as used by mavlink_parse_char. The mavlink channel is only
    /// set into the link when it is added to LinkManager
117
    uint8_t mavlinkChannel(void) const;
118

119 120 121 122 123
    /// Returns whether this link is high latency or not. High latency links should only perform
    /// minimal communication with vehicle.
    ///     signals: highLatencyChanged
    bool highLatency(void) const { return _highLatency; }

124 125 126
    bool decodedFirstMavlinkPacket(void) const { return _decodedFirstMavlinkPacket; }
    bool setDecodedFirstMavlinkPacket(bool decodedFirstMavlinkPacket) { return _decodedFirstMavlinkPacket = decodedFirstMavlinkPacket; }

Don Gagne's avatar
Don Gagne committed
127 128 129 130
    // 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);
131

pixhawk's avatar
pixhawk committed
132 133
public slots:

134 135 136 137 138
    /**
     * @brief This method allows to write bytes to the interface.
     *
     * If the underlying communication is packet oriented,
     * one write command equals a datagram. In case of serial
139 140
     * communication arbitrary byte lengths can be written. The method ensures
     * thread safety regardless of the underlying LinkInterface implementation.
141 142 143 144
     *
     * @param bytes The pointer to the byte array containing the data
     * @param length The length of the data array
     **/
145 146 147 148 149 150
    void writeBytesSafe(const char *bytes, int length)
    {
        emit _invokeWriteBytes(QByteArray(bytes, length));
    }

private slots:
151
    virtual void _writeBytes(const QByteArray) = 0;
152
    
pixhawk's avatar
pixhawk committed
153
signals:
Don Gagne's avatar
Don Gagne committed
154 155
    void autoconnectChanged(bool autoconnect);
    void activeChanged(bool active);
156
    void _invokeWriteBytes(QByteArray);
157
    void highLatencyChanged(bool highLatency);
158

159 160 161
    /// Signalled when a link suddenly goes away due to it being removed by for example pulling the cable to the connection.
    void connectionRemoved(LinkInterface* link);

162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187
    /**
     * @brief New data arrived
     *
     * The new data is contained in the QByteArray data. The data is copied for each
     * receiving protocol. For high-speed links like image transmission this might
     * affect performance, for control links it is however desirable to directly
     * forward the link data.
     *
     * @param data the new bytes
     */
    void bytesReceived(LinkInterface* link, QByteArray data);

    /**
     * @brief This signal is emitted instantly when the link is connected
     **/
    void connected();

    /**
     * @brief This signal is emitted instantly when the link is disconnected
     **/
    void disconnected();

    /**
     * @brief This signal is emitted if the human readable name of this link changes
     */
    void nameChanged(QString name);
pixhawk's avatar
pixhawk committed
188

Ricardo de Almeida Gonzaga's avatar
Ricardo de Almeida Gonzaga committed
189
    /** @brief Communication error occurred */
190
    void communicationError(const QString& title, const QString& error);
191

192 193
    void communicationUpdate(const QString& linkname, const QString& text);

pixhawk's avatar
pixhawk committed
194
protected:
195
    // Links are only created by LinkManager so constructor is not public
196
    LinkInterface(SharedLinkConfigurationPointer& config);
197

198 199 200
    /// This function logs the send times and amounts of datas for input. Data is used for calculating
    /// the transmission rate.
    ///     @param byteCount Number of bytes received
Ricardo de Almeida Gonzaga's avatar
Ricardo de Almeida Gonzaga committed
201
    ///     @param time Time in ms send occurred
202
    void _logInputDataRate(quint64 byteCount, qint64 time);
203 204 205 206
    
    /// This function logs the send times and amounts of datas for output. Data is used for calculating
    /// the transmission rate.
    ///     @param byteCount Number of bytes sent
Ricardo de Almeida Gonzaga's avatar
Ricardo de Almeida Gonzaga committed
207
    ///     @param time Time in ms receive occurred
208 209 210
    void _logOutputDataRate(quint64 byteCount, qint64 time);

    SharedLinkConfigurationPointer _config;
211 212
    bool _highLatency;

213
private:
214 215 216 217 218 219 220 221 222 223 224 225
    /**
     * @brief logDataRateToBuffer Stores transmission times/amounts for statistics
     *
     * This function logs the send times and amounts of datas to the given circular buffers.
     * This data is used for calculating the transmission rate.
     *
     * @param bytesBuffer[out] The buffer to write the bytes value into.
     * @param timeBuffer[out] The buffer to write the time value into
     * @param writeIndex[out] The write index used for this buffer.
     * @param bytes The amount of bytes transmit.
     * @param time The time (in ms) this transmission occurred.
     */
226
    void _logDataRateToBuffer(quint64 *bytesBuffer, qint64 *timeBuffer, int *writeIndex, quint64 bytes, qint64 time);
227 228 229 230 231 232

    /**
     * @brief getCurrentDataRate Get the current data rate given a data rate buffer.
     *
     * This function attempts to use the times and number of bytes transmit into a current data rate
     * estimation. Since it needs to use timestamps to get the timeperiods over when the data was sent,
233
     * this is effectively a global data rate over the last _dataRateBufferSize - 1 data points. Also note
234 235 236 237 238 239 240
     * that data points older than NOW - dataRateCurrentTimespan are ignored.
     *
     * @param index The first valid sample in the data rate buffer. Refers to the oldest time sample.
     * @param dataWriteTimes The time, in ms since epoch, that each data sample took place.
     * @param dataWriteAmounts The amount of data (in bits) that was transferred.
     * @return The bits per second of data transferrence of the interface over the last [-statsCurrentTimespan, 0] timespan.
     */
241
    qint64 _getCurrentDataRate(int index, const qint64 dataWriteTimes[], const quint64 dataWriteAmounts[]) const;
242

243 244 245 246 247 248
    /**
     * @brief Connect this interface logically
     *
     * @return True if connection could be established, false otherwise
     **/
    virtual bool _connect(void) = 0;
249

Don Gagne's avatar
Don Gagne committed
250
    virtual void _disconnect(void) = 0;
251 252
    
    /// Sets the mavlink channel to use for this link
253
    void _setMavlinkChannel(uint8_t channel);
254 255 256
    
    bool _mavlinkChannelSet;    ///< true: _mavlinkChannel has been set
    uint8_t _mavlinkChannel;    ///< mavlink channel to use for this link, as used by mavlink_parse_char
257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274
    
    static const int _dataRateBufferSize = 20; ///< Specify how many data points to capture for data rate calculations.
    
    static const qint64 _dataRateCurrentTimespan = 500; ///< Set the maximum age of samples to use for data calculations (ms).
    
    // Implement a simple circular buffer for storing when and how much data was received.
    // Used for calculating the incoming data rate. Use with *StatsBuffer() functions.
    int     _inDataIndex;
    quint64 _inDataWriteAmounts[_dataRateBufferSize]; // In bytes
    qint64  _inDataWriteTimes[_dataRateBufferSize]; // in ms
    
    // Implement a simple circular buffer for storing when and how much data was transmit.
    // Used for calculating the outgoing data rate. Use with *StatsBuffer() functions.
    int     _outDataIndex;
    quint64 _outDataWriteAmounts[_dataRateBufferSize]; // In bytes
    qint64  _outDataWriteTimes[_dataRateBufferSize]; // in ms
    
    mutable QMutex _dataRateMutex; // Mutex for accessing the data rate member variables
Don Gagne's avatar
Don Gagne committed
275

276
    bool _active;                       ///< true: link is actively receiving mavlink messages
dogmaphobic's avatar
dogmaphobic committed
277
    bool _enableRateCollection;
278
    bool _decodedFirstMavlinkPacket;    ///< true: link has correctly decoded it's first mavlink packet
pixhawk's avatar
pixhawk committed
279 280
};

281
typedef QSharedPointer<LinkInterface> SharedLinkInterfacePointer;
282

pixhawk's avatar
pixhawk committed
283
#endif // _LINKINTERFACE_H_