PX4 Firmware
PX4 Autopilot Software http://px4.io
log_writer_file.cpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2016 PX4 Development Team. All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 
34 #include "log_writer_file.h"
35 #include "messages.h"
36 
37 #include <fcntl.h>
38 #include <string.h>
39 #include <errno.h>
40 
41 #include <mathlib/mathlib.h>
42 #include <px4_platform_common/posix.h>
43 #ifdef __PX4_NUTTX
45 #endif /* __PX4_NUTTX */
46 
47 using namespace time_literals;
48 
49 
50 namespace px4
51 {
52 namespace logger
53 {
54 constexpr size_t LogWriterFile::_min_write_chunk;
55 
56 LogWriterFile::LogWriterFile(size_t buffer_size)
57  : _buffers{
58  //We always write larger chunks (orb messages) to the buffer, so the buffer
59  //needs to be larger than the minimum write chunk (300 is somewhat arbitrary)
60  {
61  math::max(buffer_size, _min_write_chunk + 300),
62  perf_alloc(PC_ELAPSED, "logger_sd_write"), perf_alloc(PC_ELAPSED, "logger_sd_fsync")},
63 
64  {
65  300, // buffer size for the mission log (can be kept fairly small)
66  perf_alloc(PC_ELAPSED, "logger_sd_write_mission"), perf_alloc(PC_ELAPSED, "logger_sd_fsync_mission")}
67 }
68 {
69  pthread_mutex_init(&_mtx, nullptr);
70  pthread_cond_init(&_cv, nullptr);
71 }
72 
74 {
75  return true;
76 }
77 
79 {
80  pthread_mutex_destroy(&_mtx);
81  pthread_cond_destroy(&_cv);
82 }
83 
84 void LogWriterFile::start_log(LogType type, const char *filename)
85 {
86  // At this point we don't expect the file to be open, but it can happen for very fast consecutive stop & start
87  // calls. In that case we wait for the thread to close the file first.
88  lock();
89 
90  while (_buffers[(int)type].fd() >= 0) {
91  unlock();
92  system_usleep(5000);
93  lock();
94  }
95 
96  unlock();
97 
98  if (type == LogType::Full) {
99  // register the current file with the hardfault handler: if the system crashes,
100  // the hardfault handler will append the crash log to that file on the next reboot.
101  // Note that we don't deregister it when closing the log, so that crashes after disarming
102  // are appended as well (the same holds for crashes before arming, which can be a bit misleading)
103  int ret = hardfault_store_filename(filename);
104 
105  if (ret) {
106  PX4_ERR("Failed to register ULog file to the hardfault handler (%i)", ret);
107  }
108  }
109 
110  if (_buffers[(int)type].start_log(filename)) {
111  PX4_INFO("Opened %s log file: %s", log_type_str(type), filename);
112  notify();
113  }
114 }
115 
117 {
118 #ifdef __PX4_NUTTX
119  int fd = open(HARDFAULT_ULOG_PATH, O_TRUNC | O_WRONLY | O_CREAT);
120 
121  if (fd < 0) {
122  return -errno;
123  }
124 
125  int n = strlen(log_file);
126 
127  if (n >= HARDFAULT_MAX_ULOG_FILE_LEN) {
128  PX4_ERR("ULog file name too long (%s, %i>=%i)\n", log_file, n, HARDFAULT_MAX_ULOG_FILE_LEN);
129  return -EINVAL;
130  }
131 
132  if (n + 1 != ::write(fd, log_file, n + 1)) {
133  close(fd);
134  return -errno;
135  }
136 
137  int ret = close(fd);
138 
139  if (ret != 0) {
140  return -errno;
141  }
142 
143 #endif /* __PX4_NUTTX */
144 
145  return 0;
146 }
147 
149 {
150  _buffers[(int)type]._should_run = false;
151  notify();
152 }
153 
155 {
156  pthread_attr_t thr_attr;
157  pthread_attr_init(&thr_attr);
158 
159  sched_param param;
160  /* low priority, as this is expensive disk I/O */
161  param.sched_priority = SCHED_PRIORITY_DEFAULT - 40;
162  (void)pthread_attr_setschedparam(&thr_attr, &param);
163 
164  pthread_attr_setstacksize(&thr_attr, PX4_STACK_ADJUSTED(1170));
165 
166  int ret = pthread_create(&_thread, &thr_attr, &LogWriterFile::run_helper, this);
167  pthread_attr_destroy(&thr_attr);
168 
169  return ret;
170 }
171 
173 {
174  // this will terminate the main loop of the writer thread
175  _exit_thread = true;
176  _buffers[0]._should_run = _buffers[1]._should_run = false;
177 
178  notify();
179 
180  // wait for thread to complete
181  int ret = pthread_join(_thread, nullptr);
182 
183  if (ret) {
184  PX4_WARN("join failed: %d", ret);
185  }
186 
187 }
188 
189 void *LogWriterFile::run_helper(void *context)
190 {
191  px4_prctl(PR_SET_NAME, "log_writer_file", px4_getpid());
192 
193  static_cast<LogWriterFile *>(context)->run();
194  return nullptr;
195 }
196 
198 {
199  while (!_exit_thread) {
200  // Outer endless loop
201  // Wait for _should_run flag
202  while (!_exit_thread) {
203  bool start = false;
204  pthread_mutex_lock(&_mtx);
205  pthread_cond_wait(&_cv, &_mtx);
206  start = _buffers[0]._should_run || _buffers[1]._should_run;
207  pthread_mutex_unlock(&_mtx);
208 
209  if (start) {
210  break;
211  }
212  }
213 
214  if (_exit_thread) {
215  break;
216  }
217 
218  int poll_count = 0;
219  int written = 0;
220  hrt_abstime last_fsync = hrt_absolute_time();
221 
222  pthread_mutex_lock(&_mtx);
223 
224  while (true) {
225 
226  const hrt_abstime now = hrt_absolute_time();
227 
228  /* call fsync periodically to minimize potential loss of data */
229  const bool call_fsync = ++poll_count >= 100 || now - last_fsync > 1_s;
230 
231  if (call_fsync) {
232  last_fsync = now;
233  poll_count = 0;
234  }
235 
236  constexpr size_t min_available[(int)LogType::Count] = {
238  1 // For the mission log, write as soon as there is data available
239  };
240 
241  /* Check all buffers for available data. Mission log is first to avoid drops */
242  int i = (int)LogType::Count - 1;
243 
244  while (i >= 0) {
245  void *read_ptr;
246  bool is_part;
247  LogFileBuffer &buffer = _buffers[i];
248  size_t available = buffer.get_read_ptr(&read_ptr, &is_part);
249 
250  /* if sufficient data available or partial read or terminating, write data */
251  if (available >= min_available[i] || is_part || (!buffer._should_run && available > 0)) {
252  pthread_mutex_unlock(&_mtx);
253 
254  written = buffer.write_to_file(read_ptr, available, call_fsync);
255 
256  /* buffer.mark_read() requires _mtx to be locked */
257  pthread_mutex_lock(&_mtx);
258 
259  if (written >= 0) {
260  /* subtract bytes written from number in buffer (count -= written) */
261  buffer.mark_read(written);
262 
263  if (!buffer._should_run && written == static_cast<int>(available) && !is_part) {
264  /* Stop only when all data written */
265  buffer.close_file();
266  }
267 
268  } else {
269  PX4_ERR("write failed (%i)", errno);
270  buffer._should_run = false;
271  buffer.close_file();
272  }
273 
274  } else if (call_fsync && buffer._should_run) {
275  pthread_mutex_unlock(&_mtx);
276  buffer.fsync();
277  pthread_mutex_lock(&_mtx);
278 
279  } else if (available == 0 && !buffer._should_run) {
280  buffer.close_file();
281  }
282 
283  /* if split into 2 parts, write the second part immediately as well */
284  if (!is_part) {
285  --i;
286  }
287  }
288 
289 
290  if (_buffers[0].fd() < 0 && _buffers[1].fd() < 0) {
291  // stop when both files are closed
292  break;
293  }
294 
295  /* Wait for a call to notify(), which indicates new data is available.
296  * Note that at this point there could already be new data available (because of a longer write),
297  * and calling pthread_cond_wait() will still wait for the next notify(). But this is generally
298  * not an issue because notify() is called regularly. */
299  pthread_cond_wait(&_cv, &_mtx);
300  }
301 
302  // go back to idle
303  pthread_mutex_unlock(&_mtx);
304  }
305 }
306 
307 int LogWriterFile::write_message(LogType type, void *ptr, size_t size, uint64_t dropout_start)
308 {
310  int ret;
311 
312  // if there's a dropout, write it first (because we might split the message)
313  if (dropout_start) {
314  while ((ret = write(type, ptr, 0, dropout_start)) == -1) {
315  unlock();
316  notify();
317  px4_usleep(3000);
318  lock();
319  }
320  }
321 
322  uint8_t *uptr = (uint8_t *)ptr;
323 
324  do {
325  // Split into several blocks if the data is longer than the write buffer
326  size_t write_size = math::min(size, _buffers[(int)type].buffer_size());
327 
328  while ((ret = write(type, uptr, write_size, 0)) == -1) {
329  unlock();
330  notify();
331  px4_usleep(3000);
332  lock();
333  }
334 
335  uptr += write_size;
336  size -= write_size;
337  } while (size > 0);
338 
339  return ret;
340  }
341 
342  return write(type, ptr, size, dropout_start);
343 }
344 
345 int LogWriterFile::write(LogType type, void *ptr, size_t size, uint64_t dropout_start)
346 {
347  if (!is_started(type)) {
348  return 0;
349  }
350 
351  // Bytes available to write
352  size_t available = _buffers[(int)type].available();
353  size_t dropout_size = 0;
354 
355  if (dropout_start) {
356  dropout_size = sizeof(ulog_message_dropout_s);
357  }
358 
359  if (size + dropout_size > available) {
360  // buffer overflow
361  return -1;
362  }
363 
364  if (dropout_start) {
365  //write dropout msg
366  ulog_message_dropout_s dropout_msg;
367  dropout_msg.duration = (uint16_t)(hrt_elapsed_time(&dropout_start) / 1000);
368  _buffers[(int)type].write_no_check(&dropout_msg, sizeof(dropout_msg));
369  }
370 
371  _buffers[(int)type].write_no_check(ptr, size);
372  return 0;
373 }
374 
375 const char *log_type_str(LogType type)
376 {
377  switch (type) {
378  case LogType::Full: return "full";
379 
380  case LogType::Mission: return "mission";
381 
382  case LogType::Count: break;
383  }
384 
385  return "unknown";
386 }
387 
389  perf_counter_t perf_fsync)
390  : _buffer_size(log_buffer_size), _perf_write(perf_write), _perf_fsync(perf_fsync)
391 {
392 }
393 
395 {
396  if (_fd >= 0) {
397  close(_fd);
398  }
399 
400  delete[] _buffer;
401 
404 }
405 
407 {
408  size_t n = _buffer_size - _head; // bytes to end of the buffer
409 
410  uint8_t *buffer_c = static_cast<uint8_t *>(ptr);
411 
412  if (size > n) {
413  // Message goes over the end of the buffer
414  memcpy(&(_buffer[_head]), buffer_c, n);
415  _head = 0;
416 
417  } else {
418  n = 0;
419  }
420 
421  // now: n = bytes already written
422  size_t p = size - n; // number of bytes to write
423  memcpy(&(_buffer[_head]), &(buffer_c[n]), p);
424  _head = (_head + p) % _buffer_size;
425  _count += size;
426 }
427 
428 size_t LogWriterFile::LogFileBuffer::get_read_ptr(void **ptr, bool *is_part)
429 {
430  // bytes available to read
431  int read_ptr = _head - _count;
432 
433  if (read_ptr < 0) {
434  read_ptr += _buffer_size;
435  *ptr = &_buffer[read_ptr];
436  *is_part = true;
437  return _buffer_size - read_ptr;
438 
439  } else {
440  *ptr = &_buffer[read_ptr];
441  *is_part = false;
442  return _count;
443  }
444 }
445 
446 bool LogWriterFile::LogFileBuffer::start_log(const char *filename)
447 {
448  _fd = ::open(filename, O_CREAT | O_WRONLY, PX4_O_MODE_666);
449 
450  if (_fd < 0) {
451  PX4_ERR("Can't open log file %s, errno: %d", filename, errno);
452  return false;
453  }
454 
455  if (_buffer == nullptr) {
456  _buffer = new uint8_t[_buffer_size];
457 
458  if (_buffer == nullptr) {
459  PX4_ERR("Can't create log buffer");
460  ::close(_fd);
461  _fd = -1;
462  return false;
463  }
464  }
465 
466  // Clear buffer and counters
467  _head = 0;
468  _count = 0;
469  _total_written = 0;
470 
471  _should_run = true;
472 
473  return true;
474 }
475 
477 {
479  ::fsync(_fd);
481 }
482 
483 ssize_t LogWriterFile::LogFileBuffer::write_to_file(const void *buffer, size_t size, bool call_fsync) const
484 {
486  ssize_t ret = ::write(_fd, buffer, size);
488 
489  if (call_fsync) {
490  fsync();
491  }
492 
493  return ret;
494 }
495 
497 {
498  _head = 0;
499  _count = 0;
500 
501  if (_fd >= 0) {
502  int res = close(_fd);
503  _fd = -1;
504 
505  if (res) {
506  PX4_WARN("closing log file failed (%i)", errno);
507 
508  } else {
509  PX4_INFO("closed logfile, bytes written: %zu", _total_written);
510  }
511  }
512 }
513 
514 }
515 }
static constexpr size_t _min_write_chunk
measure the time elapsed performing an event
Definition: perf_counter.h:56
void write_no_check(void *ptr, size_t size)
Write to the buffer but assuming there is enough space.
static void * run_helper(void *)
void start_log(LogType type, const char *filename)
int hardfault_store_filename(const char *log_file)
permanently store the ulog file name for the hardfault crash handler, so that it can append crash log...
size_t _head
next position to write to
LogType
Defines different log (file) types.
#define HARDFAULT_ULOG_PATH
Definition: hardfault_log.h:47
#define HARDFAULT_MAX_ULOG_FILE_LEN
Definition: hardfault_log.h:51
reduced mission log (e.g. for geotagging)
int thread_start()
start the thread
size_t _count
number of bytes in _buffer to be written
Header common to all counters.
void perf_free(perf_counter_t handle)
Free a counter.
#define perf_alloc(a, b)
Definition: px4io.h:59
Writes logging data to a file.
LogFileBuffer _buffers[(int) LogType::Count]
Normal, full size log.
LogFileBuffer(size_t log_buffer_size, perf_counter_t perf_write, perf_counter_t perf_fsync)
static hrt_abstime hrt_elapsed_time(const hrt_abstime *then)
Compute the delta between a timestamp taken in the past and now.
Definition: drv_hrt.h:102
int write(LogType type, void *ptr, size_t size, uint64_t dropout_start)
write w/o waiting/blocking
int write_message(LogType type, void *ptr, size_t size, uint64_t dropout_start=0)
void perf_end(perf_counter_t handle)
End a performance event.
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
Definition: drv_hrt.h:58
int fd
Definition: dataman.cpp:146
bool is_started(LogType type) const
constexpr _Tp min(_Tp a, _Tp b)
Definition: Limits.hpp:54
static int start()
Definition: dataman.cpp:1452
constexpr _Tp max(_Tp a, _Tp b)
Definition: Limits.hpp:60
#define system_usleep
Definition: visibility.h:108
ssize_t write_to_file(const void *buffer, size_t size, bool call_fsync) const
Definition: bst.cpp:62
size_t get_read_ptr(void **ptr, bool *is_part)
void perf_begin(perf_counter_t handle)
Begin a performance event.
const char * log_type_str(LogType type)
__EXPORT hrt_abstime hrt_absolute_time(void)
Get absolute time in [us] (does not wrap).