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
c9f5a02a
Commit
c9f5a02a
authored
Feb 04, 2013
by
Thomas Gubler
Browse files
Options
Browse Files
Download
Plain Diff
manual merge of master into hil_flightgear_dev
parents
dfdc7295
cf176d0c
Changes
10
Hide whitespace changes
Inline
Side-by-side
Showing
10 changed files
with
57 additions
and
49 deletions
+57
-49
GAudioOutput.h
src/GAudioOutput.h
+2
-2
QGCFlightGearLink.cc
src/comm/QGCFlightGearLink.cc
+3
-3
configuration.h
src/configuration.h
+2
-2
UAS.cc
src/uas/UAS.cc
+2
-1
MAVLinkDecoder.cc
src/ui/MAVLinkDecoder.cc
+16
-21
QGCHilFlightGearConfiguration.cc
src/ui/QGCHilFlightGearConfiguration.cc
+5
-0
QGCHilFlightGearConfiguration.h
src/ui/QGCHilFlightGearConfiguration.h
+1
-0
QGCHilFlightGearConfiguration.ui
src/ui/QGCHilFlightGearConfiguration.ui
+25
-18
QGCToolBar.cc
src/ui/QGCToolBar.cc
+1
-1
LinechartWidget.cc
src/ui/linechart/LinechartWidget.cc
+0
-1
No files found.
src/GAudioOutput.h
View file @
c9f5a02a
...
...
@@ -41,8 +41,8 @@ This file is part of the PIXHAWK project
#endif
#ifdef Q_OS_LINUX
//#include <flite/flite.h>
#include <
P
honon/MediaObject>
#include <
P
honon/AudioOutput>
#include <
p
honon/MediaObject>
#include <
p
honon/AudioOutput>
#endif
#ifdef Q_OS_WIN
#include <Phonon/MediaObject>
...
...
src/comm/QGCFlightGearLink.cc
View file @
c9f5a02a
...
...
@@ -254,9 +254,9 @@ void QGCFlightGearLink::readBytes()
pitchspeed
=
values
.
at
(
8
).
toDouble
();
yawspeed
=
values
.
at
(
9
).
toDouble
();
xacc
=
values
.
at
(
10
).
toDouble
()
;
yacc
=
values
.
at
(
11
).
toDouble
();
zacc
=
values
.
at
(
12
).
toDouble
();
xacc
=
values
.
at
(
10
).
toDouble
()
*
1e3
/
9.8
;
// convert to mg's
yacc
=
values
.
at
(
11
).
toDouble
()
*
1e3
/
9.8
;
zacc
=
values
.
at
(
12
).
toDouble
()
*
1e3
/
9.8
;
vx
=
values
.
at
(
13
).
toDouble
()
*
1e2
;
vy
=
values
.
at
(
14
).
toDouble
()
*
1e2
;
...
...
src/configuration.h
View file @
c9f5a02a
...
...
@@ -12,14 +12,14 @@
#define WITH_TEXT_TO_SPEECH 1
#define QGC_APPLICATION_NAME "QGroundControl"
#define QGC_APPLICATION_VERSION "v. 1.0.
3
(beta)"
#define QGC_APPLICATION_VERSION "v. 1.0.
4
(beta)"
namespace
QGC
{
const
QString
APPNAME
=
"QGROUNDCONTROL"
;
const
QString
COMPANYNAME
=
"QGROUNDCONTROL"
;
const
int
APPLICATIONVERSION
=
10
2
;
// 1.0.1
const
int
APPLICATIONVERSION
=
10
4
;
// 1.0.4
}
#endif // QGC_CONFIGURATION_H
src/uas/UAS.cc
View file @
c9f5a02a
...
...
@@ -1100,6 +1100,8 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
imageWidth
=
p
.
width
;
imageHeight
=
p
.
height
;
imageStart
=
QGC
::
groundTimeMilliseconds
();
imagePacketsArrived
=
0
;
}
break
;
...
...
@@ -1132,7 +1134,6 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
if
((
imagePacketsArrived
>=
imagePackets
))
{
// Restart statemachine
imagePacketsArrived
=
0
;
emit
imageReady
(
this
);
//qDebug() << "imageReady emitted. all packets arrived";
}
...
...
src/ui/MAVLinkDecoder.cc
View file @
c9f5a02a
...
...
@@ -215,7 +215,7 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
char
buf
[
11
];
strncpy
(
buf
,
debug
.
name
,
10
);
buf
[
10
]
=
'\0'
;
name
=
QString
(
buf
);
name
=
QString
(
"%1.%2"
).
arg
(
buf
).
arg
(
fieldName
);
time
=
getUnixTimeFromMs
(
msg
->
sysid
,
(
debug
.
time_usec
+
500
)
/
1000
);
// Scale to milliseconds, round up/down correctly
}
else
if
(
msgid
==
MAVLINK_MSG_ID_DEBUG
)
...
...
@@ -245,24 +245,17 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
name
=
QString
(
buf
);
time
=
getUnixTimeFromMs
(
msg
->
sysid
,
debug
.
time_boot_ms
);
}
// else if (msgid == MAVLINK_MSG_ID_HIGHRES_IMU)
// {
// mavlink_highres_imu_t d;
// mavlink_msg_highres_imu_decode(msg, &d);
// name = name.arg(debug.name).arg(fieldName);
// time = getUnixTimeFromMs(msg->sysid, debug.time_boot_ms);
// }
else
{
name
=
name
.
arg
(
messageInfo
[
msgid
].
name
,
fieldName
);
name
=
name
.
arg
(
messageInfo
[
msgid
].
name
).
arg
(
fieldName
);
}
if
(
multiComponentSourceDetected
)
{
name
.
prepend
(
QString
(
"C%1:"
).
arg
(
msg
->
compid
));
name
=
name
.
prepend
(
QString
(
"C%1:"
).
arg
(
msg
->
compid
));
}
name
.
prepend
(
QString
(
"M%1:"
).
arg
(
msg
->
sysid
));
name
=
name
.
prepend
(
QString
(
"M%1:"
).
arg
(
msg
->
sysid
));
switch
(
messageInfo
[
msgid
].
fields
[
fieldid
].
type
)
{
...
...
@@ -306,7 +299,7 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
{
int8_t
*
nums
=
(
int8_t
*
)(
m
+
messageInfo
[
msgid
].
fields
[
fieldid
].
wire_offset
);
fieldType
=
QString
(
"int8_t[%1]"
).
arg
(
messageInfo
[
msgid
].
fields
[
fieldid
].
array_length
);
for
(
unsigned
int
j
=
0
;
j
<
messageInfo
[
msgid
].
fields
[
j
].
array_length
;
++
j
)
for
(
unsigned
int
j
=
0
;
j
<
messageInfo
[
msgid
].
fields
[
fieldid
].
array_length
;
++
j
)
{
emit
valueChanged
(
msg
->
sysid
,
QString
(
"%1.%2"
).
arg
(
name
).
arg
(
j
),
fieldType
,
nums
[
j
],
time
);
}
...
...
@@ -324,7 +317,7 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
{
uint16_t
*
nums
=
(
uint16_t
*
)(
m
+
messageInfo
[
msgid
].
fields
[
fieldid
].
wire_offset
);
fieldType
=
QString
(
"uint16_t[%1]"
).
arg
(
messageInfo
[
msgid
].
fields
[
fieldid
].
array_length
);
for
(
unsigned
int
j
=
0
;
j
<
messageInfo
[
msgid
].
fields
[
j
].
array_length
;
++
j
)
for
(
unsigned
int
j
=
0
;
j
<
messageInfo
[
msgid
].
fields
[
fieldid
].
array_length
;
++
j
)
{
emit
valueChanged
(
msg
->
sysid
,
QString
(
"%1.%2"
).
arg
(
name
).
arg
(
j
),
fieldType
,
nums
[
j
],
time
);
}
...
...
@@ -342,7 +335,7 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
{
int16_t
*
nums
=
(
int16_t
*
)(
m
+
messageInfo
[
msgid
].
fields
[
fieldid
].
wire_offset
);
fieldType
=
QString
(
"int16_t[%1]"
).
arg
(
messageInfo
[
msgid
].
fields
[
fieldid
].
array_length
);
for
(
unsigned
int
j
=
0
;
j
<
messageInfo
[
msgid
].
fields
[
j
].
array_length
;
++
j
)
for
(
unsigned
int
j
=
0
;
j
<
messageInfo
[
msgid
].
fields
[
fieldid
].
array_length
;
++
j
)
{
emit
valueChanged
(
msg
->
sysid
,
QString
(
"%1.%2"
).
arg
(
name
).
arg
(
j
),
fieldType
,
nums
[
j
],
time
);
}
...
...
@@ -360,7 +353,7 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
{
uint32_t
*
nums
=
(
uint32_t
*
)(
m
+
messageInfo
[
msgid
].
fields
[
fieldid
].
wire_offset
);
fieldType
=
QString
(
"uint32_t[%1]"
).
arg
(
messageInfo
[
msgid
].
fields
[
fieldid
].
array_length
);
for
(
unsigned
int
j
=
0
;
j
<
messageInfo
[
msgid
].
fields
[
j
].
array_length
;
++
j
)
for
(
unsigned
int
j
=
0
;
j
<
messageInfo
[
msgid
].
fields
[
fieldid
].
array_length
;
++
j
)
{
emit
valueChanged
(
msg
->
sysid
,
QString
(
"%1.%2"
).
arg
(
name
).
arg
(
j
),
fieldType
,
nums
[
j
],
time
);
}
...
...
@@ -378,7 +371,7 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
{
int32_t
*
nums
=
(
int32_t
*
)(
m
+
messageInfo
[
msgid
].
fields
[
fieldid
].
wire_offset
);
fieldType
=
QString
(
"int32_t[%1]"
).
arg
(
messageInfo
[
msgid
].
fields
[
fieldid
].
array_length
);
for
(
unsigned
int
j
=
0
;
j
<
messageInfo
[
msgid
].
fields
[
j
].
array_length
;
++
j
)
for
(
unsigned
int
j
=
0
;
j
<
messageInfo
[
msgid
].
fields
[
fieldid
].
array_length
;
++
j
)
{
emit
valueChanged
(
msg
->
sysid
,
QString
(
"%1.%2"
).
arg
(
name
).
arg
(
j
),
fieldType
,
nums
[
j
],
time
);
}
...
...
@@ -396,9 +389,9 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
{
float
*
nums
=
(
float
*
)(
m
+
messageInfo
[
msgid
].
fields
[
fieldid
].
wire_offset
);
fieldType
=
QString
(
"float[%1]"
).
arg
(
messageInfo
[
msgid
].
fields
[
fieldid
].
array_length
);
for
(
unsigned
int
j
=
0
;
j
<
messageInfo
[
msgid
].
fields
[
j
].
array_length
;
++
j
)
for
(
unsigned
int
j
=
0
;
j
<
messageInfo
[
msgid
].
fields
[
fieldid
].
array_length
;
++
j
)
{
emit
valueChanged
(
msg
->
sysid
,
QString
(
"%1.%2"
).
arg
(
name
).
arg
(
j
),
fieldType
,
nums
[
j
]
,
time
);
emit
valueChanged
(
msg
->
sysid
,
QString
(
"%1.%2"
).
arg
(
name
).
arg
(
j
),
fieldType
,
(
float
)(
nums
[
j
])
,
time
);
}
}
else
...
...
@@ -414,7 +407,7 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
{
double
*
nums
=
(
double
*
)(
m
+
messageInfo
[
msgid
].
fields
[
fieldid
].
wire_offset
);
fieldType
=
QString
(
"double[%1]"
).
arg
(
messageInfo
[
msgid
].
fields
[
fieldid
].
array_length
);
for
(
unsigned
int
j
=
0
;
j
<
messageInfo
[
msgid
].
fields
[
j
].
array_length
;
++
j
)
for
(
unsigned
int
j
=
0
;
j
<
messageInfo
[
msgid
].
fields
[
fieldid
].
array_length
;
++
j
)
{
emit
valueChanged
(
msg
->
sysid
,
QString
(
"%1.%2"
).
arg
(
name
).
arg
(
j
),
fieldType
,
nums
[
j
],
time
);
}
...
...
@@ -432,7 +425,7 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
{
uint64_t
*
nums
=
(
uint64_t
*
)(
m
+
messageInfo
[
msgid
].
fields
[
fieldid
].
wire_offset
);
fieldType
=
QString
(
"uint64_t[%1]"
).
arg
(
messageInfo
[
msgid
].
fields
[
fieldid
].
array_length
);
for
(
unsigned
int
j
=
0
;
j
<
messageInfo
[
msgid
].
fields
[
j
].
array_length
;
++
j
)
for
(
unsigned
int
j
=
0
;
j
<
messageInfo
[
msgid
].
fields
[
fieldid
].
array_length
;
++
j
)
{
emit
valueChanged
(
msg
->
sysid
,
QString
(
"%1.%2"
).
arg
(
name
).
arg
(
j
),
fieldType
,
(
quint64
)
nums
[
j
],
time
);
}
...
...
@@ -450,7 +443,7 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
{
int64_t
*
nums
=
(
int64_t
*
)(
m
+
messageInfo
[
msgid
].
fields
[
fieldid
].
wire_offset
);
fieldType
=
QString
(
"int64_t[%1]"
).
arg
(
messageInfo
[
msgid
].
fields
[
fieldid
].
array_length
);
for
(
unsigned
int
j
=
0
;
j
<
messageInfo
[
msgid
].
fields
[
j
].
array_length
;
++
j
)
for
(
unsigned
int
j
=
0
;
j
<
messageInfo
[
msgid
].
fields
[
fieldid
].
array_length
;
++
j
)
{
emit
valueChanged
(
msg
->
sysid
,
QString
(
"%1.%2"
).
arg
(
name
).
arg
(
j
),
fieldType
,
(
qint64
)
nums
[
j
],
time
);
}
...
...
@@ -463,5 +456,7 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
emit
valueChanged
(
msg
->
sysid
,
name
,
fieldType
,
(
qint64
)
n
,
time
);
}
break
;
default:
qDebug
()
<<
"WARNING: UNKNOWN MAVLINK TYPE"
;
}
}
src/ui/QGCHilFlightGearConfiguration.cc
View file @
c9f5a02a
...
...
@@ -42,3 +42,8 @@ void QGCHilFlightGearConfiguration::on_startButton_clicked()
options
.
append
(
" --aircraft="
+
ui
->
aircraftComboBox
->
currentText
());
mav
->
enableHilFlightGear
(
true
,
options
);
}
void
QGCHilFlightGearConfiguration
::
on_stopButton_clicked
()
{
mav
->
stopHil
();
}
src/ui/QGCHilFlightGearConfiguration.h
View file @
c9f5a02a
...
...
@@ -24,6 +24,7 @@ protected:
private
slots
:
void
on_startButton_clicked
();
void
on_stopButton_clicked
();
private:
Ui
::
QGCHilFlightGearConfiguration
*
ui
;
...
...
src/ui/QGCHilFlightGearConfiguration.ui
View file @
c9f5a02a
...
...
@@ -6,8 +6,8 @@
<rect>
<x>
0
</x>
<y>
0
</y>
<width>
190
</width>
<height>
2
46
</height>
<width>
237
</width>
<height>
2
04
</height>
</rect>
</property>
<property
name=
"sizePolicy"
>
...
...
@@ -25,26 +25,13 @@
<property
name=
"autoFillBackground"
>
<bool>
false
</bool>
</property>
<layout
class=
"QGridLayout"
name=
"gridLayout"
rowminimumheight=
"0,0,0,0,0,0"
>
<layout
class=
"QGridLayout"
name=
"gridLayout"
rowminimumheight=
"0,0,0,0,0,0
,0,0
"
>
<property
name=
"margin"
>
<number>
0
</number>
</property>
<property
name=
"spacing"
>
<number>
6
</number>
</property>
<item
row=
"5"
column=
"0"
>
<widget
class=
"QPushButton"
name=
"startButton"
>
<property
name=
"sizePolicy"
>
<sizepolicy
hsizetype=
"Preferred"
vsizetype=
"Fixed"
>
<horstretch>
0
</horstretch>
<verstretch>
0
</verstretch>
</sizepolicy>
</property>
<property
name=
"text"
>
<string>
Start
</string>
</property>
</widget>
</item>
<item
row=
"0"
column=
"0"
>
<widget
class=
"QLabel"
name=
"aircraftPlaintextInfoLabel"
>
<property
name=
"text"
>
...
...
@@ -52,7 +39,7 @@
</property>
</widget>
</item>
<item
row=
"1"
column=
"0"
>
<item
row=
"1"
column=
"0"
colspan=
"2"
>
<widget
class=
"QComboBox"
name=
"aircraftComboBox"
>
<property
name=
"sizePolicy"
>
<sizepolicy
hsizetype=
"Preferred"
vsizetype=
"Fixed"
>
...
...
@@ -72,7 +59,7 @@
</property>
</widget>
</item>
<item
row=
"3"
column=
"0"
>
<item
row=
"3"
column=
"0"
colspan=
"2"
>
<widget
class=
"QPlainTextEdit"
name=
"optionsPlainTextEdit"
>
<property
name=
"sizePolicy"
>
<sizepolicy
hsizetype=
"Preferred"
vsizetype=
"Preferred"
>
...
...
@@ -85,6 +72,26 @@
</property>
</widget>
</item>
<item
row=
"5"
column=
"0"
>
<widget
class=
"QPushButton"
name=
"startButton"
>
<property
name=
"sizePolicy"
>
<sizepolicy
hsizetype=
"Minimum"
vsizetype=
"Fixed"
>
<horstretch>
0
</horstretch>
<verstretch>
0
</verstretch>
</sizepolicy>
</property>
<property
name=
"text"
>
<string>
Start
</string>
</property>
</widget>
</item>
<item
row=
"5"
column=
"1"
>
<widget
class=
"QPushButton"
name=
"stopButton"
>
<property
name=
"text"
>
<string>
Stop
</string>
</property>
</widget>
</item>
</layout>
</widget>
<resources/>
...
...
src/ui/QGCToolBar.cc
View file @
c9f5a02a
...
...
@@ -397,7 +397,7 @@ void QGCToolBar::setSystemType(UASInterface* uas, unsigned int systemType)
symbolButton
->
setIcon
(
QIcon
(
":/files/images/mavs/helicopter.svg"
));
break
;
case
MAV_TYPE_ANTENNA_TRACKER
:
symbolButton
->
setIcon
(
QIcon
(
":/files/images/mavs/antenn-tracker.svg"
));
symbolButton
->
setIcon
(
QIcon
(
":/files/images/mavs/antenn
a
-tracker.svg"
));
break
;
case
MAV_TYPE_GCS
:
symbolButton
->
setIcon
(
QIcon
(
":files/images/mavs/groundstation.svg"
));
...
...
src/ui/linechart/LinechartWidget.cc
View file @
c9f5a02a
...
...
@@ -436,7 +436,6 @@ void LinechartWidget::appendData(int uasId, const QString& curve, const QString&
// Make sure the curve will be created if it does not yet exist
if
(
!
label
)
{
//qDebug() << "ADDING CURVE IN APPENDDATE DOUBLE";
addCurve
(
curve
,
unit
);
}
}
...
...
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