Browse Source

ADSB: Fix and improve messages parsing and displaying

Fixes #10143 (#10170)
QGC4.4
Bartek Zdanowski 3 years ago committed by GitHub
parent
commit
aa727a3b04
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
  1. 7
      src/ADSB/ADSBVehicle.cc
  2. 8
      src/ADSB/ADSBVehicle.h
  3. 168
      src/ADSB/ADSBVehicleManager.cc
  4. 7
      src/ADSB/ADSBVehicleManager.h
  5. 2
      src/Vehicle/Vehicle.cc
  6. 2
      src/ui/preferences/GeneralSettings.qml

7
src/ADSB/ADSBVehicle.cc

@ -14,9 +14,10 @@
#include <QDebug> #include <QDebug>
#include <QtMath> #include <QtMath>
ADSBVehicle::ADSBVehicle(const VehicleInfo_t& vehicleInfo, QObject* parent) ADSBVehicle::ADSBVehicle(const ADSBVehicleInfo_t & vehicleInfo, QObject* parent)
: QObject (parent) : QObject (parent)
, _icaoAddress (vehicleInfo.icaoAddress) , _icaoAddress (vehicleInfo.icaoAddress)
, _coordinate (QGeoCoordinate(qQNaN(),qQNaN()))
, _altitude (qQNaN()) , _altitude (qQNaN())
, _heading (qQNaN()) , _heading (qQNaN())
, _alert (false) , _alert (false)
@ -24,12 +25,14 @@ ADSBVehicle::ADSBVehicle(const VehicleInfo_t& vehicleInfo, QObject* parent)
update(vehicleInfo); update(vehicleInfo);
} }
void ADSBVehicle::update(const VehicleInfo_t& vehicleInfo) void ADSBVehicle::update(const ADSBVehicleInfo_t & vehicleInfo)
{ {
if (_icaoAddress != vehicleInfo.icaoAddress) { if (_icaoAddress != vehicleInfo.icaoAddress) {
qCWarning(ADSBVehicleManagerLog) << "ICAO address mismatch expected:actual" << _icaoAddress << vehicleInfo.icaoAddress; qCWarning(ADSBVehicleManagerLog) << "ICAO address mismatch expected:actual" << _icaoAddress << vehicleInfo.icaoAddress;
return; return;
} }
qCDebug(ADSBVehicleManagerLog) << "Updating" << QStringLiteral("%1 Flags: %2").arg(vehicleInfo.icaoAddress, 0, 16).arg(vehicleInfo.availableFlags, 0, 2);
if (vehicleInfo.availableFlags & CallsignAvailable) { if (vehicleInfo.availableFlags & CallsignAvailable) {
if (vehicleInfo.callsign != _callsign) { if (vehicleInfo.callsign != _callsign) {
_callsign = vehicleInfo.callsign; _callsign = vehicleInfo.callsign;

8
src/ADSB/ADSBVehicle.h

@ -36,9 +36,9 @@ public:
double heading; double heading;
bool alert; bool alert;
uint32_t availableFlags; uint32_t availableFlags;
} VehicleInfo_t; } ADSBVehicleInfo_t;
ADSBVehicle(const VehicleInfo_t& vehicleInfo, QObject* parent); ADSBVehicle(const ADSBVehicleInfo_t & vehicleInfo, QObject* parent);
Q_PROPERTY(int icaoAddress READ icaoAddress CONSTANT) Q_PROPERTY(int icaoAddress READ icaoAddress CONSTANT)
Q_PROPERTY(QString callsign READ callsign NOTIFY callsignChanged) Q_PROPERTY(QString callsign READ callsign NOTIFY callsignChanged)
@ -54,7 +54,7 @@ public:
double heading (void) const { return _heading; } double heading (void) const { return _heading; }
bool alert (void) const { return _alert; } bool alert (void) const { return _alert; }
void update(const VehicleInfo_t& vehicleInfo); void update(const ADSBVehicleInfo_t & vehicleInfo);
/// check if the vehicle is expired and should be removed /// check if the vehicle is expired and should be removed
bool expired(); bool expired();
@ -80,5 +80,5 @@ private:
///< AirMap sends updates for each vehicle every second. ///< AirMap sends updates for each vehicle every second.
}; };
Q_DECLARE_METATYPE(ADSBVehicle::VehicleInfo_t) Q_DECLARE_METATYPE(ADSBVehicle::ADSBVehicleInfo_t)

168
src/ADSB/ADSBVehicleManager.cc

@ -23,7 +23,6 @@ ADSBVehicleManager::ADSBVehicleManager(QGCApplication* app, QGCToolbox* toolbox)
void ADSBVehicleManager::setToolbox(QGCToolbox* toolbox) void ADSBVehicleManager::setToolbox(QGCToolbox* toolbox)
{ {
QGCTool::setToolbox(toolbox); QGCTool::setToolbox(toolbox);
connect(&_adsbVehicleCleanupTimer, &QTimer::timeout, this, &ADSBVehicleManager::_cleanupStaleVehicles); connect(&_adsbVehicleCleanupTimer, &QTimer::timeout, this, &ADSBVehicleManager::_cleanupStaleVehicles);
_adsbVehicleCleanupTimer.setSingleShot(false); _adsbVehicleCleanupTimer.setSingleShot(false);
_adsbVehicleCleanupTimer.start(1000); _adsbVehicleCleanupTimer.start(1000);
@ -42,7 +41,7 @@ void ADSBVehicleManager::_cleanupStaleVehicles()
for (int i=_adsbVehicles.count()-1; i>=0; i--) { for (int i=_adsbVehicles.count()-1; i>=0; i--) {
ADSBVehicle* adsbVehicle = _adsbVehicles.value<ADSBVehicle*>(i); ADSBVehicle* adsbVehicle = _adsbVehicles.value<ADSBVehicle*>(i);
if (adsbVehicle->expired()) { if (adsbVehicle->expired()) {
qCDebug(ADSBVehicleManagerLog) << "Expired" << QStringLiteral("%1").arg(adsbVehicle->icaoAddress(), 0, 16); qCDebug(ADSBVehicleManagerLog) << "Expired " << QStringLiteral("%1").arg(adsbVehicle->icaoAddress(), 0, 16);
_adsbVehicles.removeAt(i); _adsbVehicles.removeAt(i);
_adsbICAOMap.remove(adsbVehicle->icaoAddress()); _adsbICAOMap.remove(adsbVehicle->icaoAddress());
adsbVehicle->deleteLater(); adsbVehicle->deleteLater();
@ -50,7 +49,7 @@ void ADSBVehicleManager::_cleanupStaleVehicles()
} }
} }
void ADSBVehicleManager::adsbVehicleUpdate(const ADSBVehicle::VehicleInfo_t vehicleInfo) void ADSBVehicleManager::adsbVehicleUpdate(const ADSBVehicle::ADSBVehicleInfo_t vehicleInfo)
{ {
uint32_t icaoAddress = vehicleInfo.icaoAddress; uint32_t icaoAddress = vehicleInfo.icaoAddress;
@ -61,6 +60,7 @@ void ADSBVehicleManager::adsbVehicleUpdate(const ADSBVehicle::VehicleInfo_t vehi
ADSBVehicle* adsbVehicle = new ADSBVehicle(vehicleInfo, this); ADSBVehicle* adsbVehicle = new ADSBVehicle(vehicleInfo, this);
_adsbICAOMap[icaoAddress] = adsbVehicle; _adsbICAOMap[icaoAddress] = adsbVehicle;
_adsbVehicles.append(adsbVehicle); _adsbVehicles.append(adsbVehicle);
qCDebug(ADSBVehicleManagerLog) << "Added " << QStringLiteral("%1").arg(adsbVehicle->icaoAddress(), 0, 16);
} }
} }
} }
@ -101,9 +101,7 @@ void ADSBTCPLink::run(void)
void ADSBTCPLink::_hardwareConnect() void ADSBTCPLink::_hardwareConnect()
{ {
_socket = new QTcpSocket(); _socket = new QTcpSocket();
QObject::connect(_socket, &QTcpSocket::readyRead, this, &ADSBTCPLink::_readBytes); QObject::connect(_socket, &QTcpSocket::readyRead, this, &ADSBTCPLink::_readBytes);
_socket->connectToHost(_hostAddress, static_cast<quint16>(_port)); _socket->connectToHost(_hostAddress, static_cast<quint16>(_port));
// Give the socket a second to connect to the other side otherwise error out // Give the socket a second to connect to the other side otherwise error out
@ -121,72 +119,110 @@ void ADSBTCPLink::_hardwareConnect()
void ADSBTCPLink::_readBytes(void) void ADSBTCPLink::_readBytes(void)
{ {
if (_socket) { if (_socket) {
QByteArray bytes = _socket->readLine(); while(_socket->canReadLine()) {
_parseLine(QString::fromLocal8Bit(bytes)); QByteArray bytes = _socket->readLine();
_parseLine(QString::fromLocal8Bit(bytes));
}
} }
} }
void ADSBTCPLink::_parseLine(const QString& line) void ADSBTCPLink::_parseLine(const QString &line)
{ {
if (line.startsWith(QStringLiteral("MSG"))) { if (line.startsWith(QStringLiteral("MSG"))) {
qCDebug(ADSBVehicleManagerLog) << "ADSB SBS-1" << line; bool icaoOk;
int msgType = line.at(4).digitValue();
QStringList values = line.split(QStringLiteral(",")); if (msgType == -1) {
qCDebug(ADSBVehicleManagerLog) << "ADSB Invalid message type " << line.at(4);
if (values[1] == QStringLiteral("3")) { return;
bool icaoOk, altOk, latOk, lonOk; }
// Skip unsupported mesg types to avoid parsing
uint32_t icaoAddress = values[4].toUInt(&icaoOk, 16); if (msgType == 2 || msgType > 6) {
int modeCAltitude = values[11].toInt(&altOk); return;
double lat = values[14].toDouble(&latOk); }
double lon = values[15].toDouble(&lonOk); qCDebug(ADSBVehicleManagerLog) << " ADSB SBS-1 " << line;
QString callsign = values[10]; QStringList values = line.split(QChar(','));
uint32_t icaoAddress = values[4].toUInt(&icaoOk, 16);
if (!icaoOk || !altOk || !latOk || !lonOk) {
return; if (!icaoOk) {
} return;
if (lat == 0 && lon == 0) { }
return;
} ADSBVehicle::ADSBVehicleInfo_t adsbInfo;
adsbInfo.icaoAddress = icaoAddress;
double altitude = modeCAltitude / 3.048;
QGeoCoordinate location(lat, lon); switch (msgType) {
case 1:
ADSBVehicle::VehicleInfo_t adsbInfo; case 5:
adsbInfo.icaoAddress = icaoAddress; case 6:
adsbInfo.callsign = callsign; _parseAndEmitCallsign(adsbInfo, values);
adsbInfo.location = location; break;
adsbInfo.altitude = altitude; case 3:
adsbInfo.availableFlags = ADSBVehicle::CallsignAvailable | ADSBVehicle::LocationAvailable | ADSBVehicle::AltitudeAvailable; _parseAndEmitLocation(adsbInfo, values);
emit adsbVehicleUpdate(adsbInfo); break;
} else if (values[1] == QStringLiteral("4")) { case 4:
bool icaoOk, headingOk; _parseAndEmitHeading(adsbInfo, values);
break;
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);
} }
} }
} }
void ADSBTCPLink::_parseAndEmitCallsign(ADSBVehicle::ADSBVehicleInfo_t &adsbInfo, QStringList values)
{
QString callsign = values[10].trimmed();
if (callsign.isEmpty()) {
return;
}
adsbInfo.callsign = callsign;
adsbInfo.availableFlags = ADSBVehicle::CallsignAvailable;
emit adsbVehicleUpdate(adsbInfo);
}
void ADSBTCPLink::_parseAndEmitLocation(ADSBVehicle::ADSBVehicleInfo_t &adsbInfo, QStringList values)
{
bool altOk, latOk, lonOk;
int modeCAltitude;
QString altitudeStr = values[11];
// Altitude is either Barometric - based on pressure, in ft
// or HAE - as reported by GPS - based on WGS84 Ellipsoid, in ft
// If altitude ends with H, we have HAE
// There's a slight difference between Barometric alt and HAE, but it would require
// knowledge about Geoid shape in particular Lat, Lon. It's not worth complicating the code
if (altitudeStr.endsWith('H')) {
altitudeStr.chop(1);
}
modeCAltitude = altitudeStr.toInt(&altOk);
double lat = values[14].toDouble(&latOk);
double lon = values[15].toDouble(&lonOk);
int alert = values[19].toInt();
if (!altOk || !latOk || !lonOk) {
return;
}
if (lat == 0 && lon == 0) {
return;
}
double altitude = modeCAltitude * 0.3048;
QGeoCoordinate location(lat, lon);
adsbInfo.location = location;
adsbInfo.altitude = altitude;
adsbInfo.alert = alert == 1;
adsbInfo.availableFlags = ADSBVehicle::LocationAvailable | ADSBVehicle::AltitudeAvailable | ADSBVehicle::AlertAvailable;
emit adsbVehicleUpdate(adsbInfo);
}
void ADSBTCPLink::_parseAndEmitHeading(ADSBVehicle::ADSBVehicleInfo_t &adsbInfo, QStringList values)
{
bool headingOk;
double heading = values[13].toDouble(&headingOk);
if (!headingOk) {
return;
}
adsbInfo.heading = heading;
adsbInfo.availableFlags = ADSBVehicle::HeadingAvailable;
emit adsbVehicleUpdate(adsbInfo);
}

7
src/ADSB/ADSBVehicleManager.h

@ -29,7 +29,7 @@ public:
~ADSBTCPLink(); ~ADSBTCPLink();
signals: signals:
void adsbVehicleUpdate(const ADSBVehicle::VehicleInfo_t vehicleInfo); void adsbVehicleUpdate(const ADSBVehicle::ADSBVehicleInfo_t vehicleInfo);
void error(const QString errorMsg); void error(const QString errorMsg);
protected: protected:
@ -45,6 +45,9 @@ private:
QString _hostAddress; QString _hostAddress;
int _port; int _port;
QTcpSocket* _socket = nullptr; QTcpSocket* _socket = nullptr;
void _parseAndEmitCallsign(ADSBVehicle::ADSBVehicleInfo_t &adsbInfo, QStringList values);
void _parseAndEmitLocation(ADSBVehicle::ADSBVehicleInfo_t &adsbInfo, QStringList values);
void _parseAndEmitHeading(ADSBVehicle::ADSBVehicleInfo_t &adsbInfo, QStringList values);
}; };
class ADSBVehicleManager : public QGCTool { class ADSBVehicleManager : public QGCTool {
@ -61,7 +64,7 @@ public:
void setToolbox(QGCToolbox* toolbox) final; void setToolbox(QGCToolbox* toolbox) final;
public slots: public slots:
void adsbVehicleUpdate (const ADSBVehicle::VehicleInfo_t vehicleInfo); void adsbVehicleUpdate (const ADSBVehicle::ADSBVehicleInfo_t vehicleInfo);
void _tcpError (const QString errorMsg); void _tcpError (const QString errorMsg);
private slots: private slots:

2
src/Vehicle/Vehicle.cc

@ -3585,7 +3585,7 @@ void Vehicle::_handleADSBVehicle(const mavlink_message_t& message)
mavlink_msg_adsb_vehicle_decode(&message, &adsbVehicleMsg); mavlink_msg_adsb_vehicle_decode(&message, &adsbVehicleMsg);
if ((adsbVehicleMsg.flags & ADSB_FLAGS_VALID_COORDS) && adsbVehicleMsg.tslc <= maxTimeSinceLastSeen) { if ((adsbVehicleMsg.flags & ADSB_FLAGS_VALID_COORDS) && adsbVehicleMsg.tslc <= maxTimeSinceLastSeen) {
ADSBVehicle::VehicleInfo_t vehicleInfo; ADSBVehicle::ADSBVehicleInfo_t vehicleInfo;
vehicleInfo.availableFlags = 0; vehicleInfo.availableFlags = 0;
vehicleInfo.icaoAddress = adsbVehicleMsg.ICAO_address; vehicleInfo.icaoAddress = adsbVehicleMsg.ICAO_address;

2
src/ui/preferences/GeneralSettings.qml

@ -1030,7 +1030,7 @@ Rectangle {
FactTextField { FactTextField {
fact: adsbGrid.adsbSettings.adsbServerHostAddress fact: adsbGrid.adsbSettings.adsbServerHostAddress
visible: adsbGrid.adsbSettings.adsbServerHostAddress.visible visible: adsbGrid.adsbSettings.adsbServerHostAddress.visible
Layout.preferredWidth: _valueFieldWidth Layout.fillWidth: true
} }
QGCLabel { QGCLabel {

Loading…
Cancel
Save