From 50c36bb59f84bf6c38667fb3d692938de5b743a7 Mon Sep 17 00:00:00 2001 From: Christopher Hrabia Date: Thu, 11 Apr 2013 12:42:15 +0800 Subject: [PATCH] Revert last change on new logfile structure and added nulling of buffer. The reason for this is, because the last change in the file structure is buggy, it was only written the message length of the buffer to the file and missed to add the length for the timestamp. For fixing this problem it would be possible to insert something like len += sizeof(quint64); after: int len = mavlink_msg_to_send_buffer(buf+sizeof(quint64), &message); But I think a consistent file structure has more adavatages for a logfile over a more compressed structure. E.g. it would be necessary to go through all packages to proceed a jump during a replay. Additional the LogPlayer was not updated during the last 7 month since the logfile structure was changed (even it was buggy)... If filesize is really a problem I would recommend to change the logfile handling in a way of writting a temporary consistend logfile and compress it afterwards (QCompress) like done by many programs --- src/comm/MAVLinkProtocol.cc | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/src/comm/MAVLinkProtocol.cc b/src/comm/MAVLinkProtocol.cc index cee05d9..e14d6bd 100644 --- a/src/comm/MAVLinkProtocol.cc +++ b/src/comm/MAVLinkProtocol.cc @@ -291,11 +291,14 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b) // Log data if (m_loggingEnabled && m_logfile) { - uint8_t buf[MAVLINK_MAX_PACKET_LEN+sizeof(quint64)]; + uint8_t buf[MAVLINK_MAX_PACKET_LEN+sizeof(quint64)] = {0}; quint64 time = QGC::groundTimeUsecs(); memcpy(buf, (void*)&time, sizeof(quint64)); // Write message to buffer - int len = mavlink_msg_to_send_buffer(buf+sizeof(quint64), &message); + mavlink_msg_to_send_buffer(buf+sizeof(quint64), &message); + //we need to write the maximum package length for having a + //consistent file structure and beeing able to parse it again + int len = MAVLINK_MAX_PACKET_LEN + sizeof(quint64); QByteArray b((const char*)buf, len); if(m_logfile->write(b) != len) {