Skip to content

Commit

Permalink
ADSB: Handle Missing Data
Browse files Browse the repository at this point in the history
  • Loading branch information
HTRamsey committed Nov 22, 2024
1 parent fb11f31 commit a3e7464
Show file tree
Hide file tree
Showing 10 changed files with 220 additions and 100 deletions.
29 changes: 19 additions & 10 deletions src/ADSB/ADSB.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,24 +38,33 @@ Q_ENUM_NS(MessageType)

/// Enum for ADSB Info Types Available.
enum AvailableInfoType {
CallsignAvailable = 1 << 0,
LocationAvailable = 1 << 1,
AltitudeAvailable = 1 << 2,
HeadingAvailable = 1 << 3,
AlertAvailable = 1 << 4,
LocationAvailable = 1 << 0,
AltitudeAvailable = 1 << 1,
HeadingAvailable = 1 << 2,
VelocityAvailable = 1 << 3,
CallsignAvailable = 1 << 4,
SquawkAvailable = 1 << 5,
VerticalVelAvailable = 1 << 6,
AlertAvailable = 1 << 7
};
Q_FLAG_NS(AvailableInfoType)
Q_DECLARE_FLAGS(AvailableInfoTypes, AvailableInfoType)
Q_DECLARE_OPERATORS_FOR_FLAGS(AvailableInfoTypes)

struct VehicleInfo_t {
uint32_t icaoAddress;
AvailableInfoTypes availableFlags;
uint32_t icaoAddress = 0;
QString callsign;
QGeoCoordinate location;
double altitude; // TODO: Use Altitude in QGeoCoordinate?
double heading;
bool alert;
AvailableInfoTypes availableFlags;
double heading = 0.0;
uint16_t squawk = 0;
double velocity = 0.0;
double verticalVel = 0.0;
uint32_t lastContact = 0;
bool simulated = false;
bool baro = false;
bool alert = false;
// TODO: Use QGeoPositionInfo, QGeoPositionInfoSource, QGeoPositionInfoSourceFactory
};
} // namespace ADSB

