DataFlash: move send-logs-via-mavlink code into DataFlash
This commit is contained in:
parent
cbbee995b6
commit
305531952f
@ -460,11 +460,20 @@ bool DataFlash_Class::logging_started(void) {
|
||||
return false;
|
||||
}
|
||||
|
||||
void DataFlash_Class::handle_mavlink_msg(mavlink_channel_t chan, mavlink_message_t* msg)
|
||||
void DataFlash_Class::handle_mavlink_msg(GCS_MAVLINK &link, mavlink_message_t* msg)
|
||||
{
|
||||
switch (msg->msgid) {
|
||||
case MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS:
|
||||
FOR_EACH_BACKEND(remote_log_block_status_msg(chan, msg));
|
||||
FOR_EACH_BACKEND(remote_log_block_status_msg(link.get_chan(), msg));
|
||||
break;
|
||||
case MAVLINK_MSG_ID_LOG_REQUEST_LIST:
|
||||
/* fall through */
|
||||
case MAVLINK_MSG_ID_LOG_REQUEST_DATA:
|
||||
/* fall through */
|
||||
case MAVLINK_MSG_ID_LOG_ERASE:
|
||||
/* fall through */
|
||||
case MAVLINK_MSG_ID_LOG_REQUEST_END:
|
||||
handle_log_message(link, msg);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
@ -88,7 +88,6 @@ public:
|
||||
// high level interface
|
||||
uint16_t find_last_log() const;
|
||||
void get_log_boundaries(uint16_t log_num, uint16_t & start_page, uint16_t & end_page);
|
||||
void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc);
|
||||
int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data);
|
||||
uint16_t get_num_logs(void);
|
||||
void LogReadProcess(uint16_t log_num,
|
||||
@ -178,7 +177,7 @@ public:
|
||||
void flush(void);
|
||||
#endif
|
||||
|
||||
void handle_mavlink_msg(mavlink_channel_t chan, mavlink_message_t* msg);
|
||||
void handle_mavlink_msg(class GCS_MAVLINK &, mavlink_message_t* msg);
|
||||
|
||||
void periodic_tasks(); // may want to split this into GCS/non-GCS duties
|
||||
|
||||
@ -213,6 +212,8 @@ public:
|
||||
void set_vehicle_armed(bool armed_state);
|
||||
bool vehicle_is_armed() const { return _armed; }
|
||||
|
||||
void handle_log_send(class GCS_MAVLINK &);
|
||||
|
||||
protected:
|
||||
|
||||
const struct LogStructure *_structures;
|
||||
@ -289,4 +290,44 @@ private:
|
||||
|
||||
bool _writes_enabled;
|
||||
|
||||
/* support for retrieving logs via mavlink: */
|
||||
uint8_t _log_listing:1; // sending log list
|
||||
uint8_t _log_sending:1; // sending log data
|
||||
|
||||
// next log list entry to send
|
||||
uint16_t _log_next_list_entry;
|
||||
|
||||
// last log list entry to send
|
||||
uint16_t _log_last_list_entry;
|
||||
|
||||
// number of log files
|
||||
uint16_t _log_num_logs;
|
||||
|
||||
// log number for data send
|
||||
uint16_t _log_num_data;
|
||||
|
||||
// offset in log
|
||||
uint32_t _log_data_offset;
|
||||
|
||||
// size of log file
|
||||
uint32_t _log_data_size;
|
||||
|
||||
// number of bytes left to send
|
||||
uint32_t _log_data_remaining;
|
||||
|
||||
// start page of log data
|
||||
uint16_t _log_data_page;
|
||||
|
||||
void handle_log_message(class GCS_MAVLINK &, mavlink_message_t *msg);
|
||||
|
||||
void handle_log_request_list(class GCS_MAVLINK &, mavlink_message_t *msg);
|
||||
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 get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc);
|
||||
/* end support for retrieving logs via mavlink: */
|
||||
|
||||
};
|
||||
|
@ -19,37 +19,36 @@
|
||||
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "GCS.h"
|
||||
#include <DataFlash/DataFlash.h>
|
||||
#include <GCS_MAVLink/GCS.h> // for LOG_ENTRY
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
/**
|
||||
handle all types of log download requests from the GCS
|
||||
*/
|
||||
void GCS_MAVLINK::handle_log_message(mavlink_message_t *msg, DataFlash_Class &dataflash)
|
||||
void DataFlash_Class::handle_log_message(GCS_MAVLINK &link, mavlink_message_t *msg)
|
||||
{
|
||||
switch (msg->msgid) {
|
||||
case MAVLINK_MSG_ID_LOG_REQUEST_LIST:
|
||||
handle_log_request_list(msg, dataflash);
|
||||
handle_log_request_list(link, msg);
|
||||
break;
|
||||
case MAVLINK_MSG_ID_LOG_REQUEST_DATA:
|
||||
handle_log_request_data(msg, dataflash);
|
||||
handle_log_request_data(link, msg);
|
||||
break;
|
||||
case MAVLINK_MSG_ID_LOG_ERASE:
|
||||
handle_log_request_erase(msg, dataflash);
|
||||
handle_log_request_erase(link, msg);
|
||||
break;
|
||||
case MAVLINK_MSG_ID_LOG_REQUEST_END:
|
||||
handle_log_request_end(msg, dataflash);
|
||||
handle_log_request_end(link, msg);
|
||||
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)
|
||||
void DataFlash_Class::handle_log_request_list(GCS_MAVLINK &link, mavlink_message_t *msg)
|
||||
{
|
||||
mavlink_log_request_list_t packet;
|
||||
mavlink_msg_log_request_list_decode(msg, &packet);
|
||||
@ -57,7 +56,7 @@ void GCS_MAVLINK::handle_log_request_list(mavlink_message_t *msg, DataFlash_Clas
|
||||
_log_listing = false;
|
||||
_log_sending = false;
|
||||
|
||||
_log_num_logs = dataflash.get_num_logs();
|
||||
_log_num_logs = get_num_logs();
|
||||
if (_log_num_logs == 0) {
|
||||
_log_next_list_entry = 0;
|
||||
_log_last_list_entry = 0;
|
||||
@ -74,14 +73,14 @@ void GCS_MAVLINK::handle_log_request_list(mavlink_message_t *msg, DataFlash_Clas
|
||||
}
|
||||
|
||||
_log_listing = true;
|
||||
handle_log_send_listing(dataflash);
|
||||
handle_log_send_listing(link);
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
handle request for log data
|
||||
*/
|
||||
void GCS_MAVLINK::handle_log_request_data(mavlink_message_t *msg, DataFlash_Class &dataflash)
|
||||
void DataFlash_Class::handle_log_request_data(GCS_MAVLINK &link, mavlink_message_t *msg)
|
||||
{
|
||||
mavlink_log_request_data_t packet;
|
||||
mavlink_msg_log_request_data_decode(msg, &packet);
|
||||
@ -90,18 +89,18 @@ void GCS_MAVLINK::handle_log_request_data(mavlink_message_t *msg, DataFlash_Clas
|
||||
if (!_log_sending || _log_num_data != packet.id) {
|
||||
_log_sending = false;
|
||||
|
||||
uint16_t num_logs = dataflash.get_num_logs();
|
||||
uint16_t num_logs = get_num_logs();
|
||||
if (packet.id > num_logs || packet.id < 1) {
|
||||
return;
|
||||
}
|
||||
|
||||
uint32_t time_utc, size;
|
||||
dataflash.get_log_info(packet.id, size, time_utc);
|
||||
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);
|
||||
get_log_boundaries(packet.id, _log_data_page, end);
|
||||
}
|
||||
|
||||
_log_data_offset = packet.ofs;
|
||||
@ -115,24 +114,24 @@ void GCS_MAVLINK::handle_log_request_data(mavlink_message_t *msg, DataFlash_Clas
|
||||
}
|
||||
_log_sending = true;
|
||||
|
||||
handle_log_send(dataflash);
|
||||
handle_log_send(link);
|
||||
}
|
||||
|
||||
/**
|
||||
handle request to erase log data
|
||||
*/
|
||||
void GCS_MAVLINK::handle_log_request_erase(mavlink_message_t *msg, DataFlash_Class &dataflash)
|
||||
void DataFlash_Class::handle_log_request_erase(GCS_MAVLINK &link, mavlink_message_t *msg)
|
||||
{
|
||||
mavlink_log_erase_t packet;
|
||||
mavlink_msg_log_erase_decode(msg, &packet);
|
||||
// mavlink_log_erase_t packet;
|
||||
// mavlink_msg_log_erase_decode(msg, &packet);
|
||||
|
||||
dataflash.EraseAll();
|
||||
EraseAll();
|
||||
}
|
||||
|
||||
/**
|
||||
handle request to stop transfer and resume normal logging
|
||||
*/
|
||||
void GCS_MAVLINK::handle_log_request_end(mavlink_message_t *msg, DataFlash_Class &dataflash)
|
||||
void DataFlash_Class::handle_log_request_end(GCS_MAVLINK &link, mavlink_message_t *msg)
|
||||
{
|
||||
mavlink_log_request_end_t packet;
|
||||
mavlink_msg_log_request_end_decode(msg, &packet);
|
||||
@ -142,10 +141,10 @@ void GCS_MAVLINK::handle_log_request_end(mavlink_message_t *msg, DataFlash_Class
|
||||
/**
|
||||
trigger sending of log messages if there are some pending
|
||||
*/
|
||||
void GCS_MAVLINK::handle_log_send(DataFlash_Class &dataflash)
|
||||
void DataFlash_Class::handle_log_send(GCS_MAVLINK &link)
|
||||
{
|
||||
if (_log_listing) {
|
||||
handle_log_send_listing(dataflash);
|
||||
handle_log_send_listing(link);
|
||||
}
|
||||
if (!_log_sending) {
|
||||
return;
|
||||
@ -156,10 +155,10 @@ void GCS_MAVLINK::handle_log_send(DataFlash_Class &dataflash)
|
||||
const uint8_t num_sends = 40;
|
||||
#else
|
||||
uint8_t num_sends = 1;
|
||||
if (chan == MAVLINK_COMM_0 && hal.gpio->usb_connected()) {
|
||||
if (link.is_high_bandwidth() && hal.gpio->usb_connected()) {
|
||||
// when on USB we can send a lot more data
|
||||
num_sends = 250;
|
||||
} else if (have_flow_control()) {
|
||||
} else if (link.have_flow_control()) {
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||
num_sends = 80;
|
||||
#else
|
||||
@ -170,7 +169,7 @@ void GCS_MAVLINK::handle_log_send(DataFlash_Class &dataflash)
|
||||
|
||||
for (uint8_t i=0; i<num_sends; i++) {
|
||||
if (_log_sending) {
|
||||
if (!handle_log_send_data(dataflash)) break;
|
||||
if (!handle_log_send_data(link)) break;
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -178,13 +177,13 @@ void GCS_MAVLINK::handle_log_send(DataFlash_Class &dataflash)
|
||||
/**
|
||||
trigger sending of log messages if there are some pending
|
||||
*/
|
||||
void GCS_MAVLINK::handle_log_send_listing(DataFlash_Class &dataflash)
|
||||
void DataFlash_Class::handle_log_send_listing(GCS_MAVLINK &link)
|
||||
{
|
||||
if (!HAVE_PAYLOAD_SPACE(chan, LOG_ENTRY)) {
|
||||
if (!HAVE_PAYLOAD_SPACE(link.get_chan(), LOG_ENTRY)) {
|
||||
// no space
|
||||
return;
|
||||
}
|
||||
if (AP_HAL::millis() - last_heartbeat_time > 3000) {
|
||||
if (AP_HAL::millis() - link.get_last_heartbeat_time() > 3000) {
|
||||
// give a heartbeat a chance
|
||||
return;
|
||||
}
|
||||
@ -194,9 +193,9 @@ void GCS_MAVLINK::handle_log_send_listing(DataFlash_Class &dataflash)
|
||||
size = 0;
|
||||
time_utc = 0;
|
||||
} else {
|
||||
dataflash.get_log_info(_log_next_list_entry, size, time_utc);
|
||||
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);
|
||||
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;
|
||||
} else {
|
||||
@ -207,13 +206,13 @@ void GCS_MAVLINK::handle_log_send_listing(DataFlash_Class &dataflash)
|
||||
/**
|
||||
trigger sending of log data if there are some pending
|
||||
*/
|
||||
bool GCS_MAVLINK::handle_log_send_data(DataFlash_Class &dataflash)
|
||||
bool DataFlash_Class::handle_log_send_data(GCS_MAVLINK &link)
|
||||
{
|
||||
if (!HAVE_PAYLOAD_SPACE(chan, LOG_DATA)) {
|
||||
if (!HAVE_PAYLOAD_SPACE(link.get_chan(), LOG_DATA)) {
|
||||
// no space
|
||||
return false;
|
||||
}
|
||||
if (AP_HAL::millis() - last_heartbeat_time > 3000) {
|
||||
if (AP_HAL::millis() - link.get_last_heartbeat_time() > 3000) {
|
||||
// give a heartbeat a chance
|
||||
return false;
|
||||
}
|
||||
@ -225,7 +224,7 @@ bool GCS_MAVLINK::handle_log_send_data(DataFlash_Class &dataflash)
|
||||
if (len > 90) {
|
||||
len = 90;
|
||||
}
|
||||
ret = dataflash.get_log_data(_log_num_data, _log_data_page, _log_data_offset, len, packet.data);
|
||||
ret = get_log_data(_log_num_data, _log_data_page, _log_data_offset, len, packet.data);
|
||||
if (ret < 0) {
|
||||
// report as EOF on error
|
||||
ret = 0;
|
||||
@ -237,7 +236,7 @@ bool GCS_MAVLINK::handle_log_send_data(DataFlash_Class &dataflash)
|
||||
packet.ofs = _log_data_offset;
|
||||
packet.id = _log_num_data;
|
||||
packet.count = ret;
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, (const char *)&packet,
|
||||
_mav_finalize_message_chan_send(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);
|
||||
|
Loading…
Reference in New Issue
Block a user