From 788faf1f7d570bc80dd1e4498bfd904bba91c07b Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 26 Jun 2015 09:11:32 +1000 Subject: [PATCH] Copter: DataFlash frontend/backend split --- ArduCopter/Copter.cpp | 3 --- ArduCopter/Copter.h | 6 +----- 2 files changed, 1 insertion(+), 8 deletions(-) diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index f1d93343ee..86f5779d63 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -22,9 +22,6 @@ const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; Copter::Copter(void) : -#if defined(HAL_BOARD_LOG_DIRECTORY) - DataFlash(HAL_BOARD_LOG_DIRECTORY), -#endif ins_sample_rate(AP_InertialSensor::RATE_400HZ), flight_modes(&g.flight_mode1), sonar_enabled(true), diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 64c7095cf0..bf3f2c121d 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -153,11 +153,7 @@ private: RC_Channel *channel_yaw; // Dataflash -#if defined(HAL_BOARD_LOG_DIRECTORY) - DataFlash_File DataFlash; -#else - DataFlash_Empty DataFlash; -#endif + DataFlash_Class DataFlash; // the rate we run the main loop at const AP_InertialSensor::Sample_rate ins_sample_rate;