Open sahilsihag opened 1 year ago
Can you provide a pull request that sanitizes the MAVlink packet before interpretation?
This may be a bit more than checking the validity of the incoming LOG_REQUEST_LIST packet.... I can think of 3 cases, which I believe trigger this behaviour: 1/ Incoming packet has start > end - this is clearly invalid, so maybe it is appropriate to ignore it. 2/ Incoming packet has start = end = 0 - this could be seen invalid, as maybe end should always >= 1, but actually could be seen as a 'nice' way to request the number of logs without getting the whole list. 3/ Incoming packet requests a valid interval, which just happens to be empty. i.e. start=10, end=15, when there are <10 logs available.
In the 3rd case, I believe the correct response is a LOG_ENTRY packet with id=0, numLogs correctly set, and lastLog=0. In the 2nd case, I think it would be nice to also do the same as 3rd case, to give a easy means to get the total number of logs. In the 1st case, I could go either way - maybe I'd lean towards doing the same as other cases (to avoid sending back nothing, and to avoid risk/effort for an unlikely case by keeping code changes more constrained).
I agree with enforcing:
To handle case 3 is it correct to use _log_num_logs
and restrict both _log_last_list_entry
and _log_next_list_entry
in AP_Logger::handle_log_request_list
if (_log_last_list_entry > _log_num_logs) {
_log_last_list_entry = _log_num_logs;
}
if (_log_next_list_entry > _log_num_logs) {
_log_next_list_entry = _log_num_logs;
}
This would then only send back one LOG_ENTRY with id = _log_num_logs
I also see #define MAX_LOG_FILES 500
inside the repository. Can we use this to restrict difference between start and end?
Deciding whether to i.) simply ignore such packets or ii.) send LOG_ENTRY packet with id = 0 and numLogs correctly set is beyond my control.
Bug report
Issue summary
Malformed MAVLink packet leads to firmware requesting size (
_get_log_size
) and time (_get_log_time
) statistics for 65535 (max uint16_t) log files. Firmware keeps requesting statistics irrespective of log file existing or not.Issue details
leads to
in AP_Logger::handle_log_request_list. Later, AP_Logger::handle_log_send_listing keeps calling
get_log_info
until_log_next_list_entry == _log_last_list_entry
._log_next_list_entry
is incremented in steps of 1. So, the firmware requests statistics for log files until_log_next_list_entry
wraps to 0 after 65535 increments._log_last_list_entry
and_log_next_list_entry
are bothuint16_t
.Version
ArduCopter V4.4.0 (502702df)
Platform
Airframe type
Not applicable.
Hardware type
Board: omnibusF4
Logs
For example: 4 log files exist on my card. Mavproxy output with above packet: