Skip to content
Projects
Groups
Snippets
Help
Loading...
Help
Support
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Q
qgroundcontrol
Project
Project
Details
Activity
Releases
Cycle Analytics
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Charts
Issues
0
Issues
0
List
Boards
Labels
Milestones
Merge Requests
0
Merge Requests
0
CI / CD
CI / CD
Pipelines
Jobs
Schedules
Charts
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Charts
Create a new issue
Jobs
Commits
Issue Boards
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
3eec1ca0
Unverified
Commit
3eec1ca0
authored
Nov 16, 2019
by
Don Gagne
Committed by
GitHub
Nov 16, 2019
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #8046 from DonLakeFlyer/ADSBServer
ADSB server support
parents
a1ddad8c
99665bcc
Changes
24
Hide whitespace changes
Inline
Side-by-side
Showing
24 changed files
with
550 additions
and
174 deletions
+550
-174
ChangeLog.md
ChangeLog.md
+1
-0
qgroundcontrol.pro
qgroundcontrol.pro
+7
-2
qgroundcontrol.qrc
qgroundcontrol.qrc
+1
-0
ADSBVehicle.cc
src/ADSB/ADSBVehicle.cc
+68
-0
ADSBVehicle.h
src/ADSB/ADSBVehicle.h
+23
-7
ADSBVehicleManager.cc
src/ADSB/ADSBVehicleManager.cc
+190
-0
ADSBVehicleManager.h
src/ADSB/ADSBVehicleManager.h
+75
-0
FlightDisplayViewMap.qml
src/FlightDisplay/FlightDisplayViewMap.qml
+1
-2
VehicleMapItem.qml
src/FlightMap/MapItems/VehicleMapItem.qml
+1
-11
QGCLoggingCategory.cc
src/QGCLoggingCategory.cc
+1
-0
QGCLoggingCategory.h
src/QGCLoggingCategory.h
+1
-0
QGCToolbox.cc
src/QGCToolbox.cc
+3
-0
QGCToolbox.h
src/QGCToolbox.h
+3
-0
QGroundControlQmlGlobal.cc
src/QmlControls/QGroundControlQmlGlobal.cc
+1
-0
QGroundControlQmlGlobal.h
src/QmlControls/QGroundControlQmlGlobal.h
+4
-0
ADSBVehicleManager.SettingsGroup.json
src/Settings/ADSBVehicleManager.SettingsGroup.json
+24
-0
ADSBVehicleManagerSettings.cc
src/Settings/ADSBVehicleManagerSettings.cc
+22
-0
ADSBVehicleManagerSettings.h
src/Settings/ADSBVehicleManagerSettings.h
+24
-0
SettingsManager.cc
src/Settings/SettingsManager.cc
+13
-11
SettingsManager.h
src/Settings/SettingsManager.h
+4
-0
ADSBVehicle.cc
src/Vehicle/ADSBVehicle.cc
+0
-98
Vehicle.cc
src/Vehicle/Vehicle.cc
+29
-35
Vehicle.h
src/Vehicle/Vehicle.h
+1
-8
GeneralSettings.qml
src/ui/preferences/GeneralSettings.qml
+53
-0
No files found.
ChangeLog.md
View file @
3eec1ca0
...
...
@@ -6,6 +6,7 @@ Note: This file only contains high level features or important fixes.
### 3.6.0 - Daily Build
*
ADSB: Added support for connecting to SBS server. Adds support for ADSB data from USB SDR Dongle running 'dump190 --net' for example.
*
Toolbar: Scrollable left/right on small screens like phones
*
Plan View: New create plan UI for initial plan creation
*
New Corridor editing tools ui. Includes ability to trace polyline by clicking.
...
...
qgroundcontrol.pro
View file @
3eec1ca0
...
...
@@ -398,6 +398,7 @@ INCLUDEPATH += .
INCLUDEPATH
+=
\
include
/
ui
\
src
\
src
/
ADSB
\
src
/
api
\
src
/
AnalyzeView
\
src
/
Camera
\
...
...
@@ -566,6 +567,8 @@ DebugBuild { PX4FirmwarePlugin { PX4FirmwarePluginFactory { APMFirmwarePlugin {
#
Main
QGC
Headers
and
Source
files
HEADERS
+=
\
src
/
ADSB
/
ADSBVehicle
.
h
\
src
/
ADSB
/
ADSBVehicleManager
.
h
\
src
/
AnalyzeView
/
LogDownloadController
.
h
\
src
/
AnalyzeView
/
PX4LogParser
.
h
\
src
/
AnalyzeView
/
ULogParser
.
h
\
...
...
@@ -652,6 +655,7 @@ HEADERS += \
src
/
QmlControls
/
RCChannelMonitorController
.
h
\
src
/
QmlControls
/
ScreenToolsController
.
h
\
src
/
QtLocationPlugin
/
QMLControl
/
QGCMapEngineManager
.
h
\
src
/
Settings
/
ADSBVehicleManagerSettings
.
h
\
src
/
Settings
/
AppSettings
.
h
\
src
/
Settings
/
AutoConnectSettings
.
h
\
src
/
Settings
/
BrandImageSettings
.
h
\
...
...
@@ -669,7 +673,6 @@ HEADERS += \
src
/
SHPFileHelper
.
h
\
src
/
Terrain
/
TerrainQuery
.
h
\
src
/
TerrainTile
.
h
\
src
/
Vehicle
/
ADSBVehicle
.
h
\
src
/
Vehicle
/
GPSRTKFactGroup
.
h
\
src
/
Vehicle
/
MAVLinkLogManager
.
h
\
src
/
Vehicle
/
MultiVehicleManager
.
h
\
...
...
@@ -800,6 +803,8 @@ AndroidBuild {
}
SOURCES
+=
\
src
/
ADSB
/
ADSBVehicle
.
cc
\
src
/
ADSB
/
ADSBVehicleManager
.
cc
\
src
/
AnalyzeView
/
LogDownloadController
.
cc
\
src
/
AnalyzeView
/
PX4LogParser
.
cc
\
src
/
AnalyzeView
/
ULogParser
.
cc
\
...
...
@@ -882,6 +887,7 @@ SOURCES += \
src
/
QmlControls
/
RCChannelMonitorController
.
cc
\
src
/
QmlControls
/
ScreenToolsController
.
cc
\
src
/
QtLocationPlugin
/
QMLControl
/
QGCMapEngineManager
.
cc
\
src
/
Settings
/
ADSBVehicleManagerSettings
.
cc
\
src
/
Settings
/
AppSettings
.
cc
\
src
/
Settings
/
AutoConnectSettings
.
cc
\
src
/
Settings
/
BrandImageSettings
.
cc
\
...
...
@@ -899,7 +905,6 @@ SOURCES += \
src
/
SHPFileHelper
.
cc
\
src
/
Terrain
/
TerrainQuery
.
cc
\
src
/
TerrainTile
.
cc
\
src
/
Vehicle
/
ADSBVehicle
.
cc
\
src
/
Vehicle
/
GPSRTKFactGroup
.
cc
\
src
/
Vehicle
/
MAVLinkLogManager
.
cc
\
src
/
Vehicle
/
MultiVehicleManager
.
cc
\
...
...
qgroundcontrol.qrc
View file @
3eec1ca0
...
...
@@ -234,6 +234,7 @@
<qresource prefix="/json">
<file alias="APMMavlinkStreamRate.SettingsGroup.json">src/Settings/APMMavlinkStreamRate.SettingsGroup.json</file>
<file alias="BreachReturn.FactMetaData.json">src/MissionManager/BreachReturn.FactMetaData.json</file>
<file alias="ADSBVehicleManager.SettingsGroup.json">src/Settings/ADSBVehicleManager.SettingsGroup.json</file>
<file alias="App.SettingsGroup.json">src/Settings/App.SettingsGroup.json</file>
<file alias="AutoConnect.SettingsGroup.json">src/Settings/AutoConnect.SettingsGroup.json</file>
<file alias="BrandImage.SettingsGroup.json">src/Settings/BrandImage.SettingsGroup.json</file>
...
...
src/ADSB/ADSBVehicle.cc
0 → 100644
View file @
3eec1ca0
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#include "ADSBVehicle.h"
#include "QGCLoggingCategory.h"
#include <QDebug>
#include <QtMath>
ADSBVehicle
::
ADSBVehicle
(
const
VehicleInfo_t
&
vehicleInfo
,
QObject
*
parent
)
:
QObject
(
parent
)
,
_icaoAddress
(
vehicleInfo
.
icaoAddress
)
,
_altitude
(
qQNaN
())
,
_heading
(
qQNaN
())
,
_alert
(
false
)
{
update
(
vehicleInfo
);
}
void
ADSBVehicle
::
update
(
const
VehicleInfo_t
&
vehicleInfo
)
{
if
(
_icaoAddress
!=
vehicleInfo
.
icaoAddress
)
{
qCWarning
(
ADSBVehicleManagerLog
)
<<
"ICAO address mismatch expected:actual"
<<
_icaoAddress
<<
vehicleInfo
.
icaoAddress
;
return
;
}
if
(
vehicleInfo
.
availableFlags
&
CallsignAvailable
)
{
if
(
vehicleInfo
.
callsign
!=
_callsign
)
{
_callsign
=
vehicleInfo
.
callsign
;
emit
callsignChanged
();
}
}
if
(
vehicleInfo
.
availableFlags
&
LocationAvailable
)
{
if
(
_coordinate
!=
vehicleInfo
.
location
)
{
_coordinate
=
vehicleInfo
.
location
;
emit
coordinateChanged
();
}
}
if
(
vehicleInfo
.
availableFlags
&
AltitudeAvailable
)
{
if
(
!
(
qIsNaN
(
vehicleInfo
.
altitude
)
&&
qIsNaN
(
_altitude
))
&&
!
qFuzzyCompare
(
vehicleInfo
.
altitude
,
_altitude
))
{
_altitude
=
vehicleInfo
.
altitude
;
emit
altitudeChanged
();
}
}
if
(
vehicleInfo
.
availableFlags
&
HeadingAvailable
)
{
if
(
!
(
qIsNaN
(
vehicleInfo
.
heading
)
&&
qIsNaN
(
_heading
))
&&
!
qFuzzyCompare
(
vehicleInfo
.
heading
,
_heading
))
{
_heading
=
vehicleInfo
.
heading
;
emit
headingChanged
();
}
}
if
(
vehicleInfo
.
availableFlags
&
AlertAvailable
)
{
if
(
vehicleInfo
.
alert
!=
_alert
)
{
_alert
=
vehicleInfo
.
alert
;
emit
alertChanged
();
}
}
_lastUpdateTimer
.
restart
();
}
bool
ADSBVehicle
::
expired
()
{
return
_lastUpdateTimer
.
hasExpired
(
expirationTimeoutMs
);
}
src/
Vehicle
/ADSBVehicle.h
→
src/
ADSB
/ADSBVehicle.h
View file @
3eec1ca0
...
...
@@ -20,9 +20,25 @@ class ADSBVehicle : public QObject
Q_OBJECT
public:
ADSBVehicle
(
mavlink_adsb_vehicle_t
&
adsbVehicle
,
QObject
*
parent
=
nullptr
);
enum
{
CallsignAvailable
=
1
<<
1
,
LocationAvailable
=
1
<<
2
,
AltitudeAvailable
=
1
<<
3
,
HeadingAvailable
=
1
<<
4
,
AlertAvailable
=
1
<<
5
,
};
ADSBVehicle
(
const
QGeoCoordinate
&
location
,
float
heading
,
bool
alert
=
false
,
QObject
*
parent
=
nullptr
);
typedef
struct
{
uint32_t
icaoAddress
;
// Required
QString
callsign
;
QGeoCoordinate
location
;
double
altitude
;
double
heading
;
bool
alert
;
uint32_t
availableFlags
;
}
VehicleInfo_t
;
ADSBVehicle
(
const
VehicleInfo_t
&
vehicleInfo
,
QObject
*
parent
);
Q_PROPERTY
(
int
icaoAddress
READ
icaoAddress
CONSTANT
)
Q_PROPERTY
(
QString
callsign
READ
callsign
NOTIFY
callsignChanged
)
...
...
@@ -31,17 +47,14 @@ public:
Q_PROPERTY
(
double
heading
READ
heading
NOTIFY
headingChanged
)
// NaN for not available
Q_PROPERTY
(
bool
alert
READ
alert
NOTIFY
alertChanged
)
// Collision path
int
icaoAddress
(
void
)
const
{
return
_icaoAddress
;
}
int
icaoAddress
(
void
)
const
{
return
static_cast
<
int
>
(
_icaoAddress
)
;
}
QString
callsign
(
void
)
const
{
return
_callsign
;
}
QGeoCoordinate
coordinate
(
void
)
const
{
return
_coordinate
;
}
double
altitude
(
void
)
const
{
return
_altitude
;
}
double
heading
(
void
)
const
{
return
_heading
;
}
bool
alert
(
void
)
const
{
return
_alert
;
}
/// Update the vehicle with new information
void
update
(
mavlink_adsb_vehicle_t
&
adsbVehicle
);
void
update
(
bool
alert
,
const
QGeoCoordinate
&
location
,
float
heading
);
void
update
(
const
VehicleInfo_t
&
vehicleInfo
);
/// check if the vehicle is expired and should be removed
bool
expired
();
...
...
@@ -69,3 +82,6 @@ private:
QElapsedTimer
_lastUpdateTimer
;
};
Q_DECLARE_METATYPE
(
ADSBVehicle
::
VehicleInfo_t
)
src/ADSB/ADSBVehicleManager.cc
0 → 100644
View file @
3eec1ca0
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#include "ADSBVehicleManager.h"
#include "QGCLoggingCategory.h"
#include "QGCApplication.h"
#include "SettingsManager.h"
#include "ADSBVehicleManagerSettings.h"
#include <QDebug>
ADSBVehicleManager
::
ADSBVehicleManager
(
QGCApplication
*
app
,
QGCToolbox
*
toolbox
)
:
QGCTool
(
app
,
toolbox
)
{
}
void
ADSBVehicleManager
::
setToolbox
(
QGCToolbox
*
toolbox
)
{
QGCTool
::
setToolbox
(
toolbox
);
connect
(
&
_adsbVehicleCleanupTimer
,
&
QTimer
::
timeout
,
this
,
&
ADSBVehicleManager
::
_cleanupStaleVehicles
);
_adsbVehicleCleanupTimer
.
setSingleShot
(
false
);
_adsbVehicleCleanupTimer
.
start
(
1000
);
ADSBVehicleManagerSettings
*
settings
=
qgcApp
()
->
toolbox
()
->
settingsManager
()
->
adsbVehicleManagerSettings
();
if
(
settings
->
adsbServerConnectEnabled
()
->
rawValue
().
toBool
())
{
_tcpLink
=
new
ADSBTCPLink
(
settings
->
adsbServerHostAddress
()
->
rawValue
().
toString
(),
settings
->
adsbServerPort
()
->
rawValue
().
toInt
(),
this
);
connect
(
_tcpLink
,
&
ADSBTCPLink
::
adsbVehicleUpdate
,
this
,
&
ADSBVehicleManager
::
adsbVehicleUpdate
,
Qt
::
QueuedConnection
);
connect
(
_tcpLink
,
&
ADSBTCPLink
::
error
,
this
,
&
ADSBVehicleManager
::
_tcpError
,
Qt
::
QueuedConnection
);
}
}
void
ADSBVehicleManager
::
_cleanupStaleVehicles
()
{
// Remove all expired ADSB vehicles
for
(
int
i
=
_adsbVehicles
.
count
()
-
1
;
i
>=
0
;
i
--
)
{
ADSBVehicle
*
adsbVehicle
=
_adsbVehicles
.
value
<
ADSBVehicle
*>
(
i
);
if
(
adsbVehicle
->
expired
())
{
qCDebug
(
ADSBVehicleManagerLog
)
<<
"Expired"
<<
QStringLiteral
(
"%1"
).
arg
(
adsbVehicle
->
icaoAddress
(),
0
,
16
);
_adsbVehicles
.
removeAt
(
i
);
adsbVehicle
->
deleteLater
();
}
}
}
void
ADSBVehicleManager
::
adsbVehicleUpdate
(
const
ADSBVehicle
::
VehicleInfo_t
vehicleInfo
)
{
uint32_t
icaoAddress
=
vehicleInfo
.
icaoAddress
;
if
(
_adsbICAOMap
.
contains
(
icaoAddress
))
{
_adsbICAOMap
[
icaoAddress
]
->
update
(
vehicleInfo
);
}
else
{
if
(
vehicleInfo
.
availableFlags
&
ADSBVehicle
::
LocationAvailable
)
{
ADSBVehicle
*
adsbVehicle
=
new
ADSBVehicle
(
vehicleInfo
,
this
);
_adsbICAOMap
[
icaoAddress
]
=
adsbVehicle
;
_adsbVehicles
.
append
(
adsbVehicle
);
}
}
}
void
ADSBVehicleManager
::
_tcpError
(
const
QString
errorMsg
)
{
qgcApp
()
->
showMessage
(
tr
(
"ADSB Server Error: %1"
).
arg
(
errorMsg
));
}
ADSBTCPLink
::
ADSBTCPLink
(
const
QString
&
hostAddress
,
int
port
,
QObject
*
parent
)
:
QThread
(
parent
)
,
_hostAddress
(
hostAddress
)
,
_port
(
port
)
{
moveToThread
(
this
);
start
();
}
ADSBTCPLink
::~
ADSBTCPLink
(
void
)
{
if
(
_socket
)
{
_socket
->
disconnectFromHost
();
_socket
->
deleteLater
();
_socket
=
nullptr
;
}
quit
();
wait
();
}
void
ADSBTCPLink
::
run
(
void
)
{
_hardwareConnect
();
exec
();
}
void
ADSBTCPLink
::
_hardwareConnect
()
{
_socket
=
new
QTcpSocket
();
QObject
::
connect
(
_socket
,
&
QTcpSocket
::
readyRead
,
this
,
&
ADSBTCPLink
::
_readBytes
);
_socket
->
connectToHost
(
_hostAddress
,
static_cast
<
quint16
>
(
_port
));
// Give the socket a second to connect to the other side otherwise error out
if
(
!
_socket
->
waitForConnected
(
1000
))
{
qCDebug
(
ADSBVehicleManagerLog
)
<<
"ADSB Socket failed to connect"
;
emit
error
(
_socket
->
errorString
());
delete
_socket
;
_socket
=
nullptr
;
return
;
}
qCDebug
(
ADSBVehicleManagerLog
)
<<
"ADSB Socket connected"
;
}
void
ADSBTCPLink
::
_readBytes
(
void
)
{
if
(
_socket
)
{
QByteArray
bytes
=
_socket
->
readLine
();
_parseLine
(
QString
::
fromLocal8Bit
(
bytes
));
}
}
void
ADSBTCPLink
::
_parseLine
(
const
QString
&
line
)
{
if
(
line
.
startsWith
(
QStringLiteral
(
"MSG"
)))
{
qCDebug
(
ADSBVehicleManagerLog
)
<<
"ADSB SBS-1"
<<
line
;
QStringList
values
=
line
.
split
(
QStringLiteral
(
","
));
if
(
values
[
1
]
==
QStringLiteral
(
"3"
))
{
bool
icaoOk
,
altOk
,
latOk
,
lonOk
;
uint32_t
icaoAddress
=
values
[
4
].
toUInt
(
&
icaoOk
,
16
);
int
modeCAltitude
=
values
[
11
].
toInt
(
&
altOk
);
double
lat
=
values
[
14
].
toDouble
(
&
latOk
);
double
lon
=
values
[
15
].
toDouble
(
&
lonOk
);
QString
callsign
=
values
[
10
];
if
(
!
icaoOk
||
!
altOk
||
!
latOk
||
!
lonOk
)
{
return
;
}
if
(
lat
==
0
&&
lon
==
0
)
{
return
;
}
double
altitude
=
modeCAltitude
/
3.048
;
QGeoCoordinate
location
(
lat
,
lon
);
ADSBVehicle
::
VehicleInfo_t
adsbInfo
;
adsbInfo
.
icaoAddress
=
icaoAddress
;
adsbInfo
.
callsign
=
callsign
;
adsbInfo
.
location
=
location
;
adsbInfo
.
altitude
=
altitude
;
adsbInfo
.
availableFlags
=
ADSBVehicle
::
CallsignAvailable
|
ADSBVehicle
::
LocationAvailable
|
ADSBVehicle
::
AltitudeAvailable
;
emit
adsbVehicleUpdate
(
adsbInfo
);
}
else
if
(
values
[
1
]
==
QStringLiteral
(
"4"
))
{
bool
icaoOk
,
headingOk
;
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
);
}
}
}
src/ADSB/ADSBVehicleManager.h
0 → 100644
View file @
3eec1ca0
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#pragma once
#include "QGCToolbox.h"
#include "QmlObjectListModel.h"
#include "ADSBVehicle.h"
#include <QThread>
#include <QTcpSocket>
#include <QTimer>
#include <QGeoCoordinate>
class
ADSBVehicleManagerSettings
;
class
ADSBTCPLink
:
public
QThread
{
Q_OBJECT
public:
ADSBTCPLink
(
const
QString
&
hostAddress
,
int
port
,
QObject
*
parent
);
~
ADSBTCPLink
();
signals:
void
adsbVehicleUpdate
(
const
ADSBVehicle
::
VehicleInfo_t
vehicleInfo
);
void
error
(
const
QString
errorMsg
);
protected:
void
run
(
void
)
final
;
private
slots
:
void
_readBytes
(
void
);
private:
void
_hardwareConnect
(
void
);
void
_parseLine
(
const
QString
&
line
);
QString
_hostAddress
;
int
_port
;
QTcpSocket
*
_socket
=
nullptr
;
};
class
ADSBVehicleManager
:
public
QGCTool
{
Q_OBJECT
public:
ADSBVehicleManager
(
QGCApplication
*
app
,
QGCToolbox
*
toolbox
);
Q_PROPERTY
(
QmlObjectListModel
*
adsbVehicles
READ
adsbVehicles
CONSTANT
)
QmlObjectListModel
*
adsbVehicles
(
void
)
{
return
&
_adsbVehicles
;
}
// QGCTool overrides
void
setToolbox
(
QGCToolbox
*
toolbox
)
final
;
public
slots
:
void
adsbVehicleUpdate
(
const
ADSBVehicle
::
VehicleInfo_t
vehicleInfo
);
void
_tcpError
(
const
QString
errorMsg
);
private
slots
:
void
_cleanupStaleVehicles
(
void
);
private:
QmlObjectListModel
_adsbVehicles
;
QMap
<
uint32_t
,
ADSBVehicle
*>
_adsbICAOMap
;
QTimer
_adsbVehicleCleanupTimer
;
ADSBTCPLink
*
_tcpLink
=
nullptr
;
};
src/FlightDisplay/FlightDisplayViewMap.qml
View file @
3eec1ca0
...
...
@@ -214,8 +214,7 @@ FlightMap {
// Add ADSB vehicles to the map
MapItemView
{
model
:
activeVehicle
?
activeVehicle
.
adsbVehicles
:
[]
property
var
activeVehicle
:
QGroundControl
.
multiVehicleManager
.
activeVehicle
model
:
QGroundControl
.
adsbVehicleManager
.
adsbVehicles
delegate
:
VehicleMapItem
{
coordinate
:
object
.
coordinate
altitude
:
object
.
altitude
...
...
src/FlightMap/MapItems/VehicleMapItem.qml
View file @
3eec1ca0
...
...
@@ -80,7 +80,7 @@ MapQuickItem {
anchors.horizontalCenter
:
parent
.
horizontalCenter
map
:
_map
text
:
vehicleLabelText
font.pointSize
:
ScreenTools
.
smallFontPointSize
font.pointSize
:
_adsbVehicle
?
ScreenTools
.
defaultFontPointSize
:
ScreenTools
.
smallFontPointSize
visible
:
_adsbVehicle
?
!
isNaN
(
altitude
)
:
_multiVehicle
property
string
vehicleLabelText
:
visible
?
(
_adsbVehicle
?
...
...
@@ -89,15 +89,5 @@ MapQuickItem {
""
}
QGCMapLabel
{
anchors.top
:
vehicleLabel
.
bottom
anchors.horizontalCenter
:
parent
.
horizontalCenter
map
:
_map
text
:
vehicleLabelText
font.pointSize
:
ScreenTools
.
smallFontPointSize
visible
:
_adsbVehicle
?
!
isNaN
(
altitude
)
:
_multiVehicle
property
string
vehicleLabelText
:
visible
&&
_adsbVehicle
?
callsign
:
""
}
}
}
src/QGCLoggingCategory.cc
View file @
3eec1ca0
...
...
@@ -24,6 +24,7 @@ QGC_LOGGING_CATEGORY(ParameterManagerLog, "ParameterManagerLog")
QGC_LOGGING_CATEGORY
(
GeotaggingLog
,
"GeotaggingLog"
)
QGC_LOGGING_CATEGORY
(
RTKGPSLog
,
"RTKGPSLog"
)
QGC_LOGGING_CATEGORY
(
GuidedActionsControllerLog
,
"GuidedActionsControllerLog"
)
QGC_LOGGING_CATEGORY
(
ADSBVehicleManagerLog
,
"ADSBVehicleManagerLog"
)
QGCLoggingCategoryRegister
*
_instance
=
nullptr
;
const
char
*
QGCLoggingCategoryRegister
::
_filterRulesSettingsGroup
=
"LoggingFilters"
;
...
...
src/QGCLoggingCategory.h
View file @
3eec1ca0
...
...
@@ -26,6 +26,7 @@ Q_DECLARE_LOGGING_CATEGORY(ParameterManagerLog)
Q_DECLARE_LOGGING_CATEGORY
(
GeotaggingLog
)
Q_DECLARE_LOGGING_CATEGORY
(
RTKGPSLog
)
Q_DECLARE_LOGGING_CATEGORY
(
GuidedActionsControllerLog
)
Q_DECLARE_LOGGING_CATEGORY
(
ADSBVehicleManagerLog
)
/// @def QGC_LOGGING_CATEGORY
/// This is a QGC specific replacement for Q_LOGGING_CATEGORY. It will register the category name into a
...
...
src/QGCToolbox.cc
View file @
3eec1ca0
...
...
@@ -30,6 +30,7 @@
#include "QGCOptions.h"
#include "SettingsManager.h"
#include "QGCApplication.h"
#include "ADSBVehicleManager.h"
#if defined(QGC_ENABLE_PAIRING)
#include "PairingManager.h"
#endif
...
...
@@ -73,6 +74,7 @@ QGCToolbox::QGCToolbox(QGCApplication* app)
_followMe
=
new
FollowMe
(
app
,
this
);
_videoManager
=
new
VideoManager
(
app
,
this
);
_mavlinkLogManager
=
new
MAVLinkLogManager
(
app
,
this
);
_adsbVehicleManager
=
new
ADSBVehicleManager
(
app
,
this
);
#if defined(QGC_ENABLE_PAIRING)
_pairingManager
=
new
PairingManager
(
app
,
this
);
#endif
...
...
@@ -116,6 +118,7 @@ void QGCToolbox::setChildToolboxes(void)
_videoManager
->
setToolbox
(
this
);
_mavlinkLogManager
->
setToolbox
(
this
);
_airspaceManager
->
setToolbox
(
this
);
_adsbVehicleManager
->
setToolbox
(
this
);
#if defined(QGC_GST_TAISYNC_ENABLED)
_taisyncManager
->
setToolbox
(
this
);
#endif
...
...
src/QGCToolbox.h
View file @
3eec1ca0
...
...
@@ -33,6 +33,7 @@ class MAVLinkLogManager;
class
QGCCorePlugin
;
class
SettingsManager
;
class
AirspaceManager
;
class
ADSBVehicleManager
;
#if defined(QGC_ENABLE_PAIRING)
class
PairingManager
;
#endif
...
...
@@ -67,6 +68,7 @@ public:
QGCCorePlugin
*
corePlugin
()
{
return
_corePlugin
;
}
SettingsManager
*
settingsManager
()
{
return
_settingsManager
;
}
AirspaceManager
*
airspaceManager
()
{
return
_airspaceManager
;
}
ADSBVehicleManager
*
adsbVehicleManager
()
{
return
_adsbVehicleManager
;
}
#if defined(QGC_ENABLE_PAIRING)
PairingManager
*
pairingManager
()
{
return
_pairingManager
;
}
#endif
...
...
@@ -106,6 +108,7 @@ private:
QGCCorePlugin
*
_corePlugin
=
nullptr
;
SettingsManager
*
_settingsManager
=
nullptr
;
AirspaceManager
*
_airspaceManager
=
nullptr
;
ADSBVehicleManager
*
_adsbVehicleManager
=
nullptr
;
#if defined(QGC_ENABLE_PAIRING)
PairingManager
*
_pairingManager
=
nullptr
;
#endif
...
...
src/QmlControls/QGroundControlQmlGlobal.cc
View file @
3eec1ca0
...
...
@@ -66,6 +66,7 @@ void QGroundControlQmlGlobal::setToolbox(QGCToolbox* toolbox)
_settingsManager
=
toolbox
->
settingsManager
();
_gpsRtkFactGroup
=
qgcApp
()
->
gpsRtkFactGroup
();
_airspaceManager
=
toolbox
->
airspaceManager
();
_adsbVehicleManager
=
toolbox
->
adsbVehicleManager
();
#if defined(QGC_ENABLE_PAIRING)
_pairingManager
=
toolbox
->
pairingManager
();
#endif
...
...
src/QmlControls/QGroundControlQmlGlobal.h
View file @
3eec1ca0
...
...
@@ -23,6 +23,7 @@
#include "QGCLoggingCategory.h"
#include "AppSettings.h"
#include "AirspaceManager.h"
#include "ADSBVehicleManager.h"
#if defined(QGC_ENABLE_PAIRING)
#include "PairingManager.h"
#endif
...
...
@@ -73,6 +74,7 @@ public:
Q_PROPERTY
(
SettingsManager
*
settingsManager
READ
settingsManager
CONSTANT
)
Q_PROPERTY
(
FactGroup
*
gpsRtk
READ
gpsRtkFactGroup
CONSTANT
)
Q_PROPERTY
(
AirspaceManager
*
airspaceManager
READ
airspaceManager
CONSTANT
)
Q_PROPERTY
(
ADSBVehicleManager
*
adsbVehicleManager
READ
adsbVehicleManager
CONSTANT
)
Q_PROPERTY
(
bool
airmapSupported
READ
airmapSupported
CONSTANT
)
Q_PROPERTY
(
TaisyncManager
*
taisyncManager
READ
taisyncManager
CONSTANT
)
Q_PROPERTY
(
bool
taisyncSupported
READ
taisyncSupported
CONSTANT
)
...
...
@@ -179,6 +181,7 @@ public:
SettingsManager
*
settingsManager
()
{
return
_settingsManager
;
}
FactGroup
*
gpsRtkFactGroup
()
{
return
_gpsRtkFactGroup
;
}
AirspaceManager
*
airspaceManager
()
{
return
_airspaceManager
;
}
ADSBVehicleManager
*
adsbVehicleManager
()
{
return
_adsbVehicleManager
;
}
#if defined(QGC_ENABLE_PAIRING)
bool
supportsPairing
()
{
return
true
;
}
PairingManager
*
pairingManager
()
{
return
_pairingManager
;
}
...
...
@@ -269,6 +272,7 @@ private:
AirspaceManager
*
_airspaceManager
=
nullptr
;
TaisyncManager
*
_taisyncManager
=
nullptr
;
MicrohardManager
*
_microhardManager
=
nullptr
;
ADSBVehicleManager
*
_adsbVehicleManager
=
nullptr
;
#if defined(QGC_ENABLE_PAIRING)
PairingManager
*
_pairingManager
=
nullptr
;
#endif
...
...
src/Settings/ADSBVehicleManager.SettingsGroup.json
0 → 100644
View file @
3eec1ca0
[
{
"name"
:
"adsbServerConnectEnabled"
,
"shortDescription"
:
"Connect to ADSB SBS server"
,
"longDescription"
:
"Connect to ADSB SBS-1 server using specified address/port"
,
"type"
:
"bool"
,
"defaultValue"
:
false
,
"qgcRebootRequired"
:
true
},
{
"name"
:
"adsbServerHostAddress"
,
"shortDescription"
:
"Host address"
,
"type"
:
"string"
,
"defaultValue"
:
"127.0.0.1"
,
"qgcRebootRequired"
:
true
},
{
"name"
:
"adsbServerPort"
,
"shortDescription"
:
"Server port"
,
"type"
:
"string"
,
"defaultValue"
:
30003
,
"qgcRebootRequired"
:
true
}
]
src/Settings/ADSBVehicleManagerSettings.cc
0 → 100644
View file @
3eec1ca0
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#include "ADSBVehicleManagerSettings.h"
#include <QQmlEngine>
#include <QtQml>
DECLARE_SETTINGGROUP
(
ADSBVehicleManager
,
"ADSBVehicleManager"
)
{
qmlRegisterUncreatableType
<
ADSBVehicleManagerSettings
>
(
"QGroundControl.SettingsManager"
,
1
,
0
,
"ADSBVehicleManagerSettings"
,
"Reference only"
);
}
DECLARE_SETTINGSFACT
(
ADSBVehicleManagerSettings
,
adsbServerConnectEnabled
)
DECLARE_SETTINGSFACT
(
ADSBVehicleManagerSettings
,
adsbServerHostAddress
)
DECLARE_SETTINGSFACT
(
ADSBVehicleManagerSettings
,
adsbServerPort
)
src/Settings/ADSBVehicleManagerSettings.h
0 → 100644
View file @
3eec1ca0
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#pragma once
#include "SettingsGroup.h"
class
ADSBVehicleManagerSettings
:
public
SettingsGroup
{
Q_OBJECT
public:
ADSBVehicleManagerSettings
(
QObject
*
parent
=
nullptr
);
DEFINE_SETTING_NAME_GROUP
()
DEFINE_SETTINGFACT
(
adsbServerConnectEnabled
)
DEFINE_SETTINGFACT
(
adsbServerHostAddress
)
DEFINE_SETTINGFACT
(
adsbServerPort
)
};
src/Settings/SettingsManager.cc
View file @
3eec1ca0
...
...
@@ -28,6 +28,7 @@ SettingsManager::SettingsManager(QGCApplication* app, QGCToolbox* toolbox)
,
_brandImageSettings
(
nullptr
)
,
_offlineMapsSettings
(
nullptr
)
,
_firmwareUpgradeSettings
(
nullptr
)
,
_adsbVehicleManagerSettings
(
nullptr
)
#if !defined(NO_ARDUPILOT_DIALECT)
,
_apmMavlinkStreamRateSettings
(
nullptr
)
#endif
...
...
@@ -41,17 +42,18 @@ void SettingsManager::setToolbox(QGCToolbox *toolbox)
QQmlEngine
::
setObjectOwnership
(
this
,
QQmlEngine
::
CppOwnership
);
qmlRegisterUncreatableType
<
SettingsManager
>
(
"QGroundControl.SettingsManager"
,
1
,
0
,
"SettingsManager"
,
"Reference only"
);
_unitsSettings
=
new
UnitsSettings
(
this
);
// Must be first since AppSettings references it
_appSettings
=
new
AppSettings
(
this
);
_autoConnectSettings
=
new
AutoConnectSettings
(
this
);
_videoSettings
=
new
VideoSettings
(
this
);
_flightMapSettings
=
new
FlightMapSettings
(
this
);
_rtkSettings
=
new
RTKSettings
(
this
);
_flyViewSettings
=
new
FlyViewSettings
(
this
);
_planViewSettings
=
new
PlanViewSettings
(
this
);
_brandImageSettings
=
new
BrandImageSettings
(
this
);
_offlineMapsSettings
=
new
OfflineMapsSettings
(
this
);
_firmwareUpgradeSettings
=
new
FirmwareUpgradeSettings
(
this
);
_unitsSettings
=
new
UnitsSettings
(
this
);
// Must be first since AppSettings references it
_appSettings
=
new
AppSettings
(
this
);
_autoConnectSettings
=
new
AutoConnectSettings
(
this
);
_videoSettings
=
new
VideoSettings
(
this
);
_flightMapSettings
=
new
FlightMapSettings
(
this
);
_rtkSettings
=
new
RTKSettings
(
this
);
_flyViewSettings
=
new
FlyViewSettings
(
this
);
_planViewSettings
=
new
PlanViewSettings
(
this
);
_brandImageSettings
=
new
BrandImageSettings
(
this
);
_offlineMapsSettings
=
new
OfflineMapsSettings
(
this
);
_firmwareUpgradeSettings
=
new
FirmwareUpgradeSettings
(
this
);
_adsbVehicleManagerSettings
=
new
ADSBVehicleManagerSettings
(
this
);
#if !defined(NO_ARDUPILOT_DIALECT)
_apmMavlinkStreamRateSettings
=
new
APMMavlinkStreamRateSettings
(
this
);
#endif
...
...
src/Settings/SettingsManager.h
View file @
3eec1ca0
...
...
@@ -26,6 +26,7 @@
#include "OfflineMapsSettings.h"
#include "APMMavlinkStreamRateSettings.h"
#include "FirmwareUpgradeSettings.h"
#include "ADSBVehicleManagerSettings.h"
#if defined(QGC_AIRMAP_ENABLED)
#include "AirMapSettings.h"
#endif
...
...
@@ -53,6 +54,7 @@ public:
Q_PROPERTY
(
QObject
*
brandImageSettings
READ
brandImageSettings
CONSTANT
)
Q_PROPERTY
(
QObject
*
offlineMapsSettings
READ
offlineMapsSettings
CONSTANT
)
Q_PROPERTY
(
QObject
*
firmwareUpgradeSettings
READ
firmwareUpgradeSettings
CONSTANT
)
Q_PROPERTY
(
QObject
*
adsbVehicleManagerSettings
READ
adsbVehicleManagerSettings
CONSTANT
)
#if !defined(NO_ARDUPILOT_DIALECT)
Q_PROPERTY
(
QObject
*
apmMavlinkStreamRateSettings
READ
apmMavlinkStreamRateSettings
CONSTANT
)
#endif
...
...
@@ -73,6 +75,7 @@ public:
BrandImageSettings
*
brandImageSettings
(
void
)
{
return
_brandImageSettings
;
}
OfflineMapsSettings
*
offlineMapsSettings
(
void
)
{
return
_offlineMapsSettings
;
}
FirmwareUpgradeSettings
*
firmwareUpgradeSettings
(
void
)
{
return
_firmwareUpgradeSettings
;
}
ADSBVehicleManagerSettings
*
adsbVehicleManagerSettings
(
void
)
{
return
_adsbVehicleManagerSettings
;
}
#if !defined(NO_ARDUPILOT_DIALECT)
APMMavlinkStreamRateSettings
*
apmMavlinkStreamRateSettings
(
void
)
{
return
_apmMavlinkStreamRateSettings
;
}
#endif
...
...
@@ -91,6 +94,7 @@ private:
BrandImageSettings
*
_brandImageSettings
;
OfflineMapsSettings
*
_offlineMapsSettings
;
FirmwareUpgradeSettings
*
_firmwareUpgradeSettings
;
ADSBVehicleManagerSettings
*
_adsbVehicleManagerSettings
;
#if !defined(NO_ARDUPILOT_DIALECT)
APMMavlinkStreamRateSettings
*
_apmMavlinkStreamRateSettings
;
#endif
...
...
src/Vehicle/ADSBVehicle.cc
deleted
100644 → 0
View file @
a1ddad8c
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#include "ADSBVehicle.h"
#include <QDebug>
#include <QtMath>
ADSBVehicle
::
ADSBVehicle
(
mavlink_adsb_vehicle_t
&
adsbVehicle
,
QObject
*
parent
)
:
QObject
(
parent
)
,
_icaoAddress
(
adsbVehicle
.
ICAO_address
)
,
_callsign
(
adsbVehicle
.
callsign
)
,
_altitude
(
NAN
)
,
_heading
(
NAN
)
,
_alert
(
false
)
{
if
(
!
(
adsbVehicle
.
flags
&
ADSB_FLAGS_VALID_COORDS
))
{
qWarning
()
<<
"At least coords must be valid"
;
return
;
}
update
(
adsbVehicle
);
}
ADSBVehicle
::
ADSBVehicle
(
const
QGeoCoordinate
&
location
,
float
heading
,
bool
alert
,
QObject
*
parent
)
:
QObject
(
parent
)
,
_icaoAddress
(
0
)
,
_alert
(
alert
)
{
update
(
alert
,
location
,
heading
);
}
void
ADSBVehicle
::
update
(
bool
alert
,
const
QGeoCoordinate
&
location
,
float
heading
)
{
_coordinate
=
location
;
_altitude
=
location
.
altitude
();
_heading
=
heading
;
_alert
=
alert
;
emit
coordinateChanged
();
emit
altitudeChanged
();
emit
headingChanged
();
emit
alertChanged
();
_lastUpdateTimer
.
restart
();
}
void
ADSBVehicle
::
update
(
mavlink_adsb_vehicle_t
&
adsbVehicle
)
{
if
(
_icaoAddress
!=
adsbVehicle
.
ICAO_address
)
{
qWarning
()
<<
"ICAO address mismatch expected:actual"
<<
_icaoAddress
<<
adsbVehicle
.
ICAO_address
;
return
;
}
if
(
!
(
adsbVehicle
.
flags
&
ADSB_FLAGS_VALID_COORDS
))
{
return
;
}
QString
currCallsign
(
adsbVehicle
.
callsign
);
if
(
currCallsign
!=
_callsign
)
{
_callsign
=
currCallsign
;
emit
callsignChanged
();
}
QGeoCoordinate
newCoordinate
(
adsbVehicle
.
lat
/
1e7
,
adsbVehicle
.
lon
/
1e7
);
if
(
newCoordinate
!=
_coordinate
)
{
_coordinate
=
newCoordinate
;
emit
coordinateChanged
();
}
double
newAltitude
=
NAN
;
if
(
adsbVehicle
.
flags
&
ADSB_FLAGS_VALID_ALTITUDE
)
{
newAltitude
=
(
double
)
adsbVehicle
.
altitude
/
1e3
;
}
if
(
!
(
qIsNaN
(
newAltitude
)
&&
qIsNaN
(
_altitude
))
&&
!
qFuzzyCompare
(
newAltitude
,
_altitude
))
{
_altitude
=
newAltitude
;
emit
altitudeChanged
();
}
double
newHeading
=
NAN
;
if
(
adsbVehicle
.
flags
&
ADSB_FLAGS_VALID_HEADING
)
{
newHeading
=
(
double
)
adsbVehicle
.
heading
/
100.0
;
}
if
(
!
(
qIsNaN
(
newHeading
)
&&
qIsNaN
(
_heading
))
&&
!
qFuzzyCompare
(
newHeading
,
_heading
))
{
_heading
=
newHeading
;
emit
headingChanged
();
}
_lastUpdateTimer
.
restart
();
}
bool
ADSBVehicle
::
expired
()
{
return
_lastUpdateTimer
.
hasExpired
(
expirationTimeoutMs
);
}
src/Vehicle/Vehicle.cc
View file @
3eec1ca0
...
...
@@ -36,7 +36,7 @@
#include "QGCQGeoCoordinate.h"
#include "QGCCorePlugin.h"
#include "QGCOptions.h"
#include "ADSBVehicle.h"
#include "ADSBVehicle
Manager
.h"
#include "QGCCameraManager.h"
#include "VideoReceiver.h"
#include "VideoManager.h"
...
...
@@ -113,7 +113,6 @@ Vehicle::Vehicle(LinkInterface* link,
,
_soloFirmware
(
false
)
,
_toolbox
(
qgcApp
()
->
toolbox
())
,
_settingsManager
(
_toolbox
->
settingsManager
())
,
_csvLogTimer
(
this
)
,
_joystickMode
(
JoystickModeRC
)
,
_joystickEnabled
(
false
)
,
_uas
(
nullptr
)
...
...
@@ -297,10 +296,6 @@ Vehicle::Vehicle(LinkInterface* link,
_cameras
=
_firmwarePlugin
->
createCameraManager
(
this
);
emit
dynamicCamerasChanged
();
connect
(
&
_adsbTimer
,
&
QTimer
::
timeout
,
this
,
&
Vehicle
::
_adsbTimerTimeout
);
_adsbTimer
.
setSingleShot
(
false
);
_adsbTimer
.
start
(
1000
);
// Start csv logger
connect
(
&
_csvLogTimer
,
&
QTimer
::
timeout
,
this
,
&
Vehicle
::
_writeCsvLine
);
_csvLogTimer
.
start
(
1000
);
...
...
@@ -325,7 +320,6 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
,
_soloFirmware
(
false
)
,
_toolbox
(
qgcApp
()
->
toolbox
())
,
_settingsManager
(
_toolbox
->
settingsManager
())
,
_csvLogTimer
(
this
)
,
_joystickMode
(
JoystickModeRC
)
,
_joystickEnabled
(
false
)
,
_uas
(
nullptr
)
...
...
@@ -3770,20 +3764,32 @@ bool Vehicle::autoDisarm(void)
void
Vehicle
::
_handleADSBVehicle
(
const
mavlink_message_t
&
message
)
{
mavlink_adsb_vehicle_t
adsbVehicle
;
mavlink_adsb_vehicle_t
adsbVehicle
Msg
;
static
const
int
maxTimeSinceLastSeen
=
15
;
mavlink_msg_adsb_vehicle_decode
(
&
message
,
&
adsbVehicle
);
if
(
adsbVehicle
.
flags
|
ADSB_FLAGS_VALID_COORDS
)
{
if
(
_adsbICAOMap
.
contains
(
adsbVehicle
.
ICAO_address
))
{
if
(
adsbVehicle
.
tslc
<=
maxTimeSinceLastSeen
)
{
_adsbICAOMap
[
adsbVehicle
.
ICAO_address
]
->
update
(
adsbVehicle
);
}
}
else
if
(
adsbVehicle
.
tslc
<=
maxTimeSinceLastSeen
)
{
ADSBVehicle
*
vehicle
=
new
ADSBVehicle
(
adsbVehicle
,
this
);
_adsbICAOMap
[
adsbVehicle
.
ICAO_address
]
=
vehicle
;
_adsbVehicles
.
append
(
vehicle
);
mavlink_msg_adsb_vehicle_decode
(
&
message
,
&
adsbVehicleMsg
);
if
(
adsbVehicleMsg
.
flags
|
ADSB_FLAGS_VALID_COORDS
&&
adsbVehicleMsg
.
tslc
<=
maxTimeSinceLastSeen
)
{
ADSBVehicle
::
VehicleInfo_t
vehicleInfo
;
vehicleInfo
.
availableFlags
=
0
;
vehicleInfo
.
location
.
setLatitude
(
adsbVehicleMsg
.
lat
/
1e7
);
vehicleInfo
.
location
.
setLatitude
(
adsbVehicleMsg
.
lon
/
1e7
);
vehicleInfo
.
callsign
=
adsbVehicleMsg
.
callsign
;
vehicleInfo
.
availableFlags
|=
ADSBVehicle
::
CallsignAvailable
;
if
(
adsbVehicleMsg
.
flags
&
ADSB_FLAGS_VALID_ALTITUDE
)
{
vehicleInfo
.
altitude
=
(
double
)
adsbVehicleMsg
.
altitude
/
1e3
;
vehicleInfo
.
availableFlags
|=
ADSBVehicle
::
AltitudeAvailable
;
}
if
(
adsbVehicleMsg
.
flags
&
ADSB_FLAGS_VALID_HEADING
)
{
vehicleInfo
.
heading
=
(
double
)
adsbVehicleMsg
.
heading
/
100.0
;
vehicleInfo
.
availableFlags
|=
ADSBVehicle
::
HeadingAvailable
;
}
_toolbox
->
adsbVehicleManager
()
->
adsbVehicleUpdate
(
vehicleInfo
);
}
}
...
...
@@ -3895,11 +3901,11 @@ void Vehicle::_updateHighLatencyLink(bool sendCommand)
}
}
void
Vehicle
::
_trafficUpdate
(
bool
alert
,
QString
traffic_id
,
QString
vehicle_id
,
QGeoCoordinate
location
,
float
heading
)
void
Vehicle
::
_trafficUpdate
(
bool
/*alert*/
,
QString
/*traffic_id*/
,
QString
/*vehicle_id*/
,
QGeoCoordinate
/*location*/
,
float
/*heading*/
)
{
Q_UNUSED
(
vehicle_id
);
//
qDebug() << "traffic update:" << traffic_id << vehicle_id << heading << location;
//
TODO: filter based on minimum altitude?
#if 0
//
This is ifdef'ed out for now since this code doesn't mesh with the recent ADSB manager changes. Also airmap isn't in any
//
released build. So not going to waste time trying to fix up unused code.
if (_trafficVehicleMap.contains(traffic_id)) {
_trafficVehicleMap[traffic_id]->update(alert, location, heading);
} else {
...
...
@@ -3907,19 +3913,7 @@ void Vehicle::_trafficUpdate(bool alert, QString traffic_id, QString vehicle_id,
_trafficVehicleMap[traffic_id] = vehicle;
_adsbVehicles.append(vehicle);
}
}
void
Vehicle
::
_adsbTimerTimeout
()
{
// Remove all expired ADSB vehicle whether from AirMap or ADSB Mavlink
for
(
int
i
=
_adsbVehicles
.
count
()
-
1
;
i
>=
0
;
i
--
)
{
ADSBVehicle
*
adsbVehicle
=
_adsbVehicles
.
value
<
ADSBVehicle
*>
(
i
);
if
(
adsbVehicle
->
expired
())
{
qDebug
()
<<
"ADSB expired"
;
_adsbVehicles
.
removeAt
(
i
);
adsbVehicle
->
deleteLater
();
}
}
#endif
}
void
Vehicle
::
_mavlinkMessageStatus
(
int
uasId
,
uint64_t
totalSent
,
uint64_t
totalReceived
,
uint64_t
totalLoss
,
float
lossPercent
)
...
...
src/Vehicle/Vehicle.h
View file @
3eec1ca0
...
...
@@ -34,7 +34,6 @@ class ParameterManager;
class
JoystickManager
;
class
UASMessage
;
class
SettingsManager
;
class
ADSBVehicle
;
class
QGCCameraManager
;
class
Joystick
;
class
VehicleObjectAvoidance
;
...
...
@@ -621,7 +620,6 @@ public:
Q_PROPERTY
(
int
telemetryLNoise
READ
telemetryLNoise
NOTIFY
telemetryLNoiseChanged
)
Q_PROPERTY
(
int
telemetryRNoise
READ
telemetryRNoise
NOTIFY
telemetryRNoiseChanged
)
Q_PROPERTY
(
QVariantList
toolBarIndicators
READ
toolBarIndicators
NOTIFY
toolBarIndicatorsChanged
)
Q_PROPERTY
(
QmlObjectListModel
*
adsbVehicles
READ
adsbVehicles
CONSTANT
)
Q_PROPERTY
(
bool
initialPlanRequestComplete
READ
initialPlanRequestComplete
NOTIFY
initialPlanRequestCompleteChanged
)
Q_PROPERTY
(
QVariantList
staticCameraList
READ
staticCameraList
CONSTANT
)
Q_PROPERTY
(
QGCCameraManager
*
dynamicCameras
READ
dynamicCameras
NOTIFY
dynamicCamerasChanged
)
...
...
@@ -880,7 +878,6 @@ public:
void
setPrearmError
(
const
QString
&
prearmError
);
QmlObjectListModel
*
cameraTriggerPoints
(
void
)
{
return
&
_cameraTriggerPoints
;
}
QmlObjectListModel
*
adsbVehicles
(
void
)
{
return
&
_adsbVehicles
;
}
int
flowImageIndex
()
{
return
_flowImageIndex
;
}
...
...
@@ -1257,7 +1254,6 @@ private slots:
void
_mavlinkMessageStatus
(
int
uasId
,
uint64_t
totalSent
,
uint64_t
totalReceived
,
uint64_t
totalLoss
,
float
lossPercent
);
void
_trafficUpdate
(
bool
alert
,
QString
traffic_id
,
QString
vehicle_id
,
QGeoCoordinate
location
,
float
heading
);
void
_adsbTimerTimeout
();
void
_orbitTelemetryTimeout
(
void
);
void
_protocolVersionTimeOut
(
void
);
void
_updateFlightTime
(
void
);
...
...
@@ -1468,10 +1464,7 @@ private:
QTimer
_flightTimeUpdater
;
TrajectoryPoints
*
_trajectoryPoints
;
QmlObjectListModel
_cameraTriggerPoints
;
QmlObjectListModel
_adsbVehicles
;
QMap
<
uint32_t
,
ADSBVehicle
*>
_adsbICAOMap
;
QMap
<
QString
,
ADSBVehicle
*>
_trafficVehicleMap
;
QTimer
_adsbTimer
;
//QMap<QString, ADSBVehicle*> _trafficVehicleMap;
// Toolbox references
FirmwarePluginManager
*
_firmwarePluginManager
;
...
...
src/ui/preferences/GeneralSettings.qml
View file @
3eec1ca0
...
...
@@ -840,6 +840,59 @@ Rectangle {
Item
{
width
:
1
;
height
:
_margins
}
QGCLabel
{
id
:
adsbSectionLabel
text
:
qsTr
(
"
ADSB Server
"
)
visible
:
QGroundControl
.
settingsManager
.
adsbVehicleManagerSettings
.
visible
}
Rectangle
{
Layout.preferredHeight
:
adsbGrid
.
height
+
(
_margins
*
2
)
Layout.preferredWidth
:
adsbGrid
.
width
+
(
_margins
*
2
)
color
:
qgcPal
.
windowShade
visible
:
adsbSectionLabel
.
visible
Layout.fillWidth
:
true
GridLayout
{
id
:
adsbGrid
anchors.topMargin
:
_margins
anchors.top
:
parent
.
top
Layout.fillWidth
:
true
anchors.horizontalCenter
:
parent
.
horizontalCenter
columns
:
2
property
var
adsbSettings
:
QGroundControl
.
settingsManager
.
adsbVehicleManagerSettings
FactCheckBox
{
text
:
adsbGrid
.
adsbSettings
.
adsbServerConnectEnabled
.
shortDescription
fact
:
adsbGrid
.
adsbSettings
.
adsbServerConnectEnabled
visible
:
adsbGrid
.
adsbSettings
.
adsbServerConnectEnabled
.
visible
Layout.columnSpan
:
2
}
QGCLabel
{
text
:
adsbGrid
.
adsbSettings
.
adsbServerHostAddress
.
shortDescription
visible
:
adsbGrid
.
adsbSettings
.
adsbServerHostAddress
.
visible
}
FactTextField
{
fact
:
adsbGrid
.
adsbSettings
.
adsbServerHostAddress
visible
:
adsbGrid
.
adsbSettings
.
adsbServerHostAddress
.
visible
Layout.preferredWidth
:
_valueFieldWidth
}
QGCLabel
{
text
:
adsbGrid
.
adsbSettings
.
adsbServerPort
.
shortDescription
visible
:
adsbGrid
.
adsbSettings
.
adsbServerPort
.
visible
}
FactTextField
{
fact
:
adsbGrid
.
adsbSettings
.
adsbServerPort
visible
:
adsbGrid
.
adsbSettings
.
adsbServerPort
.
visible
Layout.preferredWidth
:
_valueFieldWidth
}
}
}
Item
{
width
:
1
;
height
:
_margins
}
QGCLabel
{
id
:
videoSectionLabel
text
:
qsTr
(
"
Video
"
)
...
...
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment