ADSBVehicle.cc 2.14 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17
/****************************************************************************
 *
 *   (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.
 *
 ****************************************************************************/

#include "ADSBVehicle.h"

#include <QDebug>
#include <QtMath>

ADSBVehicle::ADSBVehicle(mavlink_adsb_vehicle_t& adsbVehicle, QObject* parent)
    : QObject       (parent)
    , _icaoAddress  (adsbVehicle.ICAO_address)
18
    , _callsign     (adsbVehicle.callsign)
19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40
    , _altitude     (NAN)
    , _heading      (NAN)
{
    if (!(adsbVehicle.flags | ADSB_FLAGS_VALID_COORDS)) {
        qWarning() << "At least coords must be valid";
        return;
    }

    update(adsbVehicle);
}

void ADSBVehicle::update(mavlink_adsb_vehicle_t& adsbVehicle)
{
    if (_icaoAddress != adsbVehicle.ICAO_address) {
        qWarning() << "ICAO address mismatch expected:actual" << _icaoAddress << adsbVehicle.ICAO_address;
        return;
    }

    if (!(adsbVehicle.flags | ADSB_FLAGS_VALID_COORDS)) {
        return;
    }

41 42 43 44 45 46 47 48
    QString currCallsign(adsbVehicle.callsign);

    if (currCallsign != _callsign) {
        _callsign = currCallsign;
        emit callsignChanged(_callsign);
    }

    QGeoCoordinate newCoordinate(adsbVehicle.lat / 1e7, adsbVehicle.lon / 1e7);
49 50 51 52 53 54 55
    if (newCoordinate != _coordinate) {
        _coordinate = newCoordinate;
        emit coordinateChanged(_coordinate);
    }

    double newAltitude = NAN;
    if (adsbVehicle.flags | ADSB_FLAGS_VALID_ALTITUDE) {
56
        newAltitude = (double)adsbVehicle.altitude / 1e3;
57 58 59 60 61 62 63 64 65 66 67 68 69 70 71
    }
    if (!(qIsNaN(newAltitude) && qIsNaN(_altitude)) && !qFuzzyCompare(newAltitude, _altitude)) {
        _altitude = newAltitude;
        emit altitudeChanged(_altitude);
    }

    double newHeading = NAN;
    if (adsbVehicle.flags | ADSB_FLAGS_VALID_HEADING) {
        newHeading = (double)adsbVehicle.heading / 100.0;
    }
    if (!(qIsNaN(newHeading) && qIsNaN(_heading)) && !qFuzzyCompare(newHeading, _heading)) {
        _heading = newHeading;
        emit headingChanged(_heading);
    }
}