mirror of https://github.com/ArduPilot/ardupilot
Rover: Doubled the rate at which read_control_switch is called.
As the previous commit as doubled the number of reads required to confirm that the mode change switch has been changed this means it will halve the speed it changes at. So we double the rate at which we read it to keep things consistent.
This commit is contained in:
parent
4f6259f374
commit
873e6c8e29
|
@ -61,7 +61,7 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] PROGMEM = {
|
|||
{ SCHED_TASK(gcs_retry_deferred), 1, 1000 },
|
||||
{ SCHED_TASK(gcs_update), 1, 1700 },
|
||||
{ SCHED_TASK(gcs_data_stream_send), 1, 3000 },
|
||||
{ SCHED_TASK(read_control_switch), 15, 1000 },
|
||||
{ SCHED_TASK(read_control_switch), 7, 1000 },
|
||||
{ SCHED_TASK(read_trim_switch), 5, 1000 },
|
||||
{ SCHED_TASK(read_battery), 5, 1000 },
|
||||
{ SCHED_TASK(read_receiver_rssi), 5, 1000 },
|
||||
|
|
Loading…
Reference in New Issue