ArduPilot / ardupilot

ArduPlane, ArduCopter, ArduRover, ArduSub source
http://ardupilot.org/
GNU General Public License v3.0
11.01k stars 17.56k forks source link

ArduPilot: Firmware requests statistics for 65535 logs even if they don't exist #24940

Open sahilsihag opened 1 year ago

sahilsihag commented 1 year ago

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

MAVLink packet: fd0500008effe675000000000000017166

Information:
Payload: LOG_REQUEST_LIST (117)
    target_system (uint8_t): 1
    target_component (uint8_t): 0
    start (uint16_t): 0
    end (uint16_t): 0

leads to

_log_last_list_entry = 0
_log_next_list_entry = 1

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.

    if (_log_next_list_entry == 0) {
        size = 0;
        time_utc = 0;
    } else {
        get_log_info(_log_next_list_entry, size, time_utc);
    }
    ...
    ...
    if (_log_next_list_entry == _log_last_list_entry) {
        transfer_activity = TransferActivity::IDLE;
        _log_sending_link = nullptr;
    } else {
        _log_next_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 both uint16_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:

Log 1  numLogs 4 lastLog 0 size 73728 Tue Jan  1 01:00:00 1980     
Log 2  numLogs 4 lastLog 0 size 114688 Tue Jan  1 01:00:00 1980    
Log 3  numLogs 4 lastLog 0 size 65536 Tue Jan  1 01:00:00 1980     
Log 4  numLogs 4 lastLog 0 size 108004 Tue Jan  1 01:00:00 1980    
Log 5  numLogs 4 lastLog 0 size 0    
Log 6  numLogs 4 lastLog 0 size 0    
Log 7  numLogs 4 lastLog 0 size 0    
Log 8  numLogs 4 lastLog 0 size 0    
Log 9  numLogs 4 lastLog 0 size 0    
Log 10  numLogs 4 lastLog 0 size 0   
Log 11  numLogs 4 lastLog 0 size 0   
Log 12  numLogs 4 lastLog 0 size 0   
Log 13  numLogs 4 lastLog 0 size 0   
Log 14  numLogs 4 lastLog 0 size 0   
Log 15  numLogs 4 lastLog 0 size 0 
Log 16  numLogs 4 lastLog 0 size 0 
Log 17  numLogs 4 lastLog 0 size 0 
Log 18  numLogs 4 lastLog 0 size 0 
Log 19  numLogs 4 lastLog 0 size 0 
Log 20  numLogs 4 lastLog 0 size 0 
Log 21  numLogs 4 lastLog 0 size 0 
Log 22  numLogs 4 lastLog 0 size 0 
Log 23  numLogs 4 lastLog 0 size 0 
Log 24  numLogs 4 lastLog 0 size 0 
Log 25  numLogs 4 lastLog 0 size 0 
Log 26  numLogs 4 lastLog 0 size 0 
Log 27  numLogs 4 lastLog 0 size 0 
Log 28  numLogs 4 lastLog 0 size 0 
Log 29  numLogs 4 lastLog 0 size 0 
Log 30  numLogs 4 lastLog 0 size 0 
Log 31  numLogs 4 lastLog 0 size 0 
Log 32  numLogs 4 lastLog 0 size 0 
Log 33  numLogs 4 lastLog 0 size 0 
Log 34  numLogs 4 lastLog 0 size 0 
Log 35  numLogs 4 lastLog 0 size 0 
Log 36  numLogs 4 lastLog 0 size 0 
...
...
<keeps going>
...
...
Log 65501  numLogs 4 lastLog 0 size 0 
Log 65502  numLogs 4 lastLog 0 size 0 
Log 65503  numLogs 4 lastLog 0 size 0 
Log 65504  numLogs 4 lastLog 0 size 0 
Log 65505  numLogs 4 lastLog 0 size 0 
Log 65506  numLogs 4 lastLog 0 size 0 
Log 65507  numLogs 4 lastLog 0 size 0
Log 65508  numLogs 4 lastLog 0 size 0 
Log 65509  numLogs 4 lastLog 0 size 0 
Log 65510  numLogs 4 lastLog 0 size 0 
Log 65511  numLogs 4 lastLog 0 size 0 
Log 65512  numLogs 4 lastLog 0 size 0 
Log 65513  numLogs 4 lastLog 0 size 0 
Log 65514  numLogs 4 lastLog 0 size 0 
Log 65515  numLogs 4 lastLog 0 size 0 
Log 65516  numLogs 4 lastLog 0 size 0 
Log 65517  numLogs 4 lastLog 0 size 0 
Log 65518  numLogs 4 lastLog 0 size 0 
Log 65519  numLogs 4 lastLog 0 size 0 
Log 65520  numLogs 4 lastLog 0 size 0 
Log 65521  numLogs 4 lastLog 0 size 0 
Log 65522  numLogs 4 lastLog 0 size 0 
Log 65523  numLogs 4 lastLog 0 size 0 
Log 65524  numLogs 4 lastLog 0 size 0 
Log 65525  numLogs 4 lastLog 0 size 0
...
amilcarlucas commented 1 year ago

Can you provide a pull request that sanitizes the MAVlink packet before interpretation?

shancock884 commented 1 year ago

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).

sahilsihag commented 1 year ago

I agree with enforcing:

  1. start <= end

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.