@@ -101,6 +101,7 @@ void AP_Logger_Backend::start_new_log_reset_variables()
101
101
_startup_messagewriter->reset ();
102
102
_front.backend_starting_new_log (this );
103
103
_log_file_size_bytes = 0 ;
104
+ _formats_written.clearall ();
104
105
}
105
106
106
107
// We may need to make sure data is loggable before starting the
@@ -124,42 +125,6 @@ void AP_Logger_Backend::push_log_blocks() {
124
125
WriteMoreStartupMessages ();
125
126
}
126
127
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
-
163
128
// source more messages from the startup message writer:
164
129
void AP_Logger_Backend::WriteMoreStartupMessages ()
165
130
{
@@ -363,6 +328,23 @@ bool AP_Logger_Backend::StartNewLogOK() const
363
328
return true ;
364
329
}
365
330
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
+
366
348
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
367
349
void AP_Logger_Backend::validate_WritePrioritisedBlock (const void *pBuffer,
368
350
uint16_t size)
@@ -381,11 +363,10 @@ void AP_Logger_Backend::validate_WritePrioritisedBlock(const void *pBuffer,
381
363
if (size < 3 ) {
382
364
AP_HAL::panic (" Short prioritised block" );
383
365
}
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) ) {
386
368
AP_HAL::panic (" Not passed a message" );
387
369
}
388
- const uint8_t type = ((uint8_t *)pBuffer)[2 ];
389
370
uint8_t type_len;
390
371
const char *name_src;
391
372
const struct LogStructure *s = _front.structure_for_msg_type (type);
@@ -413,6 +394,56 @@ void AP_Logger_Backend::validate_WritePrioritisedBlock(const void *pBuffer,
413
394
}
414
395
#endif
415
396
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 (_startup_messagewriter->fmt_done ()) {
422
+ return true ;
423
+ }
424
+
425
+ // extract the ID:
426
+ LogMessages type;
427
+ if (!message_type_from_block (pBuffer, size, type)) {
428
+ return false ;
429
+ }
430
+ if (have_emitted_format_for_type (type)) {
431
+ return true ;
432
+ }
433
+
434
+ // make sure the FMT message has gone out!
435
+ if (type == LOG_FORMAT_MSG) {
436
+ // kind of? Our caller is just about to emit this....
437
+ return true ;
438
+ }
439
+ if (!have_emitted_format_for_type (LOG_FORMAT_MSG) &&
440
+ !emit_format_for_type (LOG_FORMAT_MSG)) {
441
+ return false ;
442
+ }
443
+
444
+ return emit_format_for_type (type);
445
+ }
446
+
416
447
bool AP_Logger_Backend::WritePrioritisedBlock (const void *pBuffer, uint16_t size, bool is_critical, bool writev_streaming)
417
448
{
418
449
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL && !APM_BUILD_TYPE(APM_BUILD_Replay)
@@ -435,6 +466,10 @@ bool AP_Logger_Backend::WritePrioritisedBlock(const void *pBuffer, uint16_t size
435
466
}
436
467
}
437
468
469
+ if (!ensure_format_emitted (pBuffer, size)) {
470
+ return false ;
471
+ }
472
+
438
473
return _WritePrioritisedBlock (pBuffer, size, is_critical);
439
474
}
440
475
0 commit comments