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


pixhawk's avatar
pixhawk committed
11
/**
12 13 14 15 16 17
* @file
*   @brief Brief Description
*
*   @author Lorenz Meier <mavteam@student.ethz.ch>
*
*/
pixhawk's avatar
pixhawk committed
18 19 20 21 22

#ifndef _LINKINTERFACE_H_
#define _LINKINTERFACE_H_

#include <QThread>
23 24 25
#include <QDateTime>
#include <QMutex>
#include <QMutexLocker>
Lorenz Meier's avatar
Lorenz Meier committed
26
#include <QMetaType>
27
#include <QSharedPointer>
pixhawk's avatar
pixhawk committed
28

Don Gagne's avatar
Don Gagne committed
29 30
#include "QGCMAVLink.h"

31
class LinkManager;
32
class LinkConfiguration;
33

pixhawk's avatar
pixhawk committed
34
/**
35 36 37 38
* The link interface defines the interface for all links used to communicate
* with the groundstation application.
*
**/
39 40
class LinkInterface : public QThread
{
41
    Q_OBJECT
42

43
    // Only LinkManager is allowed to create/delete or _connect/_disconnect a link
44
    friend class LinkManager;
45

pixhawk's avatar
pixhawk committed
46
public:
Don Gagne's avatar
Don Gagne committed
47 48 49 50 51 52
    Q_PROPERTY(bool active      READ active         WRITE setActive         NOTIFY activeChanged)

    // Property accessors
    bool active(void)                       { return _active; }
    void setActive(bool active)             { _active = active; emit activeChanged(active); }

53
    /**
54 55
     * @brief Get link configuration
     * @return A pointer to the instance of LinkConfiguration
56
     **/
57
    virtual LinkConfiguration* getLinkConfiguration() = 0;
58

59 60 61 62 63
    /* Connection management */

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

66 67
    virtual void requestReset() = 0;

68 69 70 71 72
    /**
     * @brief Determine the connection status
     *
     * @return True if the connection is established, false otherwise
     **/
73
    virtual bool isConnected() const = 0;
74 75 76 77

    /* Connection characteristics */

    /**
78
     * @Brief Get the maximum connection speed for this interface.
79 80 81 82 83 84 85
     *
     * 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
     **/
86
    virtual qint64 getConnectionSpeed() const = 0;
Don Gagne's avatar
Don Gagne committed
87 88 89
    
    /// @return true: This link is replaying a log file, false: Normal two-way communication link
    virtual bool isLogReplay(void) { return false; }
90

dogmaphobic's avatar
dogmaphobic committed
91 92 93 94 95 96 97 98
    /**
     * @Enable/Disable data rate collection
     **/
    void enableDataRate(bool enable)
    {
        _enableRateCollection = enable;
    }

99 100 101 102 103 104 105 106
    /**
     * @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
     **/
107
    qint64 getCurrentInputDataRate() const
108
    {
109
        return _getCurrentDataRate(_inDataIndex, _inDataWriteTimes, _inDataWriteAmounts);
110
    }
111 112 113 114 115 116 117 118 119

    /**
     * @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
     **/
120
    qint64 getCurrentOutputDataRate() const
121
    {
122
        return _getCurrentDataRate(_outDataIndex, _outDataWriteTimes, _outDataWriteAmounts);
123
    }
124 125 126 127
    
    /// 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
    uint8_t getMavlinkChannel(void) const { Q_ASSERT(_mavlinkChannelSet); return _mavlinkChannel; }
128

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

pixhawk's avatar
pixhawk committed
134 135
public slots:

136 137 138 139 140
    /**
     * @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
141 142
     * communication arbitrary byte lengths can be written. The method ensures
     * thread safety regardless of the underlying LinkInterface implementation.
143 144 145 146
     *
     * @param bytes The pointer to the byte array containing the data
     * @param length The length of the data array
     **/
147 148 149 150 151 152
    void writeBytesSafe(const char *bytes, int length)
    {
        emit _invokeWriteBytes(QByteArray(bytes, length));
    }

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

160 161 162
    /// 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);

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 188
    /**
     * @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
189

190
    /** @brief Communication error occured */
191
    void communicationError(const QString& title, const QString& error);
192

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

pixhawk's avatar
pixhawk committed
195
protected:
196 197
    // Links are only created by LinkManager so constructor is not public
    LinkInterface() :
Don Gagne's avatar
Don Gagne committed
198 199 200
        QThread(0)
        , _mavlinkChannelSet(false)
        , _active(false)
dogmaphobic's avatar
dogmaphobic committed
201
        , _enableRateCollection(false)
202 203 204 205 206 207 208 209 210 211 212
    {
        // Initialize everything for the data rate calculation buffers.
        _inDataIndex  = 0;
        _outDataIndex = 0;
        
        // Initialize our data rate buffers.
        memset(_inDataWriteAmounts, 0, sizeof(_inDataWriteAmounts));
        memset(_inDataWriteTimes,   0, sizeof(_inDataWriteTimes));
        memset(_outDataWriteAmounts,0, sizeof(_outDataWriteAmounts));
        memset(_outDataWriteTimes,  0, sizeof(_outDataWriteTimes));
        
213
        QObject::connect(this, &LinkInterface::_invokeWriteBytes, this, &LinkInterface::_writeBytes);
214 215
        qRegisterMetaType<LinkInterface*>("LinkInterface*");
    }
216

217 218 219 220 221
    /// 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
    ///     @param time Time in ms send occured
    void _logInputDataRate(quint64 byteCount, qint64 time) {
dogmaphobic's avatar
dogmaphobic committed
222 223
        if(_enableRateCollection)
            _logDataRateToBuffer(_inDataWriteAmounts, _inDataWriteTimes, &_inDataIndex, byteCount, time);
224 225 226 227 228 229 230
    }
    
