From a27f3836129757f5d3f1dd940798d01eee6bd8cd Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 20 Apr 2015 11:23:57 +0900 Subject: [PATCH] Copter: remove duplicate IMU/ATT logging Previously IMU and ATT data could be logged at both a high rate and a low rate. This patch makes it skip the low rate logging if the high rate is enabled --- ArduCopter/ArduCopter.pde | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 1249e83ff4..4b7dd3d251 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -965,7 +965,8 @@ static void update_batt_compass(void) // should be run at 10hz static void ten_hz_logging_loop() { - if (should_log(MASK_LOG_ATTITUDE_MED)) { + // log attitude data if we're not already logging at the higher rate + if (should_log(MASK_LOG_ATTITUDE_MED) && !should_log(MASK_LOG_ATTITUDE_FAST)) { Log_Write_Attitude(); Log_Write_Rate(); } @@ -998,7 +999,8 @@ static void fifty_hz_logging_loop() Log_Write_Rate(); } - if (should_log(MASK_LOG_IMU)) { + // log IMU data if we're not already logging at the higher rate + if (should_log(MASK_LOG_IMU) && !should_log(MASK_LOG_IMU_FAST)) { DataFlash.Log_Write_IMU(ins); } #endif