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
bcff0d52
Commit
bcff0d52
authored
Dec 19, 2013
by
Lorenz Meier
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #434 from Susurrus/exposeSysTime
Expose SYSTEM_TIME message to QGC
parents
7d136aca
cf17ec0e
Changes
1
Hide whitespace changes
Inline
Side-by-side
Showing
1 changed file
with
12 additions
and
18 deletions
+12
-18
MAVLinkDecoder.cc
src/ui/MAVLinkDecoder.cc
+12
-18
No files found.
src/ui/MAVLinkDecoder.cc
View file @
bcff0d52
...
...
@@ -54,7 +54,10 @@ void MAVLinkDecoder::receiveMessage(LinkInterface* link,mavlink_message_t messag
uint8_t
msgid
=
message
.
msgid
;
// Handle time sync message
// Store an arrival time for this message. This value ends up being calculated later.
quint64
time
=
0
;
// The SYSTEM_TIME message is special, in that it's handled here for synchronizing the QGC time with the remote time.
if
(
message
.
msgid
==
MAVLINK_MSG_ID_SYSTEM_TIME
)
{
mavlink_system_time_t
timebase
;
...
...
@@ -65,11 +68,7 @@ void MAVLinkDecoder::receiveMessage(LinkInterface* link,mavlink_message_t messag
else
{
QString
messageName
(
"%1 (#%2)"
);
messageName
=
messageName
.
arg
(
messageInfo
[
msgid
].
name
).
arg
(
msgid
);
// See if first value is a time value
quint64
time
=
0
;
// See if first value is a time value and if it is, use that as the arrival time for this data.
uint8_t
fieldid
=
0
;
uint8_t
*
m
=
((
uint8_t
*
)(
receivedMessages
+
msgid
))
+
8
;
if
(
QString
(
messageInfo
[
msgid
].
fields
[
fieldid
].
name
)
==
QString
(
"time_boot_ms"
)
&&
messageInfo
[
msgid
].
fields
[
fieldid
].
type
==
MAVLINK_TYPE_UINT32_T
)
...
...
@@ -81,20 +80,15 @@ void MAVLinkDecoder::receiveMessage(LinkInterface* link,mavlink_message_t messag
time
=
*
((
quint64
*
)(
m
+
messageInfo
[
msgid
].
fields
[
fieldid
].
wire_offset
));
time
=
(
time
+
500
)
/
1000
;
// Scale to milliseconds, round up/down correctly
}
else
{
// First value is not time, send out value 0
emitFieldValue
(
&
message
,
fieldid
,
getUnixTimeFromMs
(
message
.
sysid
,
0
));
}
}
// Align
time to global time
time
=
getUnixTimeFromMs
(
message
.
sysid
,
time
);
// Align UAS
time to global time
time
=
getUnixTimeFromMs
(
message
.
sysid
,
time
);
// Send out field values from 1..n
for
(
unsigned
int
i
=
1
;
i
<
messageInfo
[
msgid
].
num_fields
;
++
i
)
{
emitFieldValue
(
&
message
,
i
,
time
);
}
// Send out all field values for this message
for
(
int
i
=
0
;
i
<
messageInfo
[
msgid
].
num_fields
;
++
i
)
{
emitFieldValue
(
&
message
,
i
,
time
);
}
// Send out combined math expressions
...
...
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