/** trigger sending of log messages if there are some pending */ void DataFlash_Class::handle_log_send(GCS_MAVLINK &link) { if (_log_sending_chan != link.get_chan()) { return; } if (_log_listing) { handle_log_send_listing(link); } if (!_log_sending) { return; } #if CONFIG_HAL_BOARD == HAL_BOARD_SITL // assume USB speeds in SITL for the purposes of log download const uint8_t num_sends = 40; #else uint8_t num_sends = 1; if (link.is_high_bandwidth() && hal.gpio->usb_connected()) { // when on USB we can send a lot more data num_sends = 250; } else if (link.have_flow_control()) { #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX num_sends = 80; #else num_sends = 10; #endif } #endif for (uint8_t i=0; i<num_sends; i++) { if (_log_sending) { if (!handle_log_send_data(link)) break; } } }
/** trigger sending of log messages if there are some pending */ void GCS_MAVLINK::handle_log_send(DataFlash_Class &dataflash) { if (_log_listing) { handle_log_send_listing(dataflash); } if (!_log_sending) { return; } #if CONFIG_HAL_BOARD == HAL_BOARD_SITL // assume USB speeds in SITL for the purposes of log download const uint8_t num_sends = 40; #else uint8_t num_sends = 1; if (chan == MAVLINK_COMM_0 && hal.gpio->usb_connected()) { // when on USB we can send a lot more data num_sends = 40; } else if (have_flow_control()) { #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX num_sends = 80; #else num_sends = 10; #endif } #endif for (uint8_t i=0; i<num_sends; i++) { if (_log_sending) { if (!handle_log_send_data(dataflash)) break; } } }
/** trigger sending of log messages if there are some pending */ void GCS_MAVLINK::handle_log_send(DataFlash_Class &dataflash) { if (_log_listing) { handle_log_send_listing(dataflash); } if (!_log_sending) { return; } uint8_t num_sends = 1; 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 // assume USB speeds in SITL for the purposes of log download num_sends = 40; #endif for (uint8_t i=0; i<num_sends; i++) { if (_log_sending) { if (!handle_log_send_data(dataflash)) break; } } }
void DataFlash_Class::handle_log_sending() { #if CONFIG_HAL_BOARD == HAL_BOARD_SITL // assume USB speeds in SITL for the purposes of log download const uint8_t num_sends = 40; #else uint8_t num_sends = 1; if (_log_sending_link->is_high_bandwidth() && hal.gpio->usb_connected()) { // when on USB we can send a lot more data num_sends = 250; } else if (_log_sending_link->have_flow_control()) { #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX num_sends = 80; #else num_sends = 10; #endif } #endif for (uint8_t i=0; i<num_sends; i++) { if (transfer_activity != SENDING) { // may have completed sending data break; } if (!handle_log_send_data()) { break; } } }