From 1497c3317869a2e7ad74cd7fa2846d94474d941f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 14 Feb 2014 13:15:50 +1100 Subject: [PATCH] GCS_MAVLink: run a bit faster on serial ports with flow control with flow control we can afford to push the radio a bit harder --- libraries/GCS_MAVLink/GCS_Logs.cpp | 11 +++++++---- 1 file changed, 7 insertions(+), 4 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS_Logs.cpp b/libraries/GCS_MAVLink/GCS_Logs.cpp index 11687e2806..5aef1b5289 100644 --- a/libraries/GCS_MAVLink/GCS_Logs.cpp +++ b/libraries/GCS_MAVLink/GCS_Logs.cpp @@ -136,6 +136,13 @@ void GCS_MAVLINK::handle_log_send(DataFlash_Class &dataflash) if (chan == MAVLINK_COMM_0 && hal.gpio->usb_connected()) { // when on USB we can send a lot more data num_sends = 40; + } else if (chan == MAVLINK_COMM_1 && + hal.uartC->get_flow_control() != AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE) { + num_sends = 10; + } else if (chan == MAVLINK_COMM_2 && + hal.uartD != NULL && + hal.uartD->get_flow_control() != AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE) { + num_sends = 10; } #if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL @@ -143,10 +150,6 @@ void GCS_MAVLINK::handle_log_send(DataFlash_Class &dataflash) num_sends = 40; #endif - if (stream_slowdown != 0) { - // we're using a radio and starting to clag up, slowdown log send - num_sends = 1; - } for (uint8_t i=0; i