From 85ac24d96eb478ce1f24859fb8e818625b3eed8e Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 8 Aug 2018 11:38:55 +0900 Subject: [PATCH] Rover: update wheel encoders at 50hz --- APMrover2/APMrover2.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/APMrover2/APMrover2.cpp b/APMrover2/APMrover2.cpp index a00af345ad..9438af9b09 100644 --- a/APMrover2/APMrover2.cpp +++ b/APMrover2/APMrover2.cpp @@ -54,7 +54,7 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = { SCHED_TASK_CLASS(AP_Beacon, &rover.g2.beacon, update, 50, 200), SCHED_TASK_CLASS(AP_Proximity, &rover.g2.proximity, update, 50, 200), SCHED_TASK(update_visual_odom, 50, 200), - SCHED_TASK(update_wheel_encoder, 20, 200), + SCHED_TASK(update_wheel_encoder, 50, 200), SCHED_TASK(update_compass, 10, 200), SCHED_TASK(update_mission, 50, 200), SCHED_TASK(update_logging1, 10, 200),