From 468c83c07403d3c3405502cebfea14d83e39f052 Mon Sep 17 00:00:00 2001 From: priseborough Date: Thu, 6 Nov 2014 21:27:30 +1100 Subject: [PATCH] Copter : Check for new optical flow readings every 10ms The driver polls the sensor asynchronously every 100 msec, so we need to continually check for new data. --- ArduCopter/ArduCopter.pde | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 712ba0ce7f..77635a6571 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, 40, 20 }, + { update_optical_flow, 4, 20 }, #endif { update_batt_compass, 40, 72 }, { read_aux_switches, 40, 5 }, @@ -1188,7 +1188,7 @@ static void one_hz_loop() #endif } -// called at 10hz +// called at 100hz #if OPTFLOW == ENABLED static void update_optical_flow(void) {