|
|
|
@ -156,7 +156,9 @@ struct logbuffer_s lb;
@@ -156,7 +156,9 @@ struct logbuffer_s lb;
|
|
|
|
|
static pthread_mutex_t logbuffer_mutex; |
|
|
|
|
static pthread_cond_t logbuffer_cond; |
|
|
|
|
|
|
|
|
|
static char log_dir[32]; |
|
|
|
|
#define LOG_BASE_PATH_LEN 64 |
|
|
|
|
|
|
|
|
|
static char log_dir[LOG_BASE_PATH_LEN]; |
|
|
|
|
|
|
|
|
|
/* statistics counters */ |
|
|
|
|
static uint64_t start_time = 0; |
|
|
|
@ -444,15 +446,15 @@ int create_log_dir()
@@ -444,15 +446,15 @@ int create_log_dir()
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/* print logging path, important to find log file later */ |
|
|
|
|
mavlink_and_console_log_info(mavlink_fd, "[sdlog2] log dir: %s", log_dir); |
|
|
|
|
mavlink_and_console_log_info(mavlink_fd, "[log] log dir: %s", log_dir); |
|
|
|
|
return 0; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
int open_log_file() |
|
|
|
|
{ |
|
|
|
|
/* string to hold the path to the log */ |
|
|
|
|
char log_file_name[32] = ""; |
|
|
|
|
char log_file_path[64] = ""; |
|
|
|
|
char log_file_name[64] = ""; |
|
|
|
|
char log_file_path[sizeof(log_file_name) + LOG_BASE_PATH_LEN] = ""; |
|
|
|
|
|
|
|
|
|
struct tm tt; |
|
|
|
|
bool time_ok = get_log_time_utc_tt(&tt, false); |
|
|
|
@ -480,7 +482,7 @@ int open_log_file()
@@ -480,7 +482,7 @@ int open_log_file()
|
|
|
|
|
|
|
|
|
|
if (file_number > MAX_NO_LOGFILE) { |
|
|
|
|
/* we should not end up here, either we have more than MAX_NO_LOGFILE on the SD card, or another problem */ |
|
|
|
|
mavlink_and_console_log_critical(mavlink_fd, "[sdlog2] ERR: max files %d", MAX_NO_LOGFILE); |
|
|
|
|
mavlink_and_console_log_critical(mavlink_fd, "[log] ERR: max files %d", MAX_NO_LOGFILE); |
|
|
|
|
return -1; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
@ -492,10 +494,10 @@ int open_log_file()
@@ -492,10 +494,10 @@ int open_log_file()
|
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
if (fd < 0) { |
|
|
|
|
mavlink_and_console_log_critical(mavlink_fd, "[sdlog2] failed opening: %s", log_file_name); |
|
|
|
|
mavlink_and_console_log_critical(mavlink_fd, "[log] failed: %s", log_file_name); |
|
|
|
|
|
|
|
|
|
} else { |
|
|
|
|
mavlink_and_console_log_info(mavlink_fd, "[sdlog2] starting: %s", log_file_name); |
|
|
|
|
mavlink_and_console_log_info(mavlink_fd, "[log] start: %s", log_file_name); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
return fd; |
|
|
|
@ -504,8 +506,8 @@ int open_log_file()
@@ -504,8 +506,8 @@ int open_log_file()
|
|
|
|
|
int open_perf_file(const char* str) |
|
|
|
|
{ |
|
|
|
|
/* string to hold the path to the log */ |
|
|
|
|
char log_file_name[32] = ""; |
|
|
|
|
char log_file_path[64] = ""; |
|
|
|
|
char log_file_name[64] = ""; |
|
|
|
|
char log_file_path[sizeof(log_file_name) + LOG_BASE_PATH_LEN] = ""; |
|
|
|
|
|
|
|
|
|
struct tm tt; |
|
|
|
|
bool time_ok = get_log_time_utc_tt(&tt, false); |
|
|
|
@ -532,7 +534,7 @@ int open_perf_file(const char* str)
@@ -532,7 +534,7 @@ int open_perf_file(const char* str)
|
|
|
|
|
|
|
|
|
|
if (file_number > MAX_NO_LOGFILE) { |
|
|
|
|
/* we should not end up here, either we have more than MAX_NO_LOGFILE on the SD card, or another problem */ |
|
|
|
|
mavlink_and_console_log_critical(mavlink_fd, "[sdlog2] ERR: max files %d", MAX_NO_LOGFILE); |
|
|
|
|
mavlink_and_console_log_critical(mavlink_fd, "[log] ERR: max files %d", MAX_NO_LOGFILE); |
|
|
|
|
return -1; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
@ -544,7 +546,7 @@ int open_perf_file(const char* str)
@@ -544,7 +546,7 @@ int open_perf_file(const char* str)
|
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
if (fd < 0) { |
|
|
|
|
mavlink_and_console_log_critical(mavlink_fd, "[sdlog2] failed opening: %s", log_file_name); |
|
|
|
|
mavlink_and_console_log_critical(mavlink_fd, "[log] failed: %s", log_file_name); |
|
|
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -671,7 +673,7 @@ void sdlog2_start_log()
@@ -671,7 +673,7 @@ void sdlog2_start_log()
|
|
|
|
|
|
|
|
|
|
/* create log dir if needed */ |
|
|
|
|
if (create_log_dir() != 0) { |
|
|
|
|
mavlink_and_console_log_critical(mavlink_fd, "[sdlog2] error creating log dir"); |
|
|
|
|
mavlink_and_console_log_critical(mavlink_fd, "[log] error creating log dir"); |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -761,7 +763,7 @@ void sdlog2_stop_log()
@@ -761,7 +763,7 @@ void sdlog2_stop_log()
|
|
|
|
|
/* free log writer performance counter */ |
|
|
|
|
perf_free(perf_write); |
|
|
|
|
|
|
|
|
|
mavlink_and_console_log_info(mavlink_fd, "[sdlog2] logging stopped"); |
|
|
|
|
mavlink_and_console_log_info(mavlink_fd, "[log] logging stopped"); |
|
|
|
|
|
|
|
|
|
sdlog2_status(); |
|
|
|
|
} |
|
|
|
@ -1912,7 +1914,7 @@ void sdlog2_status()
@@ -1912,7 +1914,7 @@ void sdlog2_status()
|
|
|
|
|
float seconds = ((float)(hrt_absolute_time() - start_time)) / 1000000.0f; |
|
|
|
|
|
|
|
|
|
warnx("wrote %lu msgs, %4.2f MiB (average %5.3f KiB/s), skipped %lu msgs", log_msgs_written, (double)mebibytes, (double)(kibibytes / seconds), log_msgs_skipped); |
|
|
|
|
mavlink_log_info(mavlink_fd, "[sdlog2] wrote %lu msgs, skipped %lu msgs", log_msgs_written, log_msgs_skipped); |
|
|
|
|
mavlink_log_info(mavlink_fd, "[log] wrote %lu msgs, skipped %lu msgs", log_msgs_written, log_msgs_skipped); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -1937,7 +1939,7 @@ int check_free_space()
@@ -1937,7 +1939,7 @@ int check_free_space()
|
|
|
|
|
/* use a threshold of 50 MiB */ |
|
|
|
|
if (statfs_buf.f_bavail < (px4_statfs_buf_f_bavail_t)(50 * 1024 * 1024 / statfs_buf.f_bsize)) { |
|
|
|
|
mavlink_and_console_log_critical(mavlink_fd, |
|
|
|
|
"[sdlog2] no space on MicroSD: %u MiB", |
|
|
|
|
"[log] no space on MicroSD: %u MiB", |
|
|
|
|
(unsigned int)(statfs_buf.f_bavail * statfs_buf.f_bsize) / (1024U * 1024U)); |
|
|
|
|
/* we do not need a flag to remember that we sent this warning because we will exit anyway */ |
|
|
|
|
return PX4_ERROR; |
|
|
|
@ -1945,7 +1947,7 @@ int check_free_space()
@@ -1945,7 +1947,7 @@ int check_free_space()
|
|
|
|
|
/* use a threshold of 100 MiB to send a warning */ |
|
|
|
|
} else if (!space_warning_sent && statfs_buf.f_bavail < (px4_statfs_buf_f_bavail_t)(100 * 1024 * 1024 / statfs_buf.f_bsize)) { |
|
|
|
|
mavlink_and_console_log_critical(mavlink_fd, |
|
|
|
|
"[sdlog2] space on MicroSD low: %u MiB", |
|
|
|
|
"[log] space on MicroSD low: %u MiB", |
|
|
|
|
(unsigned int)(statfs_buf.f_bavail * statfs_buf.f_bsize) / (1024U * 1024U)); |
|
|
|
|
/* we don't want to flood the user with warnings */ |
|
|
|
|
space_warning_sent = true; |
|
|
|
|