Browse Source

logger params: add SDLOG_MODE to select when to start & stop logging

sbg
Beat Küng 8 years ago committed by Lorenz Meier
parent
commit
9301e9cc50
  1. 28
      ROMFS/px4fmu_common/init.d/rcS
  2. 19
      src/modules/logger/params.c

28
ROMFS/px4fmu_common/init.d/rcS

@ -658,30 +658,34 @@ then @@ -658,30 +658,34 @@ then
then
fi
else
# check if we should increase logging rate for ekf2 replay message logging
if param greater EKF2_REC_RPL 0
if param compare SYS_LOGGER 0
then
if param compare SYS_LOGGER 0
# check if we should increase logging rate for ekf2 replay message logging
if param greater EKF2_REC_RPL 0
then
if sdlog2 start -r 500 -e -b 18 -t
then
fi
else
if logger start -r 500
if sdlog2 start -r 100 -a -b 9 -t
then
fi
fi
else
if param compare SYS_LOGGER 0
set LOGGER_ARGS ""
if param compare SDLOG_MODE 1
then
set LOGGER_ARGS "-e"
fi
if param compare SDLOG_MODE 2
then
set LOGGER_ARGS "-f"
fi
if logger start -b 12 -t $LOGGER_ARGS
then
if sdlog2 start -r 100 -a -b 9 -t
then
fi
else
if logger start -b 12 -t
then
fi
fi
unset LOGGER_ARGS
fi
fi

19
src/modules/logger/params.c

@ -48,3 +48,22 @@ @@ -48,3 +48,22 @@
* @group SD Logging
*/
PARAM_DEFINE_INT32(SDLOG_UTC_OFFSET, 0);
/**
* Logging Mode
*
* Determines when to start and stop logging. By default, logging is started
* when arming the system, and stopped when disarming.
*
* This parameter is only for the new logger (SYS_LOGGER=1).
*
* @value 0 when armed until disarm (default)
* @value 1 from boot until disarm
* @value 2 from boot until shutdown
*
* @min 0
* @max 2
* @reboot_required true
* @group SD Logging
*/
PARAM_DEFINE_INT32(SDLOG_MODE, 0);

Loading…
Cancel
Save