mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
DataFlash: move log-transfer state variables into enumerated variable
This commit is contained in:
parent
4c2925d693
commit
fc378eeae1
@ -216,7 +216,7 @@ public:
|
||||
bool vehicle_is_armed() const { return _armed; }
|
||||
|
||||
void handle_log_send();
|
||||
bool in_log_download() const { return _in_log_download; }
|
||||
bool in_log_download() const { return transfer_activity != IDLE; }
|
||||
|
||||
float quiet_nanf() const { return nanf("0x4152"); } // "AR"
|
||||
double quiet_nan() const { return nan("0x4152445550490a"); } // "ARDUPI"
|
||||
@ -332,11 +332,12 @@ private:
|
||||
bool _writes_enabled:1;
|
||||
|
||||
/* support for retrieving logs via mavlink: */
|
||||
uint8_t _log_listing:1; // sending log list
|
||||
uint8_t _log_sending:1; // sending log data
|
||||
|
||||
// bolean replicating old vehicle in_log_download flag:
|
||||
bool _in_log_download:1;
|
||||
enum transfer_activity_t : uint8_t {
|
||||
IDLE, // not doing anything, all file descriptors closed
|
||||
LISTING, // actively sending log_entry packets
|
||||
SENDING, // actively sending log_sending packets
|
||||
} transfer_activity = IDLE;
|
||||
|
||||
// next log list entry to send
|
||||
uint16_t _log_next_list_entry;
|
||||
@ -371,8 +372,9 @@ 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();
|
||||
bool handle_log_send_data();
|
||||
void handle_log_send_listing(); // handle LISTING state
|
||||
void handle_log_sending(); // handle SENDING state
|
||||
bool handle_log_send_data(); // send data chunk to client
|
||||
|
||||
void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc);
|
||||
|
||||
|
@ -74,9 +74,6 @@ void DataFlash_Class::handle_log_request_list(GCS_MAVLINK &link, mavlink_message
|
||||
mavlink_log_request_list_t packet;
|
||||
mavlink_msg_log_request_list_decode(msg, &packet);
|
||||
|
||||
_log_listing = false;
|
||||
_log_sending = false;
|
||||
|
||||
_log_num_logs = get_num_logs();
|
||||
if (_log_num_logs == 0) {
|
||||
_log_next_list_entry = 0;
|
||||
@ -93,8 +90,9 @@ void DataFlash_Class::handle_log_request_list(GCS_MAVLINK &link, mavlink_message
|
||||
}
|
||||
}
|
||||
|
||||
_log_listing = true;
|
||||
transfer_activity = LISTING;
|
||||
_log_sending_link = &link;
|
||||
|
||||
handle_log_send_listing();
|
||||
}
|
||||
|
||||
@ -118,14 +116,13 @@ void DataFlash_Class::handle_log_request_data(GCS_MAVLINK &link, mavlink_message
|
||||
mavlink_log_request_data_t packet;
|
||||
mavlink_msg_log_request_data_decode(msg, &packet);
|
||||
|
||||
_in_log_download = true;
|
||||
|
||||
_log_listing = false;
|
||||
if (!_log_sending || _log_num_data != packet.id) {
|
||||
_log_sending = false;
|
||||
// consider opening or switching logs:
|
||||
if (transfer_activity != SENDING || _log_num_data != packet.id) {
|
||||
|
||||
uint16_t num_logs = get_num_logs();
|
||||
if (packet.id > num_logs || packet.id < 1) {
|
||||
// request for an invalid log; cancel any current download
|
||||
transfer_activity = IDLE;
|
||||
return;
|
||||
}
|
||||
|
||||
@ -147,7 +144,8 @@ void DataFlash_Class::handle_log_request_data(GCS_MAVLINK &link, mavlink_message
|
||||
if (_log_data_remaining > packet.count) {
|
||||
_log_data_remaining = packet.count;
|
||||
}
|
||||
_log_sending = true;
|
||||
|
||||
transfer_activity = SENDING;
|
||||
_log_sending_link = &link;
|
||||
|
||||
handle_log_send();
|
||||
@ -171,8 +169,8 @@ void DataFlash_Class::handle_log_request_end(GCS_MAVLINK &link, mavlink_message_
|
||||
{
|
||||
mavlink_log_request_end_t packet;
|
||||
mavlink_msg_log_request_end_decode(msg, &packet);
|
||||
_in_log_download = false;
|
||||
_log_sending = false;
|
||||
|
||||
transfer_activity = IDLE;
|
||||
_log_sending_link = nullptr;
|
||||
}
|
||||
|
||||
@ -188,13 +186,20 @@ void DataFlash_Class::handle_log_send()
|
||||
// might be flying
|
||||
return;
|
||||
}
|
||||
if (_log_listing) {
|
||||
switch (transfer_activity) {
|
||||
case IDLE:
|
||||
break;
|
||||
case LISTING:
|
||||
handle_log_send_listing();
|
||||
break;
|
||||
case SENDING:
|
||||
handle_log_sending();
|
||||
break;
|
||||
}
|
||||
if (!_log_sending) {
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
void DataFlash_Class::handle_log_sending()
|
||||
{
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
// assume USB speeds in SITL for the purposes of log download
|
||||
const uint8_t num_sends = 40;
|
||||
@ -213,8 +218,12 @@ void DataFlash_Class::handle_log_send()
|
||||
#endif
|
||||
|
||||
for (uint8_t i=0; i<num_sends; i++) {
|
||||
if (_log_sending) {
|
||||
if (!handle_log_send_data()) break;
|
||||
if (transfer_activity != SENDING) {
|
||||
// may have completed sending data
|
||||
break;
|
||||
}
|
||||
if (!handle_log_send_data()) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -247,7 +256,7 @@ void DataFlash_Class::handle_log_send_listing()
|
||||
time_utc,
|
||||
size);
|
||||
if (_log_next_list_entry == _log_last_list_entry) {
|
||||
_log_listing = false;
|
||||
transfer_activity = IDLE;
|
||||
_log_sending_link = nullptr;
|
||||
} else {
|
||||
_log_next_list_entry++;
|
||||
@ -297,8 +306,7 @@ bool DataFlash_Class::handle_log_send_data()
|
||||
_log_data_offset += len;
|
||||
_log_data_remaining -= len;
|
||||
if (ret < MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN || _log_data_remaining == 0) {
|
||||
_log_sending = false;
|
||||
_in_log_download = false;
|
||||
transfer_activity = IDLE;
|
||||
_log_sending_link = nullptr;
|
||||
}
|
||||
return true;
|
||||
|
Loading…
Reference in New Issue
Block a user