2013-12-15 03:57:15 -04:00
|
|
|
/*
|
2013-12-16 20:14:53 -04:00
|
|
|
MAVLink logfile transfer functions
|
|
|
|
*/
|
2013-12-15 03:57:15 -04:00
|
|
|
|
2013-12-16 20:14:53 -04:00
|
|
|
/*
|
2013-12-15 03:57:15 -04:00
|
|
|
This program is free software: you can redistribute it and/or modify
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
GNU General Public License for more details.
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
|
|
|
|
|
2015-08-11 03:28:46 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2019-01-18 00:23:42 -04:00
|
|
|
#include <AP_Logger/AP_Logger.h>
|
2017-06-18 20:43:15 -03:00
|
|
|
#include <GCS_MAVLink/GCS.h> // for LOG_ENTRY
|
2013-12-15 18:57:28 -04:00
|
|
|
|
2021-08-18 08:42:17 -03:00
|
|
|
#if HAL_GCS_ENABLED
|
2021-05-19 23:34:13 -03:00
|
|
|
|
2013-12-15 18:57:28 -04:00
|
|
|
extern const AP_HAL::HAL& hal;
|
2013-12-15 03:57:15 -04:00
|
|
|
|
|
|
|
/**
|
|
|
|
handle all types of log download requests from the GCS
|
|
|
|
*/
|
2019-04-30 07:22:48 -03:00
|
|
|
void AP_Logger::handle_log_message(GCS_MAVLINK &link, const mavlink_message_t &msg)
|
2013-12-15 03:57:15 -04:00
|
|
|
{
|
2021-08-30 10:44:47 -03:00
|
|
|
if (!WritesEnabled()) {
|
|
|
|
// this is currently used as a proxy for "in_mavlink_delay"
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
if (vehicle_is_armed()) {
|
|
|
|
if (!_warned_log_disarm) {
|
|
|
|
link.send_text(MAV_SEVERITY_ERROR, "Disarm for log download");
|
|
|
|
_warned_log_disarm = true;
|
|
|
|
}
|
2017-06-19 22:52:47 -03:00
|
|
|
return;
|
|
|
|
}
|
2021-08-30 10:44:47 -03:00
|
|
|
_warned_log_disarm = false;
|
2021-03-19 18:28:29 -03:00
|
|
|
_last_mavlink_log_transfer_message_handled_ms = AP_HAL::millis();
|
2019-04-30 07:22:48 -03:00
|
|
|
switch (msg.msgid) {
|
2013-12-15 03:57:15 -04:00
|
|
|
case MAVLINK_MSG_ID_LOG_REQUEST_LIST:
|
2017-06-18 20:43:15 -03:00
|
|
|
handle_log_request_list(link, msg);
|
2013-12-15 03:57:15 -04:00
|
|
|
break;
|
|
|
|
case MAVLINK_MSG_ID_LOG_REQUEST_DATA:
|
2017-06-18 20:43:15 -03:00
|
|
|
handle_log_request_data(link, msg);
|
2013-12-15 03:57:15 -04:00
|
|
|
break;
|
2013-12-15 18:57:28 -04:00
|
|
|
case MAVLINK_MSG_ID_LOG_ERASE:
|
2017-06-18 20:43:15 -03:00
|
|
|
handle_log_request_erase(link, msg);
|
2013-12-15 18:57:28 -04:00
|
|
|
break;
|
2014-01-13 22:51:20 -04:00
|
|
|
case MAVLINK_MSG_ID_LOG_REQUEST_END:
|
2017-06-18 20:43:15 -03:00
|
|
|
handle_log_request_end(link, msg);
|
2014-01-13 22:51:20 -04:00
|
|
|
break;
|
2013-12-15 03:57:15 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
/**
|
|
|
|
handle all types of log download requests from the GCS
|
|
|
|
*/
|
2019-04-30 07:22:48 -03:00
|
|
|
void AP_Logger::handle_log_request_list(GCS_MAVLINK &link, const mavlink_message_t &msg)
|
2013-12-15 03:57:15 -04:00
|
|
|
{
|
2019-02-17 22:53:50 -04:00
|
|
|
WITH_SEMAPHORE(_log_send_sem);
|
|
|
|
|
2018-03-19 00:37:21 -03:00
|
|
|
if (_log_sending_link != nullptr) {
|
2017-07-16 04:04:14 -03:00
|
|
|
link.send_text(MAV_SEVERITY_INFO, "Log download in progress");
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2013-12-15 03:57:15 -04:00
|
|
|
mavlink_log_request_list_t packet;
|
2019-04-30 07:22:48 -03:00
|
|
|
mavlink_msg_log_request_list_decode(&msg, &packet);
|
2014-12-09 23:03:53 -04:00
|
|
|
|
2017-06-18 20:43:15 -03:00
|
|
|
_log_num_logs = get_num_logs();
|
2019-12-15 18:08:10 -04:00
|
|
|
|
2013-12-15 18:57:28 -04:00
|
|
|
if (_log_num_logs == 0) {
|
2014-03-11 03:12:22 -03:00
|
|
|
_log_next_list_entry = 0;
|
|
|
|
_log_last_list_entry = 0;
|
|
|
|
} else {
|
|
|
|
_log_next_list_entry = packet.start;
|
|
|
|
_log_last_list_entry = packet.end;
|
2013-12-15 03:57:15 -04:00
|
|
|
|
2020-05-05 14:00:54 -03:00
|
|
|
if (_log_last_list_entry > _log_num_logs) {
|
|
|
|
_log_last_list_entry = _log_num_logs;
|
2014-03-11 03:12:22 -03:00
|
|
|
}
|
2015-10-20 07:35:19 -03:00
|
|
|
if (_log_next_list_entry < 1) {
|
2020-05-05 14:00:54 -03:00
|
|
|
_log_next_list_entry = 1;
|
2014-03-11 03:12:22 -03:00
|
|
|
}
|
2013-12-15 03:57:15 -04:00
|
|
|
}
|
2013-12-15 18:57:28 -04:00
|
|
|
|
2019-12-04 23:29:47 -04:00
|
|
|
transfer_activity = TransferActivity::LISTING;
|
2018-03-19 00:37:21 -03:00
|
|
|
_log_sending_link = &link;
|
2018-06-19 21:13:22 -03:00
|
|
|
|
2018-03-19 00:37:21 -03:00
|
|
|
handle_log_send_listing();
|
2013-12-15 03:57:15 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
handle request for log data
|
|
|
|
*/
|
2019-04-30 07:22:48 -03:00
|
|
|
void AP_Logger::handle_log_request_data(GCS_MAVLINK &link, const mavlink_message_t &msg)
|
2013-12-15 03:57:15 -04:00
|
|
|
{
|
2019-02-17 22:53:50 -04:00
|
|
|
WITH_SEMAPHORE(_log_send_sem);
|
|
|
|
|
2018-03-19 00:37:21 -03:00
|
|
|
if (_log_sending_link != nullptr) {
|
2017-07-17 02:14:34 -03:00
|
|
|
// 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
|
2018-03-19 00:37:21 -03:00
|
|
|
if (_log_sending_link->get_chan() != link.get_chan()) {
|
2017-07-17 02:14:34 -03:00
|
|
|
link.send_text(MAV_SEVERITY_INFO, "Log download in progress");
|
|
|
|
}
|
2017-07-16 04:04:14 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2013-12-15 03:57:15 -04:00
|
|
|
mavlink_log_request_data_t packet;
|
2019-04-30 07:22:48 -03:00
|
|
|
mavlink_msg_log_request_data_decode(&msg, &packet);
|
2013-12-15 03:57:15 -04:00
|
|
|
|
2018-06-19 21:13:22 -03:00
|
|
|
// consider opening or switching logs:
|
2019-12-04 23:29:47 -04:00
|
|
|
if (transfer_activity != TransferActivity::SENDING || _log_num_data != packet.id) {
|
2013-12-15 03:57:15 -04:00
|
|
|
|
2017-06-18 20:43:15 -03:00
|
|
|
uint16_t num_logs = get_num_logs();
|
2020-05-05 14:00:54 -03:00
|
|
|
if (packet.id > num_logs || packet.id < 1) {
|
2018-06-19 21:13:22 -03:00
|
|
|
// request for an invalid log; cancel any current download
|
2019-12-04 23:29:47 -04:00
|
|
|
transfer_activity = TransferActivity::IDLE;
|
2013-12-29 00:00:04 -04:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
uint32_t time_utc, size;
|
2017-06-18 20:43:15 -03:00
|
|
|
get_log_info(packet.id, size, time_utc);
|
2013-12-29 00:00:04 -04:00
|
|
|
_log_num_data = packet.id;
|
|
|
|
_log_data_size = size;
|
|
|
|
|
2019-01-18 18:45:36 -04:00
|
|
|
uint32_t end;
|
2017-06-18 20:43:15 -03:00
|
|
|
get_log_boundaries(packet.id, _log_data_page, end);
|
2013-12-15 03:57:15 -04:00
|
|
|
}
|
|
|
|
|
2014-02-13 22:14:07 -04:00
|
|
|
_log_data_offset = packet.ofs;
|
2013-12-29 00:00:04 -04:00
|
|
|
if (_log_data_offset >= _log_data_size) {
|
2013-12-15 03:57:15 -04:00
|
|
|
_log_data_remaining = 0;
|
|
|
|
} else {
|
2013-12-29 00:00:04 -04:00
|
|
|
_log_data_remaining = _log_data_size - _log_data_offset;
|
2013-12-15 03:57:15 -04:00
|
|
|
}
|
2013-12-15 18:57:28 -04:00
|
|
|
if (_log_data_remaining > packet.count) {
|
|
|
|
_log_data_remaining = packet.count;
|
|
|
|
}
|
2018-06-19 21:13:22 -03:00
|
|
|
|
2019-12-04 23:29:47 -04:00
|
|
|
transfer_activity = TransferActivity::SENDING;
|
2018-03-19 00:37:21 -03:00
|
|
|
_log_sending_link = &link;
|
2013-12-15 18:57:28 -04:00
|
|
|
|
2018-03-19 00:37:21 -03:00
|
|
|
handle_log_send();
|
2013-12-15 03:57:15 -04:00
|
|
|
}
|
|
|
|
|
2014-09-26 23:43:14 -03:00
|
|
|
/**
|
|
|
|
handle request to erase log data
|
|
|
|
*/
|
2019-04-30 07:22:48 -03:00
|
|
|
void AP_Logger::handle_log_request_erase(GCS_MAVLINK &link, const mavlink_message_t &msg)
|
2014-09-26 23:43:14 -03:00
|
|
|
{
|
2017-06-18 20:43:15 -03:00
|
|
|
// mavlink_log_erase_t packet;
|
2019-04-30 07:22:48 -03:00
|
|
|
// mavlink_msg_log_erase_decode(&msg, &packet);
|
2014-09-26 23:43:14 -03:00
|
|
|
|
2017-06-18 20:43:15 -03:00
|
|
|
EraseAll();
|
2014-09-26 23:43:14 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
/**
|
|
|
|
handle request to stop transfer and resume normal logging
|
|
|
|
*/
|
2019-04-30 07:22:48 -03:00
|
|
|
void AP_Logger::handle_log_request_end(GCS_MAVLINK &link, const mavlink_message_t &msg)
|
2014-09-26 23:43:14 -03:00
|
|
|
{
|
2019-02-17 22:53:50 -04:00
|
|
|
WITH_SEMAPHORE(_log_send_sem);
|
2014-09-30 22:45:51 -03:00
|
|
|
mavlink_log_request_end_t packet;
|
2019-04-30 07:22:48 -03:00
|
|
|
mavlink_msg_log_request_end_decode(&msg, &packet);
|
2018-06-19 21:13:22 -03:00
|
|
|
|
2019-12-04 23:29:47 -04:00
|
|
|
transfer_activity = TransferActivity::IDLE;
|
2018-03-19 00:37:21 -03:00
|
|
|
_log_sending_link = nullptr;
|
2014-09-26 23:43:14 -03:00
|
|
|
}
|
|
|
|
|
2013-12-15 03:57:15 -04:00
|
|
|
/**
|
|
|
|
trigger sending of log messages if there are some pending
|
|
|
|
*/
|
2019-01-18 00:23:42 -04:00
|
|
|
void AP_Logger::handle_log_send()
|
2013-12-15 03:57:15 -04:00
|
|
|
{
|
2019-02-17 22:53:50 -04:00
|
|
|
WITH_SEMAPHORE(_log_send_sem);
|
|
|
|
|
2018-03-19 00:37:21 -03:00
|
|
|
if (_log_sending_link == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
if (hal.util->get_soft_armed()) {
|
|
|
|
// might be flying
|
2017-07-16 04:04:14 -03:00
|
|
|
return;
|
|
|
|
}
|
2018-06-19 21:13:22 -03:00
|
|
|
switch (transfer_activity) {
|
2019-12-04 23:29:47 -04:00
|
|
|
case TransferActivity::IDLE:
|
2018-06-19 21:13:22 -03:00
|
|
|
break;
|
2019-12-04 23:29:47 -04:00
|
|
|
case TransferActivity::LISTING:
|
2018-03-19 00:37:21 -03:00
|
|
|
handle_log_send_listing();
|
2018-06-19 21:13:22 -03:00
|
|
|
break;
|
2019-12-04 23:29:47 -04:00
|
|
|
case TransferActivity::SENDING:
|
2018-06-19 21:13:22 -03:00
|
|
|
handle_log_sending();
|
|
|
|
break;
|
2013-12-15 03:57:15 -04:00
|
|
|
}
|
2018-06-19 21:13:22 -03:00
|
|
|
}
|
2016-07-05 17:09:51 -03:00
|
|
|
|
2019-01-18 00:23:42 -04:00
|
|
|
void AP_Logger::handle_log_sending()
|
2018-06-19 21:13:22 -03:00
|
|
|
{
|
2019-02-17 22:53:50 -04:00
|
|
|
WITH_SEMAPHORE(_log_send_sem);
|
|
|
|
|
2016-07-05 17:09:51 -03:00
|
|
|
#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
|
2013-12-15 18:57:28 -04:00
|
|
|
uint8_t num_sends = 1;
|
2018-03-19 00:37:21 -03:00
|
|
|
if (_log_sending_link->is_high_bandwidth() && hal.gpio->usb_connected()) {
|
2013-12-15 18:57:28 -04:00
|
|
|
// when on USB we can send a lot more data
|
2016-11-20 03:40:58 -04:00
|
|
|
num_sends = 250;
|
2018-03-19 00:37:21 -03:00
|
|
|
} else if (_log_sending_link->have_flow_control()) {
|
2016-07-05 17:09:51 -03:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
2015-07-29 01:04:35 -03:00
|
|
|
num_sends = 80;
|
2016-07-05 17:09:51 -03:00
|
|
|
#else
|
2015-07-29 01:04:35 -03:00
|
|
|
num_sends = 10;
|
2016-07-05 17:09:51 -03:00
|
|
|
#endif
|
2013-12-15 18:57:28 -04:00
|
|
|
}
|
2013-12-16 20:14:53 -04:00
|
|
|
#endif
|
|
|
|
|
2013-12-15 03:57:15 -04:00
|
|
|
for (uint8_t i=0; i<num_sends; i++) {
|
2019-12-04 23:29:47 -04:00
|
|
|
if (transfer_activity != TransferActivity::SENDING) {
|
2018-06-19 21:13:22 -03:00
|
|
|
// may have completed sending data
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
if (!handle_log_send_data()) {
|
|
|
|
break;
|
2013-12-15 03:57:15 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
/**
|
|
|
|
trigger sending of log messages if there are some pending
|
|
|
|
*/
|
2019-01-18 00:23:42 -04:00
|
|
|
void AP_Logger::handle_log_send_listing()
|
2013-12-15 03:57:15 -04:00
|
|
|
{
|
2019-02-17 22:53:50 -04:00
|
|
|
WITH_SEMAPHORE(_log_send_sem);
|
|
|
|
|
2018-03-19 00:37:21 -03:00
|
|
|
if (!HAVE_PAYLOAD_SPACE(_log_sending_link->get_chan(), LOG_ENTRY)) {
|
2013-12-15 03:57:15 -04:00
|
|
|
// no space
|
|
|
|
return;
|
|
|
|
}
|
2018-03-19 00:37:21 -03:00
|
|
|
if (AP_HAL::millis() - _log_sending_link->get_last_heartbeat_time() > 3000) {
|
2013-12-15 18:57:28 -04:00
|
|
|
// give a heartbeat a chance
|
|
|
|
return;
|
|
|
|
}
|
2013-12-15 03:57:15 -04:00
|
|
|
|
|
|
|
uint32_t size, time_utc;
|
2014-03-11 03:12:22 -03:00
|
|
|
if (_log_next_list_entry == 0) {
|
|
|
|
size = 0;
|
|
|
|
time_utc = 0;
|
|
|
|
} else {
|
2017-06-18 20:43:15 -03:00
|
|
|
get_log_info(_log_next_list_entry, size, time_utc);
|
2014-03-11 03:12:22 -03:00
|
|
|
}
|
2018-03-19 00:37:21 -03:00
|
|
|
mavlink_msg_log_entry_send(_log_sending_link->get_chan(),
|
|
|
|
_log_next_list_entry,
|
|
|
|
_log_num_logs,
|
|
|
|
_log_last_list_entry,
|
|
|
|
time_utc,
|
|
|
|
size);
|
2013-12-15 03:57:15 -04:00
|
|
|
if (_log_next_list_entry == _log_last_list_entry) {
|
2019-12-04 23:29:47 -04:00
|
|
|
transfer_activity = TransferActivity::IDLE;
|
2018-03-19 00:37:21 -03:00
|
|
|
_log_sending_link = nullptr;
|
2013-12-15 03:57:15 -04:00
|
|
|
} else {
|
|
|
|
_log_next_list_entry++;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
/**
|
|
|
|
trigger sending of log data if there are some pending
|
|
|
|
*/
|
2019-01-18 00:23:42 -04:00
|
|
|
bool AP_Logger::handle_log_send_data()
|
2013-12-15 03:57:15 -04:00
|
|
|
{
|
2019-02-17 22:53:50 -04:00
|
|
|
WITH_SEMAPHORE(_log_send_sem);
|
|
|
|
|
2018-03-19 00:37:21 -03:00
|
|
|
if (!HAVE_PAYLOAD_SPACE(_log_sending_link->get_chan(), LOG_DATA)) {
|
2013-12-15 03:57:15 -04:00
|
|
|
// no space
|
2013-12-27 23:25:07 -04:00
|
|
|
return false;
|
2013-12-15 03:57:15 -04:00
|
|
|
}
|
2018-03-19 00:37:21 -03:00
|
|
|
if (AP_HAL::millis() - _log_sending_link->get_last_heartbeat_time() > 3000) {
|
2013-12-15 18:57:28 -04:00
|
|
|
// give a heartbeat a chance
|
2013-12-27 23:25:07 -04:00
|
|
|
return false;
|
2013-12-15 18:57:28 -04:00
|
|
|
}
|
2013-12-15 03:57:15 -04:00
|
|
|
|
2020-05-05 14:00:54 -03:00
|
|
|
int16_t nbytes = 0;
|
2013-12-15 03:57:15 -04:00
|
|
|
uint32_t len = _log_data_remaining;
|
2014-03-17 23:51:31 -03:00
|
|
|
mavlink_log_data_t packet;
|
2013-12-15 03:57:15 -04:00
|
|
|
|
2018-06-18 01:22:25 -03:00
|
|
|
if (len > MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN) {
|
|
|
|
len = MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN;
|
2013-12-15 03:57:15 -04:00
|
|
|
}
|
2020-05-05 14:00:54 -03:00
|
|
|
|
|
|
|
nbytes = get_log_data(_log_num_data, _log_data_page, _log_data_offset, len, packet.data);
|
|
|
|
|
|
|
|
if (nbytes < 0) {
|
2013-12-15 03:57:15 -04:00
|
|
|
// report as EOF on error
|
2020-05-05 14:00:54 -03:00
|
|
|
nbytes = 0;
|
2013-12-15 03:57:15 -04:00
|
|
|
}
|
2020-05-05 14:00:54 -03:00
|
|
|
if (nbytes < MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN) {
|
|
|
|
memset(&packet.data[nbytes], 0, MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN-nbytes);
|
2013-12-16 20:14:53 -04:00
|
|
|
}
|
2014-03-17 23:51:31 -03:00
|
|
|
|
|
|
|
packet.ofs = _log_data_offset;
|
|
|
|
packet.id = _log_num_data;
|
2020-05-05 14:00:54 -03:00
|
|
|
packet.count = nbytes;
|
2018-03-19 00:37:21 -03:00
|
|
|
_mav_finalize_message_chan_send(_log_sending_link->get_chan(),
|
|
|
|
MAVLINK_MSG_ID_LOG_DATA,
|
|
|
|
(const char *)&packet,
|
2016-04-06 06:30:03 -03:00
|
|
|
MAVLINK_MSG_ID_LOG_DATA_MIN_LEN,
|
|
|
|
MAVLINK_MSG_ID_LOG_DATA_LEN,
|
|
|
|
MAVLINK_MSG_ID_LOG_DATA_CRC);
|
2014-03-17 23:51:31 -03:00
|
|
|
|
2020-05-05 14:00:54 -03:00
|
|
|
_log_data_offset += nbytes;
|
|
|
|
_log_data_remaining -= nbytes;
|
|
|
|
if (nbytes < MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN || _log_data_remaining == 0) {
|
2019-12-04 23:29:47 -04:00
|
|
|
transfer_activity = TransferActivity::IDLE;
|
2018-03-19 00:37:21 -03:00
|
|
|
_log_sending_link = nullptr;
|
2013-12-15 03:57:15 -04:00
|
|
|
}
|
2013-12-27 23:25:07 -04:00
|
|
|
return true;
|
2013-12-15 03:57:15 -04:00
|
|
|
}
|
2021-05-19 23:34:13 -03:00
|
|
|
|
|
|
|
#endif
|