Skip to content
GitLab
Projects
Groups
Snippets
/
Help
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Menu
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
0ea21917
Commit
0ea21917
authored
Nov 11, 2016
by
Andreas Bircher
Browse files
reading the message lengthts from the header of the binary log file
Conflicts: src/AnalyzeView/GeoTagController.cc
parent
b36d59c0
Changes
1
Hide whitespace changes
Inline
Side-by-side
src/AnalyzeView/GeoTagController.cc
View file @
0ea21917
...
@@ -282,14 +282,21 @@ bool GeoTagWorker::parsePX4Log()
...
@@ -282,14 +282,21 @@ bool GeoTagWorker::parsePX4Log()
{
{
// general message header
// general message header
char
header
[]
=
{(
char
)
0xA3
,
(
char
)
0x95
,
(
char
)
0x00
};
char
header
[]
=
{(
char
)
0xA3
,
(
char
)
0x95
,
(
char
)
0x00
};
// header for GPOS message header
char
gposHeaderHeader
[]
=
{(
char
)
0xA3
,
(
char
)
0x95
,
(
char
)
0x80
,
(
char
)
0x10
,
(
char
)
0x00
};
int
gposHeaderOffset
;
// header for GPOS message
// header for GPOS message
char
gposHeader
[]
=
{(
char
)
0xA3
,
(
char
)
0x95
,
(
char
)
0x10
,
(
char
)
0x00
};
char
gposHeader
[]
=
{(
char
)
0xA3
,
(
char
)
0x95
,
(
char
)
0x10
,
(
char
)
0x00
};
int
gposOffsets
[
3
]
=
{
3
,
7
,
11
};
int
gposOffsets
[
3
]
=
{
3
,
7
,
11
};
int
gposLengths
[
3
]
=
{
4
,
4
,
4
};
int
gposLengths
[
3
]
=
{
4
,
4
,
4
};
// header for trigger message header
char
triggerHeaderHeader
[]
=
{(
char
)
0xA3
,
(
char
)
0x95
,
(
char
)
0x80
,
(
char
)
0x37
,
(
char
)
0x00
};
int
triggerHeaderOffset
;
// header for trigger message
// header for trigger message
char
triggerHeader
[]
=
{(
char
)
0xA3
,
(
char
)
0x95
,
(
char
)
0x37
,
(
char
)
0x00
};
char
triggerHeader
[]
=
{(
char
)
0xA3
,
(
char
)
0x95
,
(
char
)
0x37
,
(
char
)
0x00
};
int
triggerOffsets
[
2
]
=
{
3
,
11
};
int
triggerOffsets
[
2
]
=
{
3
,
11
};
int
triggerLengths
[
2
]
=
{
8
,
4
};
int
triggerLengths
[
2
]
=
{
8
,
4
};
// load log
// load log
QFile
file
(
_logFile
);
QFile
file
(
_logFile
);
if
(
!
file
.
open
(
QIODevice
::
ReadOnly
))
{
if
(
!
file
.
open
(
QIODevice
::
ReadOnly
))
{
...
@@ -299,6 +306,12 @@ bool GeoTagWorker::parsePX4Log()
...
@@ -299,6 +306,12 @@ bool GeoTagWorker::parsePX4Log()
QByteArray
log
=
file
.
readAll
();
QByteArray
log
=
file
.
readAll
();
file
.
close
();
file
.
close
();
// extract header information: message lengths
uint8_t
*
iptr
=
reinterpret_cast
<
uint8_t
*>
(
log
.
mid
(
log
.
indexOf
(
gposHeaderHeader
)
+
4
,
1
).
data
());
gposHeaderOffset
=
static_cast
<
int
>
(
qFromLittleEndian
(
*
iptr
));
iptr
=
reinterpret_cast
<
uint8_t
*>
(
log
.
mid
(
log
.
indexOf
(
triggerHeaderHeader
)
+
4
,
1
).
data
());
triggerHeaderOffset
=
static_cast
<
int
>
(
qFromLittleEndian
(
*
iptr
));
// extract trigger data
// extract trigger data
int
index
=
1
;
int
index
=
1
;
int
sequence
=
-
1
;
int
sequence
=
-
1
;
...
@@ -310,20 +323,24 @@ bool GeoTagWorker::parsePX4Log()
...
@@ -310,20 +323,24 @@ bool GeoTagWorker::parsePX4Log()
}
}
// first extract trigger
// first extract trigger
in
t
triggerIn
dex
=
log
.
indexOf
(
triggerHeader
,
index
+
1
);
index
=
log
.
indexOf
(
triggerHeader
,
index
+
1
);
// check for whether last entry has been passed
// check for whether last entry has been passed
if
(
triggerI
ndex
<
0
)
{
if
(
i
ndex
<
0
)
{
break
;
break
;
}
}
uint64_t
*
time
=
reinterpret_cast
<
uint64_t
*>
(
log
.
mid
(
triggerIndex
+
triggerOffsets
[
0
],
triggerLengths
[
0
]).
data
());
double
timeDouble
=
static_cast
<
double
>
(
qFromLittleEndian
(
*
time
));
if
(
log
.
indexOf
(
header
,
index
+
1
)
!=
index
+
triggerHeaderOffset
)
{
uint32_t
*
seq
=
reinterpret_cast
<
uint32_t
*>
(
log
.
mid
(
triggerIndex
+
triggerOffsets
[
1
],
triggerLengths
[
1
]).
data
());
continue
;
}
uint64_t
*
time
=
reinterpret_cast
<
uint64_t
*>
(
log
.
mid
(
index
+
triggerOffsets
[
0
],
triggerLengths
[
0
]).
data
());
double
timeDouble
=
static_cast
<
double
>
(
qFromLittleEndian
(
*
time
))
/
1.0e6
;
uint32_t
*
seq
=
reinterpret_cast
<
uint32_t
*>
(
log
.
mid
(
index
+
triggerOffsets
[
1
],
triggerLengths
[
1
]).
data
());
int
seqInt
=
static_cast
<
int
>
(
qFromLittleEndian
(
*
seq
));
int
seqInt
=
static_cast
<
int
>
(
qFromLittleEndian
(
*
seq
));
if
(
sequence
<
seqInt
&&
sequence
+
20
>
seqInt
)
{
// assume that logging has not skipped more than 20 triggers. this prevents wrong header detection
if
(
sequence
>=
seqInt
||
sequence
+
20
<
seqInt
)
{
// assume that logging has not skipped more than 20 triggers. this prevents wrong header detection
_triggerTime
.
append
(
timeDouble
/
1000000.0
);
continue
;
sequence
=
seqInt
;
}
}
index
=
triggerIndex
;
// extract next entry gpos
_triggerTime
.
append
(
timeDouble
);
sequence
=
seqInt
;
// second extract position
// second extract position
bool
lookForGpos
=
true
;
bool
lookForGpos
=
true
;
...
@@ -339,8 +356,8 @@ bool GeoTagWorker::parsePX4Log()
...
@@ -339,8 +356,8 @@ bool GeoTagWorker::parsePX4Log()
break
;
break
;
}
}
index
=
gposIndex
;
index
=
gposIndex
;
// verify that at an offset of
27
the next log message starts
// verify that at an offset of
gposHeaderOffset
the next log message starts
if
(
gposIndex
+
27
==
log
.
indexOf
(
header
,
gposIndex
+
1
))
{
if
(
gposIndex
+
gposHeaderOffset
==
log
.
indexOf
(
header
,
gposIndex
+
1
))
{
int32_t
*
lat
=
reinterpret_cast
<
int32_t
*>
(
log
.
mid
(
gposIndex
+
gposOffsets
[
0
],
gposLengths
[
0
]).
data
());
int32_t
*
lat
=
reinterpret_cast
<
int32_t
*>
(
log
.
mid
(
gposIndex
+
gposOffsets
[
0
],
gposLengths
[
0
]).
data
());
double
latitude
=
static_cast
<
double
>
(
qFromLittleEndian
(
*
lat
))
/
1.0e7
;
double
latitude
=
static_cast
<
double
>
(
qFromLittleEndian
(
*
lat
))
/
1.0e7
;
lastCoordinate
.
setLatitude
(
latitude
);
lastCoordinate
.
setLatitude
(
latitude
);
...
...
Write
Preview
Supports
Markdown
0%
Try again
or
attach a new 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