41 #include <mathlib/mathlib.h> 42 #include <px4_platform_common/posix.h> 54 constexpr
size_t LogWriterFile::_min_write_chunk;
56 LogWriterFile::LogWriterFile(
size_t buffer_size)
69 pthread_mutex_init(&
_mtx,
nullptr);
70 pthread_cond_init(&
_cv,
nullptr);
80 pthread_mutex_destroy(&
_mtx);
81 pthread_cond_destroy(&
_cv);
106 PX4_ERR(
"Failed to register ULog file to the hardfault handler (%i)", ret);
111 PX4_INFO(
"Opened %s log file: %s",
log_type_str(type), filename);
125 int n = strlen(log_file);
132 if (n + 1 != ::
write(fd, log_file, n + 1)) {
150 _buffers[(int)type]._should_run =
false;
156 pthread_attr_t thr_attr;
157 pthread_attr_init(&thr_attr);
161 param.sched_priority = SCHED_PRIORITY_DEFAULT - 40;
162 (void)pthread_attr_setschedparam(&thr_attr, ¶m);
164 pthread_attr_setstacksize(&thr_attr, PX4_STACK_ADJUSTED(1170));
167 pthread_attr_destroy(&thr_attr);
181 int ret = pthread_join(
_thread,
nullptr);
184 PX4_WARN(
"join failed: %d", ret);
191 px4_prctl(PR_SET_NAME,
"log_writer_file", px4_getpid());
204 pthread_mutex_lock(&
_mtx);
205 pthread_cond_wait(&
_cv, &
_mtx);
207 pthread_mutex_unlock(&
_mtx);
222 pthread_mutex_lock(&
_mtx);
229 const bool call_fsync = ++poll_count >= 100 || now - last_fsync > 1_s;
248 size_t available = buffer.
get_read_ptr(&read_ptr, &is_part);
251 if (available >= min_available[i] || is_part || (!buffer.
_should_run && available > 0)) {
252 pthread_mutex_unlock(&
_mtx);
254 written = buffer.
write_to_file(read_ptr, available, call_fsync);
257 pthread_mutex_lock(&
_mtx);
263 if (!buffer.
_should_run && written == static_cast<int>(available) && !is_part) {
269 PX4_ERR(
"write failed (%i)", errno);
275 pthread_mutex_unlock(&
_mtx);
277 pthread_mutex_lock(&
_mtx);
279 }
else if (available == 0 && !buffer.
_should_run) {
299 pthread_cond_wait(&
_cv, &
_mtx);
303 pthread_mutex_unlock(&
_mtx);
314 while ((ret =
write(type, ptr, 0, dropout_start)) == -1) {
322 uint8_t *uptr = (uint8_t *)ptr;
328 while ((ret =
write(type, uptr, write_size, 0)) == -1) {
342 return write(type, ptr, size, dropout_start);
352 size_t available =
_buffers[(int)type].available();
353 size_t dropout_size = 0;
359 if (size + dropout_size > available) {
368 _buffers[(int)type].write_no_check(&dropout_msg,
sizeof(dropout_msg));
371 _buffers[(int)type].write_no_check(ptr, size);
390 : _buffer_size(log_buffer_size), _perf_write(perf_write), _perf_fsync(perf_fsync)
410 uint8_t *buffer_c =
static_cast<uint8_t *
>(ptr);
414 memcpy(&(
_buffer[_head]), buffer_c, n);
423 memcpy(&(
_buffer[_head]), &(buffer_c[n]), p);
448 _fd = ::open(filename, O_CREAT | O_WRONLY, PX4_O_MODE_666);
451 PX4_ERR(
"Can't open log file %s, errno: %d", filename, errno);
459 PX4_ERR(
"Can't create log buffer");
502 int res = close(
_fd);
506 PX4_WARN(
"closing log file failed (%i)", errno);
static constexpr size_t _min_write_chunk
measure the time elapsed performing an event
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
#define HARDFAULT_MAX_ULOG_FILE_LEN
reduced mission log (e.g. for geotagging)
bool start_log(const char *filename)
bool _need_reliable_transfer
int thread_start()
start the thread
size_t _count
number of bytes in _buffer to be written
void perf_free(perf_counter_t handle)
Free a counter.
const size_t _buffer_size
Writes logging data to a file.
LogFileBuffer _buffers[(int) LogType::Count]
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.
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.
bool is_started(LogType type) const
constexpr _Tp min(_Tp a, _Tp b)
constexpr _Tp max(_Tp a, _Tp b)
ssize_t write_to_file(const void *buffer, size_t size, bool call_fsync) const
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).
perf_counter_t _perf_fsync
perf_counter_t _perf_write
void stop_log(LogType type)