re-apply DEFAULT_LOG_BITMASK patch

Jason, I assume you removed this patch accidentially

git-svn-id: https://arducopter.googlecode.com/svn/trunk@2995 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
tridge60@gmail.com 2011-08-01 10:06:15 +00:00
parent 9371ee545e
commit dd3dfd9f2a
6 changed files with 18 additions and 32 deletions

View File

@ -170,7 +170,6 @@ select_logs(uint8_t argc, const Menu::arg *argv)
//
if (!strcasecmp_P(argv[1].str, PSTR("all"))) {
bits = ~0;
bits = bits ^ MASK_LOG_SET_DEFAULTS;
} else {
#define TARG(_s) if (!strcasecmp_P(argv[1].str, PSTR(#_s))) bits |= MASK_LOG_ ## _s
TARG(ATTITUDE_FAST);

View File

@ -316,7 +316,7 @@ public:
pitch_max (PITCH_MAX * 100, k_param_pitch_max, PSTR("PITCH_MAX")),
log_bitmask (MASK_LOG_SET_DEFAULTS, k_param_log_bitmask, PSTR("LOG_BITMASK")),
log_bitmask (DEFAULT_LOG_BITMASK, k_param_log_bitmask, PSTR("LOG_BITMASK")),
RTL_altitude (ALT_HOLD_HOME * 100, k_param_RTL_altitude, PSTR("ALT_HOLD_RTL")),
esc_calibrate (0, k_param_esc_calibrate, PSTR("ESC")),
frame_orientation (FRAME_ORIENTATION, k_param_frame_orientation, PSTR("FRAME")),

View File

@ -516,6 +516,23 @@
# define LOG_OPTFLOW DISABLED
#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(MODE) | \
LOGBIT(RAW) | \
LOGBIT(CMD) | \
LOGBIT(CUR) | \
LOGBIT(MOTORS) | \
LOGBIT(OPTFLOW)
// if we are using fast, Disable Medium
//#if LOG_ATTITUDE_FAST == ENABLED
// #undef LOG_ATTITUDE_MED

View File

@ -279,7 +279,6 @@
#define MASK_LOG_CUR (1<<9)
#define MASK_LOG_MOTORS (1<<10)
#define MASK_LOG_OPTFLOW (1<<11)
#define MASK_LOG_SET_DEFAULTS (1<<15)
// Waypoint Modes
// ----------------

View File

@ -746,31 +746,6 @@ setup_optflow(uint8_t argc, const Menu::arg *argv)
#endif
void
default_log_bitmask()
{
// convenience macro for testing LOG_* and setting LOGBIT_*
#define LOGBIT(_s) (LOG_##_s ? MASK_LOG_##_s : 0)
g.log_bitmask =
LOGBIT(ATTITUDE_FAST) |
LOGBIT(ATTITUDE_MED) |
LOGBIT(GPS) |
LOGBIT(PM) |
LOGBIT(CTUN) |
LOGBIT(NTUN) |
LOGBIT(MODE) |
LOGBIT(RAW) |
LOGBIT(CMD) |
LOGBIT(CUR) |
LOGBIT(MOTORS) |
LOGBIT(OPTFLOW);
#undef LOGBIT
g.log_bitmask.save();
}
/***************************************************************************/
// CLI reports
/***************************************************************************/

View File

@ -150,10 +150,6 @@ static void init_ardupilot()
AP_Var::load_all();
}
if (g.log_bitmask & MASK_LOG_SET_DEFAULTS) {
default_log_bitmask();
}
#ifdef RADIO_OVERRIDE_DEFAULTS
{
int16_t rc_override[8] = RADIO_OVERRIDE_DEFAULTS;