Browse Source

AP_Logger: use enum class for transfer activity

These weren't great symbols to create...
c415-sdk
Peter Barker 5 years ago committed by Peter Barker
parent
commit
9c17fdb851
  1. 8
      libraries/AP_Logger/AP_Logger.h
  2. 22
      libraries/AP_Logger/AP_Logger_MAVLinkLogTransfer.cpp

8
libraries/AP_Logger/AP_Logger.h

@ -359,7 +359,9 @@ public:
bool vehicle_is_armed() const { return _armed; } bool vehicle_is_armed() const { return _armed; }
void handle_log_send(); void handle_log_send();
bool in_log_download() const { return transfer_activity != IDLE; } bool in_log_download() const {
return transfer_activity != TransferActivity::IDLE;
}
float quiet_nanf() const { return nanf("0x4152"); } // "AR" float quiet_nanf() const { return nanf("0x4152"); } // "AR"
double quiet_nan() const { return nan("0x4152445550490a"); } // "ARDUPI" double quiet_nan() const { return nan("0x4152445550490a"); } // "ARDUPI"
@ -476,11 +478,11 @@ private:
/* support for retrieving logs via mavlink: */ /* support for retrieving logs via mavlink: */
enum transfer_activity_t : uint8_t { enum class TransferActivity {
IDLE, // not doing anything, all file descriptors closed IDLE, // not doing anything, all file descriptors closed
LISTING, // actively sending log_entry packets LISTING, // actively sending log_entry packets
SENDING, // actively sending log_sending packets SENDING, // actively sending log_sending packets
} transfer_activity = IDLE; } transfer_activity = TransferActivity::IDLE;
// next log list entry to send // next log list entry to send
uint16_t _log_next_list_entry; uint16_t _log_next_list_entry;

22
libraries/AP_Logger/AP_Logger_MAVLinkLogTransfer.cpp

@ -92,7 +92,7 @@ void AP_Logger::handle_log_request_list(GCS_MAVLINK &link, const mavlink_message
} }
} }
transfer_activity = LISTING; transfer_activity = TransferActivity::LISTING;
_log_sending_link = &link; _log_sending_link = &link;
handle_log_send_listing(); handle_log_send_listing();
@ -121,12 +121,12 @@ void AP_Logger::handle_log_request_data(GCS_MAVLINK &link, const mavlink_message
mavlink_msg_log_request_data_decode(&msg, &packet); mavlink_msg_log_request_data_decode(&msg, &packet);
// consider opening or switching logs: // consider opening or switching logs:
if (transfer_activity != SENDING || _log_num_data != packet.id) { if (transfer_activity != TransferActivity::SENDING || _log_num_data != packet.id) {
uint16_t num_logs = get_num_logs(); uint16_t num_logs = get_num_logs();
if (packet.id > num_logs || packet.id < 1) { if (packet.id > num_logs || packet.id < 1) {
// request for an invalid log; cancel any current download // request for an invalid log; cancel any current download
transfer_activity = IDLE; transfer_activity = TransferActivity::IDLE;
return; return;
} }
@ -149,7 +149,7 @@ void AP_Logger::handle_log_request_data(GCS_MAVLINK &link, const mavlink_message
_log_data_remaining = packet.count; _log_data_remaining = packet.count;
} }
transfer_activity = SENDING; transfer_activity = TransferActivity::SENDING;
_log_sending_link = &link; _log_sending_link = &link;
handle_log_send(); handle_log_send();
@ -175,7 +175,7 @@ void AP_Logger::handle_log_request_end(GCS_MAVLINK &link, const mavlink_message_
mavlink_log_request_end_t packet; mavlink_log_request_end_t packet;
mavlink_msg_log_request_end_decode(&msg, &packet); mavlink_msg_log_request_end_decode(&msg, &packet);
transfer_activity = IDLE; transfer_activity = TransferActivity::IDLE;
_log_sending_link = nullptr; _log_sending_link = nullptr;
} }
@ -194,12 +194,12 @@ void AP_Logger::handle_log_send()
return; return;
} }
switch (transfer_activity) { switch (transfer_activity) {
case IDLE: case TransferActivity::IDLE:
break; break;
case LISTING: case TransferActivity::LISTING:
handle_log_send_listing(); handle_log_send_listing();
break; break;
case SENDING: case TransferActivity::SENDING:
handle_log_sending(); handle_log_sending();
break; break;
} }
@ -227,7 +227,7 @@ void AP_Logger::handle_log_sending()
#endif #endif
for (uint8_t i=0; i<num_sends; i++) { for (uint8_t i=0; i<num_sends; i++) {
if (transfer_activity != SENDING) { if (transfer_activity != TransferActivity::SENDING) {
// may have completed sending data // may have completed sending data
break; break;
} }
@ -267,7 +267,7 @@ void AP_Logger::handle_log_send_listing()
time_utc, time_utc,
size); size);
if (_log_next_list_entry == _log_last_list_entry) { if (_log_next_list_entry == _log_last_list_entry) {
transfer_activity = IDLE; transfer_activity = TransferActivity::IDLE;
_log_sending_link = nullptr; _log_sending_link = nullptr;
} else { } else {
_log_next_list_entry++; _log_next_list_entry++;
@ -319,7 +319,7 @@ bool AP_Logger::handle_log_send_data()
_log_data_offset += len; _log_data_offset += len;
_log_data_remaining -= len; _log_data_remaining -= len;
if (ret < MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN || _log_data_remaining == 0) { if (ret < MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN || _log_data_remaining == 0) {
transfer_activity = IDLE; transfer_activity = TransferActivity::IDLE;
_log_sending_link = nullptr; _log_sending_link = nullptr;
} }
return true; return true;

Loading…
Cancel
Save