Browse Source

AP_Logger: remove perf counters

zr-v5.1
Peter Barker 4 years ago committed by Peter Barker
parent
commit
80e8688888
  1. 11
      libraries/AP_Logger/AP_Logger_File.cpp
  2. 6
      libraries/AP_Logger/AP_Logger_File.h

11
libraries/AP_Logger/AP_Logger_File.cpp

@ -50,11 +50,7 @@ AP_Logger_File::AP_Logger_File(AP_Logger &front,
_read_fd(-1), _read_fd(-1),
_log_directory(log_directory), _log_directory(log_directory),
_writebuf(0), _writebuf(0),
_writebuf_chunk(HAL_LOGGER_WRITE_CHUNK_SIZE), _writebuf_chunk(HAL_LOGGER_WRITE_CHUNK_SIZE)
_perf_write(hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "DF_write")),
_perf_fsync(hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "DF_fsync")),
_perf_errors(hal.util->perf_alloc(AP_HAL::Util::PC_COUNT, "DF_errors")),
_perf_overruns(hal.util->perf_alloc(AP_HAL::Util::PC_COUNT, "DF_overruns"))
{ {
df_stats_clear(); df_stats_clear();
} }
@ -503,7 +499,6 @@ bool AP_Logger_File::_WritePrioritisedBlock(const void *pBuffer, uint16_t size,
// if no room for entire message - drop it: // if no room for entire message - drop it:
if (space < size) { if (space < size) {
hal.util->perf_count(_perf_overruns);
_dropped++; _dropped++;
return false; return false;
} }
@ -897,8 +892,6 @@ void AP_Logger_File::io_timer(void)
last_io_operation = ""; last_io_operation = "";
} }
hal.util->perf_begin(_perf_write);
_last_write_time = tnow; _last_write_time = tnow;
if (nbytes > _writebuf_chunk) { if (nbytes > _writebuf_chunk) {
// be kind to the filesystem layer // be kind to the filesystem layer
@ -932,7 +925,6 @@ void AP_Logger_File::io_timer(void)
// if we can't write for LOG_FILE_TIMEOUT seconds we give up and close // if we can't write for LOG_FILE_TIMEOUT seconds we give up and close
// the file. This allows us to cope with temporary write // the file. This allows us to cope with temporary write
// failures caused by directory listing // failures caused by directory listing
hal.util->perf_count(_perf_errors);
last_io_operation = "close"; last_io_operation = "close";
AP::FS().close(_write_fd); AP::FS().close(_write_fd);
last_io_operation = ""; last_io_operation = "";
@ -971,7 +963,6 @@ void AP_Logger_File::io_timer(void)
} }
write_fd_semaphore.give(); write_fd_semaphore.give();
hal.util->perf_end(_perf_write);
} }
bool AP_Logger_File::io_thread_alive() const bool AP_Logger_File::io_thread_alive() const

6
libraries/AP_Logger/AP_Logger_File.h

@ -122,12 +122,6 @@ private:
// bad fd // bad fd
HAL_Semaphore write_fd_semaphore; HAL_Semaphore write_fd_semaphore;
// performance counters
AP_HAL::Util::perf_counter_t _perf_write;
AP_HAL::Util::perf_counter_t _perf_fsync;
AP_HAL::Util::perf_counter_t _perf_errors;
AP_HAL::Util::perf_counter_t _perf_overruns;
const char *last_io_operation = ""; const char *last_io_operation = "";
}; };

Loading…
Cancel
Save