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
0846707b
Commit
0846707b
authored
Jun 19, 2011
by
pixhawk
Browse files
Options
Browse Files
Download
Plain Diff
Merge branch 'dev' of github.com:pixhawk/qgroundcontrol into opmapcontrol
parents
5aab6ca2
5f82c714
Changes
5
Show whitespace changes
Inline
Side-by-side
Showing
5 changed files
with
792 additions
and
723 deletions
+792
-723
splash.png
images/splash.png
+0
-0
UAS.cc
src/uas/UAS.cc
+767
-714
UAS.h
src/uas/UAS.h
+3
-2
HUD.cc
src/ui/HUD.cc
+18
-7
HUD.h
src/ui/HUD.h
+4
-0
No files found.
images/splash.png
View replaced file @
5aab6ca2
View file @
0846707b
27.8 KB
|
W:
|
H:
25.5 KB
|
W:
|
H:
2-up
Swipe
Onion skin
src/uas/UAS.cc
View file @
0846707b
...
...
@@ -28,53 +28,53 @@
#include "SerialLink.h"
UAS
::
UAS
(
MAVLinkProtocol
*
protocol
,
int
id
)
:
UASInterface
(),
uasId
(
id
),
startTime
(
QGC
::
groundTimeMilliseconds
()),
commStatus
(
COMM_DISCONNECTED
),
name
(
""
),
autopilot
(
-
1
),
links
(
new
QList
<
LinkInterface
*>
()),
unknownPackets
(),
mavlink
(
protocol
),
waypointManager
(
*
this
),
thrustSum
(
0
),
thrustMax
(
10
),
startVoltage
(
0
),
warnVoltage
(
9.5
f
),
warnLevelPercent
(
20.0
f
),
currentVoltage
(
12.0
f
),
lpVoltage
(
12.0
f
),
batteryRemainingEstimateEnabled
(
false
),
mode
(
-
1
),
status
(
-
1
),
navMode
(
-
1
),
onboardTimeOffset
(
0
),
controlRollManual
(
true
),
controlPitchManual
(
true
),
controlYawManual
(
true
),
controlThrustManual
(
true
),
manualRollAngle
(
0
),
manualPitchAngle
(
0
),
manualYawAngle
(
0
),
manualThrust
(
0
),
receiveDropRate
(
0
),
sendDropRate
(
0
),
lowBattAlarm
(
false
),
positionLock
(
false
),
localX
(
0.0
),
localY
(
0.0
),
localZ
(
0.0
),
latitude
(
0.0
),
longitude
(
0.0
),
altitude
(
0.0
),
roll
(
0.0
),
pitch
(
0.0
),
yaw
(
0.0
),
statusTimeout
(
new
QTimer
(
this
)),
paramsOnceRequested
(
false
),
airframe
(
0
),
attitudeKnown
(
false
),
paramManager
(
NULL
)
uasId
(
id
),
startTime
(
QGC
::
groundTimeMilliseconds
()),
commStatus
(
COMM_DISCONNECTED
),
name
(
""
),
autopilot
(
-
1
),
links
(
new
QList
<
LinkInterface
*>
()),
unknownPackets
(),
mavlink
(
protocol
),
waypointManager
(
*
this
),
thrustSum
(
0
),
thrustMax
(
10
),
startVoltage
(
0
),
warnVoltage
(
9.5
f
),
warnLevelPercent
(
20.0
f
),
currentVoltage
(
12.0
f
),
lpVoltage
(
12.0
f
),
batteryRemainingEstimateEnabled
(
false
),
mode
(
-
1
),
status
(
-
1
),
navMode
(
-
1
),
onboardTimeOffset
(
0
),
controlRollManual
(
true
),
controlPitchManual
(
true
),
controlYawManual
(
true
),
controlThrustManual
(
true
),
manualRollAngle
(
0
),
manualPitchAngle
(
0
),
manualYawAngle
(
0
),
manualThrust
(
0
),
receiveDropRate
(
0
),
sendDropRate
(
0
),
lowBattAlarm
(
false
),
positionLock
(
false
),
localX
(
0.0
),
localY
(
0.0
),
localZ
(
0.0
),
latitude
(
0.0
),
longitude
(
0.0
),
altitude
(
0.0
),
roll
(
0.0
),
pitch
(
0.0
),
yaw
(
0.0
),
statusTimeout
(
new
QTimer
(
this
)),
paramsOnceRequested
(
false
),
airframe
(
0
),
attitudeKnown
(
false
),
paramManager
(
NULL
)
{
color
=
UASInterface
::
getNextColor
();
setBattery
(
LIPOLY
,
3
);
...
...
@@ -877,6 +877,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
imagePackets
=
p
.
packets
;
imagePayload
=
p
.
payload
;
imageQuality
=
p
.
jpg_quality
;
imageType
=
p
.
type
;
imageStart
=
QGC
::
groundTimeMilliseconds
();
}
break
;
...
...
@@ -887,6 +888,14 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
int
seq
=
img
.
seqnr
;
int
pos
=
seq
*
imagePayload
;
// Check if we have a valid transaction
if
(
imagePackets
==
0
)
{
// NO VALID TRANSACTION - ABORT
// Restart statemachine
imagePacketsArrived
=
0
;
}
for
(
int
i
=
0
;
i
<
imagePayload
;
++
i
)
{
if
(
pos
<=
imageSize
)
{
imageRecBuffer
[
pos
]
=
img
.
data
[
i
];
...
...
@@ -897,14 +906,12 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
++
imagePacketsArrived
;
// emit signal if all packets arrived
if
((
imagePacketsArrived
==
imagePackets
))
{
image
.
loadFromData
(
imageRecBuffer
);
emit
imageReady
(
this
);
if
((
imagePacketsArrived
>=
imagePackets
))
{
// Restart statemachine
imagePacketsArrived
=
0
;
//this->requestImage();
//qDebug() << "SENDING REQUEST TO GET NEW IMAGE FROM SYSTEM" << uasId;
emit
imageReady
(
this
);
qDebug
()
<<
"imageReady emitted. all packets arrived"
;
}
}
break
;
...
...
@@ -1119,7 +1126,7 @@ void UAS::startPressureCalibration()
quint64
UAS
::
getUnixTime
(
quint64
time
)
{
if
(
time
==
0
)
{
// qDebug() << "XNEW time:" <<QGC::groundTimeMilliseconds();
// qDebug() << "XNEW time:" <<QGC::groundTimeMilliseconds();
return
QGC
::
groundTimeMilliseconds
();
}
// Check if time is smaller than 40 years,
...
...
@@ -1144,7 +1151,7 @@ quint64 UAS::getUnixTime(quint64 time)
else
if
(
time
<
1261440000000000
)
#endif
{
// qDebug() << "GEN time:" << time/1000 + onboardTimeOffset;
// qDebug() << "GEN time:" << time/1000 + onboardTimeOffset;
if
(
onboardTimeOffset
==
0
)
{
onboardTimeOffset
=
QGC
::
groundTimeMilliseconds
()
-
time
/
1000
;
}
...
...
@@ -1325,7 +1332,59 @@ void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDesc
QImage
UAS
::
getImage
()
{
#ifdef MAVLINK_ENABLED_PIXHAWK
qDebug
()
<<
"IMAGE TYPE:"
<<
imageType
;
// RAW greyscale
if
(
imageType
==
MAVLINK_DATA_STREAM_IMG_RAW8U
)
{
// TODO FIXME Fabian
// RAW hardcoded to 22x22
int
imgWidth
=
22
;
int
imgHeight
=
22
;
int
imgColors
=
255
;
//const int headerSize = 15;
// Construct PGM header
QString
header
(
"P5
\n
%1 %2
\n
%3
\n
"
);
header
=
header
.
arg
(
imgWidth
).
arg
(
imgHeight
).
arg
(
imgColors
);
QByteArray
tmpImage
(
header
.
toStdString
().
c_str
(),
header
.
toStdString
().
size
());
tmpImage
.
append
(
imageRecBuffer
);
//qDebug() << "IMAGE SIZE:" << tmpImage.size() << "HEADER SIZE: (15):" << header.size() << "HEADER: " << header;
if
(
imageRecBuffer
.
isNull
())
{
qDebug
()
<<
"could not convertToPGM()"
;
return
QImage
();
}
if
(
!
image
.
loadFromData
(
tmpImage
,
"PGM"
))
{
qDebug
()
<<
"could not create extracted image"
;
return
QImage
();
}
}
// BMP with header
else
if
(
imageType
==
MAVLINK_DATA_STREAM_IMG_BMP
||
imageType
==
MAVLINK_DATA_STREAM_IMG_JPEG
||
imageType
==
MAVLINK_DATA_STREAM_IMG_PGM
||
imageType
==
MAVLINK_DATA_STREAM_IMG_PNG
)
{
if
(
!
image
.
loadFromData
(
imageRecBuffer
))
{
qDebug
()
<<
"Loading data from image buffer failed!"
;
}
}
// Restart statemachine
imagePacketsArrived
=
0
;
//imageRecBuffer.clear();
return
image
;
#endif
}
void
UAS
::
requestImage
()
...
...
@@ -1333,20 +1392,14 @@ void UAS::requestImage()
#ifdef MAVLINK_ENABLED_PIXHAWK
qDebug
()
<<
"trying to get an image from the uas..."
;
if
(
imagePacketsArrived
==
0
)
{
// check if there is already an image transmission going on
if
(
imagePacketsArrived
==
0
)
{
mavlink_message_t
msg
;
mavlink_msg_data_transmission_handshake_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
DATA_TYPE_JPEG_IMAGE
,
0
,
0
,
0
,
50
);
sendMessage
(
msg
);
}
else
if
(
QGC
::
groundTimeMilliseconds
()
-
imageStart
>=
1000
)
{
// handshake happened more than 1 second ago, packets should have arrived by now
// maybe we missed some packets (dropped along the way)
image
.
loadFromData
(
imageRecBuffer
);
emit
imageReady
(
this
);
// Restart statemachine
imagePacketsArrived
=
0
;
}
#endif
// default else, wait?
}
...
...
@@ -1647,11 +1700,11 @@ void UAS::setParameter(const int component, const QString& id, const float value
if
((
int
)
i
<
id
.
length
()
&&
i
<
(
sizeof
(
p
.
param_id
)
-
1
))
{
p
.
param_id
[
i
]
=
id
.
toAscii
()[
i
];
}
// // Null termination at end of string or end of buffer
// else if ((int)i == id.length() || i == (sizeof(p.param_id) - 1))
// {
// p.param_id[i] = '\0';
// }
// // Null termination at end of string or end of buffer
// else if ((int)i == id.length() || i == (sizeof(p.param_id) - 1))
// {
// p.param_id[i] = '\0';
// }
// Zero fill
else
{
p
.
param_id
[
i
]
=
0
;
...
...
src/uas/UAS.h
View file @
0846707b
...
...
@@ -187,7 +187,8 @@ protected: //COMMENTS FOR TEST UNIT
int
imagePackets
;
///< Number of data packets being sent for this image
int
imagePacketsArrived
;
///< Number of data packets recieved
int
imagePayload
;
///< Payload size per transmitted packet (bytes). Standard is 254, and decreases when image resolution increases.
int
imageQuality
;
///< JPEG-Quality of the transmitted image (percentage)
int
imageQuality
;
///< Quality of the transmitted image (percentage)
int
imageType
;
///< Type of the transmitted image (BMP, PNG, JPEG, RAW 8 bit, RAW 32 bit)
QByteArray
imageRecBuffer
;
///< Buffer for the incoming bytestream
QImage
image
;
///< Image data of last completely transmitted image
quint64
imageStart
;
...
...
@@ -226,7 +227,7 @@ public:
}
int
getSystemType
();
QImage
getImage
();
void
requestImage
();
// ?
void
requestImage
();
int
getAutopilotType
()
{
return
autopilot
;
}
...
...
src/ui/HUD.cc
View file @
0846707b
...
...
@@ -75,6 +75,7 @@ inline bool isinf(T value)
*/
HUD
::
HUD
(
int
width
,
int
height
,
QWidget
*
parent
)
:
QGLWidget
(
QGLFormat
(
QGL
::
SampleBuffers
),
parent
),
u
(
NULL
),
uas
(
NULL
),
yawInt
(
0.0
f
),
mode
(
tr
(
"UNKNOWN MODE"
)),
...
...
@@ -136,7 +137,8 @@ HUD::HUD(int width, int height, QWidget* parent)
hudInstrumentsEnabled
(
true
),
videoEnabled
(
false
),
xImageFactor
(
1.0
),
yImageFactor
(
1.0
)
yImageFactor
(
1.0
),
imageRequested
(
false
)
{
// Set auto fill to false
setAutoFillBackground
(
false
);
...
...
@@ -158,11 +160,10 @@ HUD::HUD(int width, int height, QWidget* parent)
//qDebug() << __FILE__ << __LINE__ << "template image:" << imagePath;
//fill = QImage(imagePath);
//
glImage = QGLWidget::convertToGLFormat(fill);
glImage
=
QGLWidget
::
convertToGLFormat
(
fill
);
// Refresh timer
refreshTimer
->
setInterval
(
updateInterval
);
//connect(refreshTimer, SIGNAL(timeout()), this, SLOT(update()));
connect
(
refreshTimer
,
SIGNAL
(
timeout
()),
this
,
SLOT
(
paintHUD
()));
// Resize to correct size and fill with image
...
...
@@ -282,6 +283,7 @@ void HUD::setActiveUAS(UASInterface* uas)
UAS
*
u
=
dynamic_cast
<
UAS
*>
(
this
->
uas
);
if
(
u
)
{
disconnect
(
u
,
SIGNAL
(
imageStarted
(
quint64
)),
this
,
SLOT
(
startImage
(
quint64
)));
disconnect
(
u
,
SIGNAL
(
imageReady
(
UASInterface
*
)),
this
,
SLOT
(
copyImage
()));
}
}
...
...
@@ -303,10 +305,12 @@ void HUD::setActiveUAS(UASInterface* uas)
UAS
*
u
=
dynamic_cast
<
UAS
*>
(
uas
);
if
(
u
)
{
connect
(
u
,
SIGNAL
(
imageStarted
(
quint64
)),
this
,
SLOT
(
startImage
(
quint64
)));
connect
(
u
,
SIGNAL
(
imageReady
(
UASInterface
*
)),
this
,
SLOT
(
copyImage
()));
}
// Set new UAS
this
->
uas
=
uas
;
this
->
u
=
dynamic_cast
<
UAS
*>
(
this
->
uas
);
}
}
...
...
@@ -666,9 +670,6 @@ void HUD::paintHUD()
qDebug
()
<<
__FILE__
<<
__LINE__
<<
"template image:"
<<
nextOfflineImage
;
QImage
fill
=
QImage
(
nextOfflineImage
);
xImageFactor
=
width
()
/
(
float
)
fill
.
width
();
yImageFactor
=
height
()
/
(
float
)
fill
.
height
();
glImage
=
QGLWidget
::
convertToGLFormat
(
fill
);
// Reset to save load efforts
...
...
@@ -677,9 +678,13 @@ void HUD::paintHUD()
glRasterPos2i
(
0
,
0
);
glPixelZoom
(
xImageFactor
,
yImageFactor
);
xImageFactor
=
width
()
/
(
float
)
glImage
.
width
();
yImageFactor
=
height
()
/
(
float
)
glImage
.
height
();
float
imageFactor
=
qMin
(
xImageFactor
,
yImageFactor
);
glPixelZoom
(
imageFactor
,
imageFactor
);
// Resize to correct size and fill with image
glDrawPixels
(
glImage
.
width
(),
glImage
.
height
(),
GL_RGBA
,
GL_UNSIGNED_BYTE
,
glImage
.
bits
());
//qDebug() << "DRAWING GL IMAGE";
}
else
{
// Blue / brown background
paintCenterBackground
(
roll
,
pitch
,
yawTrans
);
...
...
@@ -1623,3 +1628,9 @@ void HUD::setPixels(int imgid, const unsigned char* imageData, int length, int s
// }
}
}
void
HUD
::
copyImage
()
{
qDebug
()
<<
"HUD::copyImage()"
;
this
->
glImage
=
QGLWidget
::
convertToGLFormat
(
this
->
u
->
getImage
());
}
src/ui/HUD.h
View file @
0846707b
...
...
@@ -88,6 +88,8 @@ public slots:
void
enableHUDInstruments
(
bool
enabled
);
/** @brief Enable Video */
void
enableVideo
(
bool
enabled
);
/** @brief Copy an image from the current active UAS */
void
copyImage
();
protected
slots
:
...
...
@@ -216,6 +218,8 @@ protected:
QAction
*
selectOfflineDirectoryAction
;
QAction
*
selectVideoChannelAction
;
void
paintEvent
(
QPaintEvent
*
event
);
bool
imageRequested
;
UAS
*
u
;
};
...
...
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