11#include <QtCore/QApplicationStatic>
12#include <QtCore/QTimer>
21 , _adsbSettings(settings)
22 , _adsbVehicleCleanupTimer(new QTimer(this))
27 (void) qRegisterMetaType<ADSB::VehicleInfo_t>(
"ADSB::VehicleInfo_t");
29 _adsbVehicleCleanupTimer->setSingleShot(
false);
30 _adsbVehicleCleanupTimer->setInterval(1000);
31 (void) connect(_adsbVehicleCleanupTimer, &QTimer::timeout,
this, &ADSBVehicleManager::_cleanupStaleVehicles);
33 Fact*
const adsbEnabled = _adsbSettings->adsbServerConnectEnabled();
34 Fact*
const hostAddress = _adsbSettings->adsbServerHostAddress();
35 Fact*
const port = _adsbSettings->adsbServerPort();
45 if (adsbEnabled->
rawValue().toBool()) {
57 return _adsbVehicleManager();
62 if (message.msgid != MAVLINK_MSG_ID_ADSB_VEHICLE) {
66 _handleADSBVehicle(message);
71 mavlink_adsb_vehicle_t adsbVehicleMsg{};
72 mavlink_msg_adsb_vehicle_decode(&message, &adsbVehicleMsg);
74 if (adsbVehicleMsg.tslc > kMaxTimeSinceLastSeen) {
82 vehicleInfo.icaoAddress = adsbVehicleMsg.ICAO_address;
83 vehicleInfo.lastContact = adsbVehicleMsg.tslc;
85 if (adsbVehicleMsg.flags & ADSB_FLAGS_VALID_COORDS) {
87 vehicleInfo.location.setLatitude(adsbVehicleMsg.lat / 1e7);
88 vehicleInfo.location.setLongitude(adsbVehicleMsg.lon / 1e7);
91 if (adsbVehicleMsg.flags & ADSB_FLAGS_VALID_ALTITUDE) {
93 vehicleInfo.location.setAltitude(adsbVehicleMsg.altitude / 1e3);
96 if (adsbVehicleMsg.flags & ADSB_FLAGS_VALID_HEADING) {
98 vehicleInfo.heading = adsbVehicleMsg.heading / 1e2;
101 if (adsbVehicleMsg.flags & ADSB_FLAGS_VALID_VELOCITY) {
103 vehicleInfo.velocity = adsbVehicleMsg.hor_velocity / 1e2;
106 if (adsbVehicleMsg.flags & ADSB_FLAGS_VALID_CALLSIGN) {
108 vehicleInfo.callsign = QString::fromLatin1(adsbVehicleMsg.callsign,
sizeof(adsbVehicleMsg.callsign));
111 if (adsbVehicleMsg.flags & ADSB_FLAGS_VALID_SQUAWK) {
113 vehicleInfo.squawk = adsbVehicleMsg.squawk;
116 if (adsbVehicleMsg.flags & ADSB_FLAGS_SIMULATED) {
117 vehicleInfo.simulated =
true;
120 if (adsbVehicleMsg.flags & ADSB_FLAGS_VERTICAL_VELOCITY_VALID) {
122 vehicleInfo.verticalVel = adsbVehicleMsg.ver_velocity;
125 if (adsbVehicleMsg.flags & ADSB_FLAGS_BARO_VALID) {
126 vehicleInfo.baro =
true;
129 if (adsbVehicleMsg.flags & ADSB_FLAGS_SOURCE_UAT) {
133 adsbVehicleMsg.altitude_type = adsbVehicleMsg.altitude_type;
134 adsbVehicleMsg.emitter_type = adsbVehicleMsg.emitter_type;
141 const uint32_t icaoAddress = vehicleInfo.
icaoAddress;
142 if (_adsbICAOMap.contains(icaoAddress)) {
143 _adsbICAOMap[icaoAddress]->update(vehicleInfo);
149 _adsbICAOMap[icaoAddress] = adsbVehicle;
150 _adsbVehicles->
append(adsbVehicle);
151 qCDebug(ADSBVehicleManagerLog) <<
"Added" << QString::number(adsbVehicle->
icaoAddress());
155void ADSBVehicleManager::_start(
const QString &hostAddress, quint16 port)
157 Q_ASSERT(!_adsbTcpLink);
160 if (!adsbTcpLink->
init()) {
162 adsbTcpLink =
nullptr;
163 qCWarning(ADSBVehicleManagerLog) <<
"Failed to Initialize TCP Link at:" << hostAddress << port;
167 _adsbTcpLink = adsbTcpLink;
171 _adsbVehicleCleanupTimer->start();
174void ADSBVehicleManager::_stop()
176 Q_CHECK_PTR(_adsbTcpLink);
177 _adsbTcpLink->deleteLater();
178 _adsbTcpLink =
nullptr;
180 _adsbVehicleCleanupTimer->stop();
183 _adsbICAOMap.clear();
186void ADSBVehicleManager::_cleanupStaleVehicles()
188 for (qsizetype i = _adsbVehicles->
count() - 1; i >= 0; i--) {
191 qCDebug(ADSBVehicleManagerLog) <<
"Expired" << QString::number(adsbVehicle->
icaoAddress());
193 (void) _adsbICAOMap.remove(adsbVehicle->
icaoAddress());
194 adsbVehicle->deleteLater();
199void ADSBVehicleManager::_linkError(
const QString &errorMsg,
bool stopped)
201 qCDebug(ADSBVehicleManagerLog) << errorMsg;
203 QString msg = QStringLiteral(
"ADSB Server Error: %1").arg(errorMsg);
206 (void) msg.append(
"\nADSB has been disabled");
207 _adsbSettings->adsbServerConnectEnabled()->setRawValue(
false);
Q_APPLICATION_STATIC(ADSBVehicleManager, _adsbVehicleManager, SettingsManager::instance() ->adsbVehicleManagerSettings())
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
The ADSBTCPLink class handles the TCP connection to an ADS-B server and processes incoming ADS-B data...
bool init()
Attempts connection to a host.
void errorOccurred(const QString &errorMsg, bool stopped=false)
void adsbVehicleUpdate(const ADSB::VehicleInfo_t &vehicleInfo)
void adsbVehicleUpdate(const ADSB::VehicleInfo_t &vehicleInfo)
void mavlinkMessageReceived(const mavlink_message_t &message)
static ADSBVehicleManager * instance()
uint32_t icaoAddress() const
A Fact is used to hold a single value within the system.
void rawValueChanged(const QVariant &value)
QVariant rawValue() const
Value after translation.
void append(QObject *object)
Caller maintains responsibility for object ownership and deletion.
QObject * removeAt(int index)
int count() const override final
void clearAndDeleteContents() override final
Clears the list and calls deleteLater on each entry.
Provides access to all app settings.
void showAppMessage(const QString &message, const QString &title)
Modal application message. Queued if the UI isn't ready yet.
AvailableInfoTypes availableFlags