mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
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:
parent
ff0f293d06
commit
f06637d48e
@ -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();
|
||||
}
|
||||
|
@ -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();
|
||||
|
@ -284,9 +284,3 @@ bool Copter::should_disarm_on_failsafe() {
|
||||
return ap.land_complete;
|
||||
}
|
||||
}
|
||||
|
||||
void Copter::update_events()
|
||||
{
|
||||
ServoRelayEvents.update_events();
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user