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
b997b4d8
Commit
b997b4d8
authored
Jan 22, 2011
by
pixhawk
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Added binary format option to MAVLink log player
parent
cb002ae9
Changes
4
Hide whitespace changes
Inline
Side-by-side
Showing
4 changed files
with
86 additions
and
3 deletions
+86
-3
QGCMAVLinkLogPlayer.cc
src/ui/QGCMAVLinkLogPlayer.cc
+74
-2
QGCMAVLinkLogPlayer.h
src/ui/QGCMAVLinkLogPlayer.h
+2
-0
WaypointView.cc
src/ui/WaypointView.cc
+7
-1
WaypointView.ui
src/ui/WaypointView.ui
+3
-0
No files found.
src/ui/QGCMAVLinkLogPlayer.cc
View file @
b997b4d8
...
...
@@ -18,6 +18,8 @@ QGCMAVLinkLogPlayer::QGCMAVLinkLogPlayer(MAVLinkProtocol* mavlink, QWidget *pare
mavlink
(
mavlink
),
logLink
(
NULL
),
loopCounter
(
0
),
mavlinkLogFormat
(
true
),
binaryBaudRate
(
57600
),
ui
(
new
Ui
::
QGCMAVLinkLogPlayer
)
{
ui
->
setupUi
(
this
);
...
...
@@ -62,7 +64,20 @@ void QGCMAVLinkLogPlayer::play()
logLink
=
new
MAVLinkSimulationLink
(
""
);
// Start timer
loopTimer
.
start
(
1
);
if
(
mavlinkLogFormat
)
{
loopTimer
.
start
(
1
);
}
else
{
// 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
.
start
(
interval
);
}
}
else
{
...
...
@@ -124,7 +139,7 @@ bool QGCMAVLinkLogPlayer::reset(int packetIndex)
void
QGCMAVLinkLogPlayer
::
selectLogFile
()
{
QString
fileName
=
QFileDialog
::
getOpenFileName
(
this
,
tr
(
"Specify MAVLink log file name"
),
QDesktopServices
::
storageLocation
(
QDesktopServices
::
DesktopLocation
),
tr
(
"MAVLink
Logfile (*.mavlink
);;"
));
QString
fileName
=
QFileDialog
::
getOpenFileName
(
this
,
tr
(
"Specify MAVLink log file name"
),
QDesktopServices
::
storageLocation
(
QDesktopServices
::
DesktopLocation
),
tr
(
"MAVLink
or Binary Logfile (*.mavlink; *.bin
);;"
));
loadLogFile
(
fileName
);
}
...
...
@@ -180,6 +195,11 @@ void QGCMAVLinkLogPlayer::loadLogFile(const QString& file)
startTime
=
0
;
ui
->
logFileNameLabel
->
setText
(
tr
(
"%1"
).
arg
(
logFileInfo
.
baseName
()));
// Select if binary or MAVLink log format is used
mavlinkLogFormat
=
file
.
endsWith
(
".mavlink"
);
if
(
mavlinkLogFormat
)
{
// Get the time interval from the logfile
QByteArray
timestamp
=
logFile
.
read
(
timeLen
);
...
...
@@ -205,6 +225,32 @@ void QGCMAVLinkLogPlayer::loadLogFile(const QString& file)
QString
timelabel
=
tr
(
"%1h:%2m:%3s"
).
arg
(
hours
,
2
).
arg
(
minutes
,
2
).
arg
(
seconds
,
2
);
ui
->
logStatsLabel
->
setText
(
tr
(
"%2 MB, %3 packets, %4"
).
arg
(
logFileInfo
.
size
()
/
1000000.0
f
,
0
,
'f'
,
2
).
arg
(
logFileInfo
.
size
()
/
(
MAVLINK_MAX_PACKET_LEN
+
sizeof
(
quint64
))).
arg
(
timelabel
));
}
else
{
QStringList
parts
=
file
.
split
(
"_"
);
if
(
parts
.
count
()
>
1
)
{
bool
ok
;
int
rate
=
parts
.
last
().
toInt
(
&
ok
);
// 9600 baud to 100 MBit
if
(
ok
&&
(
rate
>
9600
&&
rate
<
100000000
))
{
// Accept this as valid baudrate
binaryBaudRate
=
rate
;
}
}
int
seconds
=
logFileInfo
.
size
()
/
(
binaryBaudRate
/
10
);
int
minutes
=
seconds
/
60
;
int
hours
=
minutes
/
60
;
seconds
-=
60
*
minutes
;
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
));
}
}
}
/**
...
...
@@ -236,6 +282,8 @@ void QGCMAVLinkLogPlayer::jumpToSliderVal(int slidervalue)
*/
void
QGCMAVLinkLogPlayer
::
logLoop
()
{
if
(
mavlinkLogFormat
)
{
bool
ok
;
// First check initialization
...
...
@@ -346,6 +394,30 @@ void QGCMAVLinkLogPlayer::logLoop()
// Update progress bar
}
}
else
{
// Binary format - read at fixed rate
const
int
len
=
100
;
QByteArray
chunk
=
logFile
.
read
(
len
);
// Emit this packet
emit
bytesReady
(
logLink
,
chunk
);
// Check if reached end of file before reading next timestamp
if
(
chunk
.
length
()
<
len
||
logFile
.
atEnd
())
{
// Reached end of file
reset
();
QString
status
=
tr
(
"Reached end of binary log file."
);
ui
->
logStatsLabel
->
setText
(
status
);
MainWindow
::
instance
()
->
showStatusMessage
(
status
);
return
;
}
}
}
void
QGCMAVLinkLogPlayer
::
changeEvent
(
QEvent
*
e
)
{
...
...
src/ui/QGCMAVLinkLogPlayer.h
View file @
b997b4d8
...
...
@@ -61,6 +61,8 @@ protected:
QFile
logFile
;
QTimer
loopTimer
;
int
loopCounter
;
bool
mavlinkLogFormat
;
int
binaryBaudRate
;
static
const
int
packetLen
=
MAVLINK_MAX_PACKET_LEN
;
static
const
int
timeLen
=
sizeof
(
quint64
);
void
changeEvent
(
QEvent
*
e
);
...
...
src/ui/WaypointView.cc
View file @
b997b4d8
...
...
@@ -205,10 +205,15 @@ void WaypointView::changedCurrent(int state)
void
WaypointView
::
updateValues
()
{
// Deactivate signals from the WP
wp
->
blockSignals
(
true
);
// update frame
MAV_FRAME
frame
=
wp
->
getFrame
();
int
frame_index
=
m_ui
->
comboBox_frame
->
findData
(
frame
);
m_ui
->
comboBox_frame
->
setCurrentIndex
(
frame_index
);
if
(
m_ui
->
comboBox_frame
->
currentIndex
()
!=
frame_index
)
{
m_ui
->
comboBox_frame
->
setCurrentIndex
(
frame_index
);
}
switch
(
frame
)
{
case
(
MAV_FRAME_LOCAL
):
...
...
@@ -249,6 +254,7 @@ void WaypointView::updateValues()
m_ui
->
idLabel
->
setText
(
QString
(
"%1"
).
arg
(
wp
->
getId
()));
\
m_ui
->
orbitSpinBox
->
setValue
(
wp
->
getOrbit
());
m_ui
->
holdTimeSpinBox
->
setValue
(
wp
->
getHoldTime
());
wp
->
blockSignals
(
false
);
}
void
WaypointView
::
setCurrent
(
bool
state
)
...
...
src/ui/WaypointView.ui
View file @
b997b4d8
...
...
@@ -234,6 +234,9 @@ QProgressBar::chunk#thrustBar {
<property
name=
"toolTip"
>
<string>
Position X coordinate
</string>
</property>
<property
name=
"wrapping"
>
<bool>
false
</bool>
</property>
<property
name=
"prefix"
>
<string>
N
</string>
</property>
...
...
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