VehicleLinkManager.h 4.52 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 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97
/****************************************************************************
 *
 * (c) 2009-2020 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.
 *
 ****************************************************************************/

#pragma once

#include <QObject>
#include <QTimer>
#include <QDebug>
#include <QLoggingCategory>
#include <QElapsedTimer>

#include "QGCMAVLink.h"
#include "LinkInterface.h"

Q_DECLARE_LOGGING_CATEGORY(VehicleLinkManagerLog)

class Vehicle;
class LinkManager;
class VehicleLinkManagerTest;

class VehicleLinkManager : public QObject
{
    Q_OBJECT

    friend class Vehicle;
    friend class VehicleLinkManagerTest;

public:
    VehicleLinkManager(Vehicle* vehicle);

    Q_PROPERTY(LinkInterface*   primaryLink                 READ primaryLink                                                    NOTIFY primaryLinkChanged)
    Q_PROPERTY(QString          primaryLinkName             READ primaryLinkName            WRITE setPrimaryLinkByName          NOTIFY primaryLinkChanged)
    Q_PROPERTY(QStringList      linkNames                   READ linkNames                                                      NOTIFY linkNamesChanged)
    Q_PROPERTY(QStringList      linkStatuses                READ linkStatuses                                                   NOTIFY linkStatusesChanged)
    Q_PROPERTY(bool             communicationLost           READ communicationLost                                              NOTIFY communicationLostChanged)
    Q_PROPERTY(bool             communicationLostEnabled    READ communicationLostEnabled   WRITE setCommunicationLostEnabled   NOTIFY communicationLostEnabledChanged)
    Q_PROPERTY(bool             autoDisconnect              MEMBER _autoDisconnect                                              NOTIFY autoDisconnectChanged)

    void            mavlinkMessageReceived      (LinkInterface* link, mavlink_message_t message);
    bool            containsLink                (LinkInterface* link);
    LinkInterface*  primaryLink                 (void) { return _primaryLink; }
    QString         primaryLinkName             (void) const;
    QStringList     linkNames                   (void) const;
    QStringList     linkStatuses                (void) const;
    bool            communicationLost           (void) const { return _communicationLost; }
    bool            communicationLostEnabled    (void) const { return _communicationLostEnabled; }

    void            setPrimaryLinkByName        (const QString& name);
    void            setCommunicationLostEnabled (bool communicationLostEnabled);

    void            closeVehicle                (void);

signals:
    void primaryLinkChanged             (void);
    void allLinksRemoved                (Vehicle* vehicle);
    void communicationLostChanged       (bool communicationLost);
    void communicationLostEnabledChanged(bool communicationLostEnabled);
    void linkNamesChanged               (void);
    void linkStatusesChanged            (void);
    void autoDisconnectChanged          (bool autoDisconnect);

private slots:
    void _commLostCheck(void);

private:
    int             _containsLinkIndex      (LinkInterface* link);
    void            _addLink                (LinkInterface* link);
    void            _removeLink             (LinkInterface* link);
    void            _linkDisconnected       (void);
    bool            _updatePrimaryLink      (void);
    LinkInterface*  _bestActivePrimaryLink  (void);
    void            _commRegainedOnLink     (LinkInterface*  link);

    typedef struct LinkInfo {
        SharedLinkInterfacePtr  link;
        bool                    commLost = false;
        QElapsedTimer           heartbeatElapsedTimer;
    } LinkInfo_t;

    Vehicle*            _vehicle                    = nullptr;
    LinkManager*        _linkMgr                    = nullptr;
    QTimer              _commLostCheckTimer;
    QList<LinkInfo_t>   _rgLinkInfo;
    LinkInterface*      _primaryLink                = nullptr;
    bool                _communicationLost          = false;
    bool                _communicationLostEnabled   = true;
    bool                _autoDisconnect             = false;    ///< true: Automatically disconnect vehicle when last connection goes away or lost heartbeat

    static const int _commLostCheckTimeoutMSecs     = 1000;  // Check for comm lost once a second
    static const int _heartbeatMaxElpasedMSecs      = 3500;  // No heartbeat for longer than this indicates comm loss
};