|
|
|
@ -3421,8 +3421,12 @@ void Vehicle::_handleMavlinkLoggingData(mavlink_message_t& message)
@@ -3421,8 +3421,12 @@ void Vehicle::_handleMavlinkLoggingData(mavlink_message_t& message)
|
|
|
|
|
{ |
|
|
|
|
mavlink_logging_data_t log; |
|
|
|
|
mavlink_msg_logging_data_decode(&message, &log); |
|
|
|
|
emit mavlinkLogData(this, log.target_system, log.target_component, log.sequence, |
|
|
|
|
log.first_message_offset, QByteArray((const char*)log.data, log.length), false); |
|
|
|
|
if (static_cast<size_t>(log.length) > sizeof(log.data)) { |
|
|
|
|
qWarning() << "Invalid length for LOGGING_DATA, discarding." << log.length; |
|
|
|
|
} else { |
|
|
|
|
emit mavlinkLogData(this, log.target_system, log.target_component, log.sequence, |
|
|
|
|
log.first_message_offset, QByteArray((const char*)log.data, log.length), false); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void Vehicle::_handleMavlinkLoggingDataAcked(mavlink_message_t& message) |
|
|
|
@ -3430,8 +3434,12 @@ void Vehicle::_handleMavlinkLoggingDataAcked(mavlink_message_t& message)
@@ -3430,8 +3434,12 @@ void Vehicle::_handleMavlinkLoggingDataAcked(mavlink_message_t& message)
|
|
|
|
|
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); |
|
|
|
|
if (static_cast<size_t>(log.length) > sizeof(log.data)) { |
|
|
|
|
qWarning() << "Invalid length for LOGGING_DATA_ACKED, discarding." << log.length; |
|
|
|
|
} else { |
|
|
|
|
emit mavlinkLogData(this, log.target_system, log.target_component, log.sequence, |
|
|
|
|
log.first_message_offset, QByteArray((const char*)log.data, log.length), false); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void Vehicle::setFirmwarePluginInstanceData(QObject* firmwarePluginInstanceData) |
|
|
|
|