DataFlash: send log data on requesting channel only
This commit is contained in:
parent
c383d64954
commit
90c2db119e
@ -323,6 +323,8 @@ private:
|
||||
// start page of log data
|
||||
uint16_t _log_data_page;
|
||||
|
||||
int8_t _log_sending_chan = -1;
|
||||
|
||||
bool should_handle_log_message();
|
||||
void handle_log_message(class GCS_MAVLINK &, mavlink_message_t *msg);
|
||||
|
||||
|
@ -66,6 +66,11 @@ void DataFlash_Class::handle_log_message(GCS_MAVLINK &link, mavlink_message_t *m
|
||||
*/
|
||||
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);
|
||||
|
||||
@ -89,6 +94,7 @@ void DataFlash_Class::handle_log_request_list(GCS_MAVLINK &link, mavlink_message
|
||||
}
|
||||
|
||||
_log_listing = true;
|
||||
_log_sending_chan = link.get_chan();
|
||||
handle_log_send_listing(link);
|
||||
}
|
||||
|
||||
@ -98,6 +104,11 @@ void DataFlash_Class::handle_log_request_list(GCS_MAVLINK &link, mavlink_message
|
||||
*/
|
||||
void DataFlash_Class::handle_log_request_data(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_data_t packet;
|
||||
mavlink_msg_log_request_data_decode(msg, &packet);
|
||||
|
||||
@ -131,6 +142,7 @@ void DataFlash_Class::handle_log_request_data(GCS_MAVLINK &link, mavlink_message
|
||||
_log_data_remaining = packet.count;
|
||||
}
|
||||
_log_sending = true;
|
||||
_log_sending_chan = link.get_chan();
|
||||
|
||||
handle_log_send(link);
|
||||
}
|
||||
@ -155,6 +167,7 @@ void DataFlash_Class::handle_log_request_end(GCS_MAVLINK &link, mavlink_message_
|
||||
mavlink_msg_log_request_end_decode(msg, &packet);
|
||||
_in_log_download = false;
|
||||
_log_sending = false;
|
||||
_log_sending_chan = -1;
|
||||
}
|
||||
|
||||
/**
|
||||
@ -162,6 +175,9 @@ void DataFlash_Class::handle_log_request_end(GCS_MAVLINK &link, mavlink_message_
|
||||
*/
|
||||
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);
|
||||
}
|
||||
@ -217,6 +233,7 @@ void DataFlash_Class::handle_log_send_listing(GCS_MAVLINK &link)
|
||||
mavlink_msg_log_entry_send(link.get_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;
|
||||
_log_sending_chan = -1;
|
||||
} else {
|
||||
_log_next_list_entry++;
|
||||
}
|
||||
@ -264,6 +281,7 @@ bool DataFlash_Class::handle_log_send_data(GCS_MAVLINK &link)
|
||||
_log_data_remaining -= len;
|
||||
if (ret < 90 || _log_data_remaining == 0) {
|
||||
_log_sending = false;
|
||||
_log_sending_chan = -1;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user