Copter: correct mount tasks scheduler time

Having the estimate too high would mean it would likely never run
This commit is contained in:
Randy Mackay 2013-10-13 14:13:59 +09:00
parent f344c77cca
commit 959f59f623

View File

@ -879,7 +879,7 @@ static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = {
#if COPTER_LEDS == ENABLED
{ update_copter_leds, 10, 55 },
#endif
{ update_mount, 2, 2000 },
{ update_mount, 2, 450 },
{ ten_hz_logging_loop, 10, 260 },
{ fifty_hz_logging_loop, 2, 220 },
{ perf_update, 1000, 200 },