/** handle all types of log download requests from the GCS */ void DataFlash_Class::handle_log_request_list(GCS_MAVLINK &link, mavlink_message_t *msg) { if (_log_sending_chan >= 0) { link.send_text(MAV_SEVERITY_INFO, "Log download in progress"); return; } mavlink_log_request_list_t packet; mavlink_msg_log_request_list_decode(msg, &packet); _log_listing = false; _log_sending = false; _log_num_logs = get_num_logs(); if (_log_num_logs == 0) { _log_next_list_entry = 0; _log_last_list_entry = 0; } else { _log_next_list_entry = packet.start; _log_last_list_entry = packet.end; if (_log_last_list_entry > _log_num_logs) { _log_last_list_entry = _log_num_logs; } if (_log_next_list_entry < 1) { _log_next_list_entry = 1; } } _log_listing = true; _log_sending_chan = link.get_chan(); handle_log_send_listing(link); }
/** handle all types of log download requests from the GCS */ void GCS_MAVLINK::handle_log_request_list(mavlink_message_t *msg, DataFlash_Class &dataflash) { mavlink_log_request_list_t packet; mavlink_msg_log_request_list_decode(msg, &packet); if (mavlink_check_target(packet.target_system, packet.target_component)) return; _log_listing = false; _log_sending = false; _log_num_logs = dataflash.get_num_logs(); if (_log_num_logs == 0) { return; } int16_t last_log_num = dataflash.find_last_log(); _log_next_list_entry = packet.start; _log_last_list_entry = packet.end; if (_log_last_list_entry > last_log_num) { _log_last_list_entry = last_log_num; } if (_log_next_list_entry < last_log_num + 1 - _log_num_logs) { _log_next_list_entry = last_log_num + 1 - _log_num_logs; } _log_listing = true; handle_log_send_listing(dataflash); }
/** 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; } 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; } } }
/** handle all types of log download requests from the GCS */ void GCS_MAVLINK::handle_log_request_list(mavlink_message_t *msg, DataFlash_Class &dataflash) { mavlink_log_request_list_t packet; mavlink_msg_log_request_list_decode(msg, &packet); _log_listing = false; _log_sending = false; _log_num_logs = dataflash.get_num_logs(); if (_log_num_logs == 0) { _log_next_list_entry = 0; _log_last_list_entry = 0; } else { _log_next_list_entry = packet.start; _log_last_list_entry = packet.end; if (_log_last_list_entry > _log_num_logs) { _log_last_list_entry = _log_num_logs; } if (_log_next_list_entry < 1) { _log_next_list_entry = 1; } } _log_listing = true; handle_log_send_listing(dataflash); }
/** 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; } } }
/** handle all types of log download requests from the GCS */ void DataFlash_Class::handle_log_request_list(GCS_MAVLINK &link, mavlink_message_t *msg) { if (_log_sending_link != nullptr) { link.send_text(MAV_SEVERITY_INFO, "Log download in progress"); return; } mavlink_log_request_list_t packet; mavlink_msg_log_request_list_decode(msg, &packet); _log_num_logs = get_num_logs(); if (_log_num_logs == 0) { _log_next_list_entry = 0; _log_last_list_entry = 0; } else { _log_next_list_entry = packet.start; _log_last_list_entry = packet.end; if (_log_last_list_entry > _log_num_logs) { _log_last_list_entry = _log_num_logs; } if (_log_next_list_entry < 1) { _log_next_list_entry = 1; } } transfer_activity = LISTING; _log_sending_link = &link; handle_log_send_listing(); }
/** trigger sending of log messages if there are some pending */ void DataFlash_Class::handle_log_send() { if (_log_sending_link == nullptr) { return; } if (hal.util->get_soft_armed()) { // might be flying return; } switch (transfer_activity) { case IDLE: break; case LISTING: handle_log_send_listing(); break; case SENDING: handle_log_sending(); break; } }