diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index 0fee3a26f6..264b2416fb 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -78,7 +78,9 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = { SCHED_TASK(parachute_check, 10, 200), SCHED_TASK(terrain_update, 10, 200), SCHED_TASK(update_is_flying_5Hz, 5, 100), +#if LOGGING_ENABLED == ENABLED SCHED_TASK(dataflash_periodic, 50, 400), +#endif SCHED_TASK(ins_periodic, 50, 50), SCHED_TASK(avoidance_adsb_update, 10, 100), SCHED_TASK(button_update, 5, 100), diff --git a/ArduPlane/Log.cpp b/ArduPlane/Log.cpp index f0eaa5ea85..fa0cf0f262 100644 --- a/ArduPlane/Log.cpp +++ b/ArduPlane/Log.cpp @@ -375,6 +375,7 @@ void Plane::log_init(void) #else // LOGGING_ENABLED +void Plane::Log_Write_AOA_SSA(void) {} void Plane::Log_Write_Attitude(void) {} void Plane::Log_Write_Fast(void) {} void Plane::Log_Write_Performance() {} @@ -393,6 +394,7 @@ void Plane::Log_Write_IMU() {} void Plane::Log_Write_RC(void) {} void Plane::Log_Write_Airspeed(void) {} void Plane::Log_Write_Home_And_Origin() {} +void Plane::Log_Write_Vehicle_Startup_Messages() {} void Plane::log_init(void) {} diff --git a/ArduPlane/system.cpp b/ArduPlane/system.cpp index c0bc77776f..1bd98c762b 100644 --- a/ArduPlane/system.cpp +++ b/ArduPlane/system.cpp @@ -241,10 +241,12 @@ void Plane::startup_ground(void) mission.init(); // initialise DataFlash library +#if LOGGING_ENABLED == ENABLED DataFlash.set_mission(&mission); DataFlash.setVehicle_Startup_Log_Writer( FUNCTOR_BIND(&plane, &Plane::Log_Write_Vehicle_Startup_Messages, void) ); +#endif // reset last heartbeat time, so we don't trigger failsafe on slow // startup