/** trigger sending of log messages if there are some pending */ void GCS_MAVLINK::handle_log_send_listing(DataFlash_Class &dataflash) { if (!HAVE_PAYLOAD_SPACE(chan, LOG_ENTRY)) { // no space return; } if (AP_HAL::millis() - last_heartbeat_time > 3000) { // give a heartbeat a chance return; } uint32_t size, time_utc; if (_log_next_list_entry == 0) { size = 0; time_utc = 0; } else { dataflash.get_log_info(_log_next_list_entry, size, time_utc); } mavlink_msg_log_entry_send(chan, _log_next_list_entry, _log_num_logs, _log_last_list_entry, time_utc, size); if (_log_next_list_entry == _log_last_list_entry) { _log_listing = false; } else { _log_next_list_entry++; } }
/** trigger sending of log messages if there are some pending */ void GCS_MAVLINK::handle_log_send_listing(DataFlash_Class &dataflash) { uint16_t txspace = comm_get_txspace(chan); if (txspace < MAVLINK_NUM_NON_PAYLOAD_BYTES+MAVLINK_MSG_ID_LOG_ENTRY_LEN) { // no space return; } if (hal.scheduler->millis() - last_heartbeat_time > 3000) { // give a heartbeat a chance return; } uint32_t size, time_utc; if (_log_next_list_entry == 0) { size = 0; time_utc = 0; } else { dataflash.get_log_info(_log_next_list_entry, size, time_utc); } mavlink_msg_log_entry_send(chan, _log_next_list_entry, _log_num_logs, _log_last_list_entry, time_utc, size); if (_log_next_list_entry == _log_last_list_entry) { _log_listing = false; } else { _log_next_list_entry++; } }
/** handle request for log data */ void GCS_MAVLINK::handle_log_request_data(mavlink_message_t *msg, DataFlash_Class &dataflash) { mavlink_log_request_data_t packet; mavlink_msg_log_request_data_decode(msg, &packet); if (mavlink_check_target(packet.target_system, packet.target_component)) return; _log_listing = false; if (!_log_sending || _log_num_data != packet.id) { _log_sending = false; uint16_t num_logs = dataflash.get_num_logs(); int16_t last_log_num = dataflash.find_last_log(); if (packet.id > last_log_num || packet.id < last_log_num + 1 - num_logs) { return; } uint32_t time_utc, size; dataflash.get_log_info(packet.id, size, time_utc); _log_num_data = packet.id; _log_data_size = size; uint16_t end; dataflash.get_log_boundaries(packet.id, _log_data_page, end); } _log_data_offset = packet.ofs; if (_log_data_offset >= _log_data_size) { _log_data_remaining = 0; } else { _log_data_remaining = _log_data_size - _log_data_offset; } if (_log_data_remaining > packet.count) { _log_data_remaining = packet.count; } _log_sending = true; handle_log_send(dataflash); }