From 86c39c0314252024e41657251abf8d5ba476f8cc Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 13 Mar 2018 22:05:28 +0900 Subject: [PATCH] Rover: run update_mission at 50hz --- APMrover2/APMrover2.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/APMrover2/APMrover2.cpp b/APMrover2/APMrover2.cpp index abee206b52..7d6cb20fa7 100644 --- a/APMrover2/APMrover2.cpp +++ b/APMrover2/APMrover2.cpp @@ -57,7 +57,7 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = { SCHED_TASK(update_visual_odom, 50, 50), SCHED_TASK(update_wheel_encoder, 20, 50), SCHED_TASK(update_compass, 10, 2000), - SCHED_TASK(update_mission, 10, 1000), + SCHED_TASK(update_mission, 50, 500), SCHED_TASK(update_logging1, 10, 1000), SCHED_TASK(update_logging2, 10, 1000), SCHED_TASK(gcs_retry_deferred, 50, 1000),