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
75a1db30
Commit
75a1db30
authored
Jan 22, 2011
by
pixhawk
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Added status progress message to log player
parent
b997b4d8
Changes
1
Show whitespace changes
Inline
Side-by-side
Showing
1 changed file
with
151 additions
and
136 deletions
+151
-136
QGCMAVLinkLogPlayer.cc
src/ui/QGCMAVLinkLogPlayer.cc
+151
-136
No files found.
src/ui/QGCMAVLinkLogPlayer.cc
View file @
75a1db30
...
...
@@ -76,7 +76,7 @@ void QGCMAVLinkLogPlayer::play()
// to guarantee the baud rate, then divide 1000 by the number of read
// operations to obtain the interval in milliseconds
int
interval
=
1000
/
((
binaryBaudRate
/
10
)
/
len
);
loopTimer
.
start
(
interval
);
loopTimer
.
start
(
interval
*
accelerationFactor
);
}
}
else
...
...
@@ -111,6 +111,7 @@ bool QGCMAVLinkLogPlayer::reset(int packetIndex)
// Reset only for valid values
if
(
packetIndex
>=
0
&&
packetIndex
<=
logFile
.
size
()
-
(
packetLen
+
timeLen
))
{
bool
result
=
true
;
pause
();
loopCounter
=
0
;
...
...
@@ -161,6 +162,19 @@ void QGCMAVLinkLogPlayer::setAccelerationFactorInt(int factor)
accelerationFactor
=
1
+
(
f
/
2.0
f
);
}
// Update timer interval
if
(
!
mavlinkLogFormat
)
{
// Read len bytes at a time
int
len
=
100
;
// Calculate the number of times to read 100 bytes per second
// to guarantee the baud rate, then divide 1000 by the number of read
// operations to obtain the interval in milliseconds
int
interval
=
1000
/
((
binaryBaudRate
/
10
)
/
len
);
loopTimer
.
stop
();
loopTimer
.
start
(
interval
/
accelerationFactor
);
}
//qDebug() << "FACTOR:" << accelerationFactor;
ui
->
speedLabel
->
setText
(
tr
(
"Speed: %1X"
).
arg
(
accelerationFactor
,
5
,
'f'
,
2
,
'0'
));
...
...
@@ -227,7 +241,10 @@ void QGCMAVLinkLogPlayer::loadLogFile(const QString& file)
}
else
{
QStringList
parts
=
file
.
split
(
"_"
);
// Load in binary mode
// Set baud rate if any present
QStringList
parts
=
logFileInfo
.
baseName
().
split
(
"_"
);
if
(
parts
.
count
()
>
1
)
{
...
...
@@ -248,7 +265,7 @@ void QGCMAVLinkLogPlayer::loadLogFile(const QString& file)
minutes
-=
60
*
hours
;
QString
timelabel
=
tr
(
"%1h:%2m:%3s"
).
arg
(
hours
,
2
).
arg
(
minutes
,
2
).
arg
(
seconds
,
2
);
ui
->
logStatsLabel
->
setText
(
tr
(
"%2 MB, %4 at %5 KB/s"
).
arg
(
logFileInfo
.
size
()
/
1000000.0
f
,
0
,
'f'
,
2
).
arg
(
timelabel
).
arg
(
binaryBaudRate
/
10
/
1024
));
ui
->
logStatsLabel
->
setText
(
tr
(
"%2 MB, %4 at %5 KB/s"
).
arg
(
logFileInfo
.
size
()
/
1000000.0
f
,
0
,
'f'
,
2
).
arg
(
timelabel
).
arg
(
binaryBaudRate
/
10
.0
f
/
1024.0
f
,
0
,
'f'
,
2
));
}
}
}
...
...
@@ -266,9 +283,11 @@ void QGCMAVLinkLogPlayer::jumpToSliderVal(int slidervalue)
// Do only accept valid jumps
if
(
reset
(
packetIndex
))
{
if
(
mavlinkLogFormat
)
{
ui
->
logStatsLabel
->
setText
(
tr
(
"Jumped to packet %1"
).
arg
(
packetIndex
));
//qDebug() << "SET POSITION TO PACKET:" << packetIndex;
}
}
}
...
...
@@ -375,25 +394,8 @@ void QGCMAVLinkLogPlayer::logLoop()
{
loopTimer
.
start
(
nextExecutionTime
);
}
// loopTimer.start(20);
if
(
loopCounter
%
40
==
0
)
{
QFileInfo
logFileInfo
(
logFile
);
int
progress
=
(
ui
->
positionSlider
->
maximum
()
-
ui
->
positionSlider
->
minimum
())
*
(
logFile
.
pos
()
/
static_cast
<
float
>
(
logFileInfo
.
size
()));
//qDebug() << "Progress:" << progress;
ui
->
positionSlider
->
blockSignals
(
true
);
ui
->
positionSlider
->
setValue
(
progress
);
ui
->
positionSlider
->
blockSignals
(
false
);
}
loopCounter
++
;
// Ui update: Only every 20 messages
// to prevent flickering and high CPU load
// Update status label
// Update progress bar
}
}
else
{
// Binary format - read at fixed rate
...
...
@@ -414,9 +416,22 @@ void QGCMAVLinkLogPlayer::logLoop()
MainWindow
::
instance
()
->
showStatusMessage
(
status
);
return
;
}
}
// Ui update: Only every 20 messages
// to prevent flickering and high CPU load
// Update status label
// Update progress bar
if
(
loopCounter
%
40
==
0
)
{
QFileInfo
logFileInfo
(
logFile
);
int
progress
=
(
ui
->
positionSlider
->
maximum
()
-
ui
->
positionSlider
->
minimum
())
*
(
logFile
.
pos
()
/
static_cast
<
float
>
(
logFileInfo
.
size
()));
//qDebug() << "Progress:" << progress;
ui
->
positionSlider
->
blockSignals
(
true
);
ui
->
positionSlider
->
setValue
(
progress
);
ui
->
positionSlider
->
blockSignals
(
false
);
}
loopCounter
++
;
}
void
QGCMAVLinkLogPlayer
::
changeEvent
(
QEvent
*
e
)
...
...
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