Copter: increasd default logging for PX4, Pixhawk

This commit is contained in:
Randy Mackay 2013-12-05 16:04:52 +09:00
parent c5746e5434
commit 58788d2934
2 changed files with 28 additions and 72 deletions

View File

@ -352,7 +352,7 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Param: LOG_BITMASK
// @DisplayName: Log bitmask
// @Description: 2 byte bitmap of log types to enable
// @Values: 0:Disabled,830:Default,958:Default+IMU,1854:Default+Motors,17214:Default+INav
// @Values: 0:Disabled,830:Default,894:Default+RCIN,958:Default+IMU,1854:Default+Motors,17214:Default+INav,-6146:NearlyAll
// @User: Standard
GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK),

View File

@ -940,78 +940,34 @@
# define LOGGING_ENABLED ENABLED
#endif
#ifndef LOG_ATTITUDE_FAST
# define LOG_ATTITUDE_FAST DISABLED
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2
// APM1 & APM2 default logging
# define DEFAULT_LOG_BITMASK \
MASK_LOG_ATTITUDE_MED | \
MASK_LOG_GPS | \
MASK_LOG_PM | \
MASK_LOG_CTUN | \
MASK_LOG_NTUN | \
MASK_LOG_RCIN | \
MASK_LOG_CMD | \
MASK_LOG_CURRENT
#else
// PX4, Pixhawk, FlyMaple default logging
# define DEFAULT_LOG_BITMASK \
MASK_LOG_ATTITUDE_MED | \
MASK_LOG_GPS | \
MASK_LOG_PM | \
MASK_LOG_CTUN | \
MASK_LOG_NTUN | \
MASK_LOG_RCIN | \
MASK_LOG_IMU | \
MASK_LOG_CMD | \
MASK_LOG_CURRENT | \
MASK_LOG_RCOUT | \
MASK_LOG_COMPASS | \
MASK_LOG_INAV | \
MASK_LOG_CAMERA
#endif
#ifndef LOG_ATTITUDE_MED
# define LOG_ATTITUDE_MED ENABLED
#endif
#ifndef LOG_GPS
# define LOG_GPS ENABLED
#endif
#ifndef LOG_PM
# define LOG_PM ENABLED
#endif
#ifndef LOG_CTUN
# define LOG_CTUN ENABLED
#endif
#ifndef LOG_NTUN
# define LOG_NTUN ENABLED
#endif
#ifndef LOG_RCIN
# define LOG_RCIN ENABLED
#endif
#ifndef LOG_IMU
# define LOG_IMU DISABLED
#endif
#ifndef LOG_CMD
# define LOG_CMD ENABLED
#endif
// current
#ifndef LOG_CURRENT
# define LOG_CURRENT ENABLED
#endif
// quad motor PWMs
#ifndef LOG_RCOUT
# define LOG_RCOUT DISABLED
#endif
// optical flow
#ifndef LOG_OPTFLOW
# define LOG_OPTFLOW DISABLED
#endif
#ifndef LOG_PID
# define LOG_PID DISABLED
#endif
#ifndef LOG_COMPASS
# define LOG_COMPASS DISABLED
#endif
#ifndef LOG_INAV
# define LOG_INAV DISABLED
#endif
#ifndef LOG_CAMERA
# define LOG_CAMERA ENABLED
#endif
// calculate the default log_bitmask
#define LOGBIT(_s) (LOG_ ## _s ? MASK_LOG_ ## _s : 0)
#define DEFAULT_LOG_BITMASK \
LOGBIT(ATTITUDE_FAST) | \
LOGBIT(ATTITUDE_MED) | \
LOGBIT(GPS) | \
LOGBIT(PM) | \
LOGBIT(CTUN) | \
LOGBIT(NTUN) | \
LOGBIT(RCIN) | \
LOGBIT(IMU) | \
LOGBIT(CMD) | \
LOGBIT(CURRENT) | \
LOGBIT(RCOUT) | \
LOGBIT(OPTFLOW) | \
LOGBIT(PID) | \
LOGBIT(COMPASS) | \
LOGBIT(INAV)
//////////////////////////////////////////////////////////////////////////////
// AP_Limits Defaults