mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_SITL: correct segfault when uartg configured
This commit is contained in:
parent
b9d8f53af2
commit
e577a5564f
|
@ -71,13 +71,14 @@ public:
|
||||||
uint16_t current2_pin_value; // pin 14
|
uint16_t current2_pin_value; // pin 14
|
||||||
|
|
||||||
// paths for UART devices
|
// paths for UART devices
|
||||||
const char *_uart_path[6] {
|
const char *_uart_path[7] {
|
||||||
"tcp:0:wait",
|
"tcp:0:wait",
|
||||||
"GPS1",
|
"GPS1",
|
||||||
"tcp:2",
|
"tcp:2",
|
||||||
"tcp:3",
|
"tcp:3",
|
||||||
"GPS2",
|
"GPS2",
|
||||||
"tcp:5",
|
"tcp:5",
|
||||||
|
"tcp:6",
|
||||||
};
|
};
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
|
@ -294,6 +294,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
|
||||||
case CMDLINE_UARTD:
|
case CMDLINE_UARTD:
|
||||||
case CMDLINE_UARTE:
|
case CMDLINE_UARTE:
|
||||||
case CMDLINE_UARTF:
|
case CMDLINE_UARTF:
|
||||||
|
case CMDLINE_UARTG:
|
||||||
_uart_path[opt - CMDLINE_UARTA] = gopt.optarg;
|
_uart_path[opt - CMDLINE_UARTA] = gopt.optarg;
|
||||||
break;
|
break;
|
||||||
case CMDLINE_RTSCTS:
|
case CMDLINE_RTSCTS:
|
||||||
|
|
|
@ -50,6 +50,10 @@ bool UARTDriver::_console;
|
||||||
|
|
||||||
void UARTDriver::begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace)
|
void UARTDriver::begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace)
|
||||||
{
|
{
|
||||||
|
if (_portNumber > ARRAY_SIZE(_sitlState->_uart_path)) {
|
||||||
|
AP_HAL::panic("port number out of range; you may need to extend _sitlState->_uart_path");
|
||||||
|
}
|
||||||
|
|
||||||
const char *path = _sitlState->_uart_path[_portNumber];
|
const char *path = _sitlState->_uart_path[_portNumber];
|
||||||
|
|
||||||
// default to 1MBit
|
// default to 1MBit
|
||||||
|
|
Loading…
Reference in New Issue