|
|
|
@ -1,6 +1,6 @@
@@ -1,6 +1,6 @@
|
|
|
|
|
/****************************************************************************
|
|
|
|
|
* |
|
|
|
|
* Copyright (c) 2012-2014 PX4 Development Team. All rights reserved. |
|
|
|
|
* Copyright (c) 2012-2015 PX4 Development Team. All rights reserved. |
|
|
|
|
* |
|
|
|
|
* Redistribution and use in source and binary forms, with or without |
|
|
|
|
* modification, are permitted provided that the following conditions |
|
|
|
@ -39,12 +39,14 @@
@@ -39,12 +39,14 @@
|
|
|
|
|
* |
|
|
|
|
* @author Lorenz Meier <lm@inf.ethz.ch> |
|
|
|
|
* @author Anton Babushkin <anton.babushkin@me.com> |
|
|
|
|
* @author Ban Siesta <bansiesta@gmail.com> |
|
|
|
|
*/ |
|
|
|
|
|
|
|
|
|
#include <nuttx/config.h> |
|
|
|
|
#include <sys/types.h> |
|
|
|
|
#include <sys/stat.h> |
|
|
|
|
#include <sys/prctl.h> |
|
|
|
|
#include <sys/statfs.h> |
|
|
|
|
#include <fcntl.h> |
|
|
|
|
#include <errno.h> |
|
|
|
|
#include <unistd.h> |
|
|
|
@ -161,7 +163,9 @@ static const int MIN_BYTES_TO_WRITE = 512;
@@ -161,7 +163,9 @@ static const int MIN_BYTES_TO_WRITE = 512;
|
|
|
|
|
|
|
|
|
|
static bool _extended_logging = false; |
|
|
|
|
|
|
|
|
|
static const char *log_root = "/fs/microsd/log"; |
|
|
|
|
#define MOUNTPOINT "/fs/microsd" |
|
|
|
|
static const char *mountpoint = MOUNTPOINT; |
|
|
|
|
static const char *log_root = MOUNTPOINT "/log"; |
|
|
|
|
static int mavlink_fd = -1; |
|
|
|
|
struct logbuffer_s lb; |
|
|
|
|
|
|
|
|
@ -174,6 +178,7 @@ static char log_dir[32];
@@ -174,6 +178,7 @@ static char log_dir[32];
|
|
|
|
|
/* statistics counters */ |
|
|
|
|
static uint64_t start_time = 0; |
|
|
|
|
static unsigned long log_bytes_written = 0; |
|
|
|
|
static unsigned long last_checked_bytes_written = 0; |
|
|
|
|
static unsigned long log_msgs_written = 0; |
|
|
|
|
static unsigned long log_msgs_skipped = 0; |
|
|
|
|
|
|
|
|
@ -188,6 +193,9 @@ static bool log_name_timestamp = false;
@@ -188,6 +193,9 @@ static bool log_name_timestamp = false;
|
|
|
|
|
/* helper flag to track system state changes */ |
|
|
|
|
static bool flag_system_armed = false; |
|
|
|
|
|
|
|
|
|
/* flag if warning about MicroSD card being almost full has already been sent */ |
|
|
|
|
static bool space_warning_sent = false; |
|
|
|
|
|
|
|
|
|
static pthread_t logwriter_pthread = 0; |
|
|
|
|
static pthread_attr_t logwriter_attr; |
|
|
|
|
|
|
|
|
@ -247,6 +255,11 @@ static bool file_exist(const char *filename);
@@ -247,6 +255,11 @@ static bool file_exist(const char *filename);
|
|
|
|
|
|
|
|
|
|
static int file_copy(const char *file_old, const char *file_new); |
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Check if there is still free space available |
|
|
|
|
*/ |
|
|
|
|
static int check_free_space(void); |
|
|
|
|
|
|
|
|
|
static void handle_command(struct vehicle_command_s *cmd); |
|
|
|
|
|
|
|
|
|
static void handle_status(struct vehicle_status_s *cmd); |
|
|
|
@ -390,8 +403,7 @@ int create_log_dir()
@@ -390,8 +403,7 @@ int create_log_dir()
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/* print logging path, important to find log file later */ |
|
|
|
|
warnx("log dir: %s", log_dir); |
|
|
|
|
mavlink_log_info(mavlink_fd, "[sdlog2] log dir: %s", log_dir); |
|
|
|
|
mavlink_and_console_log_info(mavlink_fd, "[sdlog2] log dir: %s", log_dir); |
|
|
|
|
return 0; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -431,7 +443,7 @@ int open_log_file()
@@ -431,7 +443,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_log_critical(mavlink_fd, "[sdlog2] ERR: max files %d", MAX_NO_LOGFILE); |
|
|
|
|
mavlink_and_console_log_critical(mavlink_fd, "[sdlog2] ERR: max files %d", MAX_NO_LOGFILE); |
|
|
|
|
return -1; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
@ -439,12 +451,10 @@ int open_log_file()
@@ -439,12 +451,10 @@ int open_log_file()
|
|
|
|
|
int fd = open(log_file_path, O_CREAT | O_WRONLY | O_DSYNC); |
|
|
|
|
|
|
|
|
|
if (fd < 0) { |
|
|
|
|
warn("failed opening log: %s", log_file_name); |
|
|
|
|
mavlink_log_critical(mavlink_fd, "[sdlog2] failed opening log: %s", log_file_name); |
|
|
|
|
mavlink_and_console_log_critical(mavlink_fd, "[sdlog2] failed opening log: %s", log_file_name); |
|
|
|
|
|
|
|
|
|
} else { |
|
|
|
|
warnx("log file: %s", log_file_name); |
|
|
|
|
mavlink_log_info(mavlink_fd, "[sdlog2] log file: %s", log_file_name); |
|
|
|
|
mavlink_and_console_log_info(mavlink_fd, "[sdlog2] log file: %s", log_file_name); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
return fd; |
|
|
|
@ -485,7 +495,7 @@ int open_perf_file(const char* str)
@@ -485,7 +495,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_log_critical(mavlink_fd, "[sdlog2] ERR: max files %d", MAX_NO_LOGFILE); |
|
|
|
|
mavlink_and_console_log_critical(mavlink_fd, "[sdlog2] ERR: max files %d", MAX_NO_LOGFILE); |
|
|
|
|
return -1; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
@ -493,12 +503,8 @@ int open_perf_file(const char* str)
@@ -493,12 +503,8 @@ int open_perf_file(const char* str)
|
|
|
|
|
int fd = open(log_file_path, O_CREAT | O_WRONLY | O_DSYNC); |
|
|
|
|
|
|
|
|
|
if (fd < 0) { |
|
|
|
|
warn("failed opening log: %s", log_file_name); |
|
|
|
|
mavlink_log_critical(mavlink_fd, "[sdlog2] failed opening log: %s", log_file_name); |
|
|
|
|
mavlink_and_console_log_critical(mavlink_fd, "[sdlog2] failed opening: %s", log_file_name); |
|
|
|
|
|
|
|
|
|
} else { |
|
|
|
|
warnx("log file: %s", log_file_name); |
|
|
|
|
mavlink_log_info(mavlink_fd, "[sdlog2] log file: %s", log_file_name); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
return fd; |
|
|
|
@ -560,6 +566,7 @@ static void *logwriter_thread(void *arg)
@@ -560,6 +566,7 @@ static void *logwriter_thread(void *arg)
|
|
|
|
|
pthread_mutex_unlock(&logbuffer_mutex); |
|
|
|
|
|
|
|
|
|
if (available > 0) { |
|
|
|
|
|
|
|
|
|
/* do heavy IO here */ |
|
|
|
|
if (available > MAX_WRITE_CHUNK) { |
|
|
|
|
n = MAX_WRITE_CHUNK; |
|
|
|
@ -597,6 +604,16 @@ static void *logwriter_thread(void *arg)
@@ -597,6 +604,16 @@ static void *logwriter_thread(void *arg)
|
|
|
|
|
if (++poll_count == 10) { |
|
|
|
|
fsync(log_fd); |
|
|
|
|
poll_count = 0; |
|
|
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (log_bytes_written - last_checked_bytes_written > 20*1024*1024) { |
|
|
|
|
/* check if space is available, if not stop everything */ |
|
|
|
|
if (check_free_space() != OK) { |
|
|
|
|
logwriter_should_exit = true; |
|
|
|
|
main_thread_should_exit = true; |
|
|
|
|
} |
|
|
|
|
last_checked_bytes_written = log_bytes_written; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -611,15 +628,15 @@ static void *logwriter_thread(void *arg)
@@ -611,15 +628,15 @@ static void *logwriter_thread(void *arg)
|
|
|
|
|
|
|
|
|
|
void sdlog2_start_log() |
|
|
|
|
{ |
|
|
|
|
warnx("start logging"); |
|
|
|
|
mavlink_log_info(mavlink_fd, "[sdlog2] start logging"); |
|
|
|
|
mavlink_and_console_log_info(mavlink_fd, "[sdlog2] start logging"); |
|
|
|
|
|
|
|
|
|
/* create log dir if needed */ |
|
|
|
|
if (create_log_dir() != 0) { |
|
|
|
|
mavlink_log_critical(mavlink_fd, "[sdlog2] error creating log dir"); |
|
|
|
|
errx(1, "error creating log dir"); |
|
|
|
|
mavlink_and_console_log_critical(mavlink_fd, "[sdlog2] error creating log dir"); |
|
|
|
|
exit(1); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
/* initialize statistics counter */ |
|
|
|
|
log_bytes_written = 0; |
|
|
|
|
start_time = hrt_absolute_time(); |
|
|
|
@ -657,8 +674,7 @@ void sdlog2_start_log()
@@ -657,8 +674,7 @@ void sdlog2_start_log()
|
|
|
|
|
|
|
|
|
|
void sdlog2_stop_log() |
|
|
|
|
{ |
|
|
|
|
warnx("stop logging"); |
|
|
|
|
mavlink_log_info(mavlink_fd, "[sdlog2] stop logging"); |
|
|
|
|
mavlink_and_console_log_info(mavlink_fd, "[sdlog2] stop logging"); |
|
|
|
|
|
|
|
|
|
logging_enabled = false; |
|
|
|
|
|
|
|
|
@ -784,7 +800,7 @@ int sdlog2_thread_main(int argc, char *argv[])
@@ -784,7 +800,7 @@ int sdlog2_thread_main(int argc, char *argv[])
|
|
|
|
|
mavlink_fd = open(MAVLINK_LOG_DEVICE, 0); |
|
|
|
|
|
|
|
|
|
if (mavlink_fd < 0) { |
|
|
|
|
warnx("failed to open MAVLink log stream, start mavlink app first"); |
|
|
|
|
warnx("ERR: log stream, start mavlink app first"); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/* delay = 1 / rate (rate defined by -r option), default log rate: 50 Hz */ |
|
|
|
@ -912,11 +928,17 @@ int sdlog2_thread_main(int argc, char *argv[])
@@ -912,11 +928,17 @@ int sdlog2_thread_main(int argc, char *argv[])
|
|
|
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
if (check_free_space() != OK) { |
|
|
|
|
errx(1, "ERR: MicroSD almost full"); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
/* create log root dir */ |
|
|
|
|
int mkdir_ret = mkdir(log_root, S_IRWXU | S_IRWXG | S_IRWXO); |
|
|
|
|
|
|
|
|
|
if (mkdir_ret != 0 && errno != EEXIST) { |
|
|
|
|
err(1, "failed creating log root dir: %s", log_root); |
|
|
|
|
err(1, "ERR: failed creating log dir: %s", log_root); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/* copy conversion scripts */ |
|
|
|
@ -1768,8 +1790,6 @@ int sdlog2_thread_main(int argc, char *argv[])
@@ -1768,8 +1790,6 @@ int sdlog2_thread_main(int argc, char *argv[])
|
|
|
|
|
|
|
|
|
|
free(lb.data); |
|
|
|
|
|
|
|
|
|
warnx("exiting"); |
|
|
|
|
|
|
|
|
|
thread_running = false; |
|
|
|
|
|
|
|
|
|
return 0; |
|
|
|
@ -1802,7 +1822,7 @@ int file_copy(const char *file_old, const char *file_new)
@@ -1802,7 +1822,7 @@ int file_copy(const char *file_old, const char *file_new)
|
|
|
|
|
int ret = 0; |
|
|
|
|
|
|
|
|
|
if (source == NULL) { |
|
|
|
|
warnx("failed opening input file to copy"); |
|
|
|
|
warnx("ERR: open in"); |
|
|
|
|
return 1; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -1810,7 +1830,7 @@ int file_copy(const char *file_old, const char *file_new)
@@ -1810,7 +1830,7 @@ int file_copy(const char *file_old, const char *file_new)
|
|
|
|
|
|
|
|
|
|
if (target == NULL) { |
|
|
|
|
fclose(source); |
|
|
|
|
warnx("failed to open output file to copy"); |
|
|
|
|
warnx("ERR: open out"); |
|
|
|
|
return 1; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -1835,6 +1855,34 @@ int file_copy(const char *file_old, const char *file_new)
@@ -1835,6 +1855,34 @@ int file_copy(const char *file_old, const char *file_new)
|
|
|
|
|
return OK; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
int check_free_space() |
|
|
|
|
{ |
|
|
|
|
/* use statfs to determine the number of blocks left */ |
|
|
|
|
FAR struct statfs statfs_buf; |
|
|
|
|
if (statfs(mountpoint, &statfs_buf) != OK) { |
|
|
|
|
errx(ERROR, "ERR: statfs"); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/* use a threshold of 50 MiB */ |
|
|
|
|
if (statfs_buf.f_bavail < (int)(50 * 1024 * 1024 / statfs_buf.f_bsize)) { |
|
|
|
|
mavlink_and_console_log_critical(mavlink_fd, |
|
|
|
|
"[sdlog2] 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 ERROR; |
|
|
|
|
|
|
|
|
|
/* use a threshold of 100 MiB to send a warning */ |
|
|
|
|
} else if (!space_warning_sent && statfs_buf.f_bavail < (int)(100 * 1024 * 1024 / statfs_buf.f_bsize)) { |
|
|
|
|
mavlink_and_console_log_critical(mavlink_fd, |
|
|
|
|
"[sdlog2] 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; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
return OK; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void handle_command(struct vehicle_command_s *cmd) |
|
|
|
|
{ |
|
|
|
|
int param; |
|
|
|
|