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.
This commit is contained in:
priseborough 2014-11-06 21:27:30 +11:00 committed by Andrew Tridgell
parent 0bf991eef9
commit 468c83c074
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, 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)
{