Browse Source

AP_HAL_SITL: Correct range check on UART ports

Coverity CID 308362
master
Michael du Breuil 6 years ago committed by Peter Barker
parent
commit
a8a71db258
  1. 2
      libraries/AP_HAL_SITL/UARTDriver.cpp

2
libraries/AP_HAL_SITL/UARTDriver.cpp

@ -51,7 +51,7 @@ bool UARTDriver::_console; @@ -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…
Cancel
Save