Browse Source

MAVLinkLogManager: avoid returning too early, use mavlink_logging_data_acked_t message

The return lead to data being dropped. Some of this data could have been
part of the ulog header, which lead to corrupt files.
QGC4.4
Beat Küng 9 years ago
parent
commit
9a30008fcb
  1. 1
      src/Vehicle/MAVLinkLogManager.cc
  2. 4
      src/Vehicle/Vehicle.cc

1
src/Vehicle/MAVLinkLogManager.cc

@ -223,7 +223,6 @@ MAVLinkLogProcessor::_writeUlogMessage(QByteArray& data) @@ -223,7 +223,6 @@ MAVLinkLogProcessor::_writeUlogMessage(QByteArray& data)
break;
_writeData(data.data(), message_length);
data.remove(0, message_length);
return data;
}
return data;
}

4
src/Vehicle/Vehicle.cc

@ -2090,8 +2090,8 @@ Vehicle::_handleMavlinkLoggingData(mavlink_message_t& message) @@ -2090,8 +2090,8 @@ Vehicle::_handleMavlinkLoggingData(mavlink_message_t& message)
void
Vehicle::_handleMavlinkLoggingDataAcked(mavlink_message_t& message)
{
mavlink_logging_data_t log;
mavlink_msg_logging_data_decode(&message, &log);
mavlink_logging_data_acked_t log;
mavlink_msg_logging_data_acked_decode(&message, &log);
_ackMavlinkLogData(log.sequence);
emit mavlinkLogData(this, log.target_system, log.target_component, log.sequence,
log.first_message_offset, QByteArray((const char*)log.data, log.length), true);

Loading…
Cancel
Save