mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: use a larger log send queue for Linux
often on UDP or TCP with more bandwidth
This commit is contained in:
parent
19dee8419b
commit
28bdeaf5d9
|
@ -159,7 +159,11 @@ void GCS_MAVLINK::handle_log_send(DataFlash_Class &dataflash)
|
|||
// when on USB we can send a lot more data
|
||||
num_sends = 40;
|
||||
} else if (have_flow_control()) {
|
||||
num_sends = 10;
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||
num_sends = 80;
|
||||
#else
|
||||
num_sends = 10;
|
||||
#endif
|
||||
}
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
|
|
Loading…
Reference in New Issue