aboutsummaryrefslogtreecommitdiff
path: root/src/modules/sdlog2
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2013-06-21 19:20:52 +0200
committerLorenz Meier <lm@inf.ethz.ch>2013-06-21 19:20:52 +0200
commitc8f4f84c2bc8a4302e28ac0b3a2af7807d82dc64 (patch)
tree403a55975b2b8de3221c258d8703c920c53c0949 /src/modules/sdlog2
parent34058ae565213dca27b0937737c5f818968996b5 (diff)
parent85b5da8078873a13a5fc0fd4ee3fe0a02917e87c (diff)
downloadpx4-firmware-c8f4f84c2bc8a4302e28ac0b3a2af7807d82dc64.tar.gz
px4-firmware-c8f4f84c2bc8a4302e28ac0b3a2af7807d82dc64.tar.bz2
px4-firmware-c8f4f84c2bc8a4302e28ac0b3a2af7807d82dc64.zip
Merged master
Diffstat (limited to 'src/modules/sdlog2')
-rw-r--r--src/modules/sdlog2/logbuffer.c2
-rw-r--r--src/modules/sdlog2/sdlog2.c154
-rw-r--r--src/modules/sdlog2/sdlog2_messages.h17
3 files changed, 107 insertions, 66 deletions
diff --git a/src/modules/sdlog2/logbuffer.c b/src/modules/sdlog2/logbuffer.c
index 8aaafaf31..2e1e4fd4d 100644
--- a/src/modules/sdlog2/logbuffer.c
+++ b/src/modules/sdlog2/logbuffer.c
@@ -121,7 +121,7 @@ int logbuffer_get_ptr(struct logbuffer_s *lb, void **ptr, bool *is_part)
} else {
// read pointer is after write pointer, read bytes from read_ptr to end of the buffer
n = lb->size - lb->read_ptr;
- *is_part = true;
+ *is_part = lb->write_ptr > 0;
}
*ptr = &(lb->data[lb->read_ptr]);
diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c
index 5bc503530..f7555af70 100644
--- a/src/modules/sdlog2/sdlog2.c
+++ b/src/modules/sdlog2/sdlog2.c
@@ -64,6 +64,7 @@
#include <uORB/topics/sensor_combined.h>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_attitude_setpoint.h>
+#include <uORB/topics/vehicle_rates_setpoint.h>
#include <uORB/topics/actuator_outputs.h>
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/actuator_controls_effective.h>
@@ -102,7 +103,7 @@
//#define SDLOG2_DEBUG
-static bool thread_should_exit = false; /**< Deamon exit flag */
+static bool main_thread_should_exit = false; /**< Deamon exit flag */
static bool thread_running = false; /**< Deamon status flag */
static int deamon_task; /**< Handle of deamon task / thread */
static bool logwriter_should_exit = false; /**< Logwriter thread exit flag */
@@ -113,35 +114,34 @@ static const int MAX_WRITE_CHUNK = 512;
static const int MIN_BYTES_TO_WRITE = 512;
static const char *mountpoint = "/fs/microsd";
-int log_file = -1;
-int mavlink_fd = -1;
+static int mavlink_fd = -1;
struct logbuffer_s lb;
/* mutex / condition to synchronize threads */
-pthread_mutex_t logbuffer_mutex;
-pthread_cond_t logbuffer_cond;
+static pthread_mutex_t logbuffer_mutex;
+static pthread_cond_t logbuffer_cond;
-char folder_path[64];
+static char folder_path[64];
/* statistics counters */
-unsigned long log_bytes_written = 0;
-uint64_t start_time = 0;
-unsigned long log_msgs_written = 0;
-unsigned long log_msgs_skipped = 0;
+static unsigned long log_bytes_written = 0;
+static uint64_t start_time = 0;
+static unsigned long log_msgs_written = 0;
+static unsigned long log_msgs_skipped = 0;
/* current state of logging */
-bool logging_enabled = false;
+static bool logging_enabled = false;
/* enable logging on start (-e option) */
-bool log_on_start = false;
+static bool log_on_start = false;
/* enable logging when armed (-a option) */
-bool log_when_armed = false;
+static bool log_when_armed = false;
/* delay = 1 / rate (rate defined by -r option) */
-useconds_t sleep_delay = 0;
+static useconds_t sleep_delay = 0;
/* helper flag to track system state changes */
-bool flag_system_armed = false;
+static bool flag_system_armed = false;
-pthread_t logwriter_pthread = 0;
+static pthread_t logwriter_pthread = 0;
/**
* Log buffer writing thread. Open and close file here.
@@ -171,17 +171,17 @@ static void sdlog2_status(void);
/**
* Start logging: create new file and start log writer thread.
*/
-void sdlog2_start_log();
+static void sdlog2_start_log(void);
/**
* Stop logging: stop log writer thread and close log file.
*/
-void sdlog2_stop_log();
+static void sdlog2_stop_log(void);
/**
* Write a header to log file: list of message formats.
*/
-void write_formats(int fd);
+static void write_formats(int fd);
static bool file_exist(const char *filename);
@@ -195,12 +195,12 @@ static void handle_status(struct vehicle_status_s *cmd);
/**
* Create folder for current logging session. Store folder name in 'log_folder'.
*/
-static int create_logfolder();
+static int create_logfolder(void);
/**
* Select first free log file name and open it.
*/
-static int open_logfile();
+static int open_logfile(void);
static void
sdlog2_usage(const char *reason)
@@ -236,7 +236,7 @@ int sdlog2_main(int argc, char *argv[])
exit(0);
}
- thread_should_exit = false;
+ main_thread_should_exit = false;
deamon_task = task_spawn_cmd("sdlog2",
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT - 30,
@@ -251,7 +251,7 @@ int sdlog2_main(int argc, char *argv[])
printf("\tsdlog2 is not started\n");
}
- thread_should_exit = true;
+ main_thread_should_exit = true;
exit(0);
}
@@ -285,22 +285,6 @@ int create_logfolder()
if (mkdir_ret == 0) {
/* folder does not exist, success */
-
- /* copy parser script file */
- // TODO
- /*
- char mfile_out[100];
- sprintf(mfile_out, "%s/session%04u/run_to_plot_data.m", mountpoint, foldernumber);
- int ret = file_copy(mfile_in, mfile_out);
-
- if (!ret) {
- warnx("copied m file to %s", mfile_out);
-
- } else {
- warnx("failed copying m file from %s to\n %s", mfile_in, mfile_out);
- }
- */
-
break;
} else if (mkdir_ret == -1) {
@@ -346,10 +330,10 @@ int open_logfile()
fd = open(path_buf, O_CREAT | O_WRONLY | O_DSYNC);
if (fd == 0) {
- errx(1, "opening %s failed.", path_buf);
+ warn("opening %s failed", path_buf);
}
- warnx("logging to: %s", path_buf);
+ warnx("logging to: %s.", path_buf);
mavlink_log_info(mavlink_fd, "[sdlog2] log: %s", path_buf);
return fd;
@@ -357,7 +341,7 @@ int open_logfile()
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 */
- warn("all %d possible files exist already", MAX_NO_LOGFILE);
+ warnx("all %d possible files exist already.", MAX_NO_LOGFILE);
return -1;
}
@@ -383,8 +367,7 @@ static void *logwriter_thread(void *arg)
bool should_wait = false;
bool is_part = false;
- while (!thread_should_exit && !logwriter_should_exit) {
-
+ while (true) {
/* make sure threads are synchronized */
pthread_mutex_lock(&logbuffer_mutex);
@@ -394,7 +377,7 @@ static void *logwriter_thread(void *arg)
}
/* only wait if no data is available to process */
- if (should_wait) {
+ if (should_wait && !logwriter_should_exit) {
/* blocking wait for new data at this line */
pthread_cond_wait(&logbuffer_cond, &logbuffer_mutex);
}
@@ -402,6 +385,11 @@ static void *logwriter_thread(void *arg)
/* only get pointer to thread-safe data, do heavy I/O a few lines down */
int available = logbuffer_get_ptr(logbuf, &read_ptr, &is_part);
+#ifdef SDLOG2_DEBUG
+ int rp = logbuf->read_ptr;
+ int wp = logbuf->write_ptr;
+#endif
+
/* continue */
pthread_mutex_unlock(&logbuffer_mutex);
@@ -418,11 +406,11 @@ static void *logwriter_thread(void *arg)
should_wait = (n == available) && !is_part;
#ifdef SDLOG2_DEBUG
- printf("%i wrote: %i of %i, is_part=%i, should_wait=%i", poll_count, n, available, (int)is_part, (int)should_wait);
+ printf("write %i %i of %i rp=%i wp=%i, is_part=%i, should_wait=%i\n", log_bytes_written, n, available, rp, wp, (int)is_part, (int)should_wait);
#endif
if (n < 0) {
- thread_should_exit = true;
+ main_thread_should_exit = true;
err(1, "error writing log file");
}
@@ -431,19 +419,33 @@ static void *logwriter_thread(void *arg)
}
} else {
+ n = 0;
+#ifdef SDLOG2_DEBUG
+ printf("no data available, main_thread_should_exit=%i, logwriter_should_exit=%i\n", (int)main_thread_should_exit, (int)logwriter_should_exit);
+#endif
+ /* exit only with empty buffer */
+ if (main_thread_should_exit || logwriter_should_exit) {
+#ifdef SDLOG2_DEBUG
+ printf("break logwriter thread\n");
+#endif
+ break;
+ }
should_wait = true;
}
- if (poll_count % 10 == 0) {
+ if (++poll_count == 10) {
fsync(log_file);
+ poll_count = 0;
}
-
- poll_count++;
}
fsync(log_file);
close(log_file);
+#ifdef SDLOG2_DEBUG
+ printf("logwriter thread exit\n");
+#endif
+
return OK;
}
@@ -470,10 +472,9 @@ void sdlog2_start_log()
pthread_attr_setstacksize(&receiveloop_attr, 2048);
logwriter_should_exit = false;
- pthread_t thread;
/* start log buffer emptying thread */
- if (0 != pthread_create(&thread, &receiveloop_attr, logwriter_thread, &lb)) {
+ if (0 != pthread_create(&logwriter_pthread, &receiveloop_attr, logwriter_thread, &lb)) {
errx(1, "error creating logwriter thread");
}
@@ -487,16 +488,20 @@ void sdlog2_stop_log()
mavlink_log_info(mavlink_fd, "[sdlog2] stop logging");
logging_enabled = false;
- logwriter_should_exit = true;
/* wake up write thread one last time */
pthread_mutex_lock(&logbuffer_mutex);
+ logwriter_should_exit = true;
pthread_cond_signal(&logbuffer_cond);
/* unlock, now the writer thread may return */
pthread_mutex_unlock(&logbuffer_mutex);
/* wait for write thread to return */
- (void)pthread_join(logwriter_pthread, NULL);
+ int ret;
+ if ((ret = pthread_join(logwriter_pthread, NULL)) != 0) {
+ warnx("error joining logwriter thread: %i", ret);
+ }
+ logwriter_pthread = 0;
sdlog2_status();
}
@@ -517,7 +522,7 @@ void write_formats(int fd)
for (i = 0; i < log_formats_num; i++) {
log_format_packet.body = log_formats[i];
- write(fd, &log_format_packet, sizeof(log_format_packet));
+ log_bytes_written += write(fd, &log_format_packet, sizeof(log_format_packet));
}
fsync(fd);
@@ -607,12 +612,9 @@ int sdlog2_thread_main(int argc, char *argv[])
errx(1, "can't allocate log buffer, exiting.");
}
- /* file descriptors to wait for */
- struct pollfd fds_control[2];
-
/* --- IMPORTANT: DEFINE NUMBER OF ORB STRUCTS TO WAIT FOR HERE --- */
/* number of messages */
- const ssize_t fdsc = 16;
+ const ssize_t fdsc = 17;
/* Sanity check variable and index */
ssize_t fdsc_count = 0;
/* file descriptors to wait for */
@@ -627,6 +629,7 @@ int sdlog2_thread_main(int argc, char *argv[])
struct sensor_combined_s sensor;
struct vehicle_attitude_s att;
struct vehicle_attitude_setpoint_s att_sp;
+ struct vehicle_rates_setpoint_s rates_sp;
struct actuator_outputs_s act_outputs;
struct actuator_controls_s act_controls;
struct actuator_controls_effective_s act_controls_effective;
@@ -648,6 +651,7 @@ int sdlog2_thread_main(int argc, char *argv[])
int sensor_sub;
int att_sub;
int att_sp_sub;
+ int rates_sp_sub;
int act_outputs_sub;
int act_controls_sub;
int act_controls_effective_sub;
@@ -679,6 +683,7 @@ int sdlog2_thread_main(int argc, char *argv[])
struct log_RC_s log_RC;
struct log_OUT0_s log_OUT0;
struct log_AIRS_s log_AIRS;
+ struct log_ARSP_s log_ARSP;
} body;
} log_msg = {
LOG_PACKET_HEADER_INIT(0)
@@ -722,6 +727,12 @@ int sdlog2_thread_main(int argc, char *argv[])
fds[fdsc_count].events = POLLIN;
fdsc_count++;
+ /* --- RATES SETPOINT --- */
+ subs.rates_sp_sub = orb_subscribe(ORB_ID(vehicle_rates_setpoint));
+ fds[fdsc_count].fd = subs.rates_sp_sub;
+ fds[fdsc_count].events = POLLIN;
+ fdsc_count++;
+
/* --- ACTUATOR OUTPUTS --- */
subs.act_outputs_sub = orb_subscribe(ORB_ID_VEHICLE_CONTROLS);
fds[fdsc_count].fd = subs.act_outputs_sub;
@@ -814,7 +825,7 @@ int sdlog2_thread_main(int argc, char *argv[])
if (log_on_start)
sdlog2_start_log();
- while (!thread_should_exit) {
+ while (!main_thread_should_exit) {
/* decide use usleep() or blocking poll() */
bool use_sleep = sleep_delay > 0 && logging_enabled;
@@ -824,7 +835,7 @@ int sdlog2_thread_main(int argc, char *argv[])
/* handle the poll result */
if (poll_ret < 0) {
warnx("ERROR: poll error, stop logging.");
- thread_should_exit = true;
+ main_thread_should_exit = true;
} else if (poll_ret > 0) {
@@ -891,7 +902,7 @@ int sdlog2_thread_main(int argc, char *argv[])
log_msg.body.log_GPS.epv = buf.gps_pos.epv_m;
log_msg.body.log_GPS.lat = buf.gps_pos.lat;
log_msg.body.log_GPS.lon = buf.gps_pos.lon;
- log_msg.body.log_GPS.alt = buf.gps_pos.alt * 0.001;
+ log_msg.body.log_GPS.alt = buf.gps_pos.alt * 0.001f;
log_msg.body.log_GPS.vel_n = buf.gps_pos.vel_n_m_s;
log_msg.body.log_GPS.vel_e = buf.gps_pos.vel_e_m_s;
log_msg.body.log_GPS.vel_d = buf.gps_pos.vel_d_m_s;
@@ -961,6 +972,9 @@ int sdlog2_thread_main(int argc, char *argv[])
log_msg.body.log_ATT.roll = buf.att.roll;
log_msg.body.log_ATT.pitch = buf.att.pitch;
log_msg.body.log_ATT.yaw = buf.att.yaw;
+ log_msg.body.log_ATT.roll_rate = buf.att.rollspeed;
+ log_msg.body.log_ATT.pitch_rate = buf.att.pitchspeed;
+ log_msg.body.log_ATT.yaw_rate = buf.att.yawspeed;
LOGBUFFER_WRITE_AND_COUNT(ATT);
}
@@ -971,9 +985,20 @@ int sdlog2_thread_main(int argc, char *argv[])
log_msg.body.log_ATSP.roll_sp = buf.att_sp.roll_body;
log_msg.body.log_ATSP.pitch_sp = buf.att_sp.pitch_body;
log_msg.body.log_ATSP.yaw_sp = buf.att_sp.yaw_body;
+ log_msg.body.log_ATSP.thrust_sp = buf.att_sp.thrust;
LOGBUFFER_WRITE_AND_COUNT(ATSP);
}
+ /* --- RATES SETPOINT --- */
+ if (fds[ifds++].revents & POLLIN) {
+ orb_copy(ORB_ID(vehicle_rates_setpoint), subs.rates_sp_sub, &buf.rates_sp);
+ log_msg.msg_type = LOG_ARSP_MSG;
+ log_msg.body.log_ARSP.roll_rate_sp = buf.rates_sp.roll;
+ log_msg.body.log_ARSP.pitch_rate_sp = buf.rates_sp.pitch;
+ log_msg.body.log_ARSP.yaw_rate_sp = buf.rates_sp.yaw;
+ LOGBUFFER_WRITE_AND_COUNT(ARSP);
+ }
+
/* --- ACTUATOR OUTPUTS --- */
if (fds[ifds++].revents & POLLIN) {
orb_copy(ORB_ID(actuator_outputs_0), subs.act_outputs_sub, &buf.act_outputs);
@@ -1063,10 +1088,13 @@ int sdlog2_thread_main(int argc, char *argv[])
LOGBUFFER_WRITE_AND_COUNT(AIRS);
}
+#ifdef SDLOG2_DEBUG
+ printf("fill rp=%i wp=%i count=%i\n", lb.read_ptr, lb.write_ptr, logbuffer_count(&lb));
+#endif
/* signal the other thread new data, but not yet unlock */
if (logbuffer_count(&lb) > MIN_BYTES_TO_WRITE) {
#ifdef SDLOG2_DEBUG
- printf("signal %i", logbuffer_count(&lb));
+ printf("signal rp=%i wp=%i count=%i\n", lb.read_ptr, lb.write_ptr, logbuffer_count(&lb));
#endif
/* only request write if several packets can be written at once */
pthread_cond_signal(&logbuffer_cond);
diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h
index c71f3b7e8..7f7bf6053 100644
--- a/src/modules/sdlog2/sdlog2_messages.h
+++ b/src/modules/sdlog2/sdlog2_messages.h
@@ -60,6 +60,9 @@ struct log_ATT_s {
float roll;
float pitch;
float yaw;
+ float roll_rate;
+ float pitch_rate;
+ float yaw_rate;
};
/* --- ATSP - ATTITUDE SET POINT --- */
@@ -68,6 +71,7 @@ struct log_ATSP_s {
float roll_sp;
float pitch_sp;
float yaw_sp;
+ float thrust_sp;
};
/* --- IMU - IMU SENSORS --- */
@@ -174,14 +178,22 @@ struct log_AIRS_s {
float indicated_airspeed;
float true_airspeed;
};
+
+/* --- ARSP - ATTITUDE RATE SET POINT --- */
+#define LOG_ARSP_MSG 14
+struct log_ARSP_s {
+ float roll_rate_sp;
+ float pitch_rate_sp;
+ float yaw_rate_sp;
+};
#pragma pack(pop)
/* construct list of all message formats */
static const struct log_format_s log_formats[] = {
LOG_FORMAT(TIME, "Q", "StartTime"),
- LOG_FORMAT(ATT, "fff", "Roll,Pitch,Yaw"),
- LOG_FORMAT(ATSP, "fff", "RollSP,PitchSP,YawSP"),
+ LOG_FORMAT(ATT, "ffffff", "Roll,Pitch,Yaw,RollRate,PitchRate,YawRate"),
+ LOG_FORMAT(ATSP, "ffff", "RollSP,PitchSP,YawSP,ThrustSP"),
LOG_FORMAT(IMU, "fffffffff", "AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ"),
LOG_FORMAT(SENS, "ffff", "BaroPres,BaroAlt,BaroTemp,DiffPres"),
LOG_FORMAT(LPOS, "fffffffLLf", "X,Y,Z,VX,VY,VZ,Heading,HomeLat,HomeLon,HomeAlt"),
@@ -192,6 +204,7 @@ static const struct log_format_s log_formats[] = {
LOG_FORMAT(RC, "ffffffff", "Ch0,Ch1,Ch2,Ch3,Ch4,Ch5,Ch6,Ch7"),
LOG_FORMAT(OUT0, "ffffffff", "Out0,Out1,Out2,Out3,Out4,Out5,Out6,Out7"),
LOG_FORMAT(AIRS, "ff", "IndSpeed,TrueSpeed"),
+ LOG_FORMAT(ARSP, "fff", "RollRateSP,PitchRateSP,YawRateSP"),
};
static const int log_formats_num = sizeof(log_formats) / sizeof(struct log_format_s);