mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Plane: correct compilation when logging is disabled
This commit is contained in:
parent
4847a61868
commit
eb026e0a5f
@ -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),
|
||||
|
@ -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) {}
|
||||
|
||||
|
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user