Skip to content
GitLab
Projects
Groups
Snippets
/
Help
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Menu
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
3819cb37
Commit
3819cb37
authored
Jul 20, 2017
by
Don Gagne
Committed by
GitHub
Jul 20, 2017
Browse files
Merge pull request #5476 from mavlink/pr-adsb-tweaks
Flight display: Add callsign to transponders
parents
24a7ab10
4776f1d4
Changes
4
Hide whitespace changes
Inline
Side-by-side
src/FlightDisplay/FlightDisplayViewMap.qml
View file @
3819cb37
...
...
@@ -199,6 +199,7 @@ FlightMap {
delegate
:
VehicleMapItem
{
coordinate
:
object
.
coordinate
altitude
:
object
.
altitude
callsign
:
object
.
callsign
heading
:
object
.
heading
map
:
flightMap
z
:
QGroundControl
.
zOrderVehicles
...
...
src/FlightMap/MapItems/VehicleMapItem.qml
View file @
3819cb37
...
...
@@ -21,6 +21,7 @@ MapQuickItem {
property
var
vehicle
/// Vehicle object, undefined for ADSB vehicle
property
var
map
property
double
altitude
:
Number
.
NaN
///< NAN to not show
property
string
callsign
:
""
///< Vehicle callsign
property
double
heading
:
vehicle
?
vehicle
.
heading
.
value
:
Number
.
NaN
///< Vehicle heading, NAN for none
property
real
size
:
_adsbVehicle
?
_adsbSize
:
_uavSize
/// Size for icon
...
...
@@ -65,7 +66,7 @@ MapQuickItem {
property
string
vehicleLabelText
:
visible
?
(
_adsbVehicle
?
QGroundControl
.
metersToAppSettingsDistanceUnits
(
altitude
).
toFixed
(
0
)
+
"
"
+
QGroundControl
.
appSettingsDistanceUnitsString
:
callsign
+
"
"
+
QGroundControl
.
metersToAppSettingsDistanceUnits
(
altitude
).
toFixed
(
0
)
+
"
"
+
QGroundControl
.
appSettingsDistanceUnitsString
:
(
_multiVehicle
?
qsTr
(
"
Vehicle %1
"
).
arg
(
vehicle
.
id
)
:
""
))
:
""
...
...
src/Vehicle/ADSBVehicle.cc
View file @
3819cb37
...
...
@@ -15,6 +15,7 @@
ADSBVehicle
::
ADSBVehicle
(
mavlink_adsb_vehicle_t
&
adsbVehicle
,
QObject
*
parent
)
:
QObject
(
parent
)
,
_icaoAddress
(
adsbVehicle
.
ICAO_address
)
,
_callsign
(
adsbVehicle
.
callsign
)
,
_altitude
(
NAN
)
,
_heading
(
NAN
)
{
...
...
@@ -37,7 +38,14 @@ void ADSBVehicle::update(mavlink_adsb_vehicle_t& adsbVehicle)
return
;
}
QGeoCoordinate
newCoordinate
(
adsbVehicle
.
lat
/
qPow
(
10.0
,
7.0
),
adsbVehicle
.
lon
/
qPow
(
10.0
,
7.0
));
QString
currCallsign
(
adsbVehicle
.
callsign
);
if
(
currCallsign
!=
_callsign
)
{
_callsign
=
currCallsign
;
emit
callsignChanged
(
_callsign
);
}
QGeoCoordinate
newCoordinate
(
adsbVehicle
.
lat
/
1e7
,
adsbVehicle
.
lon
/
1e7
);
if
(
newCoordinate
!=
_coordinate
)
{
_coordinate
=
newCoordinate
;
emit
coordinateChanged
(
_coordinate
);
...
...
@@ -45,7 +53,7 @@ void ADSBVehicle::update(mavlink_adsb_vehicle_t& adsbVehicle)
double
newAltitude
=
NAN
;
if
(
adsbVehicle
.
flags
|
ADSB_FLAGS_VALID_ALTITUDE
)
{
newAltitude
=
(
double
)
adsbVehicle
.
altitude
/
1
000.0
;
newAltitude
=
(
double
)
adsbVehicle
.
altitude
/
1
e3
;
}
if
(
!
(
qIsNaN
(
newAltitude
)
&&
qIsNaN
(
_altitude
))
&&
!
qFuzzyCompare
(
newAltitude
,
_altitude
))
{
_altitude
=
newAltitude
;
...
...
src/Vehicle/ADSBVehicle.h
View file @
3819cb37
...
...
@@ -22,11 +22,13 @@ public:
ADSBVehicle
(
mavlink_adsb_vehicle_t
&
adsbVehicle
,
QObject
*
parent
=
NULL
);
Q_PROPERTY
(
int
icaoAddress
READ
icaoAddress
CONSTANT
)
Q_PROPERTY
(
QString
callsign
READ
callsign
NOTIFY
callsignChanged
)
Q_PROPERTY
(
QGeoCoordinate
coordinate
READ
coordinate
NOTIFY
coordinateChanged
)
Q_PROPERTY
(
double
altitude
READ
altitude
NOTIFY
altitudeChanged
)
// NaN for not available
Q_PROPERTY
(
double
heading
READ
heading
NOTIFY
headingChanged
)
// NaN for not available
int
icaoAddress
(
void
)
const
{
return
_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
;
}
...
...
@@ -36,11 +38,13 @@ public:
signals:
void
coordinateChanged
(
QGeoCoordinate
coordinate
);
void
callsignChanged
(
QString
callsign
);
void
altitudeChanged
(
double
altitude
);
void
headingChanged
(
double
heading
);
private:
uint32_t
_icaoAddress
;
QString
_callsign
;
QGeoCoordinate
_coordinate
;
double
_altitude
;
double
_heading
;
...
...
Write
Preview
Supports
Markdown
0%
Try again
or
attach a new 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