ADSBVehicleManager.h 1.87 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
/****************************************************************************
 *
 *   (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 "QGCToolbox.h"
#include "QmlObjectListModel.h"
#include "ADSBVehicle.h"

#include <QThread>
#include <QTcpSocket>
#include <QTimer>
#include <QGeoCoordinate>

class ADSBVehicleManagerSettings;

class ADSBTCPLink : public QThread
{
    Q_OBJECT

public:
28
    ADSBTCPLink(const QString& hostAddress, int port, QObject* parent);
29 30 31 32
    ~ADSBTCPLink();

signals:
    void adsbVehicleUpdate(const ADSBVehicle::VehicleInfo_t vehicleInfo);
DonLakeFlyer's avatar
DonLakeFlyer committed
33
    void error(const QString errorMsg);
34 35 36 37 38 39 40 41 42 43 44

protected:
    void run(void) final;

private slots:
    void _readBytes(void);

private:
    void _hardwareConnect(void);
    void _parseLine(const QString& line);

45 46 47
    QString         _hostAddress;
    int             _port;
    QTcpSocket*     _socket =   nullptr;
48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63
};

class ADSBVehicleManager : public QGCTool {
    Q_OBJECT
    
public:
    ADSBVehicleManager(QGCApplication* app, QGCToolbox* toolbox);

    Q_PROPERTY(QmlObjectListModel* adsbVehicles READ adsbVehicles CONSTANT)

    QmlObjectListModel* adsbVehicles(void) { return &_adsbVehicles; }

    // QGCTool overrides
    void setToolbox(QGCToolbox* toolbox) final;

public slots:
DonLakeFlyer's avatar
DonLakeFlyer committed
64 65
    void adsbVehicleUpdate  (const ADSBVehicle::VehicleInfo_t vehicleInfo);
    void _tcpError          (const QString errorMsg);
66 67 68 69 70 71 72 73 74 75

private slots:
    void _cleanupStaleVehicles(void);

private:
    QmlObjectListModel              _adsbVehicles;
    QMap<uint32_t, ADSBVehicle*>    _adsbICAOMap;
    QTimer                          _adsbVehicleCleanupTimer;
    ADSBTCPLink*                    _tcpLink = nullptr;
};