diff --git a/APMrover2/Log.cpp b/APMrover2/Log.cpp index 0f527dd9c4..ce8d98cde4 100644 --- a/APMrover2/Log.cpp +++ b/APMrover2/Log.cpp @@ -504,9 +504,6 @@ void Rover::log_init(void) gcs().reset_cli_timeout(); - if (g.log_bitmask != 0) { - start_logging(); - } } #if CLI_ENABLED == ENABLED diff --git a/AntennaTracker/Log.cpp b/AntennaTracker/Log.cpp index 7da8ba4ff4..b493c7a086 100644 --- a/AntennaTracker/Log.cpp +++ b/AntennaTracker/Log.cpp @@ -84,23 +84,11 @@ void Tracker::Log_Write_Vehicle_Startup_Messages() gps.Write_DataFlash_Log_Startup_messages(); } -// start a new log -void Tracker::start_logging() -{ - if (g.log_bitmask != 0) { - DataFlash.StartUnstartedLogging(); - } -} - void Tracker::log_init(void) { DataFlash.Init(log_structure, ARRAY_SIZE(log_structure)); gcs().reset_cli_timeout(); - - if (g.log_bitmask != 0) { - start_logging(); - } } #else // LOGGING_ENABLED @@ -108,7 +96,6 @@ void Tracker::log_init(void) void Tracker::Log_Write_Attitude(void) {} void Tracker::Log_Write_Baro(void) {} -void Tracker::start_logging() {} void Tracker::log_init(void) {} void Tracker::Log_Write_Vehicle_Pos(int32_t lat, int32_t lng, int32_t alt, const Vector3f& vel) {} void Tracker::Log_Write_Vehicle_Baro(float pressure, float altitude) {} diff --git a/AntennaTracker/Tracker.h b/AntennaTracker/Tracker.h index f06406c1b9..2ab482c4d0 100644 --- a/AntennaTracker/Tracker.h +++ b/AntennaTracker/Tracker.h @@ -260,7 +260,6 @@ private: void Log_Write_Vehicle_Pos(int32_t lat,int32_t lng,int32_t alt, const Vector3f& vel); void Log_Write_Vehicle_Baro(float pressure, float altitude); void Log_Write_Vehicle_Startup_Messages(); - void start_logging(); void log_init(void); bool should_log(uint32_t mask);