    /// 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
    ///     @param time Time in ms receive occured
    void _logOutputDataRate(quint64 byteCount, qint64 time) {
dogmaphobic's avatar
dogmaphobic committed
231 232
        if(_enableRateCollection)
            _logDataRateToBuffer(_outDataWriteAmounts, _outDataWriteTimes, &_outDataIndex, byteCount, time);
233 234 235
    }
    
private:
236 237 238 239 240 241 242 243 244 245 246 247
    /**
     * @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.
     */
248
    void _logDataRateToBuffer(quint64 *bytesBuffer, qint64 *timeBuffer, int *writeIndex, quint64 bytes, qint64 time)
249
    {
250 251
        QMutexLocker dataRateLocker(&_dataRateMutex);
        
252 253 254 255 256 257 258 259
        int i = *writeIndex;

        // Now write into the buffer, if there's no room, we just overwrite the first data point.
        bytesBuffer[i] = bytes;
        timeBuffer[i] = time;

        // Increment and wrap the write index
        ++i;
260
        if (i == _dataRateBufferSize)
261 262 263 264 265 266 267 268 269 270 271
        {
            i = 0;
        }
        *writeIndex = i;
    }

    /**
     * @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,
272
     * this is effectively a global data rate over the last _dataRateBufferSize - 1 data points. Also note
273 274 275 276 277 278 279
     * 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.
     */
280
    qint64 _getCurrentDataRate(int index, const qint64 dataWriteTimes[], const quint64 dataWriteAmounts[]) const
281 282 283 284
    {
        const qint64 now = QDateTime::currentMSecsSinceEpoch();

        // Limit the time we calculate to the recent past
285
        const qint64 cutoff = now - _dataRateCurrentTimespan;
286 287

        // Grab the mutex for working with the stats variables
288
        QMutexLocker dataRateLocker(&_dataRateMutex);
289 290 291 292 293 294

        // Now iterate through the buffer of all received data packets adding up all values
        // within now and our cutof.
        qint64 totalBytes = 0;
        qint64 totalTime = 0;
        qint64 lastTime = 0;
295
        int size = _dataRateBufferSize;
296 297 298 299 300 301 302 303 304 305 306 307 308 309
        while (size-- > 0)
        {
            // If this data is within our cutoff time, include it in our calculations.
            // This also accounts for when the buffer is empty and filled with 0-times.
            if (dataWriteTimes[index] > cutoff && lastTime > 0) {
                // Track the total time, using the previous time as our timeperiod.
                totalTime += dataWriteTimes[index] - lastTime;
                totalBytes += dataWriteAmounts[index];
            }

            // Track the last time sample for doing timespan calculations
            lastTime = dataWriteTimes[index];

            // Increment and wrap the index if necessary.
310
            if (++index == _dataRateBufferSize)
311 312 313 314 315 316 317 318 319 320 321 322
            {
                index = 0;
            }
        }

        // Return the final calculated value in bits / s, converted from bytes/ms.
        qint64 dataRate = (totalTime != 0)?(qint64)((float)totalBytes * 8.0f / ((float)totalTime / 1000.0f)):0;

        // Finally return our calculated data rate.
        return dataRate;
    }

323 324 325 326 327 328
    /**
     * @brief Connect this interface logically
     *
     * @return True if connection could be established, false otherwise
     **/
    virtual bool _connect(void) = 0;
329

Don Gagne's avatar
Don Gagne committed
330
    virtual void _disconnect(void) = 0;
331 332 333 334 335 336
    
    /// Sets the mavlink channel to use for this link
    void _setMavlinkChannel(uint8_t channel) { Q_ASSERT(!_mavlinkChannelSet); _mavlinkChannelSet = true; _mavlinkChannel = channel; }
    
    bool _mavlinkChannelSet;    ///< true: _mavlinkChannel has been set
    uint8_t _mavlinkChannel;    ///< mavlink channel to use for this link, as used by mavlink_parse_char
337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354
    
    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
355 356

    bool _active;       ///< true: link is actively receiving mavlink messages
dogmaphobic's avatar
dogmaphobic committed
357
    bool _enableRateCollection;
pixhawk's avatar
pixhawk committed
358 359
};

360 361
typedef QSharedPointer<LinkInterface> SharedLinkInterface;

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