ADSBVehicleManager.cc 6.33 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 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192
/****************************************************************************
 *
 * (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.
 *
 ****************************************************************************/

#include "ADSBVehicleManager.h"
#include "QGCLoggingCategory.h"
#include "QGCApplication.h"
#include "SettingsManager.h"
#include "ADSBVehicleManagerSettings.h"

#include <QDebug>

ADSBVehicleManager::ADSBVehicleManager(QGCApplication* app, QGCToolbox* toolbox)
    : QGCTool(app, toolbox)
{
}

void ADSBVehicleManager::setToolbox(QGCToolbox* toolbox)
{
    QGCTool::setToolbox(toolbox);

    connect(&_adsbVehicleCleanupTimer, &QTimer::timeout, this, &ADSBVehicleManager::_cleanupStaleVehicles);
    _adsbVehicleCleanupTimer.setSingleShot(false);
    _adsbVehicleCleanupTimer.start(1000);

    ADSBVehicleManagerSettings* settings = qgcApp()->toolbox()->settingsManager()->adsbVehicleManagerSettings();
    if (settings->adsbServerConnectEnabled()->rawValue().toBool()) {
        _tcpLink = new ADSBTCPLink(settings->adsbServerHostAddress()->rawValue().toString(), settings->adsbServerPort()->rawValue().toInt(), this);
        connect(_tcpLink, &ADSBTCPLink::adsbVehicleUpdate,  this, &ADSBVehicleManager::adsbVehicleUpdate,   Qt::QueuedConnection);
        connect(_tcpLink, &ADSBTCPLink::error,              this, &ADSBVehicleManager::_tcpError,           Qt::QueuedConnection);
    }
}

void ADSBVehicleManager::_cleanupStaleVehicles()
{
    // Remove all expired ADSB vehicles
    for (int i=_adsbVehicles.count()-1; i>=0; i--) {
        ADSBVehicle* adsbVehicle = _adsbVehicles.value<ADSBVehicle*>(i);
        if (adsbVehicle->expired()) {
            qCDebug(ADSBVehicleManagerLog) << "Expired" << QStringLiteral("%1").arg(adsbVehicle->icaoAddress(), 0, 16);
            _adsbVehicles.removeAt(i);
            _adsbICAOMap.remove(adsbVehicle->icaoAddress());
            adsbVehicle->deleteLater();
        }
    }
}

void ADSBVehicleManager::adsbVehicleUpdate(const ADSBVehicle::VehicleInfo_t vehicleInfo)
{
    uint32_t icaoAddress = vehicleInfo.icaoAddress;

    if (_adsbICAOMap.contains(icaoAddress)) {
        _adsbICAOMap[icaoAddress]->update(vehicleInfo);
    } else {
        if (vehicleInfo.availableFlags & ADSBVehicle::LocationAvailable) {
            ADSBVehicle* adsbVehicle = new ADSBVehicle(vehicleInfo, this);
            _adsbICAOMap[icaoAddress] = adsbVehicle;
            _adsbVehicles.append(adsbVehicle);
        }
    }
}

void ADSBVehicleManager::_tcpError(const QString errorMsg)
{
    qgcApp()->showAppMessage(tr("ADSB Server Error: %1").arg(errorMsg));
}


ADSBTCPLink::ADSBTCPLink(const QString& hostAddress, int port, QObject* parent)
    : QThread       (parent)
    , _hostAddress  (hostAddress)
    , _port         (port)
{
    moveToThread(this);
    start();
}

ADSBTCPLink::~ADSBTCPLink(void)
{
    if (_socket) {
        QObject::disconnect(_socket, &QTcpSocket::readyRead, this, &ADSBTCPLink::_readBytes);
        _socket->disconnectFromHost();
        _socket->deleteLater();
        _socket = nullptr;
    }
    quit();
    wait();
}

void ADSBTCPLink::run(void)
{
    _hardwareConnect();
    exec();
}

void ADSBTCPLink::_hardwareConnect()
{
    _socket = new QTcpSocket();

    QObject::connect(_socket, &QTcpSocket::readyRead, this, &ADSBTCPLink::_readBytes);

    _socket->connectToHost(_hostAddress, static_cast<quint16>(_port));

    // Give the socket a second to connect to the other side otherwise error out
    if (!_socket->waitForConnected(1000)) {
        qCDebug(ADSBVehicleManagerLog) << "ADSB Socket failed to connect";
        emit error(_socket->errorString());
        delete _socket;
        _socket = nullptr;
        return;
    }

    qCDebug(ADSBVehicleManagerLog) << "ADSB Socket connected";
}

void ADSBTCPLink::_readBytes(void)
{
    if (_socket) {
        QByteArray bytes = _socket->readLine();
        _parseLine(QString::fromLocal8Bit(bytes));
    }
}

void ADSBTCPLink::_parseLine(const QString& line)
{
    if (line.startsWith(QStringLiteral("MSG"))) {
        qCDebug(ADSBVehicleManagerLog) << "ADSB SBS-1" << line;

        QStringList values = line.split(QStringLiteral(","));

        if (values[1] == QStringLiteral("3")) {
            bool icaoOk, altOk, latOk, lonOk;

            uint32_t    icaoAddress =   values[4].toUInt(&icaoOk, 16);
            int         modeCAltitude = values[11].toInt(&altOk);
            double      lat =           values[14].toDouble(&latOk);
            double      lon =           values[15].toDouble(&lonOk);
            QString     callsign =      values[10];

            if (!icaoOk || !altOk || !latOk || !lonOk) {
                return;
            }
            if (lat == 0 && lon == 0) {
                return;
            }

            double altitude = modeCAltitude / 3.048;
            QGeoCoordinate location(lat, lon);

            ADSBVehicle::VehicleInfo_t adsbInfo;
            adsbInfo.icaoAddress = icaoAddress;
            adsbInfo.callsign = callsign;
            adsbInfo.location = location;
            adsbInfo.altitude = altitude;
            adsbInfo.availableFlags = ADSBVehicle::CallsignAvailable | ADSBVehicle::LocationAvailable | ADSBVehicle::AltitudeAvailable;
            emit adsbVehicleUpdate(adsbInfo);
        } else if (values[1] == QStringLiteral("4")) {
            bool icaoOk, headingOk;

            uint32_t    icaoAddress =   values[4].toUInt(&icaoOk, 16);
            double      heading =       values[13].toDouble(&headingOk);

            if (!icaoOk || !headingOk) {
                return;
            }

            ADSBVehicle::VehicleInfo_t adsbInfo;
            adsbInfo.icaoAddress = icaoAddress;
            adsbInfo.heading = heading;
            adsbInfo.availableFlags = ADSBVehicle::HeadingAvailable;
            emit adsbVehicleUpdate(adsbInfo);
        } else if (values[1] == QStringLiteral("1")) {
            bool icaoOk;

            uint32_t icaoAddress = values[4].toUInt(&icaoOk, 16);
            if (!icaoOk) {
                return;
            }

            ADSBVehicle::VehicleInfo_t adsbInfo;
            adsbInfo.icaoAddress = icaoAddress;
            adsbInfo.callsign = values[10];
            adsbInfo.availableFlags = ADSBVehicle::CallsignAvailable;
            emit adsbVehicleUpdate(adsbInfo);
        }
    }
}