diff --git a/libraries/AP_Logger/AP_Logger.cpp b/libraries/AP_Logger/AP_Logger.cpp index 8719accae5..e66b52e1ea 100644 --- a/libraries/AP_Logger/AP_Logger.cpp +++ b/libraries/AP_Logger/AP_Logger.cpp @@ -580,6 +580,8 @@ void AP_Logger::Write_MessageF(const char *fmt, ...) void AP_Logger::backend_starting_new_log(const AP_Logger_Backend *backend) { + _log_start_count++; + for (uint8_t i=0; i<_next_backend; i++) { if (backends[i] == backend) { // pointer comparison! // reset sent masks diff --git a/libraries/AP_Logger/AP_Logger.h b/libraries/AP_Logger/AP_Logger.h index dfe9d1408e..852997a4ae 100644 --- a/libraries/AP_Logger/AP_Logger.h +++ b/libraries/AP_Logger/AP_Logger.h @@ -408,6 +408,11 @@ public: // output a FMT message for each backend if not already done so void Safe_Write_Emit_FMT(log_write_fmt *f); + // get count of number of times we have started logging + uint8_t get_log_start_count(void) const { + return _log_start_count; + } + protected: const struct LogStructure *_structures; @@ -531,6 +536,10 @@ private: // last time arming failed, for backends uint32_t _last_arming_failure_ms; + // count of number of times we've started logging + // can be used by other subsystems to detect if they should log data + uint8_t _log_start_count; + bool should_handle_log_message(); void handle_log_message(class GCS_MAVLINK &, const mavlink_message_t &msg);