Skip to content

Commit 9dc672f

Browse files
committed
AP_Logger: write formats out as required rather than at start of log
1 parent e83afcf commit 9dc672f

7 files changed

+100
-57
lines changed

libraries/AP_Logger/AP_Logger_Backend.cpp

Lines changed: 79 additions & 39 deletions
Original file line numberDiff line numberDiff line change
@@ -101,6 +101,7 @@ void AP_Logger_Backend::start_new_log_reset_variables()
101101
_startup_messagewriter->reset();
102102
_front.backend_starting_new_log(this);
103103
_log_file_size_bytes = 0;
104+
_formats_written.clearall();
104105
}
105106

106107
// We may need to make sure data is loggable before starting the
@@ -124,42 +125,6 @@ void AP_Logger_Backend::push_log_blocks() {
124125
WriteMoreStartupMessages();
125126
}
126127

127-
// returns true if all format messages have been written, and thus it is OK
128-
// for other messages to go out to the log
129-
bool AP_Logger_Backend::WriteBlockCheckStartupMessages()
130-
{
131-
#if APM_BUILD_TYPE(APM_BUILD_Replay)
132-
return true;
133-
#endif
134-
135-
if (_startup_messagewriter->fmt_done()) {
136-
return true;
137-
}
138-
139-
if (_writing_startup_messages) {
140-
// we have been called by a messagewriter, so writing is OK
141-
return true;
142-
}
143-
144-
if (!_startup_messagewriter->finished() &&
145-
!hal.scheduler->in_main_thread()) {
146-
// only the main thread may write startup messages out
147-
return false;
148-
}
149-
150-
// we're not writing startup messages, so this must be some random
151-
// caller hoping to write blocks out. Push out log blocks - we
152-
// might end up clearing the buffer.....
153-
push_log_blocks();
154-
155-
// even if we did finish writing startup messages, we can't
156-
// permit any message to go in as its timestamp will be before
157-
// any we wrote in. Time going backwards annoys log readers.
158-
159-
// sorry! currently busy writing out startup messages...
160-
return false;
161-
}
162-
163128
// source more messages from the startup message writer:
164129
void AP_Logger_Backend::WriteMoreStartupMessages()
165130
{
@@ -363,6 +328,23 @@ bool AP_Logger_Backend::StartNewLogOK() const
363328
return true;
364329
}
365330

331+
// validate that pBuffer looks like a message, extract message type.
332+
// Returns false if this doesn't look like a valid message.
333+
bool AP_Logger_Backend::message_type_from_block(const void *pBuffer, uint16_t size, LogMessages &type) const
334+
{
335+
if (size < 3) {
336+
return false;
337+
}
338+
if (((uint8_t*)pBuffer)[0] != HEAD_BYTE1 ||
339+
((uint8_t*)pBuffer)[1] != HEAD_BYTE2) {
340+
// Not passed a message
341+
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
342+
return false;
343+
}
344+
type = LogMessages(((uint8_t*)pBuffer)[2]);
345+
return true;
346+
}
347+
366348
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
367349
void AP_Logger_Backend::validate_WritePrioritisedBlock(const void *pBuffer,
368350
uint16_t size)
@@ -381,11 +363,10 @@ void AP_Logger_Backend::validate_WritePrioritisedBlock(const void *pBuffer,
381363
if (size < 3) {
382364
AP_HAL::panic("Short prioritised block");
383365
}
384-
if (((uint8_t*)pBuffer)[0] != HEAD_BYTE1 ||
385-
((uint8_t*)pBuffer)[1] != HEAD_BYTE2) {
366+
LogMessages type;
367+
if (!message_type_from_block(pBuffer, size, type)) {
386368
AP_HAL::panic("Not passed a message");
387369
}
388-
const uint8_t type = ((uint8_t*)pBuffer)[2];
389370
uint8_t type_len;
390371
const char *name_src;
391372
const struct LogStructure *s = _front.structure_for_msg_type(type);
@@ -413,6 +394,61 @@ void AP_Logger_Backend::validate_WritePrioritisedBlock(const void *pBuffer,
413394
}
414395
#endif
415396

397+
bool AP_Logger_Backend::emit_format_for_type(LogMessages a_type)
398+
{
399+
// linearly scan the formats structure to find the format for the type:
400+
for (uint8_t i=0; i< num_types(); i++) {
401+
const auto &s { structure(i) };
402+
if (s == nullptr) {
403+
continue;
404+
}
405+
if (s->msg_type != a_type) {
406+
continue;
407+
}
408+
// found the relevant structure. Attempt to write it:
409+
if (!Write_Format(s)) {
410+
return false;
411+
}
412+
return true;
413+
}
414+
// didn't find the structure. That's probably bad...
415+
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
416+
return false;
417+
}
418+
419+
bool AP_Logger_Backend::ensure_format_emitted(const void *pBuffer, uint16_t size)
420+
{
421+
#if APM_BUILD_TYPE(APM_BUILD_Replay)
422+
// we trust that Replay will correctly emit formats as required
423+
return true;
424+
#endif
425+
426+
if (_startup_messagewriter->fmt_done()) {
427+
return true;
428+
}
429+
430+
// extract the ID:
431+
LogMessages type;
432+
if (!message_type_from_block(pBuffer, size, type)) {
433+
return false;
434+
}
435+
if (have_emitted_format_for_type(type)) {
436+
return true;
437+
}
438+
439+
// make sure the FMT message has gone out!
440+
if (type == LOG_FORMAT_MSG) {
441+
// kind of? Our caller is just about to emit this....
442+
return true;
443+
}
444+
if (!have_emitted_format_for_type(LOG_FORMAT_MSG) &&
445+
!emit_format_for_type(LOG_FORMAT_MSG)) {
446+
return false;
447+
}
448+
449+
return emit_format_for_type(type);
450+
}
451+
416452
bool AP_Logger_Backend::WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical, bool writev_streaming)
417453
{
418454
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL && !APM_BUILD_TYPE(APM_BUILD_Replay)
@@ -435,6 +471,10 @@ bool AP_Logger_Backend::WritePrioritisedBlock(const void *pBuffer, uint16_t size
435471
}
436472
}
437473

474+
if (!ensure_format_emitted(pBuffer, size)) {
475+
return false;
476+
}
477+
438478
return _WritePrioritisedBlock(pBuffer, size, is_critical);
439479
}
440480

