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
a374e265
Commit
a374e265
authored
May 29, 2010
by
pixhawk
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Minor cleanups
parent
b8ec5d47
Changes
8
Hide whitespace changes
Inline
Side-by-side
Showing
8 changed files
with
29 additions
and
10 deletions
+29
-10
MAVLinkProtocol.cc
src/comm/MAVLinkProtocol.cc
+1
-1
ProtocolInterface.h
src/comm/ProtocolInterface.h
+2
-1
UDPLink.cc
src/comm/UDPLink.cc
+3
-1
CameraView.cc
src/ui/CameraView.cc
+8
-2
CameraView.h
src/ui/CameraView.h
+2
-0
MainWindow.cc
src/ui/MainWindow.cc
+1
-1
UASInfoWidget.cc
src/ui/uas/UASInfoWidget.cc
+8
-2
UASInfoWidget.h
src/ui/uas/UASInfoWidget.h
+4
-2
No files found.
src/comm/MAVLinkProtocol.cc
View file @
a374e265
...
...
@@ -227,7 +227,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link)
// qDebug() << "LOSSCHANGED" << receiveLoss;
currLossCounter
=
0
;
currReceiveCounter
=
0
;
emit
receiveLossChanged
(
receiveLoss
);
emit
receiveLossChanged
(
message
.
sysid
,
receiveLoss
);
}
// The packet is emitted as a whole, as it is only 255 - 261 bytes short
...
...
src/comm/ProtocolInterface.h
View file @
a374e265
...
...
@@ -56,7 +56,8 @@ public slots:
virtual
void
receiveBytes
(
LinkInterface
*
link
)
=
0
;
signals:
void
receiveLossChanged
(
float
loss
);
/** @brief Update the packet loss from one system */
void
receiveLossChanged
(
int
uasId
,
float
loss
);
};
...
...
src/comm/UDPLink.cc
View file @
a374e265
...
...
@@ -67,7 +67,9 @@ void UDPLink::run()
void
UDPLink
::
setAddress
(
QString
address
)
{
// TODO Implement address
Q_UNUSED
(
address
);
// FIXME TODO Implement address
//socket->setLocalAddress(QHostAddress(address));
}
void
UDPLink
::
setPort
(
quint16
port
)
...
...
src/ui/CameraView.cc
View file @
a374e265
...
...
@@ -44,8 +44,9 @@ CameraView::CameraView(int width, int height, int depth, int channels, QWidget*
//setImageSize(width, height, depth, channels);
receivedWidth
=
width
;
receivedHeight
=
height
;
receivedDepth
=
8
;
receivedChannels
=
1
;
receivedDepth
=
depth
;
receivedChannels
=
channels
;
imageId
=
-
1
;
// Fill with black background
QImage
fill
=
QImage
(
width
,
height
,
QImage
::
Format_Indexed8
);
...
...
@@ -139,6 +140,7 @@ void CameraView::setImageSize(int width, int height, int depth, int channels)
void
CameraView
::
startImage
(
int
imgid
,
int
width
,
int
height
,
int
depth
,
int
channels
)
{
this
->
imageId
=
imgid
;
//qDebug() << "CameraView: starting image (" << width << "x" << height << ", " << depth << "bits) with " << channels << "channels";
// Copy previous image to screen if it hasn't been finished properly
...
...
@@ -208,6 +210,10 @@ void CameraView::saveImage()
void
CameraView
::
setPixels
(
int
imgid
,
const
unsigned
char
*
imageData
,
int
length
,
unsigned
int
startIndex
)
{
// FIXME imgid can be used to receive and then display multiple images
// the image buffer should be converted into a n image buffer.
Q_UNUSED
(
imgid
);
// qDebug() << "at" << __FILE__ << __LINE__ << ": Received startindex" << startIndex << "and length" << length << "(" << startIndex+length << "of" << rawExpectedBytes << "bytes)";
if
(
imageStarted
)
...
...
src/ui/CameraView.h
View file @
a374e265
...
...
@@ -71,6 +71,8 @@ protected:
int
receivedChannels
;
int
receivedWidth
;
int
receivedHeight
;
QMap
<
int
,
QImage
*>
images
;
///< Reference to the received images
int
imageId
;
///< ID of the currently displayed image
void
commitRawDataToGL
();
};
...
...
src/ui/MainWindow.cc
View file @
a374e265
...
...
@@ -166,7 +166,7 @@ settings()
adjustSize
();
//
connect
(
mavlink
,
SIGNAL
(
receiveLossChanged
(
float
)),
info
,
SLOT
(
updateSendLoss
(
float
)));
connect
(
mavlink
,
SIGNAL
(
receiveLossChanged
(
int
,
float
)),
info
,
SLOT
(
updateSendLoss
(
int
,
float
)));
}
MainWindow
::~
MainWindow
()
...
...
src/ui/uas/UASInfoWidget.cc
View file @
a374e265
...
...
@@ -117,13 +117,19 @@ void UASInfoWidget::updateCPULoad(UASInterface* uas, double load)
}
}
void
UASInfoWidget
::
updateReceiveLoss
(
float
receiveLoss
)
void
UASInfoWidget
::
updateReceiveLoss
(
int
uasId
,
float
receiveLoss
)
{
Q_UNUSED
(
uasId
);
this
->
receiveLoss
=
this
->
receiveLoss
*
0.8
f
+
receiveLoss
*
0.2
f
;
}
void
UASInfoWidget
::
updateSendLoss
(
float
sendLoss
)
/**
The send loss is typically calculated on the GCS based on packets
that were received scrambled from the MAV
*/
void
UASInfoWidget
::
updateSendLoss
(
int
uasId
,
float
sendLoss
)
{
Q_UNUSED
(
uasId
);
this
->
sendLoss
=
this
->
sendLoss
*
0.8
f
+
sendLoss
*
0.2
f
;
}
...
...
src/ui/uas/UASInfoWidget.h
View file @
a374e265
...
...
@@ -56,8 +56,10 @@ public slots:
void
updateBattery
(
UASInterface
*
uas
,
double
voltage
,
double
percent
,
int
seconds
);
void
updateCPULoad
(
UASInterface
*
uas
,
double
load
);
void
updateReceiveLoss
(
float
receiveLoss
);
void
updateSendLoss
(
float
sendLoss
);
/** @brief Set the loss rate of packets received by the MAV */
void
updateReceiveLoss
(
int
uasId
,
float
receiveLoss
);
/** @brief Set the loss rate of packets sent from the MAV */
void
updateSendLoss
(
int
uasId
,
float
sendLoss
);
void
setVoltage
(
UASInterface
*
uas
,
double
voltage
);
void
setChargeLevel
(
UASInterface
*
uas
,
double
chargeLevel
);
...
...
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