mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: update wheel encoders at 50hz
This commit is contained in:
parent
69541fc89c
commit
85ac24d96e
@ -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),
|
||||
|
Loading…
Reference in New Issue
Block a user