Expand Down
43 changes: 21 additions & 22 deletions src/ADSB/ADSBTCPLink.cc
Original file line number Diff line number Diff line change
Expand Up @@ -24,24 +24,26 @@ ADSBTCPLink::ADSBTCPLink(const QHostAddress &hostAddress, quint16 port, QObject
, _processTimer(new QTimer(this))
{
#ifdef QT_DEBUG
(void) connect(_socket, &QTcpSocket::stateChanged, this, [](QTcpSocket::SocketState state) {
switch (state) {
case QTcpSocket::UnconnectedState:
qCDebug(ADSBTCPLinkLog) << "ADSB Socket disconnected";
break;
case QTcpSocket::SocketState::ConnectingState:
qCDebug(ADSBTCPLinkLog) << "ADSB Socket connecting...";
break;
case QTcpSocket::SocketState::ConnectedState:
qCDebug(ADSBTCPLinkLog) << "ADSB Socket connected";
break;
case QTcpSocket::SocketState::ClosingState:
qCDebug(ADSBTCPLinkLog) << "ADSB Socket closing...";
break;
default:
break;
}
}, Qt::AutoConnection);
if (ADSBTCPLinkLog().isDebugEnabled()) {
(void) connect(_socket, &QTcpSocket::stateChanged, this, [](QTcpSocket::SocketState state) {
switch (state) {
case QTcpSocket::UnconnectedState:
qCDebug(ADSBTCPLinkLog) << "ADSB Socket disconnected";
break;
case QTcpSocket::SocketState::ConnectingState:
qCDebug(ADSBTCPLinkLog) << "ADSB Socket connecting...";
break;
case QTcpSocket::SocketState::ConnectedState:
qCDebug(ADSBTCPLinkLog) << "ADSB Socket connected";
break;
case QTcpSocket::SocketState::ClosingState:
qCDebug(ADSBTCPLinkLog) << "ADSB Socket closing...";
break;
default:
break;
}
}, Qt::AutoConnection);
}
#endif

(void) QObject::connect(_socket, &QTcpSocket::errorOccurred, this, [this](QTcpSocket::SocketError error) {
Expand All @@ -55,8 +57,6 @@ ADSBTCPLink::ADSBTCPLink(const QHostAddress &hostAddress, quint16 port, QObject
_processTimer->setInterval(_processInterval); // Set an interval for processing lines
(void) connect(_processTimer, &QTimer::timeout, this, &ADSBTCPLink::_processLines);

init();

// qCDebug(ADSBTCPLinkLog) << Q_FUNC_INFO << this;
}

Expand Down Expand Up @@ -209,10 +209,9 @@ void ADSBTCPLink::_parseAndEmitLocation(ADSB::VehicleInfo_t &adsbInfo, const QSt
}

const double altitude = modeCAltitude * 0.3048;
const QGeoCoordinate location(lat, lon);
const QGeoCoordinate location(lat, lon, altitude);

adsbInfo.location = location;
adsbInfo.altitude = altitude;
adsbInfo.alert = (alert == 1);
adsbInfo.availableFlags = ADSB::LocationAvailable | ADSB::AltitudeAvailable | ADSB::AlertAvailable;

Expand Down
52 changes: 37 additions & 15 deletions src/ADSB/ADSBVehicle.cc
Original file line number Diff line number Diff line change
Expand Up @@ -18,15 +18,15 @@ QGC_LOGGING_CATEGORY(ADSBVehicleLog, "qgc.adsb.adsbvehicle")
ADSBVehicle::ADSBVehicle(const ADSB::VehicleInfo_t &vehicleInfo, QObject *parent)
: QObject(parent)
{
// qCDebug(ADSBVehicleLog) << Q_FUNC_INFO << this;

_info.icaoAddress = vehicleInfo.icaoAddress;
update(vehicleInfo);

// qCDebug(ADSBTCPLinkLog) << Q_FUNC_INFO << this;
}

ADSBVehicle::~ADSBVehicle()
{
// qCDebug(ADSBTCPLinkLog) << Q_FUNC_INFO << this;
// qCDebug(ADSBVehicleLog) << Q_FUNC_INFO << this;
}

void ADSBVehicle::update(const ADSB::VehicleInfo_t &vehicleInfo)
Expand All @@ -38,23 +38,17 @@ void ADSBVehicle::update(const ADSB::VehicleInfo_t &vehicleInfo)

qCDebug(ADSBVehicleLog) << "Updating" << QStringLiteral("%1 Flags: %2").arg(vehicleInfo.icaoAddress, 0, 16).arg(vehicleInfo.availableFlags, 0, 2);

if (vehicleInfo.availableFlags & ADSB::CallsignAvailable) {
if (vehicleInfo.callsign != callsign()) {
_info.callsign = vehicleInfo.callsign;
emit callsignChanged();
}
}

if (vehicleInfo.availableFlags & ADSB::LocationAvailable) {
if (vehicleInfo.location != coordinate()) {
_info.location = vehicleInfo.location;
if (!QGC::fuzzyCompare(vehicleInfo.location.latitude(), coordinate().latitude()) || !QGC::fuzzyCompare(vehicleInfo.location.longitude(), coordinate().longitude())) {
_info.location.setLatitude(vehicleInfo.location.latitude());
_info.location.setLongitude(vehicleInfo.location.longitude());
emit coordinateChanged();
}
}

if (vehicleInfo.availableFlags & ADSB::AltitudeAvailable) {
if (!QGC::fuzzyCompare(vehicleInfo.altitude, altitude())) {
_info.altitude = vehicleInfo.altitude;
if (!QGC::fuzzyCompare(vehicleInfo.location.altitude(), altitude())) {
_info.location.setAltitude(vehicleInfo.location.altitude());
emit altitudeChanged();
}
}
Expand All @@ -66,12 +60,40 @@ void ADSBVehicle::update(const ADSB::VehicleInfo_t &vehicleInfo)
}
}

if (vehicleInfo.availableFlags & ADSB::VelocityAvailable) {
if (!QGC::fuzzyCompare(vehicleInfo.velocity, velocity())) {
_info.velocity = vehicleInfo.velocity;
emit velocityChanged();
}
}

if (vehicleInfo.availableFlags & ADSB::CallsignAvailable) {
if (vehicleInfo.callsign != callsign()) {
_info.callsign = vehicleInfo.callsign;
emit callsignChanged();
}
}

if (vehicleInfo.availableFlags & ADSB::SquawkAvailable) {
if (!QGC::fuzzyCompare(vehicleInfo.velocity, squawk())) {
_info.squawk = vehicleInfo.squawk;
emit squawkChanged();
}
}

if (vehicleInfo.availableFlags & ADSB::VerticalVelAvailable) {
if (!QGC::fuzzyCompare(vehicleInfo.verticalVel, verticalVel())) {
_info.verticalVel = vehicleInfo.verticalVel;
emit verticalVelChanged();
}
}

if (vehicleInfo.availableFlags & ADSB::AlertAvailable) {
if (vehicleInfo.alert != alert()) {
_info.alert = vehicleInfo.alert;
emit alertChanged();
}
}

(void) _lastUpdateTimer.restart();
_lastUpdateTimer.start();
}
23 changes: 16 additions & 7 deletions src/ADSB/ADSBVehicle.h
Original file line number Diff line number Diff line change
Expand Up @@ -25,12 +25,15 @@ class ADSBVehicle : public QObject
Q_OBJECT
QML_ELEMENT

Q_PROPERTY(uint icaoAddress READ icaoAddress CONSTANT)
Q_PROPERTY(QString callsign READ callsign NOTIFY callsignChanged)
Q_PROPERTY(QGeoCoordinate coordinate READ coordinate NOTIFY coordinateChanged)
Q_PROPERTY(double altitude READ altitude NOTIFY altitudeChanged)
Q_PROPERTY(double heading READ heading NOTIFY headingChanged)
Q_PROPERTY(bool alert READ alert NOTIFY alertChanged)
Q_PROPERTY(uint icaoAddress READ icaoAddress CONSTANT)
Q_PROPERTY(QString callsign READ callsign NOTIFY callsignChanged)
Q_PROPERTY(QGeoCoordinate coordinate READ coordinate NOTIFY coordinateChanged)
Q_PROPERTY(double altitude READ altitude NOTIFY altitudeChanged)
Q_PROPERTY(double heading READ heading NOTIFY headingChanged)
Q_PROPERTY(double velocity READ velocity NOTIFY velocityChanged)
Q_PROPERTY(double verticalVel READ verticalVel NOTIFY verticalVelChanged)
Q_PROPERTY(uint16_t squawk READ squawk NOTIFY squawkChanged)
Q_PROPERTY(bool alert READ alert NOTIFY alertChanged)

public:
explicit ADSBVehicle(const ADSB::VehicleInfo_t &vehicleInfo, QObject *parent = nullptr);
Expand All @@ -39,8 +42,11 @@ class ADSBVehicle : public QObject
uint32_t icaoAddress() const { return _info.icaoAddress; }
QString callsign() const { return _info.callsign; }
QGeoCoordinate coordinate() const { return _info.location; }
double altitude() const { return _info.altitude; }
double altitude() const { return _info.location.altitude(); }
double heading() const { return _info.heading; }
double velocity() const { return _info.velocity; }
double verticalVel() const { return _info.verticalVel; }
uint16_t squawk() const { return _info.squawk; }
bool alert() const { return _info.alert; }
bool expired() const { return _lastUpdateTimer.hasExpired(_expirationTimeoutMs); }
void update(const ADSB::VehicleInfo_t &vehicleInfo);
Expand All @@ -50,6 +56,9 @@ class ADSBVehicle : public QObject
void callsignChanged();
void altitudeChanged();
void headingChanged();
void velocityChanged();
void verticalVelChanged();
void squawkChanged();
void alertChanged();

private:
Expand Down
Loading

0 comments on commit a3e7464

Please sign in to comment.