ADSBVehicle.h 2.71 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13
/****************************************************************************
 *
 *   (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.
 *
 ****************************************************************************/

#pragma once

#include <QObject>
#include <QGeoCoordinate>
14
#include <QElapsedTimer>
15 16 17 18 19 20 21 22 23 24

#include "QGCMAVLink.h"

class ADSBVehicle : public QObject
{
    Q_OBJECT

public:
    ADSBVehicle(mavlink_adsb_vehicle_t& adsbVehicle, QObject* parent = NULL);

Gus Grubba's avatar
Gus Grubba committed
25
    ADSBVehicle(const QGeoCoordinate& location, float heading, bool alert = false, QObject* parent = NULL);
26

27
    Q_PROPERTY(int              icaoAddress READ icaoAddress    CONSTANT)
28
    Q_PROPERTY(QString          callsign    READ callsign       NOTIFY callsignChanged)
29 30 31
    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
32
    Q_PROPERTY(bool             alert       READ alert          NOTIFY alertChanged)        // Collision path
33 34

    int             icaoAddress (void) const { return _icaoAddress; }
35
    QString         callsign    (void) const { return _callsign; }
36 37 38
    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
39
    bool            alert       (void) const { return _alert; }
40 41 42 43

    /// Update the vehicle with new information
    void update(mavlink_adsb_vehicle_t& adsbVehicle);

Gus Grubba's avatar
Gus Grubba committed
44
    void update(bool alert, const QGeoCoordinate& location, float heading);
45 46 47 48

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

49
signals:
Gus Grubba's avatar
Gus Grubba committed
50 51 52 53 54
    void coordinateChanged  ();
    void callsignChanged    ();
    void altitudeChanged    ();
    void headingChanged     ();
    void alertChanged       ();
55 56

private:
Gus Grubba's avatar
Gus Grubba committed
57
    /* According with Thomas Voß, we should be using 2 minutes for the time being
58 59
    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
60 61
    */
    static constexpr qint64 expirationTimeoutMs = 120000;
62

63
    uint32_t        _icaoAddress;
64
    QString         _callsign;
65 66 67
    QGeoCoordinate  _coordinate;
    double          _altitude;
    double          _heading;
Gus Grubba's avatar
Gus Grubba committed
68
    bool            _alert;
69 70

    QElapsedTimer   _lastUpdateTimer;
71
};