ADSBVehicle.h 2.36 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);

25 26
    ADSBVehicle(const QGeoCoordinate& location, float heading, QObject* parent = NULL);

27
    Q_PROPERTY(int              icaoAddress READ icaoAddress    CONSTANT)
28
    Q_PROPERTY(QString          callsign    READ callsign       NOTIFY callsignChanged)
29 30 31 32 33
    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

    int             icaoAddress (void) const { return _icaoAddress; }
34
    QString         callsign    (void) const { return _callsign; }
35 36 37 38 39 40 41
    QGeoCoordinate  coordinate  (void) const { return _coordinate; }
    double          altitude    (void) const { return _altitude; }
    double          heading     (void) const { return _heading; }

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

42
    void update(const QGeoCoordinate& location, float heading);
43 44 45 46

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

47 48
signals:
    void coordinateChanged(QGeoCoordinate coordinate);
49
    void callsignChanged(QString callsign);
50 51 52 53
    void altitudeChanged(double altitude);
    void headingChanged(double heading);

private:
54 55 56
    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.

57
    uint32_t        _icaoAddress;
58
    QString         _callsign;
59 60 61
    QGeoCoordinate  _coordinate;
    double          _altitude;
    double          _heading;
62 63

    QElapsedTimer   _lastUpdateTimer;
64
};