mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 16:23:56 -04:00
AP_RCProtocol: fixed bug in FPort parser
if we got invalid frame->type values we would overrun the buffer and cause memory corruption. This was the cause of the bug Polarijet found
This commit is contained in:
parent
30baad35b2
commit
a1069d85cb
@ -322,6 +322,10 @@ void AP_RCProtocol_FPort::_process_byte(uint32_t timestamp_us, uint8_t b)
|
|||||||
(frame->type == FPORT_TYPE_DOWNLINK && frame->len != FRAME_LEN_DOWNLINK)) {
|
(frame->type == FPORT_TYPE_DOWNLINK && frame->len != FRAME_LEN_DOWNLINK)) {
|
||||||
goto reset;
|
goto reset;
|
||||||
}
|
}
|
||||||
|
if (frame->type != FPORT_TYPE_CONTROL && frame->type != FPORT_TYPE_DOWNLINK) {
|
||||||
|
// invalid type
|
||||||
|
goto reset;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if (frame->type == FPORT_TYPE_CONTROL && byte_input.ofs == FRAME_LEN_CONTROL + 4) {
|
if (frame->type == FPORT_TYPE_CONTROL && byte_input.ofs == FRAME_LEN_CONTROL + 4) {
|
||||||
@ -335,6 +339,9 @@ void AP_RCProtocol_FPort::_process_byte(uint32_t timestamp_us, uint8_t b)
|
|||||||
}
|
}
|
||||||
goto reset;
|
goto reset;
|
||||||
}
|
}
|
||||||
|
if (byte_input.ofs == sizeof(byte_input.buf)) {
|
||||||
|
goto reset;
|
||||||
|
}
|
||||||
return;
|
return;
|
||||||
|
|
||||||
reset:
|
reset:
|
||||||
|
Loading…
Reference in New Issue
Block a user