logger: check if we are in replay mode via ENV variable 'replay'

This commit is contained in:
Beat Küng
2016-06-10 12:45:22 +02:00
committed by Lorenz Meier
parent 28ad6066aa
commit 84a1a10006
2 changed files with 15 additions and 4 deletions
+13 -1
View File
@@ -37,6 +37,7 @@
#include <sys/stat.h>
#include <errno.h>
#include <string.h>
#include <stdlib.h>
#include <time.h>
#include <uORB/uORB.h>
@@ -51,6 +52,7 @@
#include <px4_getopt.h>
#include <px4_log.h>
#include <systemlib/mavlink_log.h>
#include <replay/definitions.hpp>
#ifdef __PX4_DARWIN
#include <sys/param.h>
@@ -82,7 +84,6 @@ static int logger_task = -1;
static pthread_t writer_thread;
char *Logger::_replay_file_name = nullptr;
int logger_main(int argc, char *argv[])
{
@@ -312,6 +313,13 @@ void Logger::run_trampoline(int argc, char *argv[])
PX4_ERR("alloc failed");
} else {
//check for replay mode
const char *logfile = getenv(px4::replay::ENV_FILENAME);
if (logfile) {
logger_ptr->setReplayFile(logfile);
}
logger_ptr->run();
}
@@ -353,6 +361,10 @@ Logger::~Logger()
} while (logger_task != -1);
}
if (_replay_file_name) {
free(_replay_file_name);
}
if (_msg_buffer) {
delete[](_msg_buffer);
}