diff --git a/ArduCopter/APM_Config.h b/ArduCopter/APM_Config.h index cd705d3d9f..97e59f6999 100644 --- a/ArduCopter/APM_Config.h +++ b/ArduCopter/APM_Config.h @@ -41,7 +41,6 @@ // other settings //#define THROTTLE_IN_DEADBAND 100 // redefine size of throttle deadband in pwm (0 ~ 1000) //#define LAND_REQUIRE_MIN_THROTTLE_TO_DISARM DISABLED // when set to DISABLED vehicle will disarm after landing (in LAND mode or RTL) even if pilot has not put throttle to zero -//#define LOG_FROM_STARTUP // start logging as soon as the board starts up instead of waiting for the vehicle to be armed //#define HIL_MODE HIL_MODE_SENSORS // build for hardware-in-the-loop simulation diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index 49f2d7b129..d391c5cd30 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -277,10 +277,6 @@ static void init_ardupilot() #if LOGGING_ENABLED == ENABLED Log_Write_Startup(); - #ifdef LOG_FROM_STARTUP - // start dataflash - start_logging(); - #endif #endif // we don't want writes to the serial port to cause us to pause