AP_Logger_File.h 5.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189
  1. /*
  2. AP_Logger logging - file oriented variant
  3. This uses posix file IO to create log files called logNN.dat in the
  4. given directory
  5. */
  6. #pragma once
  7. #include <AP_Filesystem/AP_Filesystem.h>
  8. #if HAVE_FILESYSTEM_SUPPORT
  9. #include <AP_HAL/utility/RingBuffer.h>
  10. #include "AP_Logger_Backend.h"
  11. class AP_Logger_File : public AP_Logger_Backend
  12. {
  13. public:
  14. // constructor
  15. AP_Logger_File(AP_Logger &front,
  16. LoggerMessageWriter_DFLogStart *,
  17. const char *log_directory);
  18. // initialisation
  19. void Init() override;
  20. bool CardInserted(void) const override;
  21. // erase handling
  22. void EraseAll() override;
  23. // possibly time-consuming preparation handling:
  24. bool NeedPrep() override;
  25. void Prep() override;
  26. /* Write a block of data at current offset */
  27. bool _WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical) override;
  28. uint32_t bufferspace_available() override;
  29. // high level interface
  30. uint16_t find_last_log() override;
  31. void get_log_boundaries(uint16_t log_num, uint32_t & start_page, uint32_t & end_page) override;
  32. void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc) override;
  33. int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data) override;
  34. uint16_t get_num_logs() override;
  35. uint16_t start_new_log(void) override;
  36. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
  37. void flush(void) override;
  38. #endif
  39. void periodic_1Hz() override;
  40. void periodic_fullrate() override;
  41. // this method is used when reporting system status over mavlink
  42. bool logging_enabled() const override;
  43. bool logging_failed() const override;
  44. bool logging_started(void) const override { return _write_fd != -1; }
  45. void vehicle_was_disarmed() override;
  46. virtual void PrepForArming() override;
  47. protected:
  48. bool WritesOK() const override;
  49. bool StartNewLogOK() const override;
  50. private:
  51. int _write_fd;
  52. char *_write_filename;
  53. uint32_t _last_write_ms;
  54. #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
  55. bool _need_rtc_update;
  56. #endif
  57. int _read_fd;
  58. uint16_t _read_fd_log_num;
  59. uint32_t _read_offset;
  60. uint32_t _write_offset;
  61. volatile bool _open_error;
  62. const char *_log_directory;
  63. bool _last_write_failed;
  64. uint32_t _io_timer_heartbeat;
  65. bool io_thread_alive() const;
  66. uint8_t io_thread_warning_decimation_counter;
  67. uint16_t _cached_oldest_log;
  68. // should we rotate when we next stop logging
  69. bool _rotate_pending;
  70. uint16_t _log_num_from_list_entry(const uint16_t list_entry);
  71. // possibly time-consuming preparations handling
  72. void Prep_MinSpace();
  73. uint16_t find_oldest_log();
  74. int64_t disk_space_avail();
  75. int64_t disk_space();
  76. float avail_space_percent();
  77. bool file_exists(const char *filename) const;
  78. bool log_exists(const uint16_t lognum) const;
  79. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
  80. // I always seem to have less than 10% free space on my laptop:
  81. const float min_avail_space_percent = 0.1f;
  82. #else
  83. const float min_avail_space_percent = 10.0f;
  84. #endif
  85. // write buffer
  86. ByteBuffer _writebuf;
  87. const uint16_t _writebuf_chunk;
  88. uint32_t _last_write_time;
  89. /* construct a file name given a log number. Caller must free. */
  90. char *_log_file_name(const uint16_t log_num) const;
  91. char *_log_file_name_long(const uint16_t log_num) const;
  92. char *_log_file_name_short(const uint16_t log_num) const;
  93. char *_lastlog_file_name() const;
  94. uint32_t _get_log_size(const uint16_t log_num);
  95. uint32_t _get_log_time(const uint16_t log_num);
  96. void stop_logging(void) override;
  97. void _io_timer(void);
  98. uint32_t critical_message_reserved_space() const {
  99. // possibly make this a proportional to buffer size?
  100. uint32_t ret = 1024;
  101. if (ret > _writebuf.get_size()) {
  102. // in this case you will only get critical messages
  103. ret = _writebuf.get_size();
  104. }
  105. return ret;
  106. };
  107. uint32_t non_messagewriter_message_reserved_space() const {
  108. // possibly make this a proportional to buffer size?
  109. uint32_t ret = 1024;
  110. if (ret >= _writebuf.get_size()) {
  111. // need to allow messages out from the messagewriters. In
  112. // this case while you have a messagewriter you won't get
  113. // any other messages. This should be a corner case!
  114. ret = 0;
  115. }
  116. return ret;
  117. };
  118. uint32_t last_messagewrite_message_sent;
  119. // free-space checks; filling up SD cards under NuttX leads to
  120. // corrupt filesystems which cause loss of data, failure to gather
  121. // data and failures-to-boot.
  122. uint32_t _free_space_last_check_time; // milliseconds
  123. const uint32_t _free_space_check_interval = 1000UL; // milliseconds
  124. const uint32_t _free_space_min_avail = 8388608; // bytes
  125. // semaphore mediates access to the ringbuffer
  126. HAL_Semaphore semaphore;
  127. // write_fd_semaphore mediates access to write_fd so the frontend
  128. // can open/close files without causing the backend to write to a
  129. // bad fd
  130. HAL_Semaphore write_fd_semaphore;
  131. // performance counters
  132. AP_HAL::Util::perf_counter_t _perf_write;
  133. AP_HAL::Util::perf_counter_t _perf_fsync;
  134. AP_HAL::Util::perf_counter_t _perf_errors;
  135. AP_HAL::Util::perf_counter_t _perf_overruns;
  136. const char *last_io_operation = "";
  137. struct df_stats {
  138. uint16_t blocks;
  139. uint32_t bytes;
  140. uint32_t buf_space_min;
  141. uint32_t buf_space_max;
  142. uint32_t buf_space_sigma;
  143. };
  144. struct df_stats stats;
  145. void Write_AP_Logger_Stats_File(const struct df_stats &_stats);
  146. void df_stats_gather(uint16_t bytes_written);
  147. void df_stats_log();
  148. void df_stats_clear();
  149. };
  150. #endif // HAVE_FILESYSTEM_SUPPORT