Browse Source

sdlog2 -b option (log buffer size) added, minor cleanup

sbg
Anton Babushkin 12 years ago
parent
commit
59b26eca48
  1. 3
      src/modules/sdlog2/logbuffer.c
  2. 4
      src/modules/sdlog2/logbuffer.h
  3. 50
      src/modules/sdlog2/sdlog2.c

3
src/modules/sdlog2/logbuffer.c

@ -45,12 +45,13 @@
#include "logbuffer.h" #include "logbuffer.h"
void logbuffer_init(struct logbuffer_s *lb, int size) int logbuffer_init(struct logbuffer_s *lb, int size)
{ {
lb->size = size; lb->size = size;
lb->write_ptr = 0; lb->write_ptr = 0;
lb->read_ptr = 0; lb->read_ptr = 0;
lb->data = malloc(lb->size); lb->data = malloc(lb->size);
return (lb->data == 0) ? ERROR : OK;
} }
int logbuffer_count(struct logbuffer_s *lb) int logbuffer_count(struct logbuffer_s *lb)

4
src/modules/sdlog2/logbuffer.h

@ -46,14 +46,14 @@
#include <stdbool.h> #include <stdbool.h>
struct logbuffer_s { struct logbuffer_s {
// all pointers are in bytes // pointers and size are in bytes
int write_ptr; int write_ptr;
int read_ptr; int read_ptr;
int size; int size;
char *data; char *data;
}; };
void logbuffer_init(struct logbuffer_s *lb, int size); int logbuffer_init(struct logbuffer_s *lb, int size);
int logbuffer_count(struct logbuffer_s *lb); int logbuffer_count(struct logbuffer_s *lb);

50
src/modules/sdlog2/sdlog2.c

