GCS_MAVLink: use a larger log send queue for Linux

often on UDP or TCP with more bandwidth
This commit is contained in:
Andrew Tridgell 2015-07-29 14:04:35 +10:00
parent 3e4b0b9869
commit 17b5d54f6b
1 changed files with 5 additions and 1 deletions

View File

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