DataFlash: handle log sending as part of periodic function

This commit is contained in:
Peter Barker 2018-03-19 14:37:21 +11:00 committed by Randy Mackay
parent 3b3341f23d
commit 96d7eb6bed
3 changed files with 41 additions and 29 deletions

View File

@ -583,7 +583,8 @@ void DataFlash_Class::handle_mavlink_msg(GCS_MAVLINK &link, mavlink_message_t* m
}
void DataFlash_Class::periodic_tasks() {
FOR_EACH_BACKEND(periodic_tasks());
handle_log_send();
FOR_EACH_BACKEND(periodic_tasks());
}
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX

View File

@ -222,7 +222,7 @@ public:
void set_vehicle_armed(bool armed_state);
bool vehicle_is_armed() const { return _armed; }
void handle_log_send(class GCS_MAVLINK &);
void handle_log_send();
bool in_log_download() const { return _in_log_download; }
float quiet_nanf() const { return nanf("0x4152"); } // "AR"
@ -370,7 +370,7 @@ private:
// start page of log data
uint16_t _log_data_page;
int8_t _log_sending_chan = -1;
GCS_MAVLINK *_log_sending_link;
bool should_handle_log_message();
void handle_log_message(class GCS_MAVLINK &, mavlink_message_t *msg);
@ -379,8 +379,8 @@ private:
void handle_log_request_data(class GCS_MAVLINK &, mavlink_message_t *msg);
void handle_log_request_erase(class GCS_MAVLINK &, mavlink_message_t *msg);
void handle_log_request_end(class GCS_MAVLINK &, mavlink_message_t *msg);
void handle_log_send_listing(class GCS_MAVLINK &);
bool handle_log_send_data(class GCS_MAVLINK &);
void handle_log_send_listing();
bool handle_log_send_data();
void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc);

View File

@ -66,7 +66,7 @@ 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) {
if (_log_sending_link != nullptr) {
link.send_text(MAV_SEVERITY_INFO, "Log download in progress");
return;
}
@ -94,8 +94,8 @@ 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);
_log_sending_link = &link;
handle_log_send_listing();
}
@ -104,12 +104,12 @@ 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) {
if (_log_sending_link != nullptr) {
// some GCS (e.g. MAVProxy) attempt to stream request_data
// messages when they're filling gaps in the downloaded logs.
// This channel check avoids complaining to them, at the cost
// of silently dropping any repeated attempts to start logging
if (_log_sending_chan != link.get_chan()) {
if (_log_sending_link->get_chan() != link.get_chan()) {
link.send_text(MAV_SEVERITY_INFO, "Log download in progress");
}
return;
@ -148,9 +148,9 @@ 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();
_log_sending_link = &link;
handle_log_send(link);
handle_log_send();
}
/**
@ -173,19 +173,23 @@ 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;
_log_sending_link = nullptr;
}
/**
trigger sending of log messages if there are some pending
*/
void DataFlash_Class::handle_log_send(GCS_MAVLINK &link)
void DataFlash_Class::handle_log_send()
{
if (_log_sending_chan != link.get_chan()) {
if (_log_sending_link == nullptr) {
return;
}
if (hal.util->get_soft_armed()) {
// might be flying
return;
}
if (_log_listing) {
handle_log_send_listing(link);
handle_log_send_listing();
}
if (!_log_sending) {
return;
@ -196,10 +200,10 @@ void DataFlash_Class::handle_log_send(GCS_MAVLINK &link)
const uint8_t num_sends = 40;
#else
uint8_t num_sends = 1;
if (link.is_high_bandwidth() && hal.gpio->usb_connected()) {
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 (link.have_flow_control()) {
} else if (_log_sending_link->have_flow_control()) {
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
num_sends = 80;
#else
@ -210,7 +214,7 @@ void DataFlash_Class::handle_log_send(GCS_MAVLINK &link)
for (uint8_t i=0; i<num_sends; i++) {
if (_log_sending) {
if (!handle_log_send_data(link)) break;
if (!handle_log_send_data()) break;
}
}
}
@ -218,13 +222,13 @@ void DataFlash_Class::handle_log_send(GCS_MAVLINK &link)
/**
trigger sending of log messages if there are some pending
*/
void DataFlash_Class::handle_log_send_listing(GCS_MAVLINK &link)
void DataFlash_Class::handle_log_send_listing()
{
if (!HAVE_PAYLOAD_SPACE(link.get_chan(), LOG_ENTRY)) {
if (!HAVE_PAYLOAD_SPACE(_log_sending_link->get_chan(), LOG_ENTRY)) {
// no space
return;
}
if (AP_HAL::millis() - link.get_last_heartbeat_time() > 3000) {
if (AP_HAL::millis() - _log_sending_link->get_last_heartbeat_time() > 3000) {
// give a heartbeat a chance
return;
}
@ -236,10 +240,15 @@ void DataFlash_Class::handle_log_send_listing(GCS_MAVLINK &link)
} else {
get_log_info(_log_next_list_entry, size, time_utc);
}
mavlink_msg_log_entry_send(link.get_chan(), _log_next_list_entry, _log_num_logs, _log_last_list_entry, time_utc, size);
mavlink_msg_log_entry_send(_log_sending_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;
_log_sending_link = nullptr;
} else {
_log_next_list_entry++;
}
@ -248,13 +257,13 @@ void DataFlash_Class::handle_log_send_listing(GCS_MAVLINK &link)
/**
trigger sending of log data if there are some pending
*/
bool DataFlash_Class::handle_log_send_data(GCS_MAVLINK &link)
bool DataFlash_Class::handle_log_send_data()
{
if (!HAVE_PAYLOAD_SPACE(link.get_chan(), LOG_DATA)) {
if (!HAVE_PAYLOAD_SPACE(_log_sending_link->get_chan(), LOG_DATA)) {
// no space
return false;
}
if (AP_HAL::millis() - link.get_last_heartbeat_time() > 3000) {
if (AP_HAL::millis() - _log_sending_link->get_last_heartbeat_time() > 3000) {
// give a heartbeat a chance
return false;
}
@ -278,7 +287,9 @@ bool DataFlash_Class::handle_log_send_data(GCS_MAVLINK &link)
packet.ofs = _log_data_offset;
packet.id = _log_num_data;
packet.count = ret;
_mav_finalize_message_chan_send(link.get_chan(), MAVLINK_MSG_ID_LOG_DATA, (const char *)&packet,
_mav_finalize_message_chan_send(_log_sending_link->get_chan(),
MAVLINK_MSG_ID_LOG_DATA,
(const char *)&packet,
MAVLINK_MSG_ID_LOG_DATA_MIN_LEN,
MAVLINK_MSG_ID_LOG_DATA_LEN,
MAVLINK_MSG_ID_LOG_DATA_CRC);
@ -287,7 +298,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;
_log_sending_link = nullptr;
}
return true;
}