@ -94,9 +94,9 @@
} }
#define LOG_ORB_SUBSCRIBE(_var, _topic) subs.##_var##_sub = orb_subscribe(ORB_ID(##_topic##)); \ #define LOG_ORB_SUBSCRIBE(_var, _topic) subs.##_var##_sub = orb_subscribe(ORB_ID(##_topic##)); \
fds[fdsc_count].fd = subs.##_var##_sub; \ fds[fdsc_count].fd = subs.##_var##_sub; \
fds[fdsc_count].events = POLLIN; \ fds[fdsc_count].events = POLLIN; \
fdsc_count++; fdsc_count++;
//#define SDLOG2_DEBUG //#define SDLOG2_DEBUG
@ -107,7 +107,7 @@ static int deamon_task; /**< Handle of deamon task / thread */
static bool logwriter_should_exit = false; /**< Logwriter thread exit flag */ static bool logwriter_should_exit = false; /**< Logwriter thread exit flag */
static const int MAX_NO_LOGFOLDER = 999; /**< Maximum number of log folders */ static const int MAX_NO_LOGFOLDER = 999; /**< Maximum number of log folders */
static const int MAX_NO_LOGFILE = 999; /**< Maximum number of log files */ static const int MAX_NO_LOGFILE = 999; /**< Maximum number of log files */
static const int LOG_BUFFER_SIZE = 8192; static const int LOG_BUFFER_SIZE_DEFAULT = 8192;
static const int MAX_WRITE_CHUNK = 512; static const int MAX_WRITE_CHUNK = 512;
static const int MIN_BYTES_TO_WRITE = 512; static const int MIN_BYTES_TO_WRITE = 512;
@ -207,8 +207,9 @@ sdlog2_usage(const char *reason)
if (reason) if (reason)
fprintf(stderr, "%s\n", reason); fprintf(stderr, "%s\n", reason);
errx(1, "usage: sdlog2 {start|stop|status} [-r <log rate>] -e -a\n" errx(1, "usage: sdlog2 {start|stop|status} [-r <log rate>] [-b <buffer size>] -e -a\n"
"\t-r\tLog rate in Hz, 0 means unlimited rate\n" "\t-r\tLog rate in Hz, 0 means unlimited rate\n"
"\t-r\tLog buffer size in KBytes, default is 8\n"
"\t-e\tEnable logging by default (if not, can be started by command)\n" "\t-e\tEnable logging by default (if not, can be started by command)\n"
"\t-a\tLog only when armed (can be still overriden by command)\n"); "\t-a\tLog only when armed (can be still overriden by command)\n");
} }
@ -529,18 +530,18 @@ int sdlog2_thread_main(int argc, char *argv[])
warnx("failed to open MAVLink log stream, start mavlink app first."); warnx("failed to open MAVLink log stream, start mavlink app first.");
} }
/* log every n'th value (skip three per default) */ /* log buffer size */
int skip_value = 3; int log_buffer_size = LOG_BUFFER_SIZE_DEFAULT;
/* work around some stupidity in task_create's argv handling */ /* work around some stupidity in task_create's argv handling */
argc -= 2; argc -= 2;
argv += 2; argv += 2;
int ch; int ch;
while ((ch = getopt(argc, argv, "r:ea")) != EOF) { while ((ch = getopt(argc, argv, "r:b:ea")) != EOF) {
switch (ch) { switch (ch) {
case 'r': { case 'r': {
unsigned r = strtoul(optarg, NULL, 10); unsigned long r = strtoul(optarg, NULL, 10);
if (r == 0) { if (r == 0) {
sleep_delay = 0; sleep_delay = 0;
@ -551,6 +552,20 @@ int sdlog2_thread_main(int argc, char *argv[])
} }
break; break;
case 'b': {
unsigned long s = strtoul(optarg, NULL, 10);
if (s < 1) {
s = 1;
} else if (s > 640) {
s = 640;
}
log_buffer_size = 1024 * s;
}
break;
case 'e': case 'e':
log_on_start = true; log_on_start = true;
break; break;
@ -572,7 +587,7 @@ int sdlog2_thread_main(int argc, char *argv[])
default: default:
sdlog2_usage("unrecognized flag"); sdlog2_usage("unrecognized flag");
errx(1, "exiting"); errx(1, "exiting.");
} }
} }
@ -580,12 +595,20 @@ int sdlog2_thread_main(int argc, char *argv[])
errx(1, "logging mount point %s not present, exiting.", mountpoint); errx(1, "logging mount point %s not present, exiting.", mountpoint);
} }
if (create_logfolder()) if (create_logfolder()) {
errx(1, "unable to create logging folder, exiting."); errx(1, "unable to create logging folder, exiting.");
}
/* only print logging path, important to find log file later */ /* only print logging path, important to find log file later */
warnx("logging to directory: %s", folder_path); warnx("logging to directory: %s", folder_path);
/* initialize log buffer with specified size */
warnx("log buffer size: %i bytes.", log_buffer_size);
if (OK != logbuffer_init(&lb, log_buffer_size)) {
errx(1, "can't allocate log buffer, exiting.");
}
/* file descriptors to wait for */ /* file descriptors to wait for */
struct pollfd fds_control[2]; struct pollfd fds_control[2];
@ -770,9 +793,6 @@ int sdlog2_thread_main(int argc, char *argv[])
thread_running = true; thread_running = true;
/* initialize log buffer with specified size */
logbuffer_init(&lb, LOG_BUFFER_SIZE);
/* initialize thread synchronization */ /* initialize thread synchronization */
pthread_mutex_init(&logbuffer_mutex, NULL); pthread_mutex_init(&logbuffer_mutex, NULL);
pthread_cond_init(&logbuffer_cond, NULL); pthread_cond_init(&logbuffer_cond, NULL);
@ -818,9 +838,11 @@ int sdlog2_thread_main(int argc, char *argv[])
/* --- VEHICLE STATUS - LOG MANAGEMENT --- */ /* --- VEHICLE STATUS - LOG MANAGEMENT --- */
if (fds[ifds++].revents & POLLIN) { if (fds[ifds++].revents & POLLIN) {
orb_copy(ORB_ID(vehicle_status), subs.status_sub, &buf_status); orb_copy(ORB_ID(vehicle_status), subs.status_sub, &buf_status);
if (log_when_armed) { if (log_when_armed) {
handle_status(&buf_status); handle_status(&buf_status);
} }
handled_topics++; handled_topics++;
} }

Loading…
Cancel
Save