mirror of https://github.com/ArduPilot/ardupilot
Copter: Change flow sensor read sample rate to 10Hz
This commit is contained in:
parent
4452aa8448
commit
5ef2208017
|
@ -777,7 +777,7 @@ static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = {
|
||||||
{ throttle_loop, 8, 45 },
|
{ throttle_loop, 8, 45 },
|
||||||
{ update_GPS, 8, 90 },
|
{ update_GPS, 8, 90 },
|
||||||
#if OPTFLOW == ENABLED
|
#if OPTFLOW == ENABLED
|
||||||
{ update_optflow, 8, 20 },
|
{ update_optflow, 40, 20 },
|
||||||
#endif
|
#endif
|
||||||
{ update_batt_compass, 40, 72 },
|
{ update_batt_compass, 40, 72 },
|
||||||
{ read_aux_switches, 40, 5 },
|
{ read_aux_switches, 40, 5 },
|
||||||
|
|
Loading…
Reference in New Issue