From c0172516af893b447dc323a5e4a700cf8da145d3 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 9 May 2016 12:06:00 +1000 Subject: [PATCH] Rover: use DataFlash::log_while_disarmed() --- APMrover2/Parameters.cpp | 4 ++-- APMrover2/defines.h | 1 - APMrover2/system.cpp | 2 +- 3 files changed, 3 insertions(+), 4 deletions(-) diff --git a/APMrover2/Parameters.cpp b/APMrover2/Parameters.cpp index b251ee78f3..2f38928679 100644 --- a/APMrover2/Parameters.cpp +++ b/APMrover2/Parameters.cpp @@ -27,9 +27,9 @@ const AP_Param::Info Rover::var_info[] = { // @Param: LOG_BITMASK // @DisplayName: Log bitmask - // @Description: Bitmap of what log types to enable in dataflash. This values is made up of the sum of each of the log types you want to be saved on dataflash. On a PX4 or Pixhawk the large storage size of a microSD card means it is usually best just to enable all log types by setting this to 65535. On APM2 the smaller 4 MByte dataflash means you need to be more selective in your logging or you may run out of log space while flying (in which case it will wrap and overwrite the start of the log). The individual bits are ATTITUDE_FAST=1, ATTITUDE_MEDIUM=2, GPS=4, PerformanceMonitoring=8, ControlTuning=16, NavigationTuning=32, Mode=64, IMU=128, Commands=256, Battery=512, Compass=1024, TECS=2048, Camera=4096, RCandServo=8192, Sonar=16384, Arming=32768, LogWhenDisarmed=65536, FullLogsArmedOnly=65535, FullLogsWhenDisarmed=131071 + // @Description: Bitmap of what log types to enable in dataflash. This values is made up of the sum of each of the log types you want to be saved on dataflash. On a PX4 or Pixhawk the large storage size of a microSD card means it is usually best just to enable all log types by setting this to 65535. On APM2 the smaller 4 MByte dataflash means you need to be more selective in your logging or you may run out of log space while flying (in which case it will wrap and overwrite the start of the log). The individual bits are ATTITUDE_FAST=1, ATTITUDE_MEDIUM=2, GPS=4, PerformanceMonitoring=8, ControlTuning=16, NavigationTuning=32, Mode=64, IMU=128, Commands=256, Battery=512, Compass=1024, TECS=2048, Camera=4096, RCandServo=8192, Sonar=16384, Arming=32768, FullLogs=65535 // @Values: 0:Disabled,5190:APM2-Default,65535:PX4/Pixhawk-Default - // @Bitmask: 0:ATTITUDE_FAST,1:ATTITUDE_MED,2:GPS,3:PM,4:CTUN,5:NTUN,6:MODE,7:IMU,8:CMD,9:CURRENT,10:COMPASS,11:TECS,12:CAMERA,13:RC,14:SONAR,15:ARM/DISARM,16:WHEN_DISARMED,19:IMU_RAW + // @Bitmask: 0:ATTITUDE_FAST,1:ATTITUDE_MED,2:GPS,3:PM,4:CTUN,5:NTUN,6:MODE,7:IMU,8:CMD,9:CURRENT,10:COMPASS,11:TECS,12:CAMERA,13:RC,14:SONAR,15:ARM/DISARM,19:IMU_RAW // @User: Advanced GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK), diff --git a/APMrover2/defines.h b/APMrover2/defines.h index 71d7ed5bd5..605a282b01 100644 --- a/APMrover2/defines.h +++ b/APMrover2/defines.h @@ -88,7 +88,6 @@ enum mode { #define MASK_LOG_STEERING (1<<13) #define MASK_LOG_RC (1<<14) #define MASK_LOG_ARM_DISARM (1<<15) -#define MASK_LOG_WHEN_DISARMED (1UL<<16) #define MASK_LOG_IMU_RAW (1UL<<19) diff --git a/APMrover2/system.cpp b/APMrover2/system.cpp index a441065dab..45dc9dc965 100644 --- a/APMrover2/system.cpp +++ b/APMrover2/system.cpp @@ -482,7 +482,7 @@ bool Rover::should_log(uint32_t mask) if (!(mask & g.log_bitmask) || in_mavlink_delay) { return false; } - bool ret = hal.util->get_soft_armed() || (g.log_bitmask & MASK_LOG_WHEN_DISARMED) != 0; + bool ret = hal.util->get_soft_armed() || DataFlash.log_while_disarmed(); if (ret && !DataFlash.logging_started() && !in_log_download) { start_logging(); }