Copter: update proximity sensor at 200hz

This commit is contained in:
Randy Mackay 2019-09-21 15:22:49 +09:00 committed by Andrew Tridgell
parent a76af0623a
commit d6e3292cfb

View File

@ -107,7 +107,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
SCHED_TASK(read_rangefinder, 20, 100),
#endif
#if PROXIMITY_ENABLED == ENABLED
SCHED_TASK_CLASS(AP_Proximity, &copter.g2.proximity, update, 100, 50),
SCHED_TASK_CLASS(AP_Proximity, &copter.g2.proximity, update, 200, 50),
#endif
#if BEACON_ENABLED == ENABLED
SCHED_TASK_CLASS(AP_Beacon, &copter.g2.beacon, update, 400, 50),