Skip to content
ADSBVehicle.h 2.91 KiB
Newer Older
/****************************************************************************
 *
Gus Grubba's avatar
Gus Grubba committed
 * (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 <QGeoCoordinate>

#include "QGCMAVLink.h"

class ADSBVehicle : public QObject
{
    Q_OBJECT

public:
DonLakeFlyer's avatar
 
DonLakeFlyer committed
    enum {
        CallsignAvailable =     1 << 1,
        LocationAvailable =     1 << 2,
        AltitudeAvailable =     1 << 3,
        HeadingAvailable =      1 << 4,
        AlertAvailable =        1 << 5,
    };
DonLakeFlyer's avatar
 
DonLakeFlyer committed
    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);
    Q_PROPERTY(int              icaoAddress READ icaoAddress    CONSTANT)
    Q_PROPERTY(QString          callsign    READ callsign       NOTIFY callsignChanged)
    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
    Q_PROPERTY(bool             alert       READ alert          NOTIFY alertChanged)        // Collision path
DonLakeFlyer's avatar
 
DonLakeFlyer committed
    int             icaoAddress (void) const { return static_cast<int>(_icaoAddress); }
    QString         callsign    (void) const { return _callsign; }
    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
    bool            alert       (void) const { return _alert; }
DonLakeFlyer's avatar
 
DonLakeFlyer committed
    void update(const VehicleInfo_t& vehicleInfo);

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

signals:
Gus Grubba's avatar
Gus Grubba committed
    void coordinateChanged  ();
    void callsignChanged    ();
    void altitudeChanged    ();
    void headingChanged     ();
    void alertChanged       ();

private:
    uint32_t        _icaoAddress;
    QString         _callsign;
    QGeoCoordinate  _coordinate;
    double          _altitude;
    double          _heading;
Gus Grubba's avatar
Gus Grubba committed
    bool            _alert;

    static constexpr qint64 expirationTimeoutMs = 120000;   ///< timeout with no update in ms after which the vehicle is removed.
                                                            ///< AirMap sends updates for each vehicle every second.
DonLakeFlyer's avatar
 
DonLakeFlyer committed

Q_DECLARE_METATYPE(ADSBVehicle::VehicleInfo_t)