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
70692347
Commit
70692347
authored
May 04, 2010
by
lm
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Drop rate view works
parent
fdc487ba
Changes
4
Hide whitespace changes
Inline
Side-by-side
Showing
4 changed files
with
41 additions
and
18 deletions
+41
-18
MAVLinkProtocol.cc
src/comm/MAVLinkProtocol.cc
+26
-8
MAVLinkProtocol.h
src/comm/MAVLinkProtocol.h
+1
-1
UASInfoWidget.cc
src/ui/uas/UASInfoWidget.cc
+11
-8
UASInfoWidget.h
src/ui/uas/UASInfoWidget.h
+3
-1
No files found.
src/comm/MAVLinkProtocol.cc
View file @
70692347
...
...
@@ -139,20 +139,37 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link)
}
else
{
if
(
lastIndex
[
message
.
sysid
][
message
.
compid
]
==
255
)
{
lastIndex
[
message
.
sysid
][
message
.
compid
]
=
0
;
}
else
{
lastIndex
[
message
.
sysid
][
message
.
compid
]
++
;
}
int
safeguard
=
0
;
while
(
lastIndex
[
message
.
sysid
][
message
.
compid
]
+
1
!=
message
.
seq
&&
safeguard
<
100
)
//qDebug() << "SYSID" << message.sysid << "COMPID" << message.compid << "LASTINDEX" << lastIndex[message.sysid][message.compid] << "SEQ" << message.seq;
while
(
lastIndex
[
message
.
sysid
][
message
.
compid
]
!=
message
.
seq
&&
safeguard
<
1
)
{
lastIndex
[
message
.
sysid
][
message
.
compid
]
+=
1
;
if
(
lastIndex
[
message
.
sysid
][
message
.
compid
]
==
255
)
{
lastIndex
[
message
.
sysid
][
message
.
compid
]
=
0
;
}
else
{
lastIndex
[
message
.
sysid
][
message
.
compid
]
++
;
}
totalLossCounter
++
;
safeguard
++
;
}
}
// if (lastIndex.contains(message.sysid))
// {
// QMap<int, int>* lastCompIndex = lastIndex.value(message.sysid);
// if (lastCompIndex->contains(message.compid))
// while (lastCompIndex->value(message.compid, 0)+1 )
// }
// if (lastIndex.contains(message.sysid))
// {
// QMap<int, int>* lastCompIndex = lastIndex.value(message.sysid);
// if (lastCompIndex->contains(message.compid))
// while (lastCompIndex->value(message.compid, 0)+1 )
// }
//if ()
if
(
lastLoss
!=
totalLossCounter
)
{
...
...
@@ -160,6 +177,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link)
// Receive loss
float
receiveLoss
=
(
double
)
totalLossCounter
/
(
double
)(
totalReceiveCounter
+
totalLossCounter
);
receiveLoss
*=
100.0
f
;
qDebug
()
<<
"LOSS"
<<
receiveLoss
;
emit
receiveLossChanged
(
receiveLoss
);
}
...
...
src/comm/MAVLinkProtocol.h
View file @
70692347
...
...
@@ -87,7 +87,7 @@ protected:
int
heartbeatRate
;
///< Heartbeat rate, controls the timer interval
bool
m_heartbeatsEnabled
;
///< Enabled/disable heartbeat emission
QMutex
receiveMutex
;
///< Mutex to protect receiveBytes function
qint64
lastIndex
[
256
][
256
];
int
lastIndex
[
256
][
256
];
int
totalReceiveCounter
;
int
totalLossCounter
;
...
...
src/ui/uas/UASInfoWidget.cc
View file @
70692347
...
...
@@ -67,6 +67,8 @@ UASInfoWidget::UASInfoWidget(QWidget *parent, QString name) : QWidget(parent)
this
->
voltage
=
0
;
this
->
chargeLevel
=
0
;
this
->
load
=
0
;
receiveLoss
=
0
;
sendLoss
=
0
;
updateTimer
=
new
QTimer
(
this
);
connect
(
updateTimer
,
SIGNAL
(
timeout
()),
this
,
SLOT
(
refresh
()));
...
...
@@ -117,17 +119,12 @@ void UASInfoWidget::updateCPULoad(UASInterface* uas, double load)
void
UASInfoWidget
::
updateReceiveLoss
(
float
receiveLoss
)
{
ui
.
receiveLossBar
->
setValue
(
receiveLoss
);
ui
.
receiveLossLabel
->
setText
(
QString
::
number
(
receiveLoss
,
'f'
,
2
));
this
->
receiveLoss
=
this
->
receiveLoss
*
0.8
f
+
receiveLoss
*
0.2
f
;
}
void
UASInfoWidget
::
update
DropRate
(
int
sysId
,
float
receiveDrop
,
float
sendDrop
)
void
UASInfoWidget
::
update
SendLoss
(
float
sendLoss
)
{
Q_UNUSED
(
sysId
);
ui
.
receiveLossBar
->
setValue
(
receiveDrop
);
ui
.
receiveLossLabel
->
setText
(
QString
::
number
(
receiveDrop
)
+
"%"
);
ui
.
sendLossBar
->
setValue
(
sendDrop
);
ui
.
sendLossLabel
->
setText
(
QString
::
number
(
receiveDrop
)
+
"%"
);
this
->
sendLoss
=
this
->
sendLoss
*
0.8
f
+
sendLoss
*
0.2
f
;
}
void
UASInfoWidget
::
setVoltage
(
UASInterface
*
uas
,
double
voltage
)
...
...
@@ -159,4 +156,10 @@ void UASInfoWidget::refresh()
ui
.
loadLabel
->
setText
(
QString
::
number
(
this
->
load
,
'f'
,
loadDecimals
));
ui
.
loadBar
->
setValue
(
static_cast
<
int
>
(
this
->
load
));
ui
.
receiveLossBar
->
setValue
(
receiveLoss
);
ui
.
receiveLossLabel
->
setText
(
QString
::
number
(
receiveLoss
,
'f'
,
2
));
ui
.
sendLossBar
->
setValue
(
sendLoss
);
ui
.
sendLossLabel
->
setText
(
QString
::
number
(
sendLoss
,
'f'
,
2
));
}
src/ui/uas/UASInfoWidget.h
View file @
70692347
...
...
@@ -57,7 +57,7 @@ public slots:
void
updateBattery
(
UASInterface
*
uas
,
double
voltage
,
double
percent
,
int
seconds
);
void
updateCPULoad
(
UASInterface
*
uas
,
double
load
);
void
updateReceiveLoss
(
float
receiveLoss
);
void
update
DropRate
(
int
sysId
,
float
receiveDrop
,
float
sendDrop
);
void
update
SendLoss
(
float
sendLoss
);
void
setVoltage
(
UASInterface
*
uas
,
double
voltage
);
void
setChargeLevel
(
UASInterface
*
uas
,
double
chargeLevel
);
...
...
@@ -83,6 +83,8 @@ protected:
double
chargeLevel
;
double
timeRemaining
;
double
load
;
float
receiveLoss
;
float
sendLoss
;
QTimer
*
updateTimer
;
QString
name
;
quint64
startTime
;
...
...
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