diff --git a/ArduPlane/ArduPlane.pde b/ArduPlane/ArduPlane.pde
index 003debc9c609dd215c0d5ea050ba008dcfeaa720..fa23641f833b763f7e9e021da7ea4b142f63bde3 100644
--- a/ArduPlane/ArduPlane.pde
+++ b/ArduPlane/ArduPlane.pde
@@ -154,7 +154,6 @@ static void print_flight_mode(AP_HAL::BetterStream *port, uint8_t mode);
 ////////////////////////////////////////////////////////////////////////////////
 // DataFlash
 ////////////////////////////////////////////////////////////////////////////////
-#if LOGGING_ENABLED == ENABLED
 #if CONFIG_HAL_BOARD == HAL_BOARD_APM1
 static DataFlash_APM1 DataFlash;
 #elif CONFIG_HAL_BOARD == HAL_BOARD_APM2
@@ -165,7 +164,6 @@ static DataFlash_File DataFlash(HAL_BOARD_LOG_DIRECTORY);
 // no dataflash driver
 DataFlash_Empty DataFlash;
 #endif
-#endif
 
 // has a log download started?
 static bool in_log_download;
diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde
index cc61f6fcd20eac4fb53f65a449f75baac4b63fbc..4b43f97669049a4021f43eca8dad793dc7d4700c 100644
--- a/ArduPlane/GCS_Mavlink.pde
+++ b/ArduPlane/GCS_Mavlink.pde
@@ -1084,7 +1084,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
                 // run pre_arm_checks and arm_checks and display failures
                 if (arming.arm(AP_Arming::MAVLINK)) {
                     //only log if arming was successful
-                    channel_throttle->enable_out();                        
+                    channel_throttle->enable_out();
                     Log_Arm_Disarm();
                     result = MAV_RESULT_ACCEPTED;
                 } else {
diff --git a/ArduPlane/Log.pde b/ArduPlane/Log.pde
index b1ec79e19dcdc7d56d635a789992c030eac3f0a3..2d1ab9b3b35c69fb40ef5f734d8935cac5b344f3 100644
--- a/ArduPlane/Log.pde
+++ b/ArduPlane/Log.pde
@@ -654,9 +654,11 @@ static void Log_Write_IMU() {}
 static void Log_Write_RC() {}
 static void Log_Write_Airspeed(void) {}
 static void Log_Write_Baro(void) {}
+static void Log_Write_Sonar() {}
 #if OPTFLOW == ENABLED
 static void Log_Write_Optflow() {}
 #endif
+static void Log_Arm_Disarm() {}
 
 static int8_t process_logs(uint8_t argc, const Menu::arg *argv) {
     return 0;
diff --git a/ArduPlane/system.pde b/ArduPlane/system.pde
index d7b4a4223513e39e049ad32826cbb8f27591d3d4..55e121a1f12b2f8082836e23562852a32c42885e 100644
--- a/ArduPlane/system.pde
+++ b/ArduPlane/system.pde
@@ -672,7 +672,9 @@ static bool should_log(uint32_t mask)
         // we have to set in_mavlink_delay to prevent logging while
         // writing headers
         in_mavlink_delay = true;
+        #if LOGGING_ENABLED == ENABLED
         start_logging();
+        #endif
         in_mavlink_delay = false;
     }
     return ret;