10#include <QtCore/QApplicationStatic>
11#include <QtCore/QTimer>
20 , _adsbSettings(settings)
21 , _adsbVehicleCleanupTimer(new QTimer(this))
26 (void) qRegisterMetaType<ADSB::VehicleInfo_t>(
"ADSB::VehicleInfo_t");
28 _adsbVehicleCleanupTimer->setSingleShot(
false);
29 _adsbVehicleCleanupTimer->setInterval(1000);
30 (void) connect(_adsbVehicleCleanupTimer, &QTimer::timeout,
this, &ADSBVehicleManager::_cleanupStaleVehicles);
32 Fact*
const adsbEnabled = _adsbSettings->adsbServerConnectEnabled();
33 Fact*
const hostAddress = _adsbSettings->adsbServerHostAddress();
34 Fact*
const port = _adsbSettings->adsbServerPort();
38 _start(hostAddress->rawValue().toString(), port->rawValue().toUInt());
44 if (adsbEnabled->rawValue().toBool()) {
45 _start(hostAddress->rawValue().toString(), port->rawValue().toUInt());
56 return _adsbVehicleManager();
61 if (message.msgid != MAVLINK_MSG_ID_ADSB_VEHICLE) {
65 _handleADSBVehicle(message);
70 mavlink_adsb_vehicle_t adsbVehicleMsg{};
71 mavlink_msg_adsb_vehicle_decode(&message, &adsbVehicleMsg);
73 if (adsbVehicleMsg.tslc > kMaxTimeSinceLastSeen) {
81 vehicleInfo.icaoAddress = adsbVehicleMsg.ICAO_address;
82 vehicleInfo.lastContact = adsbVehicleMsg.tslc;
84 if (adsbVehicleMsg.flags & ADSB_FLAGS_VALID_COORDS) {
86 vehicleInfo.location.setLatitude(adsbVehicleMsg.lat / 1e7);
87 vehicleInfo.location.setLongitude(adsbVehicleMsg.lon / 1e7);
90 if (adsbVehicleMsg.flags & ADSB_FLAGS_VALID_ALTITUDE) {
92 vehicleInfo.location.setAltitude(adsbVehicleMsg.altitude / 1e3);
95 if (adsbVehicleMsg.flags & ADSB_FLAGS_VALID_HEADING) {
97 vehicleInfo.heading = adsbVehicleMsg.heading / 1e2;
100 if (adsbVehicleMsg.flags & ADSB_FLAGS_VALID_VELOCITY) {
102 vehicleInfo.velocity = adsbVehicleMsg.hor_velocity / 1e2;
105 if (adsbVehicleMsg.flags & ADSB_FLAGS_VALID_CALLSIGN) {
107 vehicleInfo.callsign = QString::fromLatin1(adsbVehicleMsg.callsign,
sizeof(adsbVehicleMsg.callsign));
110 if (adsbVehicleMsg.flags & ADSB_FLAGS_VALID_SQUAWK) {
112 vehicleInfo.squawk = adsbVehicleMsg.squawk;
115 if (adsbVehicleMsg.flags & ADSB_FLAGS_SIMULATED) {
116 vehicleInfo.simulated =
true;
119 if (adsbVehicleMsg.flags & ADSB_FLAGS_VERTICAL_VELOCITY_VALID) {
121 vehicleInfo.verticalVel = adsbVehicleMsg.ver_velocity;
124 if (adsbVehicleMsg.flags & ADSB_FLAGS_BARO_VALID) {
125 vehicleInfo.baro =
true;
128 if (adsbVehicleMsg.flags & ADSB_FLAGS_SOURCE_UAT) {
132 adsbVehicleMsg.altitude_type = adsbVehicleMsg.altitude_type;
133 adsbVehicleMsg.emitter_type = adsbVehicleMsg.emitter_type;
140 const uint32_t icaoAddress = vehicleInfo.
icaoAddress;
141 if (_adsbICAOMap.contains(icaoAddress)) {
142 _adsbICAOMap[icaoAddress]->update(vehicleInfo);
148 _adsbICAOMap[icaoAddress] = adsbVehicle;
149 _adsbVehicles->
append(adsbVehicle);
150 qCDebug(ADSBVehicleManagerLog) <<
"Added" << QString::number(adsbVehicle->icaoAddress());
154void ADSBVehicleManager::_start(
const QString &hostAddress, quint16 port)
156 Q_ASSERT(!_adsbTcpLink);
159 if (!adsbTcpLink->
init()) {
161 adsbTcpLink =
nullptr;
162 qCWarning(ADSBVehicleManagerLog) <<
"Failed to Initialize TCP Link at:" << hostAddress << port;
166 _adsbTcpLink = adsbTcpLink;
170 _adsbVehicleCleanupTimer->start();
173void ADSBVehicleManager::_stop()
175 Q_CHECK_PTR(_adsbTcpLink);
176 _adsbTcpLink->deleteLater();
177 _adsbTcpLink =
nullptr;
179 _adsbVehicleCleanupTimer->stop();
182 _adsbICAOMap.clear();
185void ADSBVehicleManager::_cleanupStaleVehicles()
187 for (qsizetype i = _adsbVehicles->
count() - 1; i >= 0; i--) {
189 if (adsbVehicle->expired()) {
190 qCDebug(ADSBVehicleManagerLog) <<
"Expired" << QString::number(adsbVehicle->icaoAddress());
192 (void) _adsbICAOMap.remove(adsbVehicle->icaoAddress());
193 adsbVehicle->deleteLater();
198void ADSBVehicleManager::_linkError(
const QString &errorMsg,
bool stopped)
200 qCDebug(ADSBVehicleManagerLog) << errorMsg;
202 QString msg = QStringLiteral(
"ADSB Server Error: %1").arg(errorMsg);
205 (void) msg.append(
"\nADSB has been disabled");
209 qgcApp()->showAppMessage(msg);
Q_APPLICATION_STATIC(ADSBVehicleManager, _adsbVehicleManager, SettingsManager::instance() ->adsbVehicleManagerSettings())
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
bool init()
Attempts connection to a host.
void errorOccurred(const QString &errorMsg, bool stopped=false)
void adsbVehicleUpdate(const ADSB::VehicleInfo_t &vehicleInfo)
Fact *adsbServerConnectEnabled READ adsbServerConnectEnabled CONSTANT Fact * adsbServerConnectEnabled()
void adsbVehicleUpdate(const ADSB::VehicleInfo_t &vehicleInfo)
void mavlinkMessageReceived(const mavlink_message_t &message)
static ADSBVehicleManager * instance()
A Fact is used to hold a single value within the system.
void rawValueChanged(const QVariant &value)
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.
AvailableInfoTypes availableFlags