forked from Archive/PX4-Autopilot
mavlink: move ulog handling after stream updates
reduces latency for the mavlink streams
This commit is contained in:
parent
d0ad308eda
commit
fa8def903d
|
@ -2341,6 +2341,26 @@ Mavlink::task_main(int argc, char *argv[])
|
|||
}
|
||||
}
|
||||
|
||||
check_requested_subscriptions();
|
||||
|
||||
/* update streams */
|
||||
for (const auto &stream : _streams) {
|
||||
stream->update(t);
|
||||
|
||||
if (!_first_heartbeat_sent) {
|
||||
if (_mode == MAVLINK_MODE_IRIDIUM) {
|
||||
if (stream->get_id() == MAVLINK_MSG_ID_HIGH_LATENCY2) {
|
||||
_first_heartbeat_sent = stream->first_message_sent();
|
||||
}
|
||||
|
||||
} else {
|
||||
if (stream->get_id() == MAVLINK_MSG_ID_HEARTBEAT) {
|
||||
_first_heartbeat_sent = stream->first_message_sent();
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* check for ulog streaming messages */
|
||||
if (_mavlink_ulog) {
|
||||
if (_mavlink_ulog_stop_requested) {
|
||||
|
@ -2366,26 +2386,6 @@ Mavlink::task_main(int argc, char *argv[])
|
|||
}
|
||||
}
|
||||
|
||||
check_requested_subscriptions();
|
||||
|
||||
/* update streams */
|
||||
for (const auto &stream : _streams) {
|
||||
stream->update(t);
|
||||
|
||||
if (!_first_heartbeat_sent) {
|
||||
if (_mode == MAVLINK_MODE_IRIDIUM) {
|
||||
if (stream->get_id() == MAVLINK_MSG_ID_HIGH_LATENCY2) {
|
||||
_first_heartbeat_sent = stream->first_message_sent();
|
||||
}
|
||||
|
||||
} else {
|
||||
if (stream->get_id() == MAVLINK_MSG_ID_HEARTBEAT) {
|
||||
_first_heartbeat_sent = stream->first_message_sent();
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* pass messages from other UARTs */
|
||||
if (_forwarding_on) {
|
||||
|
||||
|
|
Loading…
Reference in New Issue