diff options
author | Anton Babushkin <anton.babushkin@me.com> | 2014-03-07 11:27:24 +0400 |
---|---|---|
committer | Anton Babushkin <anton.babushkin@me.com> | 2014-03-07 11:27:24 +0400 |
commit | 2ee8214244efbe09981e71ea194573daa1c2f5bc (patch) | |
tree | 77e5a0fced3b29d26853cd0937af0560b762452e /src/modules | |
parent | 85bb024537660472d88b626f58ad915bc9d4f1cd (diff) | |
download | px4-firmware-2ee8214244efbe09981e71ea194573daa1c2f5bc.tar.gz px4-firmware-2ee8214244efbe09981e71ea194573daa1c2f5bc.tar.bz2 px4-firmware-2ee8214244efbe09981e71ea194573daa1c2f5bc.zip |
sdlog2: move some global variables to local scope, set default log rate to 50 Hz
Diffstat (limited to 'src/modules')
-rw-r--r-- | src/modules/sdlog2/sdlog2.c | 15 |
1 files changed, 6 insertions, 9 deletions
diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index 5acd2b615..d784ecc4f 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -134,12 +134,6 @@ static uint64_t gps_time = 0; /* current state of logging */ static bool logging_enabled = false; -/* enable logging on start (-e option) */ -static bool log_on_start = false; -/* enable logging when armed (-a option) */ -static bool log_when_armed = false; -/* delay = 1 / rate (rate defined by -r option) */ -static useconds_t sleep_delay = 0; /* use date/time for naming directories and files (-t option) */ static bool log_name_timestamp = false; @@ -660,11 +654,14 @@ int sdlog2_thread_main(int argc, char *argv[]) warnx("failed to open MAVLink log stream, start mavlink app first"); } - useconds_t sleep_delay = 10000; // default log rate: 100 Hz + /* delay = 1 / rate (rate defined by -r option), default log rate: 50 Hz */ + useconds_t sleep_delay = 20000; int log_buffer_size = LOG_BUFFER_SIZE_DEFAULT; logging_enabled = false; - log_on_start = false; - log_when_armed = false; + /* enable logging on start (-e option) */ + bool log_on_start = false; + /* enable logging when armed (-a option) */ + bool log_when_armed = false; log_name_timestamp = false; flag_system_armed = false; |