From 715d64dce9e469dbb70b98bbeb4b6a130e615a43 Mon Sep 17 00:00:00 2001 From: priseborough Date: Fri, 7 Nov 2014 21:54:32 +1100 Subject: [PATCH] Copter: Check for new optical flow updates at 200Hz Supports use of higher flow read rates if required. --- ArduCopter/ArduCopter.pde | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 77635a6571..9aed1ac7d4 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -775,7 +775,7 @@ static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = { { throttle_loop, 8, 45 }, { update_GPS, 8, 90 }, #if OPTFLOW == ENABLED - { update_optical_flow, 4, 20 }, + { update_optical_flow, 2, 20 }, #endif { update_batt_compass, 40, 72 }, { read_aux_switches, 40, 5 }, @@ -1188,7 +1188,7 @@ static void one_hz_loop() #endif } -// called at 100hz +// called at 200hz #if OPTFLOW == ENABLED static void update_optical_flow(void) {