Copter: Check for new optical flow updates at 200Hz

Supports use of higher flow read rates if required.
This commit is contained in:
priseborough 2014-11-07 21:54:32 +11:00 committed by Andrew Tridgell
parent ca53d5fb62
commit 715d64dce9
1 changed files with 2 additions and 2 deletions

View File

@ -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)
{