diff --git a/APMrover2/Log.cpp b/APMrover2/Log.cpp index ce8d98cde4..0a48260351 100644 --- a/APMrover2/Log.cpp +++ b/APMrover2/Log.cpp @@ -531,14 +531,6 @@ void Rover::Log_Write_Vehicle_Startup_Messages() gps.Write_DataFlash_Log_Startup_messages(); } -// start a new log -void Rover::start_logging() -{ - DataFlash.EnableWrites(false); - DataFlash.StartUnstartedLogging(); - DataFlash.EnableWrites(true); -} - #else // LOGGING_ENABLED // dummy functions @@ -550,7 +542,6 @@ int8_t Rover::process_logs(uint8_t argc, const Menu::arg *argv) { return 0; } void Rover::Log_Write_Control_Tuning() {} void Rover::Log_Write_Rangefinder() {} void Rover::Log_Write_Attitude() {} -void Rover::start_logging() {} void Rover::Log_Write_RC(void) {} void Rover::Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target, const Vector3f& vel_target) {} void Rover::Log_Write_Home_And_Origin() {} diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index 8b76146a81..abc1e7acfa 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -477,7 +477,6 @@ private: void Log_Write_WheelEncoder(); void Log_Read(uint16_t log_num, uint16_t start_page, uint16_t end_page); void log_init(void); - void start_logging(); void Log_Arm_Disarm(); void load_parameters(void); diff --git a/APMrover2/system.cpp b/APMrover2/system.cpp index 4a151cf81b..2a342a8147 100644 --- a/APMrover2/system.cpp +++ b/APMrover2/system.cpp @@ -499,11 +499,7 @@ uint8_t Rover::check_digital_pin(uint8_t pin) */ bool Rover::should_log(uint32_t mask) { - if (!DataFlash.should_log(mask)) { - return false; - } - start_logging(); - return true; + return DataFlash.should_log(mask); } /*