mirror of https://github.com/ArduPilot/ardupilot
Copter: increase the telemetry receive function rate to 400Hz
gimbal loop runs at 100Hz so to respond in time the gcs_check_input must run at a faster rate, the process are asyncronus
This commit is contained in:
parent
1da4be3a87
commit
7cf883a61c
|
@ -742,7 +742,7 @@ static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = {
|
|||
{ ekf_check, 40, 2 },
|
||||
{ crash_check, 40, 2 },
|
||||
{ landinggear_update, 40, 1 },
|
||||
{ gcs_check_input, 8, 550 },
|
||||
{ gcs_check_input, 1, 550 },
|
||||
{ gcs_send_heartbeat, 400, 150 },
|
||||
{ gcs_send_deferred, 8, 720 },
|
||||
{ gcs_data_stream_send, 8, 950 },
|
||||
|
|
Loading…
Reference in New Issue