From f5fb21b1d7e29c6ca136169b073fb215ca97f835 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 5 Dec 2014 13:59:29 +0900 Subject: [PATCH] Copter: run_nav_updates at 50hz on Pixhawk, 25hz on APM2 Based on work by Jon Challinger (see earlier commit) --- ArduCopter/ArduCopter.pde | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 8f89997cb1..f03d2a5bbf 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -801,7 +801,7 @@ static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = { { arm_motors_check, 40, 1 }, { auto_trim, 40, 14 }, { update_altitude, 40, 100 }, - { run_nav_updates, 4, 80 }, + { run_nav_updates, 8, 80 }, { update_thr_cruise, 40, 10 }, { three_hz_loop, 133, 9 }, { compass_accumulate, 8, 42 }, @@ -869,7 +869,7 @@ static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = { { arm_motors_check, 10, 10 }, { auto_trim, 10, 140 }, { update_altitude, 10, 1000 }, - { run_nav_updates, 10, 800 }, + { run_nav_updates, 4, 800 }, { update_thr_cruise, 1, 50 }, { three_hz_loop, 33, 90 }, { compass_accumulate, 2, 420 },