AP_HAL_SITL: Correct range check on UART ports

Coverity CID 308362
This commit is contained in:
Michael du Breuil 2019-04-08 15:56:15 -07:00 committed by Peter Barker
parent 4b0339d940
commit a8a71db258

View File

@ -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");
}