diff --git a/AntennaTracker/AntennaTracker.cpp b/AntennaTracker/AntennaTracker.cpp index 9275e1fb74..be94b07075 100644 --- a/AntennaTracker/AntennaTracker.cpp +++ b/AntennaTracker/AntennaTracker.cpp @@ -44,7 +44,9 @@ const AP_Scheduler::Task Tracker::scheduler_tasks[] = { SCHED_TASK(compass_accumulate, 50, 1500), SCHED_TASK_CLASS(AP_Baro, &tracker.barometer, accumulate, 50, 900), SCHED_TASK(ten_hz_logging_loop, 10, 300), +#if LOGGING_ENABLED == ENABLED SCHED_TASK_CLASS(DataFlash_Class, &tracker.DataFlash, periodic_tasks, 50, 300), +#endif SCHED_TASK_CLASS(AP_InertialSensor, &tracker.ins, periodic, 50, 50), SCHED_TASK_CLASS(AP_Notify, &tracker.notify, update, 50, 100), SCHED_TASK(check_usb_mux, 10, 300), diff --git a/AntennaTracker/Log.cpp b/AntennaTracker/Log.cpp index c382d12e28..39f3d3ca74 100644 --- a/AntennaTracker/Log.cpp +++ b/AntennaTracker/Log.cpp @@ -94,5 +94,6 @@ void Tracker::Log_Write_Attitude(void) {} 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) {} +void Tracker::Log_Write_Vehicle_Startup_Messages() {} #endif // LOGGING_ENABLED