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
5505fab4
Commit
5505fab4
authored
Nov 22, 2011
by
oberion
Browse files
Options
Browse Files
Download
Plain Diff
Merge remote-tracking branch 'remotes/pixhawk/v10release' into dev_senseSoarMavlinkv10
parents
a5393402
1b6c9a55
Changes
20
Expand all
Show whitespace changes
Inline
Side-by-side
Showing
20 changed files
with
12021 additions
and
131 deletions
+12021
-131
senseSoarDummy.dae
files/vehicles/SenseSoar_Airplane/senseSoarDummy.dae
+6078
-0
sfly-hex.dae
files/vehicles/sFly_Hexrotor/sfly-hex.dae
+5681
-0
sfly-hex.skp
files/vehicles/sFly_Hexrotor/sfly-hex.skp
+0
-0
earth.html
images/earth.html
+56
-23
qgroundcontrol.pri
qgroundcontrol.pri
+2
-2
GAudioOutput.cc
src/GAudioOutput.cc
+2
-2
MAVLinkSimulationMAV.cc
src/comm/MAVLinkSimulationMAV.cc
+2
-2
QGCFlightGearLink.cc
src/comm/QGCFlightGearLink.cc
+1
-1
UDPLink.cc
src/comm/UDPLink.cc
+1
-1
providerstrings.cpp
src/libs/opmapcontrol/src/core/providerstrings.cpp
+1
-1
waypointlineitem.cpp
src/libs/opmapcontrol/src/mapwidget/waypointlineitem.cpp
+0
-1
PxQuadMAV.cc
src/uas/PxQuadMAV.cc
+10
-5
UAS.cc
src/uas/UAS.cc
+16
-8
HDDisplay.cc
src/ui/HDDisplay.cc
+2
-2
QGCMAVLinkInspector.cc
src/ui/QGCMAVLinkInspector.cc
+20
-4
QGCMAVLinkInspector.h
src/ui/QGCMAVLinkInspector.h
+2
-1
LinechartWidget.cc
src/ui/linechart/LinechartWidget.cc
+4
-0
QGCGoogleEarthView.cc
src/ui/map3D/QGCGoogleEarthView.cc
+15
-14
UASView.cc
src/ui/uas/UASView.cc
+125
-64
UASView.h
src/ui/uas/UASView.h
+3
-0
No files found.
files/vehicles/SenseSoar_Airplane/senseSoarDummy.dae
0 → 100644
View file @
5505fab4
This diff is collapsed.
Click to expand it.
files/vehicles/sFly_Hexrotor/sfly-hex.dae
0 → 100644
View file @
5505fab4
This diff is collapsed.
Click to expand it.
files/vehicles/sFly_Hexrotor/sfly-hex.skp
0 → 100644
View file @
5505fab4
B
SketchUp Model૿{8.0.4810}싀菾崲題皖⻣៓纯ÿ覡乃噃牥楳湯慍ー䌉䄀爀挀䌀甀爀瘀攀Ā䌊䄀琀琀爀椀戀甀琀攀䌓䄀琀琀爀椀戀甀琀攀䌀漀渀琀愀椀渀攀爀䌏䄀琀琀爀椀戀甀琀攀一愀洀攀搀Ā䌐䈀愀挀欀最爀漀甀渀搀䤀洀愀最攀䌇䌀愀洀攀爀愀Ԁ䌊䌀漀洀瀀漀渀攀渀琀䌒䌀漀洀瀀漀渀攀渀琀䈀攀栀愀瘀椀漀爀Ԁ䌔䌀漀洀瀀漀渀攀渀琀䐀攀昀椀渀椀琀椀漀渀䌒䌀漀洀瀀漀渀攀渀琀䤀渀猀琀愀渀挀攀Ѐ䌕䌀漀渀猀琀爀甀挀琀椀漀渀䜀攀漀洀攀琀爀礀䌑䌀漀渀猀琀爀甀挀琀椀漀渀䰀椀渀攀Ā䌒䌀漀渀猀琀爀甀挀琀椀漀渀倀漀椀渀琀䌆䌀甀爀瘀攀Ѐ䌏䐀攀昀椀渀椀琀椀漀渀䰀椀猀琀䌄䐀椀戀̀䌊䐀椀洀攀渀猀椀漀渀Ā䌐䐀椀洀攀渀猀椀漀渀䰀椀渀攀愀爀䌐䐀椀洀攀渀猀椀漀渀刀愀搀椀愀氀Ȁ䌏䐀椀洀攀渀猀椀漀渀匀琀礀氀攀Ѐ䌏䐀爀愀眀椀渀最䔀氀攀洀攀渀琀ऀ䌅䔀搀最攀Ȁ䌈䔀搀最攀唀猀攀Ā䌇䔀渀琀椀琀礀̀䌅䘀愀挀攀̀䌒䘀愀挀攀吀攀砀琀甀爀攀䌀漀漀爀搀猀Ѐ䌌䘀漀渀琀䴀愀渀愀最攀爀䌆䜀爀漀甀瀀Ā䌆䤀洀愀最攀Ā䌆䰀愀礀攀爀Ȁ䌍䰀愀礀攀爀䴀愀渀愀最攀爀Ѐ䌅䰀漀漀瀀Ā䌉䴀愀琀攀爀椀愀氀ఀ䌐䴀愀琀攀爀椀愀氀䴀愀渀愀最攀爀Ѐ䌉倀愀最攀䰀椀猀琀Ā䌋倀漀氀礀氀椀渀攀㌀搀䌍刀攀氀愀琀椀漀渀猀栀椀瀀䌐刀攀氀愀琀椀漀渀猀栀椀瀀䴀愀瀀䌑刀攀渀搀攀爀椀渀最伀瀀琀椀漀渀猀␀䌍匀攀挀琀椀漀渀倀氀愀渀攀Ȁ䌋匀栀愀搀漀眀䤀渀昀漀܀䌇匀欀䘀漀渀琀Ā䌉匀欀攀琀挀栀䌀匀䌎匀欀攀琀挀栀唀瀀䴀漀搀攀氀ᘀ䌍匀欀攀琀挀栀唀瀀倀愀最攀Ā䌉匀欀瀀匀琀礀氀攀Ā䌐匀欀瀀匀琀礀氀攀䴀愀渀愀最攀爀Ȁ䌅吀攀砀琀ऀ䌊吀攀砀琀匀琀礀氀攀Ԁ䌈吀攀砀琀甀爀攀䌊吀栀甀洀戀渀愀椀氀Ā䌇嘀攀爀琀攀砀䌉嘀椀攀眀倀愀最攀ఀ䌊圀愀琀攀爀洀愀爀欀Ā䌑圀愀琀攀爀洀愀爀欀䴀愀渀愀最攀爀Ȁ䔒渀搀ⴀ伀昀ⴀ嘀攀爀猀椀漀渀ⴀ䴀愀瀀Ȁ뀀ĀϿЀ䌀楄Ѣ洀褀乐േᨊ
images/earth.html
View file @
5505fab4
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "http://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "http://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
<html>
<head>
...
...
@@ -7,8 +7,8 @@
<!-- QGroundControl -->
<title>
QGroundControl Google Earth View
</title>
<!-- *** Replace the key below below with your own API key, available at http://code.google.com/apis/maps/signup.html *** -->
<
!--<script type="text/javascript" src="https://getfirebug.com/firebug-lite-beta.js"></script>--
>
<script
type=
"text/javascript"
src=
"http
://www.google.com/jsapi?key=ABQIAAAAwbkbZLyhsmTCWXbTcjbgbRSzHs7K5SvaUdm8ua-Xxy_-2dYwMxQMhnagaawTo7L1FE1-amhuQxIlXw
"
></script>
<
script
type=
"text/javascript"
src=
"https://getfirebug.com/firebug-lite-beta.js"
></script
>
<script
type=
"text/javascript"
src=
"http
s://www.google.com/jsapi?key=ABQIAAAA5Q6wxQ6lxKS8haLVdUJaqhSjosg_0jiTTs2iXtkDVG0n0If1mBRHzhWw5VqBZX-j4NuzoVpU-UaHVg
"
></script>
<script
type=
"text/javascript"
>
google
.
load
(
"
earth
"
,
"
1
"
,
{
'
language
'
:
'
en
'
});
...
...
@@ -99,6 +99,12 @@ var clickMode = 0;
var
homePlacemark
=
null
;
// Data / heightmap
var
heightMapPlacemark
=
null
;
var
heightMapModel
=
null
;
function
getGlobal
(
variable
)
{
return
variable
;
...
...
@@ -417,8 +423,16 @@ function createAircraft(id, type, color)
planeOrient
=
ge
.
createOrientation
(
''
);
planeModel
.
setOrientation
(
planeOrient
);
planeLink
.
setHref
(
'
http://www.asl.ethz.ch/people/rudink/senseSoarDummy.dae
'
);
var
factor
=
1.0
;
//planeLink.setHref('http://www.asl.ethz.ch/people/rudink/senseSoarDummy.dae');
planeLink
.
setHref
(
'
http://qgroundcontrol.org/_media/users/models/sfly-hex.dae
'
);
factor
=
1.0
/
1000.0
;
//planeLink.setHref('http://qgroundcontrol.org/_media/users/models/ascent-park-glider.dae');
planeModel
.
setLink
(
planeLink
);
var
scale
=
planeModel
.
getScale
();
scale
.
set
(
scale
.
getX
()
*
factor
,
scale
.
getY
()
*
factor
,
scale
.
getZ
()
*
factor
)
planeModel
.
setScale
(
scale
);
planeModel
.
setAltitudeMode
(
ge
.
ALTITUDE_ABSOLUTE
);
planeLoc
.
setLatitude
(
currLat
);
...
...
@@ -553,6 +567,34 @@ function initCallback(object)
enableEventListener
();
document
.
getElementById
(
'
JScript_initialized
'
).
setAttribute
(
'
value
'
,
'
true
'
);
// Load heightmap
// http://www.inf.ethz.ch/personal/lomeier/data/untex-environment.dae
heightMapPlacemark
=
ge
.
createPlacemark
(
''
);
heightMapPlacemark
.
setName
(
'
aircraft
'
);
heightMapModel
=
ge
.
createModel
(
''
);
ge
.
getFeatures
().
appendChild
(
heightMapPlacemark
);
planeLoc
=
ge
.
createLocation
(
''
);
heightMapModel
.
setLocation
(
planeLoc
);
planeLink
=
ge
.
createLink
(
''
);
planeOrient
=
ge
.
createOrientation
(
''
);
heightMapModel
.
setOrientation
(
planeOrient
);
planeLink
.
setHref
(
'
http://www.inf.ethz.ch/personal/lomeier/data/untex-environment.dae
'
);
heightMapModel
.
setLink
(
planeLink
);
var
scale
=
heightMapModel
.
getScale
();
var
factor
=
1.0
;
//1.0/1000.0;
scale
.
set
(
scale
.
getX
()
*
factor
,
scale
.
getY
()
*
factor
,
scale
.
getZ
()
*
factor
)
heightMapModel
.
setScale
(
scale
);
heightMapModel
.
setAltitudeMode
(
ge
.
ALTITUDE_ABSOLUTE
);
planeLoc
.
setLatitude
(
currLat
);
planeLoc
.
setLongitude
(
currLon
);
planeLoc
.
setAltitude
(
currAlt
);
heightMapPlacemark
.
setGeometry
(
heightMapModel
);
initialized
=
true
;
}
...
...
@@ -578,18 +620,16 @@ function setAircraftPositionAttitude(id, lat, lon, alt, roll, pitch, yaw)
currAlt
=
trueGroundAlt
+
0.1
;
}
// Interpolate between t-1 and t and set new states
lastLat
=
lastLat
*
0.8
+
currLat
*
0.2
;
lastLon
=
lastLon
*
0.8
+
currLon
*
0.2
;
lastAlt
=
lastAlt
*
0.8
+
currAlt
*
0.2
;
//currFollowHeading = ((yaw/M_PI)+1.0)*360.0;
lastLat
=
lastLat
*
0.5
+
currLat
*
0.5
;
lastLon
=
lastLon
*
0.5
+
currLon
*
0.5
;
lastAlt
=
lastAlt
*
0.5
+
currAlt
*
0.5
;
planeOrient
.
setRoll
(
+
((
pitch
/
M_PI
))
*
180.0
);
planeOrient
.
setTilt
(
-
((
roll
/
M_PI
))
*
180.0
);
planeOrient
.
setHeading
(((
yaw
/
M_PI
))
*
180.0
-
90.0
);
planeOrient
.
setRoll
(
+
((
roll
/
M_PI
))
*
180.0
);
planeOrient
.
setTilt
(
-
((
pitch
/
M_PI
))
*
180.0
);
planeOrient
.
setHeading
(((
yaw
/
M_PI
))
*
180.0
-
90.0
);
planeModel
.
setOrientation
(
planeOrient
);
currFollowHeading
=
((
yaw
/
M_PI
))
*
180.0
;
currFollowHeading
=
currFollowHeading
*
0.95
+
0.05
*
(((
yaw
/
M_PI
))
*
180.0
)
;
planeLoc
.
setLatitude
(
lastLat
);
planeLoc
.
setLongitude
(
lastLon
);
...
...
@@ -678,17 +718,10 @@ function updateFollowAircraft()
if
(
viewMode
!=
3
)
// VIEW_MODE_CHASE_FREE
{
ge
.
getView
().
setAbstractView
(
currView
);
var
camera
=
ge
.
getView
().
copyAsCamera
(
ge
.
ALTITUDE_ABSOLUTE
);
camera
.
setTilt
(
currFollowTilt
);
camera
.
setRoll
(
0
);
camera
.
setHeading
(
currFollowHeading
);
ge
.
getView
().
setAbstractView
(
camera
);
currView
.
setTilt
(
currFollowTilt
);
currView
.
setHeading
(
currFollowHeading
);
}
else
{
ge
.
getView
().
setAbstractView
(
currView
);
}
}
function
failureCallback
(
object
)
...
...
qgroundcontrol.pri
View file @
5505fab4
...
...
@@ -42,8 +42,8 @@ macx {
# COMPILER_VERSION = $$system(gcc -v)
#message(Using compiler $$COMPILER_VERSION)
CONFIG += x86
_64
cocoa phonon
CONFIG -= x86
CONFIG += x86 cocoa phonon
CONFIG -= x86
_64
#HARDWARE_PLATFORM = $$system(uname -a)
#contains( $$HARDWARE_PLATFORM, "9.6.0" ) || contains( $$HARDWARE_PLATFORM, "9.7.0" ) || contains( $$HARDWARE_PLATFORM, "9.8.0" ) || contains( $$HARDWARE_PLATFORM, "9.9.0" ) {
...
...
src/GAudioOutput.cc
View file @
5505fab4
...
...
@@ -184,8 +184,8 @@ bool GAudioOutput::say(QString text, int severity)
cst_wave
*
wav
=
flite_text_to_wave
(
text
.
toStdString
().
c_str
(),
v
);
// file.fileName() returns the unique file name
cst_wave_save
(
wav
,
file
.
fileName
().
toStdString
().
c_str
(),
"riff"
);
m_media
->
setCurrentSource
(
Phonon
::
MediaSource
(
file
.
fileName
().
toStdString
().
c_str
()));
m_media
->
play
();
//
m_media->setCurrentSource(Phonon::MediaSource(file.fileName().toStdString().c_str()));
//
m_media->play();
res
=
true
;
}
#endif
...
...
src/comm/MAVLinkSimulationMAV.cc
View file @
5505fab4
...
...
@@ -14,10 +14,10 @@ MAVLinkSimulationMAV::MAVLinkSimulationMAV(MAVLinkSimulationLink *parent, int sy
timer1Hz
(
0
),
latitude
(
lat
),
longitude
(
lon
),
altitude
(
0.0
),
altitude
(
55
0.0
),
x
(
lat
),
y
(
lon
),
z
(
550
),
z
(
altitude
),
roll
(
0.0
),
pitch
(
0.0
),
yaw
(
0.0
),
...
...
src/comm/QGCFlightGearLink.cc
View file @
5505fab4
...
...
@@ -188,7 +188,7 @@ void QGCFlightGearLink::writeBytes(const char* data, qint64 size)
void
QGCFlightGearLink
::
readBytes
()
{
const
qint64
maxLength
=
65536
;
static
char
data
[
maxLength
];
char
data
[
maxLength
];
QHostAddress
sender
;
quint16
senderPort
;
...
...
src/comm/UDPLink.cc
View file @
5505fab4
...
...
@@ -210,7 +210,7 @@ void UDPLink::writeBytes(const char* data, qint64 size)
void
UDPLink
::
readBytes
()
{
const
qint64
maxLength
=
65536
;
static
char
data
[
maxLength
];
char
data
[
maxLength
];
QHostAddress
sender
;
quint16
senderPort
;
...
...
src/libs/opmapcontrol/src/core/providerstrings.cpp
View file @
5505fab4
...
...
@@ -63,7 +63,7 @@ namespace core {
/// Google Maps API generated using http://greatmaps.codeplex.com/
/// from http://code.google.com/intl/en-us/apis/maps/signup.html
/// </summary>
GoogleMapsAPIKey
=
"ABQIAAAA
WaQgWiEBF3lW97ifKnAczhRAzBk5Igf8Z5n2W3hNnMT0j2TikxTLtVIGU7hCLLHMAuAMt-BO5UrEWA
"
;
GoogleMapsAPIKey
=
"ABQIAAAA
5Q6wxQ6lxKS8haLVdUJaqhSjosg_0jiTTs2iXtkDVG0n0If1mBRHzhWw5VqBZX-j4NuzoVpU-UaHVg
"
;
// Yahoo version strings
VersionYahooMap
=
"4.3"
;
...
...
src/libs/opmapcontrol/src/mapwidget/waypointlineitem.cpp
View file @
5505fab4
...
...
@@ -27,7 +27,6 @@ WaypointLineItem::WaypointLineItem(WayPointItem* wp1, WayPointItem* wp2, QColor
setLine
(
localPoint1
.
X
(),
localPoint1
.
Y
(),
localPoint2
.
X
(),
localPoint2
.
Y
());
// Connect updates
// Update line from both waypoints
connect
(
wp1
,
SIGNAL
(
WPValuesChanged
(
WayPointItem
*
)),
this
,
SLOT
(
updateWPValues
(
WayPointItem
*
)));
connect
(
wp2
,
SIGNAL
(
WPValuesChanged
(
WayPointItem
*
)),
this
,
SLOT
(
updateWPValues
(
WayPointItem
*
)));
...
...
src/uas/PxQuadMAV.cc
View file @
5505fab4
...
...
@@ -42,9 +42,12 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
#ifdef MAVLINK_ENABLED_PIXHAWK
mavlink_message_t
*
msg
=
&
message
;
if
(
message
.
sysid
==
uasId
)
{
switch
(
message
.
msgid
)
{
case
MAVLINK_MSG_ID_RAW_AUX
:
{
if
(
message
.
sysid
==
uasId
)
{
switch
(
message
.
msgid
)
{
case
MAVLINK_MSG_ID_RAW_AUX
:
{
mavlink_raw_aux_t
raw
;
mavlink_msg_raw_aux_decode
(
&
message
,
&
raw
);
quint64
time
=
getUnixTime
(
0
);
...
...
@@ -52,14 +55,16 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit
valueChanged
(
uasId
,
"Temperature"
,
"raw"
,
raw
.
temp
,
time
);
}
break
;
case
MAVLINK_MSG_ID_IMAGE_TRIGGERED
:
{
case
MAVLINK_MSG_ID_IMAGE_TRIGGERED
:
{
// FIXME Kind of a hack to load data from disk
mavlink_image_triggered_t
img
;
mavlink_msg_image_triggered_decode
(
&
message
,
&
img
);
emit
imageStarted
(
img
.
timestamp
);
}
break
;
case
MAVLINK_MSG_ID_PATTERN_DETECTED
:
{
case
MAVLINK_MSG_ID_PATTERN_DETECTED
:
{
mavlink_pattern_detected_t
detected
;
mavlink_msg_pattern_detected_decode
(
&
message
,
&
detected
);
QByteArray
b
;
...
...
src/uas/UAS.cc
View file @
5505fab4
...
...
@@ -232,6 +232,9 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
case
MAV_TYPE_QUADROTOR
:
setAirframe
(
UASInterface
::
QGC_AIRFRAME_CHEETAH
);
break
;
case
MAV_TYPE_HEXAROTOR
:
setAirframe
(
UASInterface
::
QGC_AIRFRAME_HEXCOPTER
);
break
;
default:
// Do nothing
break
;
...
...
@@ -338,8 +341,6 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit
loadChanged
(
this
,
state
.
load
/
10.0
f
);
currentVoltage
=
state
.
voltage_battery
/
1000.0
f
;
lpVoltage
=
filterVoltage
(
currentVoltage
);
...
...
@@ -463,7 +464,8 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit
globalPositionChanged
(
this
,
latitude
,
longitude
,
altitude
,
time
);
emit
speedChanged
(
this
,
speedX
,
speedY
,
speedZ
,
time
);
// Set internal state
if
(
!
positionLock
)
{
if
(
!
positionLock
)
{
// If position was not locked before, notify positive
GAudioOutput
::
instance
()
->
notifyPositive
();
}
...
...
@@ -483,29 +485,35 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
// quint64 time = getUnixTime(pos.time_usec);
quint64
time
=
getUnixTime
(
pos
.
time_usec
);
if
(
pos
.
fix_type
>
2
)
{
if
(
pos
.
fix_type
>
2
)
{
emit
globalPositionChanged
(
this
,
pos
.
lat
/
(
double
)
1E7
,
pos
.
lon
/
(
double
)
1E7
,
pos
.
alt
/
1000.0
,
time
);
latitude
=
pos
.
lat
/
(
double
)
1E7
;
longitude
=
pos
.
lon
/
(
double
)
1E7
;
altitude
=
pos
.
alt
/
1000.0
;
positionLock
=
true
;
isGlobalPositionKnown
=
true
;
// Check for NaN
int
alt
=
pos
.
alt
;
if
(
alt
!=
alt
)
{
if
(
!
isnan
(
alt
)
&&
!
isinf
(
alt
))
{
alt
=
0
;
emit
textMessageReceived
(
uasId
,
message
.
compid
,
255
,
"GCS ERROR: RECEIVED NaN FOR ALTITUDE"
);
emit
textMessageReceived
(
uasId
,
message
.
compid
,
255
,
"GCS ERROR: RECEIVED NaN
or Inf
FOR ALTITUDE"
);
}
// FIXME REMOVE LATER emit valueChanged(uasId, "altitude", "m", pos.alt/(double)1E3, time);
// Smaller than threshold and not NaN
float
vel
=
pos
.
vel
/
100.0
f
;
if
(
vel
<
1000000
&&
!
isnan
(
vel
)
&&
!
isinf
(
vel
))
{
if
(
vel
<
1000000
&&
!
isnan
(
vel
)
&&
!
isinf
(
vel
))
{
// FIXME REMOVE LATER emit valueChanged(uasId, "speed", "m/s", vel, time);
//qDebug() << "GOT GPS RAW";
// emit speedChanged(this, (double)pos.v, 0.0, 0.0, time);
}
else
{
}
else
{
emit
textMessageReceived
(
uasId
,
message
.
compid
,
255
,
QString
(
"GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s"
).
arg
(
vel
));
}
}
...
...
src/ui/HDDisplay.cc
View file @
5505fab4
...
...
@@ -186,9 +186,9 @@ void HDDisplay::triggerUpdate()
void
HDDisplay
::
paintEvent
(
QPaintEvent
*
event
)
{
Q_UNUSED
(
event
);
static
quint64
interval
=
0
;
quint64
interval
=
0
;
//qDebug() << "INTERVAL:" << MG::TIME::getGroundTimeNow() - interval << __FILE__ << __LINE__;
interval
=
MG
::
TIME
::
getGroundTimeNow
();
interval
=
QGC
::
groundTimeMilliseconds
();
renderOverlay
();
}
...
...
src/ui/QGCMAVLinkInspector.cc
View file @
5505fab4
...
...
@@ -37,10 +37,10 @@ void QGCMAVLinkInspector::refreshView()
// Ignore NULL values
if
(
!
msg
)
continue
;
// Update the tree view
QString
messageName
(
"%1 (%2 Hz, #%3)"
);
messageName
=
messageName
.
arg
(
messageInfo
[
msg
->
msgid
].
name
).
arg
(
messagesHz
.
value
(
msg
->
msgid
,
0
),
2
,
'f'
,
0
).
arg
(
msg
->
msgid
);
if
(
!
treeWidgetItems
.
contains
(
msg
->
msgid
))
{
QString
messageName
(
"%1 (#%2)"
);
messageName
=
messageName
.
arg
(
messageInfo
[
msg
->
msgid
].
name
).
arg
(
msg
->
msgid
);
QStringList
fields
;
fields
<<
messageName
;
QTreeWidgetItem
*
widget
=
new
QTreeWidgetItem
(
fields
);
...
...
@@ -56,7 +56,10 @@ void QGCMAVLinkInspector::refreshView()
ui
->
treeWidget
->
addTopLevelItem
(
widget
);
}
// Set Hz
QTreeWidgetItem
*
message
=
treeWidgetItems
.
value
(
msg
->
msgid
);
message
->
setFirstColumnSpanned
(
true
);
message
->
setData
(
0
,
Qt
::
DisplayRole
,
QVariant
(
messageName
));
for
(
unsigned
int
i
=
0
;
i
<
messageInfo
[
msg
->
msgid
].
num_fields
;
++
i
)
{
updateField
(
msg
->
msgid
,
i
,
message
->
child
(
i
));
...
...
@@ -68,9 +71,22 @@ void QGCMAVLinkInspector::receiveMessage(LinkInterface* link,mavlink_message_t m
{
Q_UNUSED
(
link
);
// Only overwrite if system filter is set
// int filterValue = ui->systemComboBox()->value().toInt();
// if (filterValue != )
memcpy
(
receivedMessages
+
message
.
msgid
,
&
message
,
sizeof
(
mavlink_message_t
));
float
msgHz
=
0.0
f
;
quint64
receiveTime
=
QGC
::
groundTimeMilliseconds
();
if
(
lastMessageUpdate
.
contains
(
message
.
msgid
))
{
msgHz
=
1000.0
/
(
double
)(
receiveTime
-
lastMessageUpdate
.
value
(
message
.
msgid
));
if
(
isinf
(
msgHz
)
||
isnan
(
msgHz
)
||
msgHz
<
0.0
f
)
{
msgHz
=
1
;
}
float
newHz
=
0.001
f
*
msgHz
+
0.999
f
*
messagesHz
.
value
(
message
.
msgid
,
1
);
messagesHz
.
insert
(
message
.
msgid
,
newHz
);
}
lastMessageUpdate
.
insert
(
message
.
msgid
,
receiveTime
);
}
QGCMAVLinkInspector
::~
QGCMAVLinkInspector
()
...
...
src/ui/QGCMAVLinkInspector.h
View file @
5505fab4
...
...
@@ -26,7 +26,8 @@ public slots:
void
refreshView
();
protected:
QMap
<
int
,
quint64
>
lastFieldUpdate
;
///< Used to switch between highlight and non-highlighting color
QMap
<
int
,
quint64
>
lastMessageUpdate
;
///< Used to switch between highlight and non-highlighting color
QMap
<
int
,
float
>
messagesHz
;
///< Used to store update rate in Hz
mavlink_message_t
receivedMessages
[
256
];
///< Available / known messages
QMap
<
int
,
QTreeWidgetItem
*>
treeWidgetItems
;
///< Available tree widget items
QTimer
updateTimer
;
///< Only update at 1 Hz to not overload the GUI
...
...
src/ui/linechart/LinechartWidget.cc
View file @
5505fab4
...
...
@@ -315,6 +315,7 @@ void LinechartWidget::appendData(int uasId, QString curve, double value, quint64
{
if
(
activePlot
->
isVisible
(
curve
+
unit
))
{
if
(
usec
==
0
)
usec
=
QGC
::
groundTimeMilliseconds
();
if
(
logStartTime
==
0
)
logStartTime
=
usec
;
qint64
time
=
usec
-
logStartTime
;
if
(
time
<
0
)
time
=
0
;
...
...
@@ -347,6 +348,7 @@ void LinechartWidget::appendData(int uasId, const QString& curve, const QString&
{
if
(
activePlot
->
isVisible
(
curve
+
unit
))
{
if
(
usec
==
0
)
usec
=
QGC
::
groundTimeMilliseconds
();
if
(
logStartTime
==
0
)
logStartTime
=
usec
;
qint64
time
=
usec
-
logStartTime
;
if
(
time
<
0
)
time
=
0
;
...
...
@@ -391,6 +393,7 @@ void LinechartWidget::appendData(int uasId, const QString& curve, const QString&
{
if
(
activePlot
->
isVisible
(
curve
+
unit
))
{
if
(
usec
==
0
)
usec
=
QGC
::
groundTimeMilliseconds
();
if
(
logStartTime
==
0
)
logStartTime
=
usec
;
qint64
time
=
usec
-
logStartTime
;
if
(
time
<
0
)
time
=
0
;
...
...
@@ -425,6 +428,7 @@ void LinechartWidget::appendData(int uasId, const QString& curve, const QString&
{
if
(
activePlot
->
isVisible
(
curve
+
unit
))
{
if
(
usec
==
0
)
usec
=
QGC
::
groundTimeMilliseconds
();
if
(
logStartTime
==
0
)
logStartTime
=
usec
;
qint64
time
=
usec
-
logStartTime
;
if
(
time
<
0
)
time
=
0
;
...
...
src/ui/map3D/QGCGoogleEarthView.cc
View file @
5505fab4
...
...
@@ -54,15 +54,15 @@ QGCGoogleEarthView::QGCGoogleEarthView(QWidget *parent) :
#ifdef _MSC_VER
// Create layout and attach webViewWin
QFile
file
(
"doc.html"
);
if
(
!
file
.
open
(
QIODevice
::
WriteOnly
|
QIODevice
::
Text
))
qDebug
()
<<
__FILE__
<<
__LINE__
<<
"Could not open log file"
;
//
QFile file("doc.html");
//
if (!file.open(QIODevice::WriteOnly | QIODevice::Text))
//
qDebug() << __FILE__ << __LINE__ << "Could not open log file";
QTextStream
out
(
&
file
);
out
<<
webViewWin
->
generateDocumentation
();
out
.
flush
();
file
.
flush
();
file
.
close
();
//
QTextStream out(&file);
//
out << webViewWin->generateDocumentation();
//
out.flush();
//
file.flush();
//
file.close();
#else
...
...
@@ -284,8 +284,6 @@ void QGCGoogleEarthView::updateGlobalPosition(UASInterface* uas, double lat, dou
{
Q_UNUSED
(
usec
);
javaScript
(
QString
(
"addTrailPosition(%1, %2, %3, %4);"
).
arg
(
uas
->
getUASID
()).
arg
(
lat
,
0
,
'f'
,
22
).
arg
(
lon
,
0
,
'f'
,
22
).
arg
(
alt
,
0
,
'f'
,
22
));
//qDebug() << QString("addTrailPosition(%1, %2, %3, %4);").arg(uas->getUASID()).arg(lat, 0, 'f', 15).arg(lon, 0, 'f', 15).arg(alt, 0, 'f', 15);
}
void
QGCGoogleEarthView
::
clearTrails
()
...
...
@@ -614,7 +612,8 @@ void QGCGoogleEarthView::updateState()
#if (QGC_EVENTLOOP_DEBUG)
qDebug
()
<<
"EVENTLOOP:"
<<
__FILE__
<<
__LINE__
;
#endif
if
(
gEarthInitialized
)
{
if
(
gEarthInitialized
)
{
int
uasId
=
0
;
double
lat
=
47.3769
;
double
lon
=
8.549444
;
...
...
@@ -628,6 +627,8 @@ void QGCGoogleEarthView::updateState()
QList
<
UASInterface
*>
mavs
=
UASManager
::
instance
()
->
getUASList
();
foreach
(
UASInterface
*
currMav
,
mavs
)
{
// Only update if known
if
(
!
currMav
->
globalPositionKnown
())
continue
;
uasId
=
currMav
->
getUASID
();
lat
=
currMav
->
getLatitude
();
lon
=
currMav
->
getLongitude
();
...
...
@@ -640,9 +641,9 @@ void QGCGoogleEarthView::updateState()
javaScript
(
QString
(
"setAircraftPositionAttitude(%1, %2, %3, %4, %6, %7, %8);"
)
.
arg
(
uasId
)
.
arg
(
lat
,
0
,
'f'
,
15
)
.
arg
(
lon
,
0
,
'f'
,
15
)
.
arg
(
alt
,
0
,
'f'
,
15
)
.
arg
(
lat
,
0
,
'f'
,
22
)
.
arg
(
lon
,
0
,
'f'
,
22
)
.
arg
(
alt
,
0
,
'f'
,
22
)
.
arg
(
roll
,
0
,
'f'
,
9
)
.
arg
(
pitch
,
0
,
'f'
,
9
)
.
arg
(
yaw
,
0
,
'f'
,
9
));
...
...
src/ui/uas/UASView.cc
View file @
5505fab4
This diff is collapsed.
Click to expand it.
src/ui/uas/UASView.h
View file @
5505fab4
...
...
@@ -117,6 +117,7 @@ protected:
float
alt
;
float
groundDistance
;
bool
localFrame
;
bool
globalFrameKnown
;
QAction
*
removeAction
;
QAction
*
renameAction
;
QAction
*
selectAction
;
...
...
@@ -126,6 +127,8 @@ protected:
static
const
int
updateInterval
=
800
;
static
const
int
errorUpdateInterval
=
200
;
bool
lowPowerModeEnabled
;
///< Low power mode reduces update rates
unsigned
int
generalUpdateCount
;
///< Skip counter for updates
double
filterTime
;
///< Filter time estimate of battery
void
mouseDoubleClickEvent
(
QMouseEvent
*
event
);
...
...
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