Browse Source

AP_Logger: move logger IO to a separate thread

zr-v5.1
Andy Piper 4 years ago committed by Peter Barker
parent
commit
779c2a9e5f
  1. 45
      libraries/AP_Logger/AP_Logger.cpp
  2. 6
      libraries/AP_Logger/AP_Logger.h
  3. 2
      libraries/AP_Logger/AP_Logger_Backend.h
  4. 2
      libraries/AP_Logger/AP_Logger_Block.cpp
  5. 2
      libraries/AP_Logger/AP_Logger_Block.h
  6. 5
      libraries/AP_Logger/AP_Logger_File.cpp
  7. 3
      libraries/AP_Logger/AP_Logger_File.h

45
libraries/AP_Logger/AP_Logger.cpp

@ -27,6 +27,10 @@ extern const AP_HAL::HAL& hal; @@ -27,6 +27,10 @@ extern const AP_HAL::HAL& hal;
#endif
#endif
#ifndef HAL_LOGGING_STACK_SIZE
#define HAL_LOGGING_STACK_SIZE 512
#endif
#ifndef HAL_LOGGING_MAV_BUFSIZE
#define HAL_LOGGING_MAV_BUFSIZE 8
#endif
@ -231,6 +235,8 @@ void AP_Logger::Init(const struct LogStructure *structures, uint8_t num_types) @@ -231,6 +235,8 @@ void AP_Logger::Init(const struct LogStructure *structures, uint8_t num_types)
Prep();
start_io_thread();
EnableWrites(true);
}
@ -1243,6 +1249,45 @@ int16_t AP_Logger::Write_calc_msg_len(const char *fmt) const @@ -1243,6 +1249,45 @@ int16_t AP_Logger::Write_calc_msg_len(const char *fmt) const
return len;
}
// thread for processing IO - in general IO involves a long blocking DMA write to an SPI device
// and the thread will sleep while this completes preventing other tasks from running, it therefore
// is necessary to run the IO in it's own thread
void AP_Logger::io_thread(void)
{
uint32_t last_run_us = AP_HAL::micros();
while (true) {
uint32_t now = AP_HAL::micros();
uint32_t delay = 250U; // always have some delay
if (now - last_run_us < 1000) {
delay = MAX(1000 - (now - last_run_us), delay);
}
hal.scheduler->delay_microseconds(delay);
last_run_us = AP_HAL::micros();
FOR_EACH_BACKEND(io_timer());
}
}
// start the update thread
void AP_Logger::start_io_thread(void)
{
WITH_SEMAPHORE(_log_send_sem);
if (_io_thread_started) {
return;
}
if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_Logger::io_thread, void), "log_io", HAL_LOGGING_STACK_SIZE, AP_HAL::Scheduler::PRIORITY_IO, 0)) {
AP_HAL::panic("Failed to start Logger IO thread");
}
_io_thread_started = true;
return;
}
/* End of Write support */
#undef FOR_EACH_BACKEND

6
libraries/AP_Logger/AP_Logger.h

@ -498,6 +498,12 @@ private: @@ -498,6 +498,12 @@ private:
// remember formats for replay
void save_format_Replay(const void *pBuffer);
// io thread support
bool _io_thread_started;
void start_io_thread(void);
void io_thread();
/* support for retrieving logs via mavlink: */
enum class TransferActivity {

2
libraries/AP_Logger/AP_Logger_Backend.h

@ -132,6 +132,8 @@ public: @@ -132,6 +132,8 @@ public:
bool Write_Multiplier(const struct MultiplierStructure *s);
bool Write_Format_Units(const struct LogStructure *structure);
virtual void io_timer(void) {}
protected:
AP_Logger &_front;

2
libraries/AP_Logger/AP_Logger_Block.cpp

@ -57,8 +57,6 @@ void AP_Logger_Block::Init(void) @@ -57,8 +57,6 @@ void AP_Logger_Block::Init(void)
}
WITH_SEMAPHORE(sem);
hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&AP_Logger_Block::io_timer, void));
}
uint32_t AP_Logger_Block::bufferspace_available()

2
libraries/AP_Logger/AP_Logger_Block.h

@ -31,6 +31,7 @@ public: @@ -31,6 +31,7 @@ public:
void stop_logging_async(void) override;
bool logging_failed() const override;
bool logging_started(void) const override { return log_write_started; }
void io_timer(void) override;
protected:
/* Write a block of data at current offset */
@ -159,6 +160,5 @@ private: @@ -159,6 +160,5 @@ private:
// callback on IO thread
bool io_thread_alive() const;
void io_timer(void);
void write_log_page();
};

5
libraries/AP_Logger/AP_Logger_File.cpp

@ -99,7 +99,6 @@ void AP_Logger_File::Init() @@ -99,7 +99,6 @@ void AP_Logger_File::Init()
hal.console->printf("AP_Logger_File: buffer size=%u\n", (unsigned)bufsize);
_initialised = true;
hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&AP_Logger_File::_io_timer, void));
const char* custom_dir = hal.util->get_custom_log_directory();
if (custom_dir != nullptr){
@ -873,7 +872,7 @@ void AP_Logger_File::flush(void) @@ -873,7 +872,7 @@ void AP_Logger_File::flush(void)
if (tnow > 2001) { // avoid resetting _last_write_time to 0
_last_write_time = tnow - 2001;
}
_io_timer();
io_timer();
}
if (write_fd_semaphore.take(1)) {
if (_write_fd != -1) {
@ -891,7 +890,7 @@ void AP_Logger_File::flush(void) @@ -891,7 +890,7 @@ void AP_Logger_File::flush(void)
#endif // APM_BUILD_TYPE(APM_BUILD_Replay) || APM_BUILD_TYPE(APM_BUILD_UNKNOWN)
#endif
void AP_Logger_File::_io_timer(void)
void AP_Logger_File::io_timer(void)
{
uint32_t tnow = AP_HAL::millis();
_io_timer_heartbeat = tnow;

3
libraries/AP_Logger/AP_Logger_File.h

@ -54,6 +54,7 @@ public: @@ -54,6 +54,7 @@ public:
bool logging_failed() const override;
bool logging_started(void) const override { return _write_fd != -1; }
void io_timer(void) override;
protected:
@ -109,8 +110,6 @@ private: @@ -109,8 +110,6 @@ private:
void stop_logging(void) override;
void _io_timer(void);
uint32_t last_messagewrite_message_sent;
// free-space checks; filling up SD cards under NuttX leads to

Loading…
Cancel
Save