aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2015-04-03 16:14:04 +0200
committerLorenz Meier <lm@inf.ethz.ch>2015-04-10 17:30:22 +0200
commitf6f8d646d1b4f849af5f0eedcf1b17dc5267a47b (patch)
tree3e08612c6d16abcf07b4ae2b5a0adefb6bb5b8a5
parent7a2bb7c03a23438b249039cdd1cf3217b2347cae (diff)
downloadpx4-firmware-f6f8d646d1b4f849af5f0eedcf1b17dc5267a47b.tar.gz
px4-firmware-f6f8d646d1b4f849af5f0eedcf1b17dc5267a47b.tar.bz2
px4-firmware-f6f8d646d1b4f849af5f0eedcf1b17dc5267a47b.zip
commander: rename variable to avoid confusion with parameter
-rw-r--r--src/modules/commander/commander.cpp16
1 files changed, 8 insertions, 8 deletions
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index 2506857a9..55a44ac2e 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -164,7 +164,7 @@ static bool commander_initialized = false;
static volatile bool thread_should_exit = false; /**< daemon exit flag */
static volatile bool thread_running = false; /**< daemon status flag */
static int daemon_task; /**< Handle of daemon task / thread */
-static bool _param_autosave = false;
+static bool need_param_autosave = false; /**< Flag set to true if parameters should be autosaved in next iteration (happens on param update and if functionality is enabled) */
static unsigned int leds_counter;
/* To remember when last notification was sent */
@@ -1162,7 +1162,7 @@ int commander_thread_main(int argc, char *argv[])
if (updated) {
/* trigger an autosave */
- _param_autosave = true;
+ need_param_autosave = true;
}
if (updated || param_init_forced) {
@@ -2532,7 +2532,7 @@ void *commander_low_prio_loop(void *arg)
memset(&cmd, 0, sizeof(cmd));
/* timeout for param autosave */
- hrt_abstime _param_autosave_timeout = 0;
+ hrt_abstime need_param_autosave_timeout = 0;
/* wakeup source(s) */
struct pollfd fds[1];
@@ -2548,8 +2548,8 @@ void *commander_low_prio_loop(void *arg)
/* timed out - periodic check for thread_should_exit, etc. */
if (pret == 0) {
/* trigger a param autosave if required */
- if (_param_autosave) {
- if (_param_autosave_timeout > 0 && hrt_elapsed_time(&_param_autosave_timeout) > 200000ULL) {
+ if (need_param_autosave) {
+ if (need_param_autosave_timeout > 0 && hrt_elapsed_time(&need_param_autosave_timeout) > 200000ULL) {
int ret = param_save_default();
if (ret == OK) {
@@ -2559,10 +2559,10 @@ void *commander_low_prio_loop(void *arg)
mavlink_and_console_log_critical(mavlink_fd, "settings save error");
}
- _param_autosave = false;
- _param_autosave_timeout = 0;
+ need_param_autosave = false;
+ need_param_autosave_timeout = 0;
} else {
- _param_autosave_timeout = hrt_absolute_time();
+ need_param_autosave_timeout = hrt_absolute_time();
}
}
} else if (pret < 0) {