AP_Logger_File.cpp 31 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960961962963964965966967968969970971972973974975976977978979980981982983984985986987988989990991992993994995996997998999100010011002100310041005100610071008100910101011101210131014101510161017101810191020102110221023102410251026102710281029103010311032103310341035103610371038103910401041104210431044104510461047104810491050105110521053105410551056105710581059106010611062106310641065106610671068106910701071107210731074107510761077107810791080108110821083108410851086108710881089109010911092109310941095109610971098109911001101110211031104110511061107110811091110111111121113111411151116111711181119112011211122112311241125112611271128112911301131
  1. /*
  2. AP_Logger logging - file oriented variant
  3. This uses posix file IO to create log files called logs/NN.bin in the
  4. given directory
  5. SD Card Rates on PixHawk:
  6. - deletion rate seems to be ~50 files/second.
  7. - stat seems to be ~150/second
  8. - readdir loop of 511 entry directory ~62,000 microseconds
  9. */
  10. #include <AP_HAL/AP_HAL.h>
  11. #include <AP_Filesystem/AP_Filesystem.h>
  12. #if HAVE_FILESYSTEM_SUPPORT
  13. #include "AP_Logger_File.h"
  14. #include <AP_Common/AP_Common.h>
  15. #include <AP_InternalError/AP_InternalError.h>
  16. #include <AP_RTC/AP_RTC.h>
  17. #include <AP_Math/AP_Math.h>
  18. #include <GCS_MAVLink/GCS.h>
  19. #include <stdio.h>
  20. extern const AP_HAL::HAL& hal;
  21. #define MAX_LOG_FILES 500U
  22. #define LOGGER_PAGE_SIZE 1024UL
  23. #ifndef HAL_LOGGER_WRITE_CHUNK_SIZE
  24. #define HAL_LOGGER_WRITE_CHUNK_SIZE 4096
  25. #endif
  26. /*
  27. constructor
  28. */
  29. AP_Logger_File::AP_Logger_File(AP_Logger &front,
  30. LoggerMessageWriter_DFLogStart *writer,
  31. const char *log_directory) :
  32. AP_Logger_Backend(front, writer),
  33. _write_fd(-1),
  34. _read_fd(-1),
  35. _log_directory(log_directory),
  36. _writebuf(0),
  37. _writebuf_chunk(HAL_LOGGER_WRITE_CHUNK_SIZE),
  38. _perf_write(hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "DF_write")),
  39. _perf_fsync(hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "DF_fsync")),
  40. _perf_errors(hal.util->perf_alloc(AP_HAL::Util::PC_COUNT, "DF_errors")),
  41. _perf_overruns(hal.util->perf_alloc(AP_HAL::Util::PC_COUNT, "DF_overruns"))
  42. {
  43. df_stats_clear();
  44. }
  45. void AP_Logger_File::Init()
  46. {
  47. AP_Logger_Backend::Init();
  48. // create the log directory if need be
  49. int ret;
  50. struct stat st;
  51. const char* custom_dir = hal.util->get_custom_log_directory();
  52. if (custom_dir != nullptr){
  53. _log_directory = custom_dir;
  54. }
  55. EXPECT_DELAY_MS(3000);
  56. ret = AP::FS().stat(_log_directory, &st);
  57. if (ret == -1) {
  58. ret = AP::FS().mkdir(_log_directory);
  59. }
  60. if (ret == -1 && errno != EEXIST) {
  61. printf("Failed to create log directory %s : %s\n", _log_directory, strerror(errno));
  62. }
  63. // determine and limit file backend buffersize
  64. uint32_t bufsize = _front._params.file_bufsize;
  65. if (bufsize > 64) {
  66. bufsize = 64; // PixHawk has DMA limitations.
  67. }
  68. bufsize *= 1024;
  69. const uint32_t desired_bufsize = bufsize;
  70. // If we can't allocate the full size, try to reduce it until we can allocate it
  71. while (!_writebuf.set_size(bufsize) && bufsize >= _writebuf_chunk) {
  72. bufsize *= 0.9;
  73. }
  74. if (bufsize >= _writebuf_chunk && bufsize != desired_bufsize) {
  75. hal.console->printf("AP_Logger: reduced buffer %u/%u\n", (unsigned)bufsize, (unsigned)desired_bufsize);
  76. }
  77. if (!_writebuf.get_size()) {
  78. hal.console->printf("Out of memory for logging\n");
  79. return;
  80. }
  81. hal.console->printf("AP_Logger_File: buffer size=%u\n", (unsigned)bufsize);
  82. _initialised = true;
  83. hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&AP_Logger_File::_io_timer, void));
  84. }
  85. bool AP_Logger_File::file_exists(const char *filename) const
  86. {
  87. struct stat st;
  88. EXPECT_DELAY_MS(3000);
  89. if (AP::FS().stat(filename, &st) == -1) {
  90. // hopefully errno==ENOENT. If some error occurs it is
  91. // probably better to assume this file exists.
  92. return false;
  93. }
  94. return true;
  95. }
  96. bool AP_Logger_File::log_exists(const uint16_t lognum) const
  97. {
  98. char *filename = _log_file_name(lognum);
  99. if (filename == nullptr) {
  100. return false; // ?!
  101. }
  102. bool ret = file_exists(filename);
  103. free(filename);
  104. return ret;
  105. }
  106. void AP_Logger_File::periodic_1Hz()
  107. {
  108. if (_rotate_pending && !logging_enabled()) {
  109. _rotate_pending = false;
  110. // handle log rotation once we stop logging
  111. stop_logging();
  112. }
  113. if (!io_thread_alive()) {
  114. if (io_thread_warning_decimation_counter == 0 && _initialised) {
  115. // we don't print this error unless we did initialise. When _initialised is set to true
  116. // we register the IO timer callback
  117. gcs().send_text(MAV_SEVERITY_CRITICAL, "AP_Logger: stuck thread (%s)", last_io_operation);
  118. }
  119. if (io_thread_warning_decimation_counter++ > 57) {
  120. io_thread_warning_decimation_counter = 0;
  121. }
  122. // If you try to close the file here then it will almost
  123. // certainly block. Since this is the main thread, this is
  124. // likely to cause a crash.
  125. // semaphore_write_fd not taken here as if the io thread is
  126. // dead it may not release lock...
  127. _write_fd = -1;
  128. _initialised = false;
  129. }
  130. df_stats_log();
  131. }
  132. void AP_Logger_File::periodic_fullrate()
  133. {
  134. AP_Logger_Backend::push_log_blocks();
  135. }
  136. uint32_t AP_Logger_File::bufferspace_available()
  137. {
  138. const uint32_t space = _writebuf.space();
  139. const uint32_t crit = critical_message_reserved_space();
  140. return (space > crit) ? space - crit : 0;
  141. }
  142. // return true for CardInserted() if we successfully initialized
  143. bool AP_Logger_File::CardInserted(void) const
  144. {
  145. return _initialised && !_open_error;
  146. }
  147. // returns the amount of disk space available in _log_directory (in bytes)
  148. // returns -1 on error
  149. int64_t AP_Logger_File::disk_space_avail()
  150. {
  151. return AP::FS().disk_free(_log_directory);
  152. }
  153. // returns the total amount of disk space (in use + available) in
  154. // _log_directory (in bytes).
  155. // returns -1 on error
  156. int64_t AP_Logger_File::disk_space()
  157. {
  158. return AP::FS().disk_space(_log_directory);
  159. }
  160. // returns the available space in _log_directory as a percentage
  161. // returns -1.0f on error
  162. float AP_Logger_File::avail_space_percent()
  163. {
  164. int64_t avail = disk_space_avail();
  165. if (avail == -1) {
  166. return -1.0f;
  167. }
  168. int64_t space = disk_space();
  169. if (space == -1) {
  170. return -1.0f;
  171. }
  172. return (avail/(float)space) * 100;
  173. }
  174. // find_oldest_log - find oldest log in _log_directory
  175. // returns 0 if no log was found
  176. uint16_t AP_Logger_File::find_oldest_log()
  177. {
  178. if (_cached_oldest_log != 0) {
  179. return _cached_oldest_log;
  180. }
  181. uint16_t last_log_num = find_last_log();
  182. if (last_log_num == 0) {
  183. return 0;
  184. }
  185. uint16_t current_oldest_log = 0; // 0 is invalid
  186. // We could count up to find_last_log(), but if people start
  187. // relying on the min_avail_space_percent feature we could end up
  188. // doing a *lot* of asprintf()s and stat()s
  189. EXPECT_DELAY_MS(3000);
  190. DIR *d = AP::FS().opendir(_log_directory);
  191. if (d == nullptr) {
  192. // SD card may have died? On linux someone may have rm-rf-d
  193. return 0;
  194. }
  195. // we only remove files which look like xxx.BIN
  196. EXPECT_DELAY_MS(3000);
  197. for (struct dirent *de=AP::FS().readdir(d); de; de=AP::FS().readdir(d)) {
  198. EXPECT_DELAY_MS(3000);
  199. uint8_t length = strlen(de->d_name);
  200. if (length < 5) {
  201. // not long enough for \d+[.]BIN
  202. continue;
  203. }
  204. if (strncmp(&de->d_name[length-4], ".BIN", 4)) {
  205. // doesn't end in .BIN
  206. continue;
  207. }
  208. uint16_t thisnum = strtoul(de->d_name, nullptr, 10);
  209. if (thisnum > MAX_LOG_FILES) {
  210. // ignore files above our official maximum...
  211. continue;
  212. }
  213. if (current_oldest_log == 0) {
  214. current_oldest_log = thisnum;
  215. } else {
  216. if (current_oldest_log <= last_log_num) {
  217. if (thisnum > last_log_num) {
  218. current_oldest_log = thisnum;
  219. } else if (thisnum < current_oldest_log) {
  220. current_oldest_log = thisnum;
  221. }
  222. } else { // current_oldest_log > last_log_num
  223. if (thisnum > last_log_num) {
  224. if (thisnum < current_oldest_log) {
  225. current_oldest_log = thisnum;
  226. }
  227. }
  228. }
  229. }
  230. }
  231. AP::FS().closedir(d);
  232. _cached_oldest_log = current_oldest_log;
  233. return current_oldest_log;
  234. }
  235. void AP_Logger_File::Prep_MinSpace()
  236. {
  237. if (hal.util->was_watchdog_reset()) {
  238. // don't clear space if watchdog reset, it takes too long
  239. return;
  240. }
  241. const uint16_t first_log_to_remove = find_oldest_log();
  242. if (first_log_to_remove == 0) {
  243. // no files to remove
  244. return;
  245. }
  246. _cached_oldest_log = 0;
  247. uint16_t log_to_remove = first_log_to_remove;
  248. uint16_t count = 0;
  249. do {
  250. float avail = avail_space_percent();
  251. if (is_equal(avail, -1.0f)) {
  252. break;
  253. }
  254. if (avail >= min_avail_space_percent) {
  255. break;
  256. }
  257. if (count++ > MAX_LOG_FILES+10) {
  258. // *way* too many deletions going on here. Possible internal error.
  259. AP::internalerror().error(AP_InternalError::error_t::logger_too_many_deletions);
  260. break;
  261. }
  262. char *filename_to_remove = _log_file_name(log_to_remove);
  263. if (filename_to_remove == nullptr) {
  264. AP::internalerror().error(AP_InternalError::error_t::logger_bad_getfilename);
  265. break;
  266. }
  267. if (file_exists(filename_to_remove)) {
  268. hal.console->printf("Removing (%s) for minimum-space requirements (%.2f%% < %.0f%%)\n",
  269. filename_to_remove, (double)avail, (double)min_avail_space_percent);
  270. EXPECT_DELAY_MS(2000);
  271. if (AP::FS().unlink(filename_to_remove) == -1) {
  272. hal.console->printf("Failed to remove %s: %s\n", filename_to_remove, strerror(errno));
  273. free(filename_to_remove);
  274. if (errno == ENOENT) {
  275. // corruption - should always have a continuous
  276. // sequence of files... however, there may be still
  277. // files out there, so keep going.
  278. } else {
  279. break;
  280. }
  281. } else {
  282. free(filename_to_remove);
  283. }
  284. }
  285. log_to_remove++;
  286. if (log_to_remove > MAX_LOG_FILES) {
  287. log_to_remove = 1;
  288. }
  289. } while (log_to_remove != first_log_to_remove);
  290. }
  291. void AP_Logger_File::Prep() {
  292. if (!NeedPrep()) {
  293. return;
  294. }
  295. if (hal.util->get_soft_armed()) {
  296. // do not want to do any filesystem operations while we are e.g. flying
  297. return;
  298. }
  299. Prep_MinSpace();
  300. }
  301. bool AP_Logger_File::NeedPrep()
  302. {
  303. if (!CardInserted()) {
  304. // should not have been called?!
  305. return false;
  306. }
  307. if (avail_space_percent() < min_avail_space_percent) {
  308. return true;
  309. }
  310. return false;
  311. }
  312. /*
  313. construct a log file name given a log number.
  314. The number in the log filename will *not* be zero-padded.
  315. Note: Caller must free.
  316. */
  317. char *AP_Logger_File::_log_file_name_short(const uint16_t log_num) const
  318. {
  319. char *buf = nullptr;
  320. if (asprintf(&buf, "%s/%u.BIN", _log_directory, (unsigned)log_num) == -1) {
  321. return nullptr;
  322. }
  323. return buf;
  324. }
  325. /*
  326. construct a log file name given a log number.
  327. The number in the log filename will be zero-padded.
  328. Note: Caller must free.
  329. */
  330. char *AP_Logger_File::_log_file_name_long(const uint16_t log_num) const
  331. {
  332. char *buf = nullptr;
  333. if (asprintf(&buf, "%s/%08u.BIN", _log_directory, (unsigned)log_num) == -1) {
  334. return nullptr;
  335. }
  336. return buf;
  337. }
  338. /*
  339. return a log filename appropriate for the supplied log_num if a
  340. filename exists with the short (not-zero-padded name) then it is the
  341. appropirate name, otherwise the long (zero-padded) version is.
  342. Note: Caller must free.
  343. */
  344. char *AP_Logger_File::_log_file_name(const uint16_t log_num) const
  345. {
  346. char *filename = _log_file_name_short(log_num);
  347. if (filename == nullptr) {
  348. return nullptr;
  349. }
  350. if (file_exists(filename)) {
  351. return filename;
  352. }
  353. free(filename);
  354. return _log_file_name_long(log_num);
  355. }
  356. /*
  357. return path name of the lastlog.txt marker file
  358. Note: Caller must free.
  359. */
  360. char *AP_Logger_File::_lastlog_file_name(void) const
  361. {
  362. char *buf = nullptr;
  363. if (asprintf(&buf, "%s/LASTLOG.TXT", _log_directory) == -1) {
  364. return nullptr;
  365. }
  366. return buf;
  367. }
  368. // remove all log files
  369. void AP_Logger_File::EraseAll()
  370. {
  371. if (hal.util->get_soft_armed()) {
  372. // do not want to do any filesystem operations while we are e.g. flying
  373. return;
  374. }
  375. if (!_initialised) {
  376. return;
  377. }
  378. const bool was_logging = (_write_fd != -1);
  379. stop_logging();
  380. for (uint16_t log_num=1; log_num<=MAX_LOG_FILES; log_num++) {
  381. char *fname = _log_file_name(log_num);
  382. if (fname == nullptr) {
  383. break;
  384. }
  385. EXPECT_DELAY_MS(3000);
  386. AP::FS().unlink(fname);
  387. free(fname);
  388. }
  389. char *fname = _lastlog_file_name();
  390. if (fname != nullptr) {
  391. AP::FS().unlink(fname);
  392. free(fname);
  393. }
  394. _cached_oldest_log = 0;
  395. if (was_logging) {
  396. start_new_log();
  397. }
  398. }
  399. bool AP_Logger_File::WritesOK() const
  400. {
  401. if (_write_fd == -1) {
  402. return false;
  403. }
  404. if (_open_error) {
  405. return false;
  406. }
  407. return true;
  408. }
  409. bool AP_Logger_File::StartNewLogOK() const
  410. {
  411. if (_open_error) {
  412. return false;
  413. }
  414. return AP_Logger_Backend::StartNewLogOK();
  415. }
  416. /* Write a block of data at current offset */
  417. bool AP_Logger_File::_WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical)
  418. {
  419. if (! WriteBlockCheckStartupMessages()) {
  420. _dropped++;
  421. return false;
  422. }
  423. if (!semaphore.take(1)) {
  424. return false;
  425. }
  426. uint32_t space = _writebuf.space();
  427. if (_writing_startup_messages &&
  428. _startup_messagewriter->fmt_done()) {
  429. // the state machine has called us, and it has finished
  430. // writing format messages out. It can always get back to us
  431. // with more messages later, so let's leave room for other
  432. // things:
  433. const uint32_t now = AP_HAL::millis();
  434. const bool must_dribble = (now - last_messagewrite_message_sent) > 100;
  435. if (!must_dribble &&
  436. space < non_messagewriter_message_reserved_space()) {
  437. // this message isn't dropped, it will be sent again...
  438. semaphore.give();
  439. return false;
  440. }
  441. last_messagewrite_message_sent = now;
  442. } else {
  443. // we reserve some amount of space for critical messages:
  444. if (!is_critical && space < critical_message_reserved_space()) {
  445. _dropped++;
  446. semaphore.give();
  447. return false;
  448. }
  449. }
  450. // if no room for entire message - drop it:
  451. if (space < size) {
  452. hal.util->perf_count(_perf_overruns);
  453. _dropped++;
  454. semaphore.give();
  455. return false;
  456. }
  457. _writebuf.write((uint8_t*)pBuffer, size);
  458. df_stats_gather(size);
  459. semaphore.give();
  460. return true;
  461. }
  462. /*
  463. find the highest log number
  464. */
  465. uint16_t AP_Logger_File::find_last_log()
  466. {
  467. unsigned ret = 0;
  468. char *fname = _lastlog_file_name();
  469. if (fname == nullptr) {
  470. return ret;
  471. }
  472. EXPECT_DELAY_MS(3000);
  473. int fd = AP::FS().open(fname, O_RDONLY);
  474. free(fname);
  475. if (fd != -1) {
  476. char buf[10];
  477. memset(buf, 0, sizeof(buf));
  478. if (AP::FS().read(fd, buf, sizeof(buf)-1) > 0) {
  479. ret = strtol(buf, NULL, 10);
  480. }
  481. AP::FS().close(fd);
  482. }
  483. return ret;
  484. }
  485. uint32_t AP_Logger_File::_get_log_size(const uint16_t log_num)
  486. {
  487. char *fname = _log_file_name(log_num);
  488. if (fname == nullptr) {
  489. return 0;
  490. }
  491. if (_write_fd != -1 && write_fd_semaphore.take_nonblocking()) {
  492. if (_write_filename != nullptr && strcmp(_write_filename, fname) == 0) {
  493. // it is the file we are currently writing
  494. free(fname);
  495. write_fd_semaphore.give();
  496. return _write_offset;
  497. }
  498. write_fd_semaphore.give();
  499. }
  500. struct stat st;
  501. EXPECT_DELAY_MS(3000);
  502. if (AP::FS().stat(fname, &st) != 0) {
  503. printf("Unable to fetch Log File Size: %s\n", strerror(errno));
  504. free(fname);
  505. return 0;
  506. }
  507. free(fname);
  508. return st.st_size;
  509. }
  510. uint32_t AP_Logger_File::_get_log_time(const uint16_t log_num)
  511. {
  512. char *fname = _log_file_name(log_num);
  513. if (fname == nullptr) {
  514. return 0;
  515. }
  516. if (_write_fd != -1 && write_fd_semaphore.take_nonblocking()) {
  517. if (_write_filename != nullptr && strcmp(_write_filename, fname) == 0) {
  518. // it is the file we are currently writing
  519. free(fname);
  520. write_fd_semaphore.give();
  521. uint64_t utc_usec;
  522. if (!AP::rtc().get_utc_usec(utc_usec)) {
  523. return 0;
  524. }
  525. return utc_usec / 1000000U;
  526. }
  527. write_fd_semaphore.give();
  528. }
  529. struct stat st;
  530. EXPECT_DELAY_MS(3000);
  531. if (AP::FS().stat(fname, &st) != 0) {
  532. free(fname);
  533. return 0;
  534. }
  535. free(fname);
  536. return st.st_mtime;
  537. }
  538. /*
  539. convert a list entry number back into a log number (which can then
  540. be converted into a filename). A "list entry number" is a sequence
  541. where the oldest log has a number of 1, the second-from-oldest 2,
  542. and so on. Thus the highest list entry number is equal to the
  543. number of logs.
  544. */
  545. uint16_t AP_Logger_File::_log_num_from_list_entry(const uint16_t list_entry)
  546. {
  547. uint16_t oldest_log = find_oldest_log();
  548. if (oldest_log == 0) {
  549. // We don't have any logs...
  550. return 0;
  551. }
  552. uint32_t log_num = oldest_log + list_entry - 1;
  553. if (log_num > MAX_LOG_FILES) {
  554. log_num -= MAX_LOG_FILES;
  555. }
  556. return (uint16_t)log_num;
  557. }
  558. /*
  559. find the number of pages in a log
  560. */
  561. void AP_Logger_File::get_log_boundaries(const uint16_t list_entry, uint32_t & start_page, uint32_t & end_page)
  562. {
  563. const uint16_t log_num = _log_num_from_list_entry(list_entry);
  564. if (log_num == 0) {
  565. // that failed - probably no logs
  566. start_page = 0;
  567. end_page = 0;
  568. return;
  569. }
  570. start_page = 0;
  571. end_page = _get_log_size(log_num) / LOGGER_PAGE_SIZE;
  572. }
  573. /*
  574. retrieve data from a log file
  575. */
  576. int16_t AP_Logger_File::get_log_data(const uint16_t list_entry, const uint16_t page, const uint32_t offset, const uint16_t len, uint8_t *data)
  577. {
  578. if (!_initialised || _open_error) {
  579. return -1;
  580. }
  581. const uint16_t log_num = _log_num_from_list_entry(list_entry);
  582. if (log_num == 0) {
  583. // that failed - probably no logs
  584. return -1;
  585. }
  586. if (_read_fd != -1 && log_num != _read_fd_log_num) {
  587. AP::FS().close(_read_fd);
  588. _read_fd = -1;
  589. }
  590. if (_read_fd == -1) {
  591. char *fname = _log_file_name(log_num);
  592. if (fname == nullptr) {
  593. return -1;
  594. }
  595. stop_logging();
  596. EXPECT_DELAY_MS(3000);
  597. _read_fd = AP::FS().open(fname, O_RDONLY);
  598. if (_read_fd == -1) {
  599. _open_error = true;
  600. int saved_errno = errno;
  601. ::printf("Log read open fail for %s - %s\n",
  602. fname, strerror(saved_errno));
  603. hal.console->printf("Log read open fail for %s - %s\n",
  604. fname, strerror(saved_errno));
  605. free(fname);
  606. return -1;
  607. }
  608. free(fname);
  609. _read_offset = 0;
  610. _read_fd_log_num = log_num;
  611. }
  612. uint32_t ofs = page * (uint32_t)LOGGER_PAGE_SIZE + offset;
  613. /*
  614. this rather strange bit of code is here to work around a bug
  615. in file offsets in NuttX. Every few hundred blocks of reads
  616. (starting at around 350k into a file) NuttX will get the
  617. wrong offset for sequential reads. The offset it gets is
  618. typically 128k earlier than it should be. It turns out that
  619. calling lseek() with 0 offset and SEEK_CUR works around the
  620. bug. We can remove this once we find the real bug.
  621. */
  622. if (ofs / 4096 != (ofs+len) / 4096) {
  623. off_t seek_current = AP::FS().lseek(_read_fd, 0, SEEK_CUR);
  624. if (seek_current == (off_t)-1) {
  625. AP::FS().close(_read_fd);
  626. _read_fd = -1;
  627. return -1;
  628. }
  629. if (seek_current != (off_t)_read_offset) {
  630. if (AP::FS().lseek(_read_fd, _read_offset, SEEK_SET) == (off_t)-1) {
  631. AP::FS().close(_read_fd);
  632. _read_fd = -1;
  633. return -1;
  634. }
  635. }
  636. }
  637. if (ofs != _read_offset) {
  638. if (AP::FS().lseek(_read_fd, ofs, SEEK_SET) == (off_t)-1) {
  639. AP::FS().close(_read_fd);
  640. _read_fd = -1;
  641. return -1;
  642. }
  643. _read_offset = ofs;
  644. }
  645. int16_t ret = (int16_t)AP::FS().read(_read_fd, data, len);
  646. if (ret > 0) {
  647. _read_offset += ret;
  648. }
  649. return ret;
  650. }
  651. /*
  652. find size and date of a log
  653. */
  654. void AP_Logger_File::get_log_info(const uint16_t list_entry, uint32_t &size, uint32_t &time_utc)
  655. {
  656. uint16_t log_num = _log_num_from_list_entry(list_entry);
  657. if (log_num == 0) {
  658. // that failed - probably no logs
  659. size = 0;
  660. time_utc = 0;
  661. return;
  662. }
  663. size = _get_log_size(log_num);
  664. time_utc = _get_log_time(log_num);
  665. }
  666. /*
  667. get the number of logs - note that the log numbers must be consecutive
  668. */
  669. uint16_t AP_Logger_File::get_num_logs()
  670. {
  671. uint16_t ret = 0;
  672. uint16_t high = find_last_log();
  673. uint16_t i;
  674. for (i=high; i>0; i--) {
  675. if (! log_exists(i)) {
  676. break;
  677. }
  678. ret++;
  679. }
  680. if (i == 0) {
  681. for (i=MAX_LOG_FILES; i>high; i--) {
  682. if (! log_exists(i)) {
  683. break;
  684. }
  685. ret++;
  686. }
  687. }
  688. return ret;
  689. }
  690. /*
  691. stop logging
  692. */
  693. void AP_Logger_File::stop_logging(void)
  694. {
  695. // best-case effort to avoid annoying the IO thread
  696. const bool have_sem = write_fd_semaphore.take(hal.util->get_soft_armed()?1:20);
  697. if (_write_fd != -1) {
  698. int fd = _write_fd;
  699. _write_fd = -1;
  700. AP::FS().close(fd);
  701. }
  702. if (have_sem) {
  703. write_fd_semaphore.give();
  704. }
  705. }
  706. void AP_Logger_File::PrepForArming()
  707. {
  708. if (logging_started()) {
  709. return;
  710. }
  711. start_new_log();
  712. }
  713. /*
  714. start writing to a new log file
  715. */
  716. uint16_t AP_Logger_File::start_new_log(void)
  717. {
  718. stop_logging();
  719. start_new_log_reset_variables();
  720. if (_open_error) {
  721. // we have previously failed to open a file - don't try again
  722. // to prevent us trying to open files while in flight
  723. return 0xFFFF;
  724. }
  725. if (_read_fd != -1) {
  726. AP::FS().close(_read_fd);
  727. _read_fd = -1;
  728. }
  729. if (disk_space_avail() < _free_space_min_avail && disk_space() > 0) {
  730. hal.console->printf("Out of space for logging\n");
  731. _open_error = true;
  732. return 0xffff;
  733. }
  734. uint16_t log_num = find_last_log();
  735. // re-use empty logs if possible
  736. if (_get_log_size(log_num) > 0 || log_num == 0) {
  737. log_num++;
  738. }
  739. if (log_num > MAX_LOG_FILES) {
  740. log_num = 1;
  741. }
  742. if (!write_fd_semaphore.take(1)) {
  743. _open_error = true;
  744. return 0xFFFF;
  745. }
  746. if (_write_filename) {
  747. free(_write_filename);
  748. _write_filename = nullptr;
  749. }
  750. _write_filename = _log_file_name(log_num);
  751. if (_write_filename == nullptr) {
  752. _open_error = true;
  753. write_fd_semaphore.give();
  754. return 0xFFFF;
  755. }
  756. #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
  757. // remember if we had utc time when we opened the file
  758. uint64_t utc_usec;
  759. _need_rtc_update = !AP::rtc().get_utc_usec(utc_usec);
  760. #endif
  761. EXPECT_DELAY_MS(3000);
  762. _write_fd = AP::FS().open(_write_filename, O_WRONLY|O_CREAT|O_TRUNC);
  763. _cached_oldest_log = 0;
  764. if (_write_fd == -1) {
  765. _initialised = false;
  766. _open_error = true;
  767. write_fd_semaphore.give();
  768. int saved_errno = errno;
  769. ::printf("Log open fail for %s - %s\n",
  770. _write_filename, strerror(saved_errno));
  771. hal.console->printf("Log open fail for %s - %s\n",
  772. _write_filename, strerror(saved_errno));
  773. return 0xFFFF;
  774. }
  775. _last_write_ms = AP_HAL::millis();
  776. _write_offset = 0;
  777. _writebuf.clear();
  778. write_fd_semaphore.give();
  779. // now update lastlog.txt with the new log number
  780. char *fname = _lastlog_file_name();
  781. // we avoid fopen()/fprintf() here as it is not available on as many
  782. // systems as open/write
  783. EXPECT_DELAY_MS(3000);
  784. int fd = AP::FS().open(fname, O_WRONLY|O_CREAT);
  785. free(fname);
  786. if (fd == -1) {
  787. _open_error = true;
  788. return 0xFFFF;
  789. }
  790. char buf[30];
  791. snprintf(buf, sizeof(buf), "%u\r\n", (unsigned)log_num);
  792. const ssize_t to_write = strlen(buf);
  793. const ssize_t written = AP::FS().write(fd, buf, to_write);
  794. AP::FS().close(fd);
  795. if (written < to_write) {
  796. _open_error = true;
  797. return 0xFFFF;
  798. }
  799. return log_num;
  800. }
  801. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
  802. void AP_Logger_File::flush(void)
  803. #if APM_BUILD_TYPE(APM_BUILD_Replay) || APM_BUILD_TYPE(APM_BUILD_UNKNOWN)
  804. {
  805. uint32_t tnow = AP_HAL::millis();
  806. while (_write_fd != -1 && _initialised && !_open_error && _writebuf.available()) {
  807. // convince the IO timer that it really is OK to write out
  808. // less than _writebuf_chunk bytes:
  809. if (tnow > 2001) { // avoid resetting _last_write_time to 0
  810. _last_write_time = tnow - 2001;
  811. }
  812. _io_timer();
  813. }
  814. if (write_fd_semaphore.take(1)) {
  815. if (_write_fd != -1) {
  816. ::fsync(_write_fd);
  817. }
  818. write_fd_semaphore.give();
  819. } else {
  820. AP::internalerror().error(AP_InternalError::error_t::logger_flushing_without_sem);
  821. }
  822. }
  823. #else
  824. {
  825. // flush is for replay and examples only
  826. }
  827. #endif // APM_BUILD_TYPE(APM_BUILD_Replay) || APM_BUILD_TYPE(APM_BUILD_UNKNOWN)
  828. #endif
  829. void AP_Logger_File::_io_timer(void)
  830. {
  831. uint32_t tnow = AP_HAL::millis();
  832. _io_timer_heartbeat = tnow;
  833. if (_write_fd == -1 || !_initialised || _open_error) {
  834. return;
  835. }
  836. uint32_t nbytes = _writebuf.available();
  837. if (nbytes == 0) {
  838. return;
  839. }
  840. if (nbytes < _writebuf_chunk &&
  841. tnow - _last_write_time < 2000UL) {
  842. // write in _writebuf_chunk-sized chunks, but always write at
  843. // least once per 2 seconds if data is available
  844. return;
  845. }
  846. if (tnow - _free_space_last_check_time > _free_space_check_interval) {
  847. _free_space_last_check_time = tnow;
  848. last_io_operation = "disk_space_avail";
  849. if (disk_space_avail() < _free_space_min_avail && disk_space() > 0) {
  850. hal.console->printf("Out of space for logging\n");
  851. stop_logging();
  852. _open_error = true; // prevent logging starting again
  853. last_io_operation = "";
  854. return;
  855. }
  856. last_io_operation = "";
  857. }
  858. hal.util->perf_begin(_perf_write);
  859. _last_write_time = tnow;
  860. if (nbytes > _writebuf_chunk) {
  861. // be kind to the filesystem layer
  862. nbytes = _writebuf_chunk;
  863. }
  864. uint32_t size;
  865. const uint8_t *head = _writebuf.readptr(size);
  866. nbytes = MIN(nbytes, size);
  867. // try to align writes on a 512 byte boundary to avoid filesystem reads
  868. if ((nbytes + _write_offset) % 512 != 0) {
  869. uint32_t ofs = (nbytes + _write_offset) % 512;
  870. if (ofs < nbytes) {
  871. nbytes -= ofs;
  872. }
  873. }
  874. last_io_operation = "write";
  875. if (!write_fd_semaphore.take(1)) {
  876. return;
  877. }
  878. if (_write_fd == -1) {
  879. write_fd_semaphore.give();
  880. return;
  881. }
  882. ssize_t nwritten = AP::FS().write(_write_fd, head, nbytes);
  883. last_io_operation = "";
  884. if (nwritten <= 0) {
  885. if ((tnow - _last_write_ms)/1000U > unsigned(_front._params.file_timeout)) {
  886. // if we can't write for LOG_FILE_TIMEOUT seconds we give up and close
  887. // the file. This allows us to cope with temporary write
  888. // failures caused by directory listing
  889. hal.util->perf_count(_perf_errors);
  890. last_io_operation = "close";
  891. AP::FS().close(_write_fd);
  892. last_io_operation = "";
  893. _write_fd = -1;
  894. _initialised = false;
  895. printf("Failed to write to File: %s\n", strerror(errno));
  896. }
  897. _last_write_failed = true;
  898. } else {
  899. _last_write_failed = false;
  900. _last_write_ms = tnow;
  901. _write_offset += nwritten;
  902. _writebuf.advance(nwritten);
  903. /*
  904. the best strategy for minimizing corruption on microSD cards
  905. seems to be to write in 4k chunks and fsync the file on each
  906. chunk, ensuring the directory entry is updated after each
  907. write.
  908. */
  909. #if CONFIG_HAL_BOARD != HAL_BOARD_SITL && CONFIG_HAL_BOARD_SUBTYPE != HAL_BOARD_SUBTYPE_LINUX_NONE
  910. last_io_operation = "fsync";
  911. AP::FS().fsync(_write_fd);
  912. last_io_operation = "";
  913. #endif
  914. #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
  915. // ChibiOS does not update mtime on writes, so if we opened
  916. // without knowing the time we should update it later
  917. if (_need_rtc_update) {
  918. uint64_t utc_usec;
  919. if (AP::rtc().get_utc_usec(utc_usec)) {
  920. AP::FS().set_mtime(_write_filename, utc_usec/(1000U*1000U));
  921. _need_rtc_update = false;
  922. }
  923. }
  924. #endif
  925. }
  926. write_fd_semaphore.give();
  927. hal.util->perf_end(_perf_write);
  928. }
  929. // this sensor is enabled if we should be logging at the moment
  930. bool AP_Logger_File::logging_enabled() const
  931. {
  932. if (hal.util->get_soft_armed() ||
  933. _front.log_while_disarmed()) {
  934. return true;
  935. }
  936. return false;
  937. }
  938. bool AP_Logger_File::io_thread_alive() const
  939. {
  940. // if the io thread hasn't had a heartbeat in a full seconds then it is dead
  941. // this is enough time for a sdcard remount
  942. return (AP_HAL::millis() - _io_timer_heartbeat) < 3000U;
  943. }
  944. bool AP_Logger_File::logging_failed() const
  945. {
  946. if (!_initialised) {
  947. return true;
  948. }
  949. if (_open_error) {
  950. return true;
  951. }
  952. if (!io_thread_alive()) {
  953. // No heartbeat in a second. IO thread is dead?! Very Not
  954. // Good.
  955. return true;
  956. }
  957. if (_last_write_failed) {
  958. return true;
  959. }
  960. return false;
  961. }
  962. void AP_Logger_File::vehicle_was_disarmed()
  963. {
  964. if (_front._params.file_disarm_rot) {
  965. // rotate our log. Closing the current one and letting the
  966. // logging restart naturally based on log_disarmed should do
  967. // the trick:
  968. _rotate_pending = true;
  969. }
  970. }
  971. void AP_Logger_File::Write_AP_Logger_Stats_File(const struct df_stats &_stats)
  972. {
  973. struct log_DSF pkt = {
  974. LOG_PACKET_HEADER_INIT(LOG_DF_FILE_STATS),
  975. time_us : AP_HAL::micros64(),
  976. dropped : _dropped,
  977. blocks : _stats.blocks,
  978. bytes : _stats.bytes,
  979. buf_space_min : _stats.buf_space_min,
  980. buf_space_max : _stats.buf_space_max,
  981. buf_space_avg : (_stats.blocks) ? (_stats.buf_space_sigma / _stats.blocks) : 0,
  982. };
  983. WriteBlock(&pkt, sizeof(pkt));
  984. }
  985. void AP_Logger_File::df_stats_gather(const uint16_t bytes_written) {
  986. const uint32_t space_remaining = _writebuf.space();
  987. if (space_remaining < stats.buf_space_min) {
  988. stats.buf_space_min = space_remaining;
  989. }
  990. if (space_remaining > stats.buf_space_max) {
  991. stats.buf_space_max = space_remaining;
  992. }
  993. stats.buf_space_sigma += space_remaining;
  994. stats.bytes += bytes_written;
  995. stats.blocks++;
  996. }
  997. void AP_Logger_File::df_stats_clear() {
  998. memset(&stats, '\0', sizeof(stats));
  999. stats.buf_space_min = -1;
  1000. }
  1001. void AP_Logger_File::df_stats_log() {
  1002. Write_AP_Logger_Stats_File(stats);
  1003. df_stats_clear();
  1004. }
  1005. #endif // HAVE_FILESYSTEM_SUPPORT