diff --git a/ArduCopter/ArduCopter.cpp b/ArduCopter/ArduCopter.cpp index 360cae76b5..0b6fb6b5bc 100644 --- a/ArduCopter/ArduCopter.cpp +++ b/ArduCopter/ArduCopter.cpp @@ -116,6 +116,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = { SCHED_TASK_CLASS(Copter::ModeSmartRTL, &copter.mode_smartrtl, save_position, 3, 100), #endif SCHED_TASK(three_hz_loop, 3, 75), + SCHED_TASK_CLASS(AP_ServoRelayEvents, &copter.ServoRelayEvents, update_events, 50, 75), SCHED_TASK(compass_accumulate, 100, 100), SCHED_TASK_CLASS(AP_Baro, &copter.barometer, accumulate, 50, 90), #if PRECISION_LANDING == ENABLED @@ -406,8 +407,6 @@ void Copter::three_hz_loop() sprayer.update(); #endif - update_events(); - // update ch6 in flight tuning tuning(); } diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index f09af88429..9c8ac4a063 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -745,7 +745,6 @@ private: void set_mode_SmartRTL_or_RTL(mode_reason_t reason); void set_mode_SmartRTL_or_land_with_pause(mode_reason_t reason); bool should_disarm_on_failsafe(); - void update_events(); // failsafe.cpp void failsafe_enable(); diff --git a/ArduCopter/events.cpp b/ArduCopter/events.cpp index d02a1f99a2..64a2ad76d6 100644 --- a/ArduCopter/events.cpp +++ b/ArduCopter/events.cpp @@ -284,9 +284,3 @@ bool Copter::should_disarm_on_failsafe() { return ap.land_complete; } } - -void Copter::update_events() -{ - ServoRelayEvents.update_events(); -} -