From f9105a056e405b545765877052d22a233afb0ba7 Mon Sep 17 00:00:00 2001 From: "tridge60@gmail.com" Date: Sun, 17 Jul 2011 10:31:17 +0000 Subject: [PATCH] logging: moved the default log_bitmask calculation to compile time this saves a little bit of code by moving the calculation of the default log bitmask to compile time from runtime (merge from APM) git-svn-id: https://arducopter.googlecode.com/svn/trunk@2887 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- ArduCopterMega/Log.pde | 1 - ArduCopterMega/Parameters.h | 2 +- ArduCopterMega/config.h | 15 +++++++++++++++ ArduCopterMega/defines.h | 1 - ArduCopterMega/setup.pde | 26 -------------------------- ArduCopterMega/system.pde | 4 ---- 6 files changed, 16 insertions(+), 33 deletions(-) diff --git a/ArduCopterMega/Log.pde b/ArduCopterMega/Log.pde index ef951cc7d1..01c57be971 100644 --- a/ArduCopterMega/Log.pde +++ b/ArduCopterMega/Log.pde @@ -168,7 +168,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); diff --git a/ArduCopterMega/Parameters.h b/ArduCopterMega/Parameters.h index dcbdfcfac0..578e64d624 100644 --- a/ArduCopterMega/Parameters.h +++ b/ArduCopterMega/Parameters.h @@ -313,7 +313,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")), diff --git a/ArduCopterMega/config.h b/ArduCopterMega/config.h index 11eae8db90..ce339ac81a 100644 --- a/ArduCopterMega/config.h +++ b/ArduCopterMega/config.h @@ -492,6 +492,21 @@ # define LOG_CURRENT 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(CURRENT) + // if we are using fast, Disable Medium //#if LOG_ATTITUDE_FAST == ENABLED // #undef LOG_ATTITUDE_MED diff --git a/ArduCopterMega/defines.h b/ArduCopterMega/defines.h index 519e44bdbb..09627cfc56 100644 --- a/ArduCopterMega/defines.h +++ b/ArduCopterMega/defines.h @@ -275,7 +275,6 @@ #define MASK_LOG_CMD (1<<8) #define MASK_LOG_CURRENT (1<<9) #define MASK_LOG_MOTORS (1<<10) -#define MASK_LOG_SET_DEFAULTS (1<<15) // Waypoint Modes // ---------------- diff --git a/ArduCopterMega/setup.pde b/ArduCopterMega/setup.pde index 229f264c06..b31f41939b 100644 --- a/ArduCopterMega/setup.pde +++ b/ArduCopterMega/setup.pde @@ -120,7 +120,6 @@ setup_factory(uint8_t argc, const Menu::arg *argv) Serial.printf_P(PSTR("\nFACTORY RESET complete - reboot APM")); delay(1000); - //default_log_bitmask(); //default_gains(); for (;;) { @@ -727,31 +726,6 @@ setup_mag_offset(uint8_t argc, const Menu::arg *argv) */ -/***************************************************************************/ -// CLI defaults -/***************************************************************************/ - -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(CURRENT); - #undef LOGBIT - - g.log_bitmask.save(); -} - /***************************************************************************/ // CLI reports /***************************************************************************/ diff --git a/ArduCopterMega/system.pde b/ArduCopterMega/system.pde index 19507b19c5..2fe7c1bc88 100644 --- a/ArduCopterMega/system.pde +++ b/ArduCopterMega/system.pde @@ -217,10 +217,6 @@ void init_ardupilot() // DataFlash log initialization DataFlash.Init(); - // setup the log bitmask - if (g.log_bitmask & MASK_LOG_SET_DEFAULTS) - default_log_bitmask(); - // If the switch is in 'menu' mode, run the main menu. // // Since we can't be sure that the setup or test mode won't leave