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
4776f1d4
Commit
4776f1d4
authored
Jul 20, 2017
by
Lorenz Meier
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Flight display: Add callsign to transponders
parent
24a7ab10
Changes
4
Show whitespace changes
Inline
Side-by-side
Showing
4 changed files
with
17 additions
and
3 deletions
+17
-3
FlightDisplayViewMap.qml
src/FlightDisplay/FlightDisplayViewMap.qml
+1
-0
VehicleMapItem.qml
src/FlightMap/MapItems/VehicleMapItem.qml
+2
-1
ADSBVehicle.cc
src/Vehicle/ADSBVehicle.cc
+10
-2
ADSBVehicle.h
src/Vehicle/ADSBVehicle.h
+4
-0
No files found.
src/FlightDisplay/FlightDisplayViewMap.qml
View file @
4776f1d4
...
@@ -199,6 +199,7 @@ FlightMap {
...
@@ -199,6 +199,7 @@ FlightMap {
delegate
:
VehicleMapItem
{
delegate
:
VehicleMapItem
{
coordinate
:
object
.
coordinate
coordinate
:
object
.
coordinate
altitude
:
object
.
altitude
altitude
:
object
.
altitude
callsign
:
object
.
callsign
heading
:
object
.
heading
heading
:
object
.
heading
map
:
flightMap
map
:
flightMap
z
:
QGroundControl
.
zOrderVehicles
z
:
QGroundControl
.
zOrderVehicles
...
...
src/FlightMap/MapItems/VehicleMapItem.qml
View file @
4776f1d4
...
@@ -21,6 +21,7 @@ MapQuickItem {
...
@@ -21,6 +21,7 @@ MapQuickItem {
property
var
vehicle
/// Vehicle object, undefined for ADSB vehicle
property
var
vehicle
/// Vehicle object, undefined for ADSB vehicle
property
var
map
property
var
map
property
double
altitude
:
Number
.
NaN
///< NAN to not show
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
double
heading
:
vehicle
?
vehicle
.
heading
.
value
:
Number
.
NaN
///< Vehicle heading, NAN for none
property
real
size
:
_adsbVehicle
?
_adsbSize
:
_uavSize
/// Size for icon
property
real
size
:
_adsbVehicle
?
_adsbSize
:
_uavSize
/// Size for icon
...
@@ -65,7 +66,7 @@ MapQuickItem {
...
@@ -65,7 +66,7 @@ MapQuickItem {
property
string
vehicleLabelText
:
visible
?
property
string
vehicleLabelText
:
visible
?
(
_adsbVehicle
?
(
_adsbVehicle
?
QGroundControl
.
metersToAppSettingsDistanceUnits
(
altitude
).
toFixed
(
0
)
+
"
"
+
QGroundControl
.
appSettingsDistanceUnitsString
:
callsign
+
"
"
+
QGroundControl
.
metersToAppSettingsDistanceUnits
(
altitude
).
toFixed
(
0
)
+
"
"
+
QGroundControl
.
appSettingsDistanceUnitsString
:
(
_multiVehicle
?
qsTr
(
"
Vehicle %1
"
).
arg
(
vehicle
.
id
)
:
""
))
:
(
_multiVehicle
?
qsTr
(
"
Vehicle %1
"
).
arg
(
vehicle
.
id
)
:
""
))
:
""
""
...
...
src/Vehicle/ADSBVehicle.cc
View file @
4776f1d4
...
@@ -15,6 +15,7 @@
...
@@ -15,6 +15,7 @@
ADSBVehicle
::
ADSBVehicle
(
mavlink_adsb_vehicle_t
&
adsbVehicle
,
QObject
*
parent
)
ADSBVehicle
::
ADSBVehicle
(
mavlink_adsb_vehicle_t
&
adsbVehicle
,
QObject
*
parent
)
:
QObject
(
parent
)
:
QObject
(
parent
)
,
_icaoAddress
(
adsbVehicle
.
ICAO_address
)
,
_icaoAddress
(
adsbVehicle
.
ICAO_address
)
,
_callsign
(
adsbVehicle
.
callsign
)
,
_altitude
(
NAN
)
,
_altitude
(
NAN
)
,
_heading
(
NAN
)
,
_heading
(
NAN
)
{
{
...
@@ -37,7 +38,14 @@ void ADSBVehicle::update(mavlink_adsb_vehicle_t& adsbVehicle)
...
@@ -37,7 +38,14 @@ void ADSBVehicle::update(mavlink_adsb_vehicle_t& adsbVehicle)
return
;
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
)
{
if
(
newCoordinate
!=
_coordinate
)
{
_coordinate
=
newCoordinate
;
_coordinate
=
newCoordinate
;
emit
coordinateChanged
(
_coordinate
);
emit
coordinateChanged
(
_coordinate
);
...
@@ -45,7 +53,7 @@ void ADSBVehicle::update(mavlink_adsb_vehicle_t& adsbVehicle)
...
@@ -45,7 +53,7 @@ void ADSBVehicle::update(mavlink_adsb_vehicle_t& adsbVehicle)
double
newAltitude
=
NAN
;
double
newAltitude
=
NAN
;
if
(
adsbVehicle
.
flags
|
ADSB_FLAGS_VALID_ALTITUDE
)
{
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
))
{
if
(
!
(
qIsNaN
(
newAltitude
)
&&
qIsNaN
(
_altitude
))
&&
!
qFuzzyCompare
(
newAltitude
,
_altitude
))
{
_altitude
=
newAltitude
;
_altitude
=
newAltitude
;
...
...
src/Vehicle/ADSBVehicle.h
View file @
4776f1d4
...
@@ -22,11 +22,13 @@ public:
...
@@ -22,11 +22,13 @@ public:
ADSBVehicle
(
mavlink_adsb_vehicle_t
&
adsbVehicle
,
QObject
*
parent
=
NULL
);
ADSBVehicle
(
mavlink_adsb_vehicle_t
&
adsbVehicle
,
QObject
*
parent
=
NULL
);
Q_PROPERTY
(
int
icaoAddress
READ
icaoAddress
CONSTANT
)
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
(
QGeoCoordinate
coordinate
READ
coordinate
NOTIFY
coordinateChanged
)
Q_PROPERTY
(
double
altitude
READ
altitude
NOTIFY
altitudeChanged
)
// NaN for not available
Q_PROPERTY
(
double
altitude
READ
altitude
NOTIFY
altitudeChanged
)
// NaN for not available
Q_PROPERTY
(
double
heading
READ
heading
NOTIFY
headingChanged
)
// NaN for not available
Q_PROPERTY
(
double
heading
READ
heading
NOTIFY
headingChanged
)
// NaN for not available
int
icaoAddress
(
void
)
const
{
return
_icaoAddress
;
}
int
icaoAddress
(
void
)
const
{
return
_icaoAddress
;
}
QString
callsign
(
void
)
const
{
return
_callsign
;
}
QGeoCoordinate
coordinate
(
void
)
const
{
return
_coordinate
;
}
QGeoCoordinate
coordinate
(
void
)
const
{
return
_coordinate
;
}
double
altitude
(
void
)
const
{
return
_altitude
;
}
double
altitude
(
void
)
const
{
return
_altitude
;
}
double
heading
(
void
)
const
{
return
_heading
;
}
double
heading
(
void
)
const
{
return
_heading
;
}
...
@@ -36,11 +38,13 @@ public:
...
@@ -36,11 +38,13 @@ public:
signals:
signals:
void
coordinateChanged
(
QGeoCoordinate
coordinate
);
void
coordinateChanged
(
QGeoCoordinate
coordinate
);
void
callsignChanged
(
QString
callsign
);
void
altitudeChanged
(
double
altitude
);
void
altitudeChanged
(
double
altitude
);
void
headingChanged
(
double
heading
);
void
headingChanged
(
double
heading
);
private:
private:
uint32_t
_icaoAddress
;
uint32_t
_icaoAddress
;
QString
_callsign
;
QGeoCoordinate
_coordinate
;
QGeoCoordinate
_coordinate
;
double
_altitude
;
double
_altitude
;
double
_heading
;
double
_heading
;
...
...
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