QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
ADSBVehicleManager.cc
Go to the documentation of this file.
2#include "QGCApplication.h"
3#include "SettingsManager.h"
5#include "ADSBTCPLink.h"
6#include "ADSBVehicle.h"
9
10#include <QtCore/QApplicationStatic>
11#include <QtCore/QTimer>
12#include <qassert.h>
13
14QGC_LOGGING_CATEGORY(ADSBVehicleManagerLog, "ADSB.ADSBVehicleManager")
15
16Q_APPLICATION_STATIC(ADSBVehicleManager, _adsbVehicleManager, SettingsManager::instance()->adsbVehicleManagerSettings());
17
19 : QObject(parent)
20 , _adsbSettings(settings)
21 , _adsbVehicleCleanupTimer(new QTimer(this))
22 , _adsbVehicles(new QmlObjectListModel(this))
23{
24 // qCDebug(ADSBVehicleManagerLog) << Q_FUNC_INFO << this;
25
26 (void) qRegisterMetaType<ADSB::VehicleInfo_t>("ADSB::VehicleInfo_t");
27
28 _adsbVehicleCleanupTimer->setSingleShot(false);
29 _adsbVehicleCleanupTimer->setInterval(1000);
30 (void) connect(_adsbVehicleCleanupTimer, &QTimer::timeout, this, &ADSBVehicleManager::_cleanupStaleVehicles);
31
32 Fact* const adsbEnabled = _adsbSettings->adsbServerConnectEnabled();
33 Fact* const hostAddress = _adsbSettings->adsbServerHostAddress();
34 Fact* const port = _adsbSettings->adsbServerPort();
35
36 (void) connect(adsbEnabled, &Fact::rawValueChanged, this, [this, hostAddress, port](QVariant value) {
37 if (value.toBool()) {
38 _start(hostAddress->rawValue().toString(), port->rawValue().toUInt());
39 } else {
40 _stop();
41 }
42 });
43
44 if (adsbEnabled->rawValue().toBool()) {
45 _start(hostAddress->rawValue().toString(), port->rawValue().toUInt());
46 }
47}
48
50{
51 // qCDebug(ADSBVehicleManagerLog) << Q_FUNC_INFO << this;
52}
53
55{
56 return _adsbVehicleManager();
57}
58
60{
61 if (message.msgid != MAVLINK_MSG_ID_ADSB_VEHICLE) {
62 return;
63 }
64
65 _handleADSBVehicle(message);
66}
67
68void ADSBVehicleManager::_handleADSBVehicle(const mavlink_message_t &message)
69{
70 mavlink_adsb_vehicle_t adsbVehicleMsg{};
71 mavlink_msg_adsb_vehicle_decode(&message, &adsbVehicleMsg);
72
73 if (adsbVehicleMsg.tslc > kMaxTimeSinceLastSeen) {
74 return;
75 }
76
77 ADSB::VehicleInfo_t vehicleInfo{};
78
79 vehicleInfo.availableFlags = ADSB::AvailableInfoTypes::fromInt(0);
80
81 vehicleInfo.icaoAddress = adsbVehicleMsg.ICAO_address;
82 vehicleInfo.lastContact = adsbVehicleMsg.tslc;
83
84 if (adsbVehicleMsg.flags & ADSB_FLAGS_VALID_COORDS) {
85 vehicleInfo.availableFlags |= ADSB::LocationAvailable;
86 vehicleInfo.location.setLatitude(adsbVehicleMsg.lat / 1e7);
87 vehicleInfo.location.setLongitude(adsbVehicleMsg.lon / 1e7);
88 }
89
90 if (adsbVehicleMsg.flags & ADSB_FLAGS_VALID_ALTITUDE) {
91 vehicleInfo.availableFlags |= ADSB::AltitudeAvailable;
92 vehicleInfo.location.setAltitude(adsbVehicleMsg.altitude / 1e3);
93 }
94
95 if (adsbVehicleMsg.flags & ADSB_FLAGS_VALID_HEADING) {
96 vehicleInfo.availableFlags |= ADSB::HeadingAvailable;
97 vehicleInfo.heading = adsbVehicleMsg.heading / 1e2;
98 }
99
100 if (adsbVehicleMsg.flags & ADSB_FLAGS_VALID_VELOCITY) {
101 vehicleInfo.availableFlags |= ADSB::VelocityAvailable;
102 vehicleInfo.velocity = adsbVehicleMsg.hor_velocity / 1e2;
103 }
104
105 if (adsbVehicleMsg.flags & ADSB_FLAGS_VALID_CALLSIGN) {
106 vehicleInfo.availableFlags |= ADSB::CallsignAvailable;
107 vehicleInfo.callsign = QString::fromLatin1(adsbVehicleMsg.callsign, sizeof(adsbVehicleMsg.callsign));
108 }
109
110 if (adsbVehicleMsg.flags & ADSB_FLAGS_VALID_SQUAWK) {
111 vehicleInfo.availableFlags |= ADSB::SquawkAvailable;
112 vehicleInfo.squawk = adsbVehicleMsg.squawk;
113 }
114
115 if (adsbVehicleMsg.flags & ADSB_FLAGS_SIMULATED) {
116 vehicleInfo.simulated = true;
117 }
118
119 if (adsbVehicleMsg.flags & ADSB_FLAGS_VERTICAL_VELOCITY_VALID) {
120 vehicleInfo.availableFlags |= ADSB::VerticalVelAvailable;
121 vehicleInfo.verticalVel = adsbVehicleMsg.ver_velocity;
122 }
123
124 if (adsbVehicleMsg.flags & ADSB_FLAGS_BARO_VALID) {
125 vehicleInfo.baro = true;
126 }
127
128 if (adsbVehicleMsg.flags & ADSB_FLAGS_SOURCE_UAT) {
129
130 }
131
132 adsbVehicleMsg.altitude_type = adsbVehicleMsg.altitude_type;
133 adsbVehicleMsg.emitter_type = adsbVehicleMsg.emitter_type;
134
135 adsbVehicleUpdate(vehicleInfo);
136}
137
139{
140 const uint32_t icaoAddress = vehicleInfo.icaoAddress;
141 if (_adsbICAOMap.contains(icaoAddress)) {
142 _adsbICAOMap[icaoAddress]->update(vehicleInfo);
143 return;
144 }
145
146 if (vehicleInfo.availableFlags & ADSB::LocationAvailable) {
147 ADSBVehicle* const adsbVehicle = new ADSBVehicle(vehicleInfo, this);
148 _adsbICAOMap[icaoAddress] = adsbVehicle;
149 _adsbVehicles->append(adsbVehicle);
150 qCDebug(ADSBVehicleManagerLog) << "Added" << QString::number(adsbVehicle->icaoAddress());
151 }
152}
153
154void ADSBVehicleManager::_start(const QString &hostAddress, quint16 port)
155{
156 Q_ASSERT(!_adsbTcpLink);
157
158 ADSBTCPLink *adsbTcpLink = new ADSBTCPLink(QHostAddress(hostAddress), port, this);
159 if (!adsbTcpLink->init()) {
160 delete adsbTcpLink;
161 adsbTcpLink = nullptr;
162 qCWarning(ADSBVehicleManagerLog) << "Failed to Initialize TCP Link at:" << hostAddress << port;
163 return;
164 }
165
166 _adsbTcpLink = adsbTcpLink;
167 (void) connect(_adsbTcpLink, &ADSBTCPLink::adsbVehicleUpdate, this, &ADSBVehicleManager::adsbVehicleUpdate, Qt::AutoConnection);
168 (void) connect(_adsbTcpLink, &ADSBTCPLink::errorOccurred, this, &ADSBVehicleManager::_linkError, Qt::AutoConnection);
169
170 _adsbVehicleCleanupTimer->start();
171}
172
173void ADSBVehicleManager::_stop()
174{
175 Q_CHECK_PTR(_adsbTcpLink);
176 _adsbTcpLink->deleteLater();
177 _adsbTcpLink = nullptr;
178
179 _adsbVehicleCleanupTimer->stop();
180
181 _adsbVehicles->clearAndDeleteContents();
182 _adsbICAOMap.clear();
183}
184
185void ADSBVehicleManager::_cleanupStaleVehicles()
186{
187 for (qsizetype i = _adsbVehicles->count() - 1; i >= 0; i--) {
188 ADSBVehicle* const adsbVehicle = _adsbVehicles->value<ADSBVehicle*>(i);
189 if (adsbVehicle->expired()) {
190 qCDebug(ADSBVehicleManagerLog) << "Expired" << QString::number(adsbVehicle->icaoAddress());
191 (void) _adsbVehicles->removeAt(i);
192 (void) _adsbICAOMap.remove(adsbVehicle->icaoAddress());
193 adsbVehicle->deleteLater();
194 }
195 }
196}
197
198void ADSBVehicleManager::_linkError(const QString &errorMsg, bool stopped)
199{
200 qCDebug(ADSBVehicleManagerLog) << errorMsg;
201
202 QString msg = QStringLiteral("ADSB Server Error: %1").arg(errorMsg);
203
204 if (stopped) {
205 (void) msg.append("\nADSB has been disabled");
206 _adsbSettings->adsbServerConnectEnabled()->setRawValue(false);
207 }
208
209 qgcApp()->showAppMessage(msg);
210}
Q_APPLICATION_STATIC(ADSBVehicleManager, _adsbVehicleManager, SettingsManager::instance() ->adsbVehicleManagerSettings())
#define qgcApp()
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
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.
Definition Fact.h:19
void rawValueChanged(const QVariant &value)
void append(QObject *object)
Caller maintains responsibility for object ownership and deletion.
T value(int index) const
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.
@ SquawkAvailable
Definition ADSB.h:39
@ VelocityAvailable
Definition ADSB.h:37
@ CallsignAvailable
Definition ADSB.h:38
@ AltitudeAvailable
Definition ADSB.h:35
@ LocationAvailable
Definition ADSB.h:34
@ VerticalVelAvailable
Definition ADSB.h:40
@ HeadingAvailable
Definition ADSB.h:36
uint32_t icaoAddress
Definition ADSB.h:49
AvailableInfoTypes availableFlags
Definition ADSB.h:48