libraries/AP_Logger/AP_Logger_Backend.h

Lines changed: 10 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,7 @@
99
#include <GCS_MAVLink/GCS_MAVLink.h>
1010
#include <AP_Mission/AP_Mission.h>
1111
#include <AP_Vehicle/ModeReason.h>
12+
#include "LogStructure.h"
1213

1314
class LoggerMessageWriter_DFLogStart;
1415

@@ -132,6 +133,9 @@ class AP_Logger_Backend
132133
bool Write_Fence();
133134
#endif
134135
bool Write_Format(const struct LogStructure *structure);
136+
bool have_emitted_format_for_type(LogMessages a_type) const {
137+
return _formats_written.get(uint8_t(a_type));
138+
}
135139
bool Write_Message(const char *message);
136140
bool Write_MessageF(const char *fmt, ...);
137141
bool Write_Mission_Cmd(const AP_Mission &mission,
@@ -195,7 +199,6 @@ class AP_Logger_Backend
195199
/*
196200
read a block
197201
*/
198-
virtual bool WriteBlockCheckStartupMessages();
199202
virtual void WriteMoreStartupMessages();
200203
virtual void push_log_blocks();
201204

@@ -262,6 +265,12 @@ class AP_Logger_Backend
262265

263266
void Write_AP_Logger_Stats_File(const struct df_stats &_stats);
264267
void validate_WritePrioritisedBlock(const void *pBuffer, uint16_t size);
268+
269+
bool message_type_from_block(const void *pBuffer, uint16_t size, LogMessages &type) const;
270+
bool ensure_format_emitted(const void *pBuffer, uint16_t size);
271+
bool emit_format_for_type(LogMessages a_type);
272+
Bitmask<256> _formats_written;
273+
265274
};
266275

267276
#endif // HAL_LOGGING_ENABLED

libraries/AP_Logger/AP_Logger_Block.cpp

Lines changed: 0 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -132,11 +132,6 @@ bool AP_Logger_Block::_WritePrioritisedBlock(const void *pBuffer, uint16_t size,
132132
return false;
133133
}
134134

135-
if (!WriteBlockCheckStartupMessages()) {
136-
_dropped++;
137-
return false;
138-
}
139-
140135
if (!write_sem.take(1)) {
141136
_dropped++;
142137
return false;

libraries/AP_Logger/AP_Logger_File.cpp

Lines changed: 0 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -474,11 +474,6 @@ bool AP_Logger_File::_WritePrioritisedBlock(const void *pBuffer, uint16_t size,
474474
{
475475
WITH_SEMAPHORE(semaphore);
476476

477-
if (! WriteBlockCheckStartupMessages()) {
478-
_dropped++;
479-
return false;
480-
}
481-
482477
#if APM_BUILD_TYPE(APM_BUILD_Replay)
483478
if (AP::FS().write(_write_fd, pBuffer, size) != size) {
484479
AP_HAL::panic("Short write");

libraries/AP_Logger/AP_Logger_MAVLink.cpp

Lines changed: 0 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -136,11 +136,6 @@ bool AP_Logger_MAVLink::_WritePrioritisedBlock(const void *pBuffer, uint16_t siz
136136
return false;
137137
}
138138

139-
if (! WriteBlockCheckStartupMessages()) {
140-
semaphore.give();
141-
return false;
142-
}
143-
144139
if (bufferspace_available() < size) {
145140
if (_startup_messagewriter->finished()) {
146141
// do not count the startup packets as being dropped...

libraries/AP_Logger/LogFile.cpp

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -60,7 +60,11 @@ bool AP_Logger_Backend::Write_Format(const struct LogStructure *s)
6060
{
6161
struct log_Format pkt;
6262
Fill_Format(s, pkt);
63-
return WriteCriticalBlock(&pkt, sizeof(pkt));
63+
if (!WriteCriticalBlock(&pkt, sizeof(pkt))) {
64+
return false;
65+
}
66+
_formats_written.set(s->msg_type);
67+
return true;
6468
}
6569

6670
/*

libraries/AP_Logger/LoggerMessageWriter.cpp

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -109,7 +109,12 @@ void LoggerMessageWriter_DFLogStart::process()
109109
case Stage::FORMATS:
110110
// write log formats so the log is self-describing
111111
while (next_format_to_send < _logger_backend->num_types()) {
112-
if (!_logger_backend->Write_Format(_logger_backend->structure(next_format_to_send))) {
112+
const auto &s { _logger_backend->structure(next_format_to_send) };
113+
if (_logger_backend->have_emitted_format_for_type((LogMessages)s->msg_type)) {
114+
next_format_to_send++;
115+
continue;
116+
}
117+
if (!_logger_backend->Write_Format(s)) {
113118
return; // call me again!
114119
}
115120
next_format_to_send++;

0 commit comments

Comments
 (0)