Copter: update servorelayevents @50Hz rather than 3Hz

One of the functions we allow for is toggling the servo at a set
frequency.  3Hz - the old rate - doesn't allow for precise triggering of
the servo.  This patch increases that rate to 50Hz - somewhat better.
This commit is contained in:
Peter Barker 2018-07-20 09:52:44 +10:00 committed by Randy Mackay
parent ff0f293d06
commit f06637d48e
3 changed files with 1 additions and 9 deletions

View File

@ -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();
}

View File

@ -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();

View File

@ -284,9 +284,3 @@ bool Copter::should_disarm_on_failsafe() {
return ap.land_complete;
}
}
void Copter::update_events()
{
ServoRelayEvents.update_events();
}