diff --git a/ArduSub/Log.cpp b/ArduSub/Log.cpp index 87b5d035bf..b851b0e4ed 100644 --- a/ArduSub/Log.cpp +++ b/ArduSub/Log.cpp @@ -482,9 +482,6 @@ void Sub::start_logging() if (!DataFlash.logging_started()) { DataFlash.StartNewLog(); } - - // enable writes - DataFlash.EnableWrites(true); } void Sub::log_init(void) diff --git a/ArduSub/motors.cpp b/ArduSub/motors.cpp index 5d145f2d39..b9e7a73e3b 100644 --- a/ArduSub/motors.cpp +++ b/ArduSub/motors.cpp @@ -120,12 +120,6 @@ void Sub::init_disarm_motors() DataFlash_Class::instance()->set_vehicle_armed(false); - if (DataFlash.log_while_disarmed()) { - start_logging(); // create a new log if necessary - } else { - DataFlash.EnableWrites(false); // suspend logging - } - // disable gps velocity based centrefugal force compensation ahrs.set_correct_centrifugal(false); hal.util->set_soft_armed(false);