Browse Source

Tracker: move starting of new logs into DataFlash

mission-4.1.18
Peter Barker 8 years ago committed by Francisco Ferreira
parent
commit
c9c1f3ea29
  1. 3
      APMrover2/Log.cpp
  2. 13
      AntennaTracker/Log.cpp
  3. 1
      AntennaTracker/Tracker.h

3
APMrover2/Log.cpp

@ -504,9 +504,6 @@ void Rover::log_init(void) @@ -504,9 +504,6 @@ void Rover::log_init(void)
gcs().reset_cli_timeout();
if (g.log_bitmask != 0) {
start_logging();
}
}
#if CLI_ENABLED == ENABLED

13
AntennaTracker/Log.cpp

@ -84,23 +84,11 @@ void Tracker::Log_Write_Vehicle_Startup_Messages() @@ -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) @@ -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) {}

1
AntennaTracker/Tracker.h

@ -260,7 +260,6 @@ private: @@ -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);

Loading…
Cancel
Save