diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index c641d3b0f9..d4cc660a42 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -372,8 +372,8 @@ const AP_Param::Info Copter::var_info[] = { // @Param: LOG_BITMASK // @DisplayName: Log bitmask // @Description: 4 byte bitmap of log types to enable - // @Values: 830:Default,894:Default+RCIN,958:Default+IMU,1854:Default+Motors,-6146:NearlyAll-AC315,45054:NearlyAll,131070:All+DisarmedLogging,131071:All+FastATT,262142:All+MotBatt,393214:All+FastIMU,397310:All+FastIMU+PID,655358:All+FullIMU,0:Disabled - // @Bitmask: 0:ATTITUDE_FAST,1:ATTITUDE_MED,2:GPS,3:PM,4:CTUN,5:NTUN,6:RCIN,7:IMU,8:CMD,9:CURRENT,10:RCOUT,11:OPTFLOW,12:PID,13:COMPASS,14:INAV,15:CAMERA,16:WHEN_DISARMED,17:MOTBATT,18:IMU_FAST,19:IMU_RAW + // @Values: 830:Default,894:Default+RCIN,958:Default+IMU,1854:Default+Motors,-6146:NearlyAll-AC315,45054:NearlyAll,131071:All+FastATT,262142:All+MotBatt,393214:All+FastIMU,397310:All+FastIMU+PID,655358:All+FullIMU,0:Disabled + // @Bitmask: 0:ATTITUDE_FAST,1:ATTITUDE_MED,2:GPS,3:PM,4:CTUN,5:NTUN,6:RCIN,7:IMU,8:CMD,9:CURRENT,10:RCOUT,11:OPTFLOW,12:PID,13:COMPASS,14:INAV,15:CAMERA,17:MOTBATT,18:IMU_FAST,19:IMU_RAW // @User: Standard GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK), diff --git a/ArduCopter/defines.h b/ArduCopter/defines.h index 2b15ff79a3..6354205f11 100644 --- a/ArduCopter/defines.h +++ b/ArduCopter/defines.h @@ -296,7 +296,6 @@ enum ThrowModeState { #define MASK_LOG_COMPASS (1<<13) #define MASK_LOG_INAV (1<<14) // deprecated #define MASK_LOG_CAMERA (1<<15) -#define MASK_LOG_WHEN_DISARMED (1UL<<16) #define MASK_LOG_MOTBATT (1UL<<17) #define MASK_LOG_IMU_FAST (1UL<<18) #define MASK_LOG_IMU_RAW (1UL<<19) diff --git a/ArduCopter/motors.cpp b/ArduCopter/motors.cpp index b14970a4c2..fc4233878f 100644 --- a/ArduCopter/motors.cpp +++ b/ArduCopter/motors.cpp @@ -250,7 +250,7 @@ void Copter::init_disarm_motors() mission.reset(); // suspend logging - if (!(g.log_bitmask & MASK_LOG_WHEN_DISARMED)) { + if (!DataFlash.log_while_disarmed()) { DataFlash.EnableWrites(false); } diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index dca8e6a8f4..cb07b9fefa 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -450,7 +450,7 @@ bool Copter::should_log(uint32_t mask) if (!(mask & g.log_bitmask) || in_mavlink_delay) { return false; } - bool ret = motors.armed() || (g.log_bitmask & MASK_LOG_WHEN_DISARMED) != 0; + bool ret = motors.armed() || DataFlash.log_while_disarmed(); if (ret && !DataFlash.logging_started() && !in_log_download) { start_logging(); }