AP_Logger: restart logging after log transfer

This commit is contained in:
Peter Barker 2024-09-02 11:18:04 +10:00 committed by Andrew Tridgell
parent ed512eaabe
commit 8856100e39
7 changed files with 22 additions and 5 deletions

View File

@ -591,6 +591,7 @@ private:
void handle_log_request_data(class GCS_MAVLINK &, const mavlink_message_t &msg);
void handle_log_request_erase(class GCS_MAVLINK &, const mavlink_message_t &msg);
void handle_log_request_end(class GCS_MAVLINK &, const mavlink_message_t &msg);
void end_log_transfer();
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

View File

@ -76,6 +76,7 @@ public:
virtual void get_log_boundaries(uint16_t list_entry, uint32_t & start_page, uint32_t & end_page) = 0;
virtual void get_log_info(uint16_t list_entry, uint32_t &size, uint32_t &time_utc) = 0;
virtual int16_t get_log_data(uint16_t list_entry, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data) = 0;
virtual void end_log_transfer() = 0;
virtual uint16_t get_num_logs() = 0;
virtual uint16_t find_oldest_log();

View File

@ -24,6 +24,7 @@ public:
void get_log_boundaries(uint16_t list_entry, uint32_t & start_page, uint32_t & end_page) override;
void get_log_info(uint16_t list_entry, uint32_t &size, uint32_t &time_utc) override;
int16_t get_log_data(uint16_t list_entry, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data) override WARN_IF_UNUSED;
void end_log_transfer() override { }
uint16_t get_num_logs() override;
void start_new_log(void) override;
uint32_t bufferspace_available() override;

View File

@ -642,6 +642,14 @@ int16_t AP_Logger_File::get_log_data(const uint16_t list_entry, const uint16_t p
return ret;
}
void AP_Logger_File::end_log_transfer()
{
if (_read_fd != -1) {
AP::FS().close(_read_fd);
_read_fd = -1;
}
}
/*
find size and date of a log
*/

View File

@ -45,6 +45,7 @@ public:
void get_log_boundaries(uint16_t log_num, uint32_t & start_page, uint32_t & end_page) override;
void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc) override;
int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data) override;
void end_log_transfer() override;
uint16_t get_num_logs() override;
void start_new_log(void) override;
uint16_t find_oldest_log() override;

View File

@ -50,6 +50,7 @@ public:
void get_log_boundaries(uint16_t log_num, uint32_t & start_page, uint32_t & end_page) override {}
void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc) override {}
int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data) override { return 0; }
void end_log_transfer() override { };
uint16_t get_num_logs(void) override { return 0; }
void remote_log_block_status_msg(const GCS_MAVLINK &link, const mavlink_message_t& msg) override;

View File

@ -128,7 +128,7 @@ void AP_Logger::handle_log_request_data(GCS_MAVLINK &link, const mavlink_message
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 = TransferActivity::IDLE;
end_log_transfer();
return;
}
@ -174,11 +174,16 @@ void AP_Logger::handle_log_request_erase(GCS_MAVLINK &link, const mavlink_messag
void AP_Logger::handle_log_request_end(GCS_MAVLINK &link, const mavlink_message_t &msg)
{
WITH_SEMAPHORE(_log_send_sem);
mavlink_log_request_end_t packet;
mavlink_msg_log_request_end_decode(&msg, &packet);
// mavlink_log_request_end_t packet;
// mavlink_msg_log_request_end_decode(&msg, &packet);
end_log_transfer();
}
void AP_Logger::end_log_transfer()
{
transfer_activity = TransferActivity::IDLE;
_log_sending_link = nullptr;
backends[0]->end_log_transfer();
}
/**
@ -323,8 +328,7 @@ bool AP_Logger::handle_log_send_data()
_log_data_offset += nbytes;
_log_data_remaining -= nbytes;
if (nbytes < MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN || _log_data_remaining == 0) {
transfer_activity = TransferActivity::IDLE;
_log_sending_link = nullptr;
end_log_transfer();
}
return true;
}