ADSBVehicle.h 3.04 KB
Newer Older
1 2
/****************************************************************************
 *
Gus Grubba's avatar
Gus Grubba committed
3
 * (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
4 5 6 7 8 9 10 11 12 13
 *
 * 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 <QGeoCoordinate>
14
#include <QElapsedTimer>
15 16 17 18 19 20 21 22

#include "QGCMAVLink.h"

class ADSBVehicle : public QObject
{
    Q_OBJECT

public:
23 24 25 26 27 28 29
    enum {
        CallsignAvailable =     1 << 1,
        LocationAvailable =     1 << 2,
        AltitudeAvailable =     1 << 3,
        HeadingAvailable =      1 << 4,
        AlertAvailable =        1 << 5,
    };
30

31 32 33 34 35 36 37 38 39 40 41
    typedef struct {
        uint32_t        icaoAddress;    // Required
        QString         callsign;
        QGeoCoordinate  location;
        double          altitude;
        double          heading;
        bool            alert;
        uint32_t        availableFlags;
    } VehicleInfo_t;

    ADSBVehicle(const VehicleInfo_t& vehicleInfo, QObject* parent);
42

43
    Q_PROPERTY(int              icaoAddress READ icaoAddress    CONSTANT)
44
    Q_PROPERTY(QString          callsign    READ callsign       NOTIFY callsignChanged)
45 46 47
    Q_PROPERTY(QGeoCoordinate   coordinate  READ coordinate     NOTIFY coordinateChanged)
    Q_PROPERTY(double           altitude    READ altitude       NOTIFY altitudeChanged)     // NaN for not available
    Q_PROPERTY(double           heading     READ heading        NOTIFY headingChanged)      // NaN for not available
Gus Grubba's avatar
Gus Grubba committed
48
    Q_PROPERTY(bool             alert       READ alert          NOTIFY alertChanged)        // Collision path
49

50
    int             icaoAddress (void) const { return static_cast<int>(_icaoAddress); }
51
    QString         callsign    (void) const { return _callsign; }
52 53 54
    QGeoCoordinate  coordinate  (void) const { return _coordinate; }
    double          altitude    (void) const { return _altitude; }
    double          heading     (void) const { return _heading; }
Gus Grubba's avatar
Gus Grubba committed
55
    bool            alert       (void) const { return _alert; }
56

57
    void update(const VehicleInfo_t& vehicleInfo);
58 59 60 61

    /// check if the vehicle is expired and should be removed
    bool expired();

62
signals:
Gus Grubba's avatar
Gus Grubba committed
63 64 65 66 67
    void coordinateChanged  ();
    void callsignChanged    ();
    void altitudeChanged    ();
    void headingChanged     ();
    void alertChanged       ();
68 69

private:
Gus Grubba's avatar
Gus Grubba committed
70
    /* According with Thomas Voß, we should be using 2 minutes for the time being
71 72
    static constexpr qint64 expirationTimeoutMs = 5000; ///< timeout with no update in ms after which the vehicle is removed.
                                                        ///< AirMap sends updates for each vehicle every second.
Gus Grubba's avatar
Gus Grubba committed
73 74
    */
    static constexpr qint64 expirationTimeoutMs = 120000;
75

76
    uint32_t        _icaoAddress;
77
    QString         _callsign;
78 79 80
    QGeoCoordinate  _coordinate;
    double          _altitude;
    double          _heading;
Gus Grubba's avatar
Gus Grubba committed
81
    bool            _alert;
82 83

    QElapsedTimer   _lastUpdateTimer;
84
};
85 86 87

Q_DECLARE_METATYPE(ADSBVehicle::VehicleInfo_t)