mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
Plane: check the control switch a bit more often
faster response to mode changes
This commit is contained in:
parent
6ed78c89ac
commit
9b70675b12
@ -690,11 +690,11 @@ static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = {
|
||||
{ update_flight_mode, 1, 1000 },
|
||||
{ stabilize, 1, 3200 },
|
||||
{ set_servos, 1, 1100 },
|
||||
{ read_control_switch, 7, 1000 },
|
||||
{ update_GPS, 5, 4000 },
|
||||
{ navigate, 5, 4800 },
|
||||
{ update_compass, 5, 1500 },
|
||||
{ read_airspeed, 5, 1500 },
|
||||
{ read_control_switch, 15, 1000 },
|
||||
{ update_alt, 5, 3400 },
|
||||
{ calc_altitude_error, 5, 1000 },
|
||||
{ update_commands, 5, 7000 },
|
||||
|
Loading…
Reference in New Issue
Block a user