diff options
Diffstat (limited to 'src/modules/commander/commander.cpp')
-rw-r--r-- | src/modules/commander/commander.cpp | 19 |
1 files changed, 13 insertions, 6 deletions
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 55a44ac2e..453d5f921 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -156,7 +156,7 @@ enum MAV_MODE_FLAG { /* Mavlink file descriptors */ static int mavlink_fd = 0; -/* Syste autostart ID */ +/* System autostart ID */ static int autostart_id; /* flags */ @@ -822,6 +822,7 @@ int commander_thread_main(int argc, char *argv[]) param_t _param_ef_current2throttle_thres = param_find("COM_EF_C2T"); param_t _param_ef_time_thres = param_find("COM_EF_TIME"); param_t _param_autostart_id = param_find("SYS_AUTOSTART"); + param_t _param_autosave_params = param_find("COM_AUTOS_PAR"); const char *main_states_str[vehicle_status_s::MAIN_STATE_MAX]; main_states_str[vehicle_status_s::MAIN_STATE_MANUAL] = "MANUAL"; @@ -1128,6 +1129,8 @@ int commander_thread_main(int argc, char *argv[]) int32_t ef_time_thres = 1000.0f; uint64_t timestamp_engine_healthy = 0; /**< absolute time when engine was healty */ + int autosave_params; /**< Autosave of parameters enabled/disabled, loaded from parameter */ + /* check which state machines for changes, clear "changed" flag */ bool arming_state_changed = false; bool main_state_changed = false; @@ -1160,11 +1163,6 @@ int commander_thread_main(int argc, char *argv[]) /* update parameters */ orb_check(param_changed_sub, &updated); - if (updated) { - /* trigger an autosave */ - need_param_autosave = true; - } - if (updated || param_init_forced) { param_init_forced = false; @@ -1232,6 +1230,15 @@ int commander_thread_main(int argc, char *argv[]) /* Autostart id */ param_get(_param_autostart_id, &autostart_id); + + /* Parameter autosave setting */ + param_get(_param_autosave_params, &autosave_params); + } + + /* Set flag to autosave parameters if necessary */ + if (updated && autosave_params != 0) { + /* trigger an autosave */ + need_param_autosave = true; } orb_check(sp_man_sub, &updated); |