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