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:
Grant Morphett 2015-07-22 12:19:20 +10:00 committed by Andrew Tridgell
parent 4f6259f374
commit 873e6c8e29
1 changed files with 1 additions and 1 deletions

View File

@ -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 },