mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_HAL_SITL: Correct range check on UART ports
Coverity CID 308362
This commit is contained in:
parent
4b0339d940
commit
a8a71db258
@ -51,7 +51,7 @@ bool UARTDriver::_console;
|
||||
|
||||
void UARTDriver::begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace)
|
||||
{
|
||||
if (_portNumber > ARRAY_SIZE(_sitlState->_uart_path)) {
|
||||
if (_portNumber >= ARRAY_SIZE(_sitlState->_uart_path)) {
|
||||
AP_HAL::panic("port number out of range; you may need to extend _sitlState->_uart_path");
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user