diff --git a/Blimp/Blimp.cpp b/Blimp/Blimp.cpp index 9c9f457b13..c923e0ea61 100644 --- a/Blimp/Blimp.cpp +++ b/Blimp/Blimp.cpp @@ -72,7 +72,9 @@ const AP_Scheduler::Task Blimp::scheduler_tasks[] = { SCHED_TASK(arm_motors_check, 10, 50, 18), SCHED_TASK(update_altitude, 10, 100, 21), SCHED_TASK(three_hz_loop, 3, 75, 24), +#if AP_SERVORELAYEVENTS_ENABLED SCHED_TASK_CLASS(AP_ServoRelayEvents, &blimp.ServoRelayEvents, update_events, 50, 75, 27), +#endif SCHED_TASK_CLASS(AP_Baro, &blimp.barometer, accumulate, 50, 90, 30), #if LOGGING_ENABLED == ENABLED SCHED_TASK(full_rate_logging, 50, 50, 33), diff --git a/Blimp/system.cpp b/Blimp/system.cpp index cec5103bb5..828d19b139 100644 --- a/Blimp/system.cpp +++ b/Blimp/system.cpp @@ -58,7 +58,9 @@ void Blimp::init_ardupilot() // motors initialised so parameters can be sent ap.initialised_params = true; +#if AP_RELAY_ENABLED relay.init(); +#endif /* * setup the 'main loop is dead' check. Note that this relies on