logger: Add arm to shutdown

This commit is contained in:
murata 2023-01-12 07:44:53 +09:00 committed by Beat Küng
parent 35d6b734f5
commit c054ca20cc
4 changed files with 17 additions and 3 deletions

View File

@ -23,6 +23,12 @@ then
set LOGGER_ARGS "${LOGGER_ARGS} -x"
fi
if param compare SDLOG_MODE 4
then
set LOGGER_ARGS "${LOGGER_ARGS} -a"
fi
if ! param compare SDLOG_MODE -1
then
logger start -b ${LOGGER_BUF} -t ${LOGGER_ARGS}

View File

@ -257,7 +257,7 @@ Logger *Logger::instantiate(int argc, char *argv[])
int ch;
const char *myoptarg = nullptr;
while ((ch = px4_getopt(argc, argv, "r:b:etfm:p:xc:", &myoptind, &myoptarg)) != EOF) {
while ((ch = px4_getopt(argc, argv, "r:b:aetfm:p:xc:", &myoptind, &myoptarg)) != EOF) {
switch (ch) {
case 'r': {
unsigned long r = strtoul(myoptarg, nullptr, 10);
@ -291,6 +291,10 @@ Logger *Logger::instantiate(int argc, char *argv[])
log_mode = Logger::LogMode::boot_until_shutdown;
break;
case 'a':
log_mode = Logger::LogMode::arm_until_shutdown;
break;
case 'b': {
unsigned long s = strtoul(myoptarg, nullptr, 10);
@ -1113,7 +1117,8 @@ bool Logger::start_stop_logging()
if (_vehicle_status_sub.update(&vehicle_status)) {
desired_state = (vehicle_status.arming_state == vehicle_status_s::ARMING_STATE_ARMED);
desired_state = (vehicle_status.arming_state == vehicle_status_s::ARMING_STATE_ARMED) || (_prev_state
&& _log_mode == LogMode::arm_until_shutdown);
updated = true;
}
}
@ -2405,6 +2410,7 @@ $ logger on
PRINT_MODULE_USAGE_COMMAND("start");
PRINT_MODULE_USAGE_PARAM_STRING('m', "all", "file|mavlink|all", "Backend mode", true);
PRINT_MODULE_USAGE_PARAM_FLAG('x', "Enable/disable logging via Aux1 RC channel", true);
PRINT_MODULE_USAGE_PARAM_FLAG('a', "Log 1st armed until shutdown", true);
PRINT_MODULE_USAGE_PARAM_FLAG('e', "Enable logging right after start until disarm (otherwise only when armed)", true);
PRINT_MODULE_USAGE_PARAM_FLAG('f', "Log until shutdown (implies -e)", true);
PRINT_MODULE_USAGE_PARAM_FLAG('t', "Use date/time for naming log directories and files", true);

View File

@ -87,7 +87,8 @@ public:
while_armed = 0,
boot_until_disarm,
boot_until_shutdown,
rc_aux1
rc_aux1,
arm_until_shutdown,
};
Logger(LogWriter::Backend backend, size_t buffer_size, uint32_t log_interval, const char *poll_topic_name,

View File

@ -60,6 +60,7 @@ PARAM_DEFINE_INT32(SDLOG_UTC_OFFSET, 0);
* @value 1 from boot until disarm
* @value 2 from boot until shutdown
* @value 3 depending on AUX1 RC channel
* @value 4 from 1st armed until shutdown
*
* @reboot_required true
* @group SD Logging