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
03ff0d1f
Commit
03ff0d1f
authored
Dec 29, 2015
by
dogmaphobic
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Using HDOP for GPS signal strength indicator.
parent
1be8c6b3
Changes
6
Show whitespace changes
Inline
Side-by-side
Showing
6 changed files
with
163 additions
and
37 deletions
+163
-37
Vehicle.cc
src/Vehicle/Vehicle.cc
+39
-2
Vehicle.h
src/Vehicle/Vehicle.h
+15
-0
UAS.cc
src/uas/UAS.cc
+27
-2
UAS.h
src/uas/UAS.h
+47
-20
MainToolBar.qml
src/ui/toolbar/MainToolBar.qml
+24
-0
MainToolBarIndicators.qml
src/ui/toolbar/MainToolBarIndicators.qml
+11
-13
No files found.
src/Vehicle/Vehicle.cc
View file @
03ff0d1f
...
@@ -90,6 +90,9 @@ Vehicle::Vehicle(LinkInterface* link,
...
@@ -90,6 +90,9 @@ Vehicle::Vehicle(LinkInterface* link,
,
_batteryConsumed
(
-
1.0
)
,
_batteryConsumed
(
-
1.0
)
,
_currentHeartbeatTimeout
(
0
)
,
_currentHeartbeatTimeout
(
0
)
,
_satelliteCount
(
-
1
)
,
_satelliteCount
(
-
1
)
,
_satRawHDOP
(
1e10
f
)
,
_satRawVDOP
(
1e10
f
)
,
_satRawCOG
(
0.0
)
,
_satelliteLock
(
0
)
,
_satelliteLock
(
0
)
,
_updateCount
(
0
)
,
_updateCount
(
0
)
,
_rcRSSI
(
0
)
,
_rcRSSI
(
0
)
...
@@ -137,9 +140,16 @@ Vehicle::Vehicle(LinkInterface* link,
...
@@ -137,9 +140,16 @@ Vehicle::Vehicle(LinkInterface* link,
emit
heartbeatTimeoutChanged
();
emit
heartbeatTimeoutChanged
();
_mav
=
uas
();
_mav
=
uas
();
// Reset satellite
count
(no GPS)
// Reset satellite
data
(no GPS)
_satelliteCount
=
-
1
;
_satelliteCount
=
-
1
;
_satRawHDOP
=
1e10
f
;
_satRawVDOP
=
1e10
f
;
_satRawCOG
=
0.0
;
emit
satRawHDOPChanged
();
emit
satRawVDOPChanged
();
emit
satRawCOGChanged
();
emit
satelliteCountChanged
();
emit
satelliteCountChanged
();
// Reset connection lost (if any)
// Reset connection lost (if any)
_currentHeartbeatTimeout
=
0
;
_currentHeartbeatTimeout
=
0
;
emit
heartbeatTimeoutChanged
();
emit
heartbeatTimeoutChanged
();
...
@@ -162,6 +172,9 @@ Vehicle::Vehicle(LinkInterface* link,
...
@@ -162,6 +172,9 @@ Vehicle::Vehicle(LinkInterface* link,
if
(
pUas
)
{
if
(
pUas
)
{
_setSatelliteCount
(
pUas
->
getSatelliteCount
(),
QString
(
""
));
_setSatelliteCount
(
pUas
->
getSatelliteCount
(),
QString
(
""
));
connect
(
pUas
,
&
UAS
::
satelliteCountChanged
,
this
,
&
Vehicle
::
_setSatelliteCount
);
connect
(
pUas
,
&
UAS
::
satelliteCountChanged
,
this
,
&
Vehicle
::
_setSatelliteCount
);
connect
(
pUas
,
&
UAS
::
satRawHDOPChanged
,
this
,
&
Vehicle
::
_setSatRawHDOP
);
connect
(
pUas
,
&
UAS
::
satRawVDOPChanged
,
this
,
&
Vehicle
::
_setSatRawVDOP
);
connect
(
pUas
,
&
UAS
::
satRawCOGChanged
,
this
,
&
Vehicle
::
_setSatRawCOG
);
}
}
_loadSettings
();
_loadSettings
();
...
@@ -754,6 +767,30 @@ void Vehicle::_setSatelliteCount(double val, QString)
...
@@ -754,6 +767,30 @@ void Vehicle::_setSatelliteCount(double val, QString)
}
}
}
}
void
Vehicle
::
_setSatRawHDOP
(
double
val
)
{
if
(
_satRawHDOP
!=
val
)
{
_satRawHDOP
=
val
;
emit
satRawHDOPChanged
();
}
}
void
Vehicle
::
_setSatRawVDOP
(
double
val
)
{
if
(
_satRawVDOP
!=
val
)
{
_satRawVDOP
=
val
;
emit
satRawVDOPChanged
();
}
}
void
Vehicle
::
_setSatRawCOG
(
double
val
)
{
if
(
_satRawCOG
!=
val
)
{
_satRawCOG
=
val
;
emit
satRawCOGChanged
();
}
}
void
Vehicle
::
_setSatLoc
(
UASInterface
*
,
int
fix
)
void
Vehicle
::
_setSatLoc
(
UASInterface
*
,
int
fix
)
{
{
// fix 0: lost, 1: at least one satellite, but no GPS fix, 2: 2D lock, 3: 3D lock
// fix 0: lost, 1: at least one satellite, but no GPS fix, 2: 2D lock, 3: 3D lock
...
...
src/Vehicle/Vehicle.h
View file @
03ff0d1f
...
@@ -93,6 +93,9 @@ public:
...
@@ -93,6 +93,9 @@ public:
Q_PROPERTY
(
double
batteryPercent
READ
batteryPercent
NOTIFY
batteryPercentChanged
)
Q_PROPERTY
(
double
batteryPercent
READ
batteryPercent
NOTIFY
batteryPercentChanged
)
Q_PROPERTY
(
double
batteryConsumed
READ
batteryConsumed
NOTIFY
batteryConsumedChanged
)
Q_PROPERTY
(
double
batteryConsumed
READ
batteryConsumed
NOTIFY
batteryConsumedChanged
)
Q_PROPERTY
(
int
satelliteCount
READ
satelliteCount
NOTIFY
satelliteCountChanged
)
Q_PROPERTY
(
int
satelliteCount
READ
satelliteCount
NOTIFY
satelliteCountChanged
)
Q_PROPERTY
(
double
satRawHDOP
READ
satRawHDOP
NOTIFY
satRawHDOPChanged
)
Q_PROPERTY
(
double
satRawVDOP
READ
satRawVDOP
NOTIFY
satRawVDOPChanged
)
Q_PROPERTY
(
double
satRawCOG
READ
satRawCOG
NOTIFY
satRawCOGChanged
)
Q_PROPERTY
(
QString
currentState
READ
currentState
NOTIFY
currentStateChanged
)
Q_PROPERTY
(
QString
currentState
READ
currentState
NOTIFY
currentStateChanged
)
Q_PROPERTY
(
int
satelliteLock
READ
satelliteLock
NOTIFY
satelliteLockChanged
)
Q_PROPERTY
(
int
satelliteLock
READ
satelliteLock
NOTIFY
satelliteLockChanged
)
Q_PROPERTY
(
unsigned
int
heartbeatTimeout
READ
heartbeatTimeout
NOTIFY
heartbeatTimeoutChanged
)
Q_PROPERTY
(
unsigned
int
heartbeatTimeout
READ
heartbeatTimeout
NOTIFY
heartbeatTimeoutChanged
)
...
@@ -250,6 +253,9 @@ public:
...
@@ -250,6 +253,9 @@ public:
float
longitude
()
{
return
_coordinate
.
longitude
();
}
float
longitude
()
{
return
_coordinate
.
longitude
();
}
bool
mavPresent
()
{
return
_mav
!=
NULL
;
}
bool
mavPresent
()
{
return
_mav
!=
NULL
;
}
int
satelliteCount
()
{
return
_satelliteCount
;
}
int
satelliteCount
()
{
return
_satelliteCount
;
}
double
satRawHDOP
()
{
return
_satRawHDOP
;
}
double
satRawVDOP
()
{
return
_satRawVDOP
;
}
double
satRawCOG
()
{
return
_satRawCOG
;
}
double
batteryVoltage
()
{
return
_batteryVoltage
;
}
double
batteryVoltage
()
{
return
_batteryVoltage
;
}
double
batteryPercent
()
{
return
_batteryPercent
;
}
double
batteryPercent
()
{
return
_batteryPercent
;
}
double
batteryConsumed
()
{
return
_batteryConsumed
;
}
double
batteryConsumed
()
{
return
_batteryConsumed
;
}
...
@@ -309,6 +315,9 @@ signals:
...
@@ -309,6 +315,9 @@ signals:
void
heartbeatTimeoutChanged
();
void
heartbeatTimeoutChanged
();
void
currentConfigChanged
();
void
currentConfigChanged
();
void
satelliteCountChanged
();
void
satelliteCountChanged
();
void
satRawHDOPChanged
();
void
satRawVDOPChanged
();
void
satRawCOGChanged
();
void
currentStateChanged
();
void
currentStateChanged
();
void
satelliteLockChanged
();
void
satelliteLockChanged
();
void
flowImageIndexChanged
();
void
flowImageIndexChanged
();
...
@@ -352,6 +361,9 @@ private slots:
...
@@ -352,6 +361,9 @@ private slots:
void
_updateState
(
UASInterface
*
system
,
QString
name
,
QString
description
);
void
_updateState
(
UASInterface
*
system
,
QString
name
,
QString
description
);
void
_heartbeatTimeout
(
bool
timeout
,
unsigned
int
ms
);
void
_heartbeatTimeout
(
bool
timeout
,
unsigned
int
ms
);
void
_setSatelliteCount
(
double
val
,
QString
name
);
void
_setSatelliteCount
(
double
val
,
QString
name
);
void
_setSatRawHDOP
(
double
val
);
void
_setSatRawVDOP
(
double
val
);
void
_setSatRawCOG
(
double
val
);
void
_setSatLoc
(
UASInterface
*
uas
,
int
fix
);
void
_setSatLoc
(
UASInterface
*
uas
,
int
fix
);
/** @brief A new camera image has arrived */
/** @brief A new camera image has arrived */
void
_imageReady
(
UASInterface
*
uas
);
void
_imageReady
(
UASInterface
*
uas
);
...
@@ -425,6 +437,9 @@ private:
...
@@ -425,6 +437,9 @@ private:
QString
_currentState
;
QString
_currentState
;
unsigned
int
_currentHeartbeatTimeout
;
unsigned
int
_currentHeartbeatTimeout
;
int
_satelliteCount
;
int
_satelliteCount
;
double
_satRawHDOP
;
double
_satRawVDOP
;
double
_satRawCOG
;
int
_satelliteLock
;
int
_satelliteLock
;
int
_updateCount
;
int
_updateCount
;
QString
_formatedMessage
;
QString
_formatedMessage
;
...
...
src/uas/UAS.cc
View file @
03ff0d1f
...
@@ -96,6 +96,10 @@ UAS::UAS(MAVLinkProtocol* protocol, Vehicle* vehicle, FirmwarePluginManager * fi
...
@@ -96,6 +96,10 @@ UAS::UAS(MAVLinkProtocol* protocol, Vehicle* vehicle, FirmwarePluginManager * fi
altitudeWGS84
(
0.0
),
altitudeWGS84
(
0.0
),
altitudeRelative
(
0.0
),
altitudeRelative
(
0.0
),
satRawHDOP
(
1e10
f
),
satRawVDOP
(
1e10
f
),
satRawCOG
(
0.0
),
globalEstimatorActive
(
false
),
globalEstimatorActive
(
false
),
latitude_gps
(
0.0
),
latitude_gps
(
0.0
),
...
@@ -738,6 +742,27 @@ void UAS::receiveMessage(mavlink_message_t message)
...
@@ -738,6 +742,27 @@ void UAS::receiveMessage(mavlink_message_t message)
}
}
}
}
double
dtmp
;
//-- Raw GPS data
dtmp
=
pos
.
eph
==
0xFFFF
?
1e10
f
:
pos
.
eph
/
100.0
;
if
(
dtmp
!=
satRawHDOP
)
{
satRawHDOP
=
dtmp
;
emit
satRawHDOPChanged
(
satRawHDOP
);
}
dtmp
=
pos
.
epv
==
0xFFFF
?
1e10
f
:
pos
.
epv
/
100.0
;
if
(
dtmp
!=
satRawVDOP
)
{
satRawVDOP
=
dtmp
;
emit
satRawVDOPChanged
(
satRawVDOP
);
}
dtmp
=
pos
.
cog
==
0xFFFF
?
0.0
:
pos
.
cog
/
100.0
;
if
(
dtmp
!=
satRawCOG
)
{
satRawCOG
=
dtmp
;
emit
satRawCOGChanged
(
satRawCOG
);
}
// Emit this signal after the above signals. This way a trigger on gps lock signal which then asks for vehicle position
// Emit this signal after the above signals. This way a trigger on gps lock signal which then asks for vehicle position
// gets a good position.
// gets a good position.
emit
localizationChanged
(
this
,
loc_type
);
emit
localizationChanged
(
this
,
loc_type
);
...
...
src/uas/UAS.h
View file @
03ff0d1f
...
@@ -96,6 +96,9 @@ public:
...
@@ -96,6 +96,9 @@ public:
Q_PROPERTY
(
double
altitudeAMSLFT
READ
getAltitudeAMSLFT
NOTIFY
altitudeAMSLFTChanged
)
Q_PROPERTY
(
double
altitudeAMSLFT
READ
getAltitudeAMSLFT
NOTIFY
altitudeAMSLFTChanged
)
Q_PROPERTY
(
double
altitudeWGS84
READ
getAltitudeWGS84
WRITE
setAltitudeWGS84
NOTIFY
altitudeWGS84Changed
)
Q_PROPERTY
(
double
altitudeWGS84
READ
getAltitudeWGS84
WRITE
setAltitudeWGS84
NOTIFY
altitudeWGS84Changed
)
Q_PROPERTY
(
double
altitudeRelative
READ
getAltitudeRelative
WRITE
setAltitudeRelative
NOTIFY
altitudeRelativeChanged
)
Q_PROPERTY
(
double
altitudeRelative
READ
getAltitudeRelative
WRITE
setAltitudeRelative
NOTIFY
altitudeRelativeChanged
)
Q_PROPERTY
(
double
satRawHDOP
READ
getSatRawHDOP
NOTIFY
satRawHDOPChanged
)
Q_PROPERTY
(
double
satRawVDOP
READ
getSatRawVDOP
NOTIFY
satRawVDOPChanged
)
Q_PROPERTY
(
double
satRawCOG
READ
getSatRawCOG
NOTIFY
satRawCOGChanged
)
void
clearVehicle
(
void
)
{
_vehicle
=
NULL
;
}
void
clearVehicle
(
void
)
{
_vehicle
=
NULL
;
}
...
@@ -225,6 +228,21 @@ public:
...
@@ -225,6 +228,21 @@ public:
return
altitudeRelative
;
return
altitudeRelative
;
}
}
double
getSatRawHDOP
()
const
{
return
satRawHDOP
;
}
double
getSatRawVDOP
()
const
{
return
satRawVDOP
;
}
double
getSatRawCOG
()
const
{
return
satRawCOG
;
}
void
setSatelliteCount
(
double
val
)
void
setSatelliteCount
(
double
val
)
{
{
satelliteCount
=
val
;
satelliteCount
=
val
;
...
@@ -419,6 +437,10 @@ protected: //COMMENTS FOR TEST UNIT
...
@@ -419,6 +437,10 @@ protected: //COMMENTS FOR TEST UNIT
double
altitudeWGS84
;
///< Global altitude as estimated by position estimator, WGS84
double
altitudeWGS84
;
///< Global altitude as estimated by position estimator, WGS84
double
altitudeRelative
;
///< Altitude above home as estimated by position estimator
double
altitudeRelative
;
///< Altitude above home as estimated by position estimator
double
satRawHDOP
;
double
satRawVDOP
;
double
satRawCOG
;
double
satelliteCount
;
///< Number of satellites visible to raw GPS
double
satelliteCount
;
///< Number of satellites visible to raw GPS
bool
globalEstimatorActive
;
///< Global position estimator present, do not fall back to GPS raw for position
bool
globalEstimatorActive
;
///< Global position estimator present, do not fall back to GPS raw for position
double
latitude_gps
;
///< Global latitude as estimated by raw GPS
double
latitude_gps
;
///< Global latitude as estimated by raw GPS
...
@@ -604,6 +626,11 @@ signals:
...
@@ -604,6 +626,11 @@ signals:
void
altitudeAMSLFTChanged
(
double
val
,
QString
name
);
void
altitudeAMSLFTChanged
(
double
val
,
QString
name
);
void
altitudeWGS84Changed
(
double
val
,
QString
name
);
void
altitudeWGS84Changed
(
double
val
,
QString
name
);
void
altitudeRelativeChanged
(
double
val
,
QString
name
);
void
altitudeRelativeChanged
(
double
val
,
QString
name
);
void
satRawHDOPChanged
(
double
value
);
void
satRawVDOPChanged
(
double
value
);
void
satRawCOGChanged
(
double
value
);
void
rollChanged
(
double
val
,
QString
name
);
void
rollChanged
(
double
val
,
QString
name
);
void
pitchChanged
(
double
val
,
QString
name
);
void
pitchChanged
(
double
val
,
QString
name
);
void
yawChanged
(
double
val
,
QString
name
);
void
yawChanged
(
double
val
,
QString
name
);
...
...
src/ui/toolbar/MainToolBar.qml
View file @
03ff0d1f
...
@@ -254,6 +254,30 @@ Rectangle {
...
@@ -254,6 +254,30 @@ Rectangle {
text
:
getGpsLockStatus
()
text
:
getGpsLockStatus
()
color
:
colorWhite
color
:
colorWhite
}
}
QGCLabel
{
text
:
"
HDOP:
"
color
:
colorWhite
}
QGCLabel
{
text
:
activeVehicle
?
(
activeVehicle
.
satRawHDOP
.
toFixed
(
0
))
:
"
N/A
"
color
:
colorWhite
}
QGCLabel
{
text
:
"
VDOP:
"
color
:
colorWhite
}
QGCLabel
{
text
:
activeVehicle
?
(
activeVehicle
.
satRawVDOP
.
toFixed
(
0
))
:
"
N/A
"
color
:
colorWhite
}
QGCLabel
{
text
:
"
Course Over Ground:
"
color
:
colorWhite
}
QGCLabel
{
text
:
activeVehicle
?
(
activeVehicle
.
satRawCOG
).
toFixed
(
2
)
:
"
N/A
"
color
:
colorWhite
}
}
}
}
}
Component.onCompleted
:
{
Component.onCompleted
:
{
...
...
src/ui/toolbar/MainToolBarIndicators.qml
View file @
03ff0d1f
...
@@ -34,18 +34,16 @@ import QGroundControl.ScreenTools 1.0
...
@@ -34,18 +34,16 @@ import QGroundControl.ScreenTools 1.0
Row
{
Row
{
spacing
:
tbSpacing
*
2
spacing
:
tbSpacing
*
2
function
getSatStrength
(
count
)
{
function
getSatStrength
(
hdop
)
{
if
(
count
<
1
)
if
(
hdop
<
3
)
return
0
if
(
count
<
4
)
return
20
if
(
count
<
6
)
return
40
if
(
count
<
8
)
return
60
if
(
count
<
10
)
return
80
return
100
return
100
if
(
hdop
<
6
)
return
75
if
(
hdop
<
11
)
return
50
if
(
hdop
<
21
)
return
25
return
0
}
}
function
getMessageColor
()
{
function
getMessageColor
()
{
...
@@ -183,7 +181,7 @@ Row {
...
@@ -183,7 +181,7 @@ Row {
}
}
SignalStrength
{
SignalStrength
{
size
:
mainWindow
.
tbCellHeight
*
0.5
size
:
mainWindow
.
tbCellHeight
*
0.5
percent
:
activeVehicle
?
getSatStrength
(
activeVehicle
.
sat
elliteCount
)
:
""
percent
:
activeVehicle
?
getSatStrength
(
activeVehicle
.
sat
RawHDOP
)
:
""
anchors.verticalCenter
:
parent
.
verticalCenter
anchors.verticalCenter
:
parent
.
verticalCenter
}
}
}
}
...